From 538455a965ce25a6f7b81d8b5c8cee46b90a7df9 Mon Sep 17 00:00:00 2001 From: Hirokazu Ishida <38597814+HiroIshida@users.noreply.github.com> Date: Wed, 30 Oct 2024 19:00:05 +0900 Subject: [PATCH 01/24] feat: enable to use multiple rgb encoders per camera in diffusion policy (#484) Co-authored-by: Alexander Soare --- .../diffusion/configuration_diffusion.py | 2 + .../policies/diffusion/modeling_diffusion.py | 43 ++++++++++++++----- 2 files changed, 34 insertions(+), 11 deletions(-) diff --git a/lerobot/common/policies/diffusion/configuration_diffusion.py b/lerobot/common/policies/diffusion/configuration_diffusion.py index bd3692ace..531f49e4d 100644 --- a/lerobot/common/policies/diffusion/configuration_diffusion.py +++ b/lerobot/common/policies/diffusion/configuration_diffusion.py @@ -67,6 +67,7 @@ class DiffusionConfig: use_group_norm: Whether to replace batch normalization with group normalization in the backbone. The group sizes are set to be about 16 (to be precise, feature_dim // 16). spatial_softmax_num_keypoints: Number of keypoints for SpatialSoftmax. + use_separate_rgb_encoders_per_camera: Whether to use a separate RGB encoder for each camera view. down_dims: Feature dimension for each stage of temporal downsampling in the diffusion modeling Unet. You may provide a variable number of dimensions, therefore also controlling the degree of downsampling. @@ -130,6 +131,7 @@ class DiffusionConfig: pretrained_backbone_weights: str | None = None use_group_norm: bool = True spatial_softmax_num_keypoints: int = 32 + use_separate_rgb_encoder_per_camera: bool = False # Unet. down_dims: tuple[int, ...] = (512, 1024, 2048) kernel_size: int = 5 diff --git a/lerobot/common/policies/diffusion/modeling_diffusion.py b/lerobot/common/policies/diffusion/modeling_diffusion.py index 308a8be3c..9ba562600 100644 --- a/lerobot/common/policies/diffusion/modeling_diffusion.py +++ b/lerobot/common/policies/diffusion/modeling_diffusion.py @@ -182,8 +182,13 @@ def __init__(self, config: DiffusionConfig): self._use_env_state = False if num_images > 0: self._use_images = True - self.rgb_encoder = DiffusionRgbEncoder(config) - global_cond_dim += self.rgb_encoder.feature_dim * num_images + if self.config.use_separate_rgb_encoder_per_camera: + encoders = [DiffusionRgbEncoder(config) for _ in range(num_images)] + self.rgb_encoder = nn.ModuleList(encoders) + global_cond_dim += encoders[0].feature_dim * num_images + else: + self.rgb_encoder = DiffusionRgbEncoder(config) + global_cond_dim += self.rgb_encoder.feature_dim * num_images if "observation.environment_state" in config.input_shapes: self._use_env_state = True global_cond_dim += config.input_shapes["observation.environment_state"][0] @@ -239,16 +244,32 @@ def _prepare_global_conditioning(self, batch: dict[str, Tensor]) -> Tensor: """Encode image features and concatenate them all together along with the state vector.""" batch_size, n_obs_steps = batch["observation.state"].shape[:2] global_cond_feats = [batch["observation.state"]] - # Extract image feature (first combine batch, sequence, and camera index dims). + # Extract image features. if self._use_images: - img_features = self.rgb_encoder( - einops.rearrange(batch["observation.images"], "b s n ... -> (b s n) ...") - ) - # Separate batch dim and sequence dim back out. The camera index dim gets absorbed into the - # feature dim (effectively concatenating the camera features). - img_features = einops.rearrange( - img_features, "(b s n) ... -> b s (n ...)", b=batch_size, s=n_obs_steps - ) + if self.config.use_separate_rgb_encoder_per_camera: + # Combine batch and sequence dims while rearranging to make the camera index dimension first. + images_per_camera = einops.rearrange(batch["observation.images"], "b s n ... -> n (b s) ...") + img_features_list = torch.cat( + [ + encoder(images) + for encoder, images in zip(self.rgb_encoder, images_per_camera, strict=True) + ] + ) + # Separate batch and sequence dims back out. The camera index dim gets absorbed into the + # feature dim (effectively concatenating the camera features). + img_features = einops.rearrange( + img_features_list, "(n b s) ... -> b s (n ...)", b=batch_size, s=n_obs_steps + ) + else: + # Combine batch, sequence, and "which camera" dims before passing to shared encoder. + img_features = self.rgb_encoder( + einops.rearrange(batch["observation.images"], "b s n ... -> (b s n) ...") + ) + # Separate batch dim and sequence dim back out. The camera index dim gets absorbed into the + # feature dim (effectively concatenating the camera features). + img_features = einops.rearrange( + img_features, "(b s n) ... -> b s (n ...)", b=batch_size, s=n_obs_steps + ) global_cond_feats.append(img_features) if self._use_env_state: From e0df56de621b6f7ee501719ee0b1e4af00a98635 Mon Sep 17 00:00:00 2001 From: Arsen Ohanyan Date: Thu, 31 Oct 2024 08:41:49 -0700 Subject: [PATCH 02/24] Fix config file (#495) --- examples/10_use_so100.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index 405e80ec0..32d7f22dd 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -135,7 +135,7 @@ You will need to move the follower arm to these positions sequentially: Make sure both arms are connected and run this script to launch manual calibration: ```bash python lerobot/scripts/control_robot.py calibrate \ - --robot-path lerobot/configs/robot/moss.yaml \ + --robot-path lerobot/configs/robot/so100.yaml \ --robot-overrides '~cameras' --arms main_follower ``` From 963738d983480b1cd19295b2cb0630d0cf5c5bb5 Mon Sep 17 00:00:00 2001 From: Ivelin Ivanov Date: Tue, 5 Nov 2024 08:30:59 -0600 Subject: [PATCH 03/24] fix: broken images and a few minor typos in README (#499) Signed-off-by: ivelin --- README.md | 10 +++++----- media/gym/aloha_act.gif | Bin 0 -> 3027981 bytes media/gym/pusht_diffusion.gif | Bin 0 -> 189800 bytes media/gym/simxarm_tdmpc.gif | Bin 0 -> 475007 bytes 4 files changed, 5 insertions(+), 5 deletions(-) create mode 100644 media/gym/aloha_act.gif create mode 100644 media/gym/pusht_diffusion.gif create mode 100644 media/gym/simxarm_tdmpc.gif diff --git a/README.md b/README.md index b505c545d..5fbf74f44 100644 --- a/README.md +++ b/README.md @@ -55,9 +55,9 @@ - - - + + + @@ -144,7 +144,7 @@ wandb login ### Visualize datasets -Check out [example 1](./examples/1_load_lerobot_dataset.py) that illustrates how to use our dataset class which automatically download data from the Hugging Face hub. +Check out [example 1](./examples/1_load_lerobot_dataset.py) that illustrates how to use our dataset class which automatically downloads data from the Hugging Face hub. You can also locally visualize episodes from a dataset on the hub by executing our script from the command line: ```bash @@ -280,7 +280,7 @@ To use wandb for logging training and evaluation curves, make sure you've run `w wandb.enable=true ``` -A link to the wandb logs for the run will also show up in yellow in your terminal. Here is an example of what they look like in your browser. Please also check [here](https://github.com/huggingface/lerobot/blob/main/examples/4_train_policy_with_script.md#typical-logs-and-metrics) for the explaination of some commonly used metrics in logs. +A link to the wandb logs for the run will also show up in yellow in your terminal. Here is an example of what they look like in your browser. Please also check [here](https://github.com/huggingface/lerobot/blob/main/examples/4_train_policy_with_script.md#typical-logs-and-metrics) for the explanation of some commonly used metrics in logs. ![](media/wandb.png) diff --git a/media/gym/aloha_act.gif b/media/gym/aloha_act.gif new file mode 100644 index 0000000000000000000000000000000000000000..0285a3dd10b2e3b8f787b4e3f0eb740968074c3b GIT binary patch literal 3027981 zcmeF&^w#?iejOLTMNs5_=&HBHP&Lu8Dw@fRu=&ba$uH(xsG& z$=CPa@%`L?yRP%ob#Bkcxt;Sow@dGVu7aZT4PhwZ_d9}r2>%B|L_`Dt0EhvZ#Qy+$ zK!AD>arwP__b4eTX=p=esaomi=$IIanV6WEnVDG_2Ux&=SXfxt*w{EYI5^p_IXOAG zShu;jxVTv-c)0)a@bK{QdGYiA65u@(5D*X)uovQ=6%zFk5q>HnA|fX6LPA0UDq1Eb z_D1R-4Vbi)i;UQ|%s(3Hva+&r;=OW`&*bFfM{6QCsPMRFu?U%Kww0qNJ?y zKcT9ss%k10YHDigYQ^g6>KbY)uzxfkX+niG)nS_d6RM>N)A}EMZEbCxe{_>||Iu^Q zla@`GJzYIKJUrb! zJU!ez|MBwm@_Fv$)&-2aT`OowJd7-9OR8;ix<;!9znd0K&l9H10^72=&UR6|7R8>{g)YR10*4FV0 zzmbxD^X5%MLqlU@E-o%FFR!Smtgfzp{P=NWV`F=Jdxu|W=YiJl?(TuE>hbaM z`F)lP6~!NN@_)!E{y-(~_yh><2)OUaO>`_Rv|w-@DRC%(@LwLde-HzK|As{W7mokM zB<}x0@_!-u|2ZV2cLao_Z2AqweHhaF!uF#LB?ECZyaomOZ%c=gz|ubJqi@Sb(zvt| z*&Z~Ok7YqDs_n-bUrppeUB?R^ysMacq44Bnee7N3%u5Xn8M{GK)m)i=maxNk)9Zyw zc$q<=L38y|jrBX9jq&E1l{biiM0UfL+7Iu%7OEX4TI$wXk-OuChOPA*9bwle8xyT> zwt8X!E={N>zA!w3^}JsXWQlOXqJf6bZ7hZ;cS`VOOvkmUr$%x zJ>Ht`>iGU;dm!nK)3m$u$Mw-djnhnb*RSsvyAv->d%FMpy1hQ#n(67eyCVQWwquAH zy|z)L0#(~+3b~_g42>?{j)4A=*A5o!QMH3(3pv_}RlBJw-;Q?EG(bXo>Dr9mdl~uyulF*IAJ$l<#8U)C^rVtlH-a3|C7PWVw~_vRe7$@$?K|$>XYi) zmXnj3hT%Km)7qwGpPFhoJm$C>esgmArWYh~)-cHU`0VYdK+Rd>q}=J*yIEb4^QJ`( zRvlo+C)@Lu^^nu^)@_`~=e8}!7k<@y6*ZsVpS7HR?wHMIwE=eaKmO8ndr*Y|P=?0I%RnDUT9hn_1=G?1P%&G%{y zQdxU7F4}r_H31zFy`Gd=@x7i>IAnYGhD}=c&9nxI*v+gqli$spzF?hH%e7L;%>rCc z?CYYX6{XC=os!?zW&6}^?O^HTAl4u>EJD|+%JZb8sCnh zc6mB#>c4k~IOQVg$0|F2e;1Va+&K~X^TVH8L9HF_FN>{CPiYPL#IJwY zc?PUr-o)K?o%7nIs!b%HTK=y8-jiNu8u8hXiy93lUZHIWM7(oy_R#CdeCm6zAMoL? z+-M(F#07?nqU5}OJC+T95v%A`d`bZ6XM9f+#bd$wi@vItlY%f>q+p9YRA1>H9WJoz zCq3xyVJPvD7%Ec5sFW_ROeqA;79NmIRlaV12VaTC6u9{x=5IkLf?R#_Q00 z^9`h0FFYyz-od3EK-w=-#&)Q$2VpD0&HsV{B44R1{k#kW6*x0p-VX6p{lPBF6%eDt$j8~}qa^BJ6US(pct8Cb;CGC?ceM(&Bvs8MD zE^Dh;Zi>E?wq!?f>G(k^&`C~j6gNE@X~03T6E8qs!Bzq%K7QVSFWMud$E3sDqc4(+ zo}f>B!zb(`vhq2}xr=Kbm{6f7vmGejNO^u zex(a%V-r*(@lg!=D~_U=ED^bP(hp(VNw_NTlzf^u8!2@Y_?CjA>vn98b@;7mx9FnI zhPQ!1X;#E*woQHYc$GbN8Z2GmA(K^QbB>Eeh{?8>o_DocCD5{5q`5*GwbGGgGJ|{A z=>k{9kMh#ouaLwF=zRAwi`rZaQ(Ss&(rzSw-98f+{#u{=`!H;goxP0F zYU7Ly+-yclME}Ygvu(`XDI?=dYfruce3X&UbH*WrB_A1YJ16R_uIbiGehrf;bqJd@&h>ugS!SBFcCeI z@4m#eMbQksBeKJ;%k|1^Y_fw#<3|%#lQ%7!Gx|S!JvJ)|N5zSe<~qufbbWbggULp| zC(p|wwXbQH=ZmSD{lAoN6RWZ0(-sOO7?Y_4GtRwrD)gmcuj<}87jL_$dtCTZVPE8z z?Mix4O?ls#hZz&u0?Sg+vsRW>YtNkzv%2(6Fa6GZc)yfrQMUZ@cnp{Sne|`$Q@P!y zcH_@i)_nq#ugqxMK3hCip2*&7Y)(sA>6x7vn)q9xXLajMZ>nrIyV;+2=y&Yg&AQ3n zT`89ket}btS~KCgElw}Aa^GFc-E7(ycAh%$wy^s+!+6`vZz9CQ#I#C%msj;=8@%rC zqPP#8@uf{P4pcK+-(>8$P5NGadHZK!YYr67sI7LDuk1r+lJjN4)loH3yzm&Fc1+{t zc>Utn{-)B3qPU-pZ6)@82JDUHsH*=>netqVS=z~)h3Ri}rd?-G8zY<=ih`p&3r=fK zWmc0+s$wDwz90n`>2oh`TE4u$z?uHO*<%lDzs5RNCq;>!`iJ_@-*i8d&)$;e44Yyq z8BhG~cB5(f(*@Li{l4z|(wNwfF^j*S>gB`^3AZYHo^X6cYbw1oeA&z9Mb;93_;k@T zHDcro@TxBK&*}BK&pOe@H&mnQ&41KY;`XSHeyivHxTrPCY4w;C$j7JHW)ArOW>%tM1K zO->Hc7bGYnJl3`?R$CsZsP9r98i>mS49a@S(d#+P0I%J3>l~ZK|wGf@l0X( zxbfB~%h+(6)wmpRqOAgul`#Q(>tEsKwmle=eDq)HC=L>$M|FtE7fhTFO$g0M$d8Z7 zBk^pxP3l#^l#{9=!V<4@^wg{Y4Gh4uJP+;L#4|yEqz=x!#dPG>p&6V!i%SYAN$MC) zD6B~Nq>$<+pZsO%=`h&aG{|k3-W7J3I15hUw0`C}tjapK1vIc zG~|>E&u=rXZ%wdYv9^E)fta)U!n~9~-tG|e$2*Ye%#r&GlC(FZS+071=kk7`rN-zW z0})UC82Riy{mdsY39z=Ie0HWF*!EShKCw`i?SnWhF7;+V(qtAvITph8Bl$uh%Z9-8 zORxd&fv!P&4##13AdIl;osi&zoQH}z{aQiD4|yd=IX4f9m-BMF01?nUKsG3Eap=LS zpkrN&iNtZIJZb(QGs+N&BpQj)8i}4Hc1P-)nql!T z#{^?5)0=fH$@L2YnVINmo->C(?i_nzd3WsgYQOM{Rl$*Wqy+)q>3PBYN&$s{yH|5a zRW3d{+;-_0zeo=pYA-~Z5&i|)@BDa?KPpta8x@mTM5g2?d(T^ayQrl#{=H6ev#g6H zv2e-*eRagk=zA|Z4|GNb(NXvE{{CPjFz_Q%Dh|DeWsdcFAX`ArQpP8fe{b*Kbfoan z=Wu@0)!R!7HGif*R)TB?dhS2aX^5UX%Huy_B*-s#|Eg4k3>%>*#iE^I4=w}VL-#Qf z-*1mS;FU^*1U}8QSPr+G=gUZZuFrk+ApHX_v%TDJu6(iL1w23V_dWCVg=il6Qfu1+ zxJFs{9&yyqB&!&|nLTAzrsv*DMniW;YTMbsWQ8iJdzHT2m5`s$g!3~$gKcJxDxNC& zW%{J^X&a>oKh)E3FuF~wQ+P@gYN!RxIAE^c4FftL3tmN7{>0-R-#*WN&&Ze_?q5|F zmSD$un3P(DeK4M;O`4Agi>K>CdysurAm6?99h|HsQ!|0O>b5F>2tlc{F+U& zh87#amKC65{A=R;D4m;3p7sLu2bfD+%*Z&FS-G4A@^G=d>e=Xdk0Lf-ed0Z38!>chpmuTit{Z_lgWv5H_6C*FSd@!|aS+Q!x^Hm;HOtBzh1 zu4cSuC!Yz*TCy5ZFUy*G@%`OGVzUivn%YFOZ99;CBG+EGNs<}3j%|v|e^i**06cE= zrfoJJMGt^;M17jgYntahGe~P%32IvH6oJgbFSra_K0%PNhZto6QxT^B2*1}oJ#O(L zY^ANXJJD*TdE6Rm_txsPm3FkXalG{zYa9NRUaVdEs_=X0zVhm7o3C=_dpc&MUF;X1 zC)?ref8V!<{R%A-L1Nx_v`w^2h68`;se0wTX|{Q9q@SVK9GSG7y9KPSn@F>`c%M%A z&N1?}l2Y;XN_+8(_M)1Oj=Qyv9g(aLwpRB&vLzY2Pdd8iSQ9gvfwPG!8rA7=hG?!| z^$S0m!koK`$>FN}!Y)nCy{B2-tg+cVa_71k^Zjc4jH`csOz z50r^p?J~|qQmr()(olpn>pj!MT|lGWt%>&}zP)rRea}XlHc$E_><3PNB{>Kg+spMZ zjJxi=>IaCX{)}V-(^Lo*U}^39#cBuT)(1^$TQhzRnyU=u8~Oz3At=JHWWyd&14dE9KApq9>%+IKfo6yb`k~H*4usxpmValri#-z~{8jkxkxuf_ z6gX+M7!@)&-#>!ZzBwBA%`5{F__BloLm>u z&>zPw_)edxOm);utx(KFtxdOxPOY9z{j?u&AOKS8j@;S;(C=s7#7`q(ghY!<{Jt|E z3TEJEvqg_*zS~dH{h6gPo&`J1{Oxodbq82n06X&MKz|rX#WXIp-qM{g9E&2YpQg|hV=vwhsUH!7Y zk|XvZPjyu*?gOrCCZ64*GGbZ!>2!$Sd|_i=WZ_tW*ud+;57?=XUX*JEg&&(7)>@vf zHU9yc5v<6_%x0ym^-|6xcQK|KFEXrutWQ~N{PVF@Y;}BN9nQW!ue!15H}igKtwPS3 z?hkPN4{+%&Wz7yLlwr0$%)a5Uy}{76o=v&2UAQhvxw*x@b;Z8EqKYdqdNI&&7X3 z)Wk_Y(hdPVa3BDgsqI?)J$QMQsVKhT9K9Fpzv%dPf8lIDa_Z3M?_q56o{gMKcjX~u z`oR3|?}0_CU1ZUr_2!YS{}J`)!?5T>p~Axu|KsMaVO{Z~kGTLnu4AgyBmerN0FDo+ z&qrx$$M~Y1RLA4|&FO0K6Q%l-*}7r1&&PcpnxVCulqM&H{wIl_l|-#i-%;(=Zk{0g zPbccn8l%sq{+?tOo;0Pd_oQsUulJLKI#0a*)cY4qBz{&@Dnv-}8iCk(@Mm}S@7XEU z@%;4X^XZ9^)HB@_1k0eK#Gq0Tt>*!BQf6h};v*kRW!Im~E(vO~c4SI`z zAvFCm%<*MW?aP?Sc#qz5oStkpwq<^WFO9D}gkbz9#x|4Kw{t z>vX9V@EyE0y|QviB2QdceRIVeC)YsC82y+jhe#e4(hmHOR{>D`tFMPLK4?d7j^r(Xnf zI@`VCP81y4c=(Pc?jE^Z>@9YCP(ml{cW->gh;AyoYBcfKr5=r-O$$Xb-h7`4YUX24 z!7P11&Eeo7X_sr^Iqf#n7`!%Y3~BY#X=dKgtuxP-rRY<^lI8G&F)Rf3L-`L+AJsc_ zMFUwMomn@!_n2FM(muCsd7RgY{nZlB<2sqSA)71z#ldB!#Tmc`wreTVdH0lj`OrI0 zOpvoamd)nMZJbt+?6=gOi*CM@YUE$Sq08NIkv_K{&Slq!c*Q{bGoDjsnWE4;KMBK@ zGp`-Lk4^3XDz-H_??}hr$insJNnW}>Ygtx@pFt-}b&qw{9(8231*D1ocpJAW<67ORIjt{KRimtyo9O|exy_HHTIvo zmwtGy>6!bVz>9AY*J27=Q8l1+hA?=&_WdUi%~Ek_TfGjGQ|#N?vzEs-%7Xpm0?e+{ zyJmW>#oUvvlpC&ZSP?B?o}{1pS)$dIR5HfZ0)^|;$>J4Y%|0O0Dd97SOOjM^(pyvYyIOx;mJReo0@t@uzq=8R8R=nW zj|T3+?&2r)>H@QXWf4VFM zz7M6D?e9JYzwnvg6Jd7Qt3nBgsbaQm($xP-+p_GSKh3fw%!%0fJ(=)kdC(s<5t%GLv~q$|qMlnV3cIM-Ond{ozjTjd2K%$EOizg`VuKKK?(cE}`GpaI!< z85&IoE1q-sjU4>mL6j&YP}vzcAu+Ok1*rgwox~S3^exRm$x2CU_M>)xwJ>QP@o#qi@}`gM+JiM9<~1)lwB@#x z;(S8ClY8*>&ELqJ?k_>yR}&I`kzZFld!BxOZLsvDvVzM@z)F^^AF*iT^t4jvD~qXY zqZy?$ZJA2shq)8cgOzR9m$gXM8*cX)g~5<>!{`GH`p9kmIoqf+ z<4inA#t2NQ2-AuU%uknT($^8eT`s49P$=3=>V*rC`hb03UldCkCSoZwSSuu5H`TN6ow;=qopt)a%Jiuh`qmh zL9bBTcMoPsN?WL@#&!VB)|xb>UYOOoeo!tcs95^rJqr6$&pg* zC~qigDy1Q-F5MpM4M2zZ{=(x-LQ2#=SeUuiBS#cDoGGhrvHVJsWQO$gbU3iKCgIyS zrBN7F49$>mkR-VVA}vlshEpUselC`VHaj_TU5`~W-HP#u+)=~Zz)aZucebZ9P6il-vE;9B&5kI z)`8;8Gynp;;J|pox!gxGtO{HOyV^Cuqyz*cF@mH4*weR;4L}V@e|>0|2p_#6&l94EMq9`B7INj0fq9~mPU6{IWf&6iE_r2Y;Seko#evxz=SMymh+UOeny`%qhV`mpZR4t>wG$|g1fp;%#i+Jnv3l0j zQ;ovBli_~&RJL*MO^1lwAiNgL6-VK!=MTr)XhkBDIbufy1=_fT%snL6+Y z&CP`(vnJqW9>D9$a(&49hFyK6N3o^8u*QN$Z7Q-$M$@RG1K=l zog`Le^fkZXd!xAwiKCT?n z;9gSQhL&pM2Q0g8kbxKD7j%@Az#-NTRXXh5F)sA-L-zs*hNa-NyWTRa(4Vh{WeOyd zOh!v6Fr>QgDp83d1%abmpwPCVu6Hufa0>hBIJKJ$|KQfhjbE#AYTq)_!YW^E{y2(L zzuKXGdi`Sa_eGpkEG_5`RbJArzIX(KE?{jzwWL5La&$Vr~qITc33XjjPOlC z^WqGd#{5jgBl1ZX7KTq|cNat&_MySxwo4I~&_S5~*9yo|?;r!4&$+B9j9QixDC--g zxn0%8vVa(tFybbWOD1Aj=p7aonDgULTl?~iMCHeLin;jrfs0?zsP6j#VbRi?oQcn( zcKK%l#`SC{z7k?s=VOrOa(rZ)LA5+lB`KDGey&#+!%BKlO3^qb!qAA~0+txq^1S&!^W$WrvnddG*lEwF@%c)}sh@n5{)(!|v zCj05D2-I(TIHN6V`xy>GfuaU)|C%Se&};3-iulZtm?0p+&jol-S_reL?!BTnL?nn- z0U+R5uQo8OG4=sMz)%A_T?+D!0jl1jt&7`zZUJBWvwIhMDJeSpuF+Ou*a5B1A>O{x z3HfKMB;(4k@g$XJ1PZ7HG*n-xNT?Bes{(pXWLbp~f&lHvaSnK(9GDmZAz2oQbGOD` zX<^OvH8iTQ-tgGPK(u*7Qr9h%CO<{u1Q&qdM&M)Jkw6O?pcz8_+pq42F~Dm(tgPF> zoh*gczf+=z29RvFd((#Cei$JOJcS#|uF)F{_=Qnl1*leGG-U>z2Z$|hyRGp++bXPm z70`JeD4~KjXdu>yR2ix8!3;qDx9RkySn-QYi8i#sD#!tXkw9SnZIwBSQ4C>#9-4Mj zeKD6KkoTyB1_5U6RGI2VhtiTWO}JG`q%%53K1^Dd&T@DJqcUdKcR#jI>Y7OE0{t4F z80#7jX}F)-fD%IjHQICy*f$t@Suj_Eyjb37p#|mg`e;+K%-c zACc4sS|9*ARanF=(5bD~Ax2w285_M9OL%{O4SKoO?oDykbuufOY;a0a!dS6{eHyEl6?X4{&)i%uH7SFm9&lW>u0*;mKCAOO= zcALfAW`ca-X=bBDBbt&5qtYh5IA;VV;w5%9O7lUqHrXOJaqG=-n~OYjc;3DOu5qlffu7{HUxK;w>U>L<>tpN>x&Y-;9{Tc zd$ut^gP%a_hFJSsVh%9&u2Egg1$2)VD`icDg1ol+iMGEOq&$|jyhV#u#kz-q^zqfQ zVHjCbB32DTjU!NV$GFHW#%&fi-;YyoBZAIlH}K68u^Tq1Oe_f-ag;v#6` zLW^g~>fnLJ@Q`9S#l|c}9h`Cs9#I_kNC6Aw0{9fbRukhzq1h<}Mt!0HBQPUkHA7Wl zB&Zzc55Z=;VyYtmidBH1WRL@5W?g~WvY}E8p2;tJk3|z(?~EfclGXqHZx&ECa9+y> z38yfgKKS%DDOKOB#EJ+Ocr?0IPDP}Fz4Pl;mIz+(G@SO~0@;jWox^3Vs$%V}aVAw* ze}%+1W+n#Y{SGeX0vl*s$PA^VfmH*_Axv542yKD}$lan?G*If>IF>b#$te1dn^8uG zhS3K@R^eH5zn9!f4|yUu8|`PW=ZYk6iD3G%7G6MOFQB#;)^_Tl-PDrf`9sI%hsHF^ zcB(*Q$g-_*tTq_nBZHx5;Gb9}y3?Q%jG5~%FYi3Uux=Qz=e*;n6CR$&Q1>fwz_6l- z>L;pJPnuc0k7icGm3+=hXG;K>7Fy(2UDTGH@z)1w=u>;$ zV#LD$P-HDvgQd}urO6V&wHQP<4$??35G#fW+Hi)^e=K4DX#Q~N;W_tPm5-13IoHSl z=%hZ0S+qpV$H2AD1I^dsqhk9$^_ABAhY=sai$s$8nEQUqIksXsZFJ#dgg)%C;IG0g zvN&Izk-9w`d$4GLJ4OnDLG+gD2w4T`tW-r{Y+^wBi@3aZtS;#wf3DmZ6(g5hAWv|Y zWb^t2`@-*W9MASBS}f_6od`$o&~GB^Np=fgB*>-;>ylq?1;E)Hy^8#rAisq3Ca}q1 zx5?75eDH&2roZVf{}iBznUPQbU^un-qRGa!s@*Leq&Q0W^QegM;Y(Qv;M@G#>ComW z|Ht!Jj-MsrRu65t$hJ5PguHzlp)`P-ryrqUz&F3f@4;J8>zD3Nx7=Up(iaZ%y-ODP zw?NcA;v8INecI7+zRbbCDMbMC9!TK0XWyr~B7^|g5YR<`71@dejcfo$Uo|@wW9xUP90jAk?K@dSAkLI> zXW~4E4Z2fC9+R@3NMId9S{y^#yKmnTL$$q6LrO?#jlPry8iLE+FBE(bMxBv3&dJ*4 zt{tZs2i5%@`9C{r44*RiKXKF287%Wyt?DrFIowcT zyF+#?@hf5s}G7jwH)Ur}wte=AKCf!k*lnVi{qp#q5OF&MU#~ z+wVV$-Zxhk0U!y;dI{*k84hH-S*to@mbL0ffFeG;N-~P3YR35px0;;wZ%uJ(I4P{* ztHC)qAaKrLQ6JDJ$gRtU?1yg`Zfj9E9}OTWZbXV}lLbF+bk6vKALqmk3VL*S_Fy;K z5d*0@Y->C0W%LaeM)#|sdEgRI=)*zDhifip!_jBoGMp+@;mBWTQEMVwvIE#HIteEW z@UaPE+fJRf3rLxPAsjR1(ykP|Nld&=K~(U+v?EKHJlyev{*@uieVXCpJLw!KOD}PU zZG}03x|MamRIR|Jg|^|guT}|4rJV3SDcZIn)&b${W8FO2e^U2R(Ygj`bPM#vtD1%^ z_)vX#JMH0zEBDraY=L-u@)W~K7;yS?Y-Eb83#p&(@|;MR+d|Q6-eRAtHHV202fHknvkC0grOmjUIFc%j)SFRf3e{-3=1h1GKfmcZMS3ZE;s@jx*cvd9sH(2 z3!0B>>21%)P(N}{jW>uCZvzo9&p!uWPQC`1ZxqRrUJ%LO5K8zCq`v;_hXlp>lBQh% zttA}7_)HuArbKbYD^ z)O-Kc}TizDp5xq{DD;QGG+I`yBzHIA${JfWz9)i5-^s=UX$(!0F1whR-ox-f=l}2>S_gl2 z6_(3DRLj`OOrQl4Yh&GS+8g_z3L^qRbA=K5Q4^9^5s+FF0HHBgoCGJztH<#7Z%AVZ zAc?W(K*i`FgUd`jrRy>fdtc5sQ&`#zDK&=7I-*c zXV*%)*=pEbYjgVj%g3e|lKbMmw-WfffkY;0|4HyKf zg{q~EnFMMZ(D%p-V>6_21Qw}sD$aZ<@R_JQ3b7^?45esc8+uIeW$&kP;a8JV6M_Lo zm%~POi-UG1%3qt@WoK1*H>B_0-Mo5458H!lQ9{m2*rgZ1E}Hbi8c)`xopdAxSY25_ z3$%u-ONVqQvY&@9!-s%6E~!HAt6U6@#~|ey;viinIEAwoeLZ*{C^$x(We6RPVzf0} z$K&#SYEY67UNnRsXZXF_Teb@bEiFxw=$LdN6U@E!iRaGB<{{&%qRC2@p7n}NkrR0e zo>o`_Td+1y6ny6oby9jKhF>>hFqWB*KRwAC1K&4-b}tf8W+qmav9^)Q;^iA zk*%FYff%!SCL~Uc?ao8guBztbwlr8jDeza^UJM-J%S_~KiZ9TblR;U=a_g}GO1?oP zuf5!=n^ua<-*m)*S=_6I1(kh{5b^631VK=pPe&M||H{o-8ju#cwflq)vMBc3SyMH@QS-kYk{r zzwD~M)|Bol@v97(jjtwlehZ|p%=YWefm5NDsuokht2qnM1ezCj4N5b6F>tDhsNE^~ zk4D!ik~yNh>b`dqFC*FBH>xBgiop949>j2yIaq5kjU%x_x3%Ub$o}HMM#`+`wQdWy zkIV$#=E~cnNIcQ`92GDMSCukq0X&f;g11m~mW#{|-_P>5A-{XkPt1+g(qSGa*YZ}3 z%n8rB;nN0YnV*$}Sz6Kzg~;>KU5W;PCs+~Aq`iLpOx^l8j$WF4KTB8Enksm;xkVhJ zQ`detVTrLc=9NSPt(4PIKg0Y{n|$p~iZ7U0@b5!%hk_c$o~j{nTt=sF@g6sCt#P|b zW3oi}o=R`z9`C!M!tfKV_G4c-EkmVAi;UwG_I6&n^yB%+=Aaa^pJ-9Hv-~`BqDX>4uD=8%a{bPfm}1~g z0e6bJml?}C^tnhccvz6GEO{P@YtDs{EBK3}Qe6OSM+$Eq3?4qmYYatHJxuXc!LUq1 zhb5E<<5d@(sln{TmYAjY5C1iuKBVjNCXkHj(WSA#Y|7Kb6$(qU8*2*&IUqv}l&)uY znv7qButK<3h9*Ip^eK3t(rD#)U=y9o(QS?5GHr^GXrG!Bn25LxiiIc;lG*4_vVNUS zupK1=&#dYQ=}MAm(bJGUO$Vj2eM$+U8KALHAnK0p#Vj3gk++9!$;I}olz`tLqa+2D zo)nwVH!Oe`&;YX11`;_96bMq>M;>^AVd*Ske7+yc^KI6w@i#v?jpdp>MZR3@$Dw;p ztUOw*O8AS!?-Dx>knjmZv!1s9s1wr#xK1uWO8z%bvYs^^OGpidkzG2od}4nuyb{#L^z35SInKwjlH^nT5(29k@W3iB)qHX9Dfh5EF$WOMDtfO4Ca=o-U_u$jLqWr&+vKt2LMt<_zTLb!Ut4|7g$JxGj%W5-D6Q<;_XG!ReIL9 zMPH-MUaCU)J?scDvAn+rRXgQ)SxZ2YjnIEjFs8NQYk7kY2_^~{@Z>GMSdmPUb+HS5 z7Ymjj1mo1f^Dupy%e`sI*$of_-1jBbtiLqJsr8~7+&eU1`BP$rd`rlkkYAp56zKi2JbBii#Yq7Lf!VrG2R?A`Bn8zDupfKjMdNo;%icM;(1?t@ z+m`6@DbTK+qdk^B@JSGtdE^y2(a&j3ByiKmxT?X6$7mr2q~R>mi)es2#eirsaRop) zR)gKBUm`ipk=8+^`K4k5XJYLDVYQZ0HsYS<21zbP$(~&aPArSiWWFF6{!JurpC*$G zkR0u!p+NbB(@?JxfXkUJ`SOJ*uzbcC2;cZ;vAe#~65Hwrm`Bhg`C7oz*nr9?VCalU z7}C$sfZ|Ek6ooSi@0s(unj97lh~=x&mapL3kl6}|1_aBeE16MMlf zyvB+mWII9)ZcqruqlE_1=1YW58YniSeo^fKg-L+gDn=C#c&9LPnFEW3ndmX2vsAYv zpMqGynu0Q#?46E9wZlF)Ys(KX*N_<&WD(C|KZz83VI5ksNeiFwVW8F=pAs*hoGCr2 z$-ml5#YjjG&3!4_M}5Y{m5dg$MpOQVDJCcP>vQ$?&B&@v$OrBIio%RgXwqh{iX-$C zXdLFAoBpaR8?41}R~6r@&{FWi$nf0(9vSZ_HEl2d*UxlBPIlDq1zwe3?5E>np=NWX zCn)Cch0!X&=x<=*qKHt-fxrB^@7Q5fzqy{>vfq17A>V{i8N}!hWBAP3l`IFK#hTGU zFSxyOg)IA}e`HM*4l#AYlh{#o1c|IyENtUDY(Pw#@ zj~msLIe{@#Oz|D{%fw=ojCj;W0V=&173)vL!L(xAmL~swV!i2;_-*q|Wne3)uNqIp zmy9)^%o89&OUMulIRj*T`v9_N3B1<5(t)^IBFQ5ji6T;^)KSo*GHDI|j`Ng5F_;nb z;VHhK`B9m?TZKmiz!0%2r*=0H7v`!ErX`2hW#{*RU)!?9(THt_!7eK&zjDcnfT5JgYttpj^)&Nd1cA8CeWlS3N(PV4N(3`fv zwRri`ZGBNCA9~4WHE0O>W#TPOqulgU-Bj8DD(U5_wUtUy15!7AoHsBhNIxHbhwBW* zb_0B6y>PH!Zt}St)>p!KF=UzvV?S}`Amis$f*`=|=0#XGg#PDXq9|}b%OZ@OKvPsj zYhehZIyn&0=&2H0t`fVP=Y|pOM6vb4OoTYu7W+iK27LR5WhRNhMku@GjEVO3wcoP= z@#*czVTnc9GnTu4iP~Z%yq0{jmMF!5(uIqQ4_5-z2yd({%csSUpJp1Jr1eEX;JG4D zHetkpN8o`$ZLECD>lZkHyaJ|jh)6IQ9Vln?xT4IdPk{6UrV#c4ud|^-Gax#urKU6} zrJ>0VL30yma*V~jL7=(M`k2YAcqxdu2sAm*2rGGxMZ+GnMP*7K^hp^CYX{UOS~^b_)f0o zotj9K?&JG6$;_5D%;_j*6$nNb5-VO6`w`wMm1rK1WxGM~X!O6ifiaUZ@!`>uh<}xP z$}oN>+?5NEE1(zqgJwe>C8fTIeM=}@FnK*R%qNq>LCRyv?`t9}9KSJn8inR>Tj7HA z3x*AlJ=#?mMQ59P=j4(OBm?5JwRGY|KmYE}BGBX|#)wa9ip}P!G23eQT zmBa%cM`*xuzbHIaz-C5z5ylj+!$=RKAtnUZYKl&dH2o%$Q6Od*7p`0OQQq^bd#@ES z4N$=kND}~{QD_cdl=bK!E5jj!N*^8cl%8}dnAWSfm!N)bs3`)57WRVE?Q?YBaU2TI z9fo{93_PV38ls+~Z9nPbKnO>>!I%_WWPG)hCPnH`{OVdNH-@#EdN6gI4x z|Nao_^m-iTv`;!D+NL=%ui2~eMFQE+64Vd9MK9sV0%-v6!^UNziWP&(MCb)ZLTX*2 zYZcX!mixBk*Pn|jXzA82LEF+i>V^Ic`{vhc;|c{o`;PFWn2ObU2%j%G3$QB}y^QDk z*On148Q1cw9?;&?xA{Xnl1-r-G$2~s%R;}^l`;Z!~f(Ol*!U(}$efObvrwn)$%{l=C z^pcVbbzlB1y|N@7l#tH;^1hQKy^|yZ62%L%ST(Vn2*ue?myf zxjy-{`0s1`UzV_vq_LAcLCR5J%3=tq7kg=ZQQ|6?zkx=kL3bFX(TmNG)sz4!E<^Tv z)c~cYO7SbG0MhG7rSCpu`93M^9yCT%LPkrzNlU#+D>8<3U8A`I#$0pB?0UoePEwE6 zUC+IbE(pd>ffi~@Q_6PYUJ<9flZ*^`WysX{nQAFF>;MY4V`rXj_4OEeyg8g)R(_EP)n@~L){F=MNXF}| zbaIUD*aK-7!l$omH>K6IS{8K*{iHUQ#vW&hYY9=@5z(vkQSk*4(rXaKfAbR5@Xl)S zstoapYays@dHm*^m$U}8WlgJpklvP@f1K4G8;ZkPQwR*0--Ip}2D$BuskLgUwgy?T z1U4ZjT>>!TF@4?dSCGN0Cf{YQ&%QcZVBWa&dvOILluhNr0w&)RLCXW3>KZ{UQeG`W zg*jTk{a^FP>)z;(q)<}7-x zLZTx-+b@hrLpX)m(1z^YphQNAxH_jevNbQUPlWum)RXoo7A_(V{LUM1k<#8-A+Elc z_)2I$BeaiFMg!p1OX$`Mx>ZQO`*(4t0V22yPp4MQyx*S5`y-txh6Qm7wr@H-kjt_9 z;g?1vJT^dS72>DqK*<^U-c7y`=xd} zgIo`+IXeWkna-p4Z6pX{p@zJEx&-3DAQ?L=Eaar-H|iF>Z{-*G8TMu?O74U?F#A=V z`j%XNB-glh#&uHLbt;I^({8QNZr#)2bPT%N(-|J#=A;d?!MA5dX4|WESM``J^d~kt zsVOm3Q?4uLPikNngEYut1uDr(lzz$E`1344DZ;2}dUpu#>9$T(>TuYTtWK4DmHS1L zPmTZFKy`=nsw>dh1T+U!Qhv(cd+_S@j>pQ6@wfpj;YbDAbqK>%3UpPTbtLu!MK2r} z)&Y6hAJmjFN8D?#4Zm3DM3brps$kdx{?cS9S7c?P>Ed7H2|7wFI{Rn7$RAvJBQ!6f zrxWZC?EP`n2o!Hr#1Y*31yh*Vi%A`>J?+NF9ZxTHL};wu>uC=HK*~u7o39v3OZWRr z@6x~8a;={(WHsw`fae=}XEk1Y{3e|DTty8iGs24@o)%a8&$!X3oDT>By<)p<{mBd! zrM~n59Zjc)mk*6JRTg%_?}1QGk@594M%vw;E52_$#8uD_D~$h41<>Wv3e?jIAl*9S zWdq}jC)Gu|)7Jw>cQhwC2RNCS@15Wm1!HjcUQL3iQmna!d3}`lc0-q|muX;p( zaaC`NRwwF|ey4GJ(FDm%?B#%!qQ7l@S|+h@K3OR39sk@a{(Hpqb=AI=P zB+!Bn_P0`;Pq>z6v|4S+sh;gM?K9iV{;aKmU)fhb_VSPin^1Sadn+b;&osuZ#lTO) zCDOd#Z`nTcd{uEx;I`nZ|DC>}oMYLw&cMMGOZ$bPW!2lkUnjUV^Koze!aWL(b6(-c+m!giC7L`<++G7|*=-t;MF6c{d=$R7g8~Va_(n z+o8j6wcP6Xv)oP1d!ojr=W67HetpKyR=`i^v0JZ4(C;4p{G7^n!OGMm-`}}6^w*c^ zqA%3-{`+ia*9Ic`F2{2JU>5tl*!MIdA{OLn4@{B;&^CC3R+tjYL3-w+v@AP*NM%85 zqAW)39m!Ss(gL6?+0Z~5DODbKSR=_^QEF80?=ZdH+A^{dS3l|%Gu|QqXVldd6HAvr z7f2^4#5c6x9&EwUmaagu?8XlD^M(bJO=S5c2gZ%0SN9M~o21fV+C=3q$>Q4T>Ted2?*gLc48k?b`M)rAg8{ip8y)r=PezA}L!Y?f zo2(4WsxLf^8msZCUKZ!$EOKvH=28)O#pSdTrXYAb?ohXt zf0o&JOk|zkAxbKo3P9Hu!$n4>W)UM6o$nw8NZ^Lld1TTbY< zE|(9#H{sSfOqEqQ&oy5Um)SQLmlA#>)zw(5`0upQy83UgY;mf6y6iGhym@7Nq{z+X zP!xs(tl5|vzM*hk`Z=?DW79-ye$MOK`Rb-Q3v0iXtt#&OI%x*WBg_ar6I;$Fp}H_{ z>zl$S7b}U2=W=@tUgxXZ#!cRsZRbo39L~9(e_y$_jDif3Y8v%Ws60`xr&krCx)f{r_fZ{Rs#6a zpbOte+{D$pLzJ9^2DjydVW+qf$ajpij<1b9!NHGA8od08cSa&!sg{;{dvM6$-EIl$IlHd#ZMLB4GO$wf9>QCd6v~8Qt|z%+El$u!v%) zQ$rW(l?nogjj@jB^4!o@n?zG}_#fN_pRLG9op|#pUW@Ak`q)y6^|R9nNscnE{OizbUN3(lBl#v|q)L;bdgIbUSq8Yj8rbl5?y;)*m9X`YDwT-p zNMd#=dvI6(8Gu3p{x^+#(nepUU>b>O`6N9lAj{Li?{E)2m8z1#;Ox^0)wxb$k5Dac`TfHeaH1 z8dPH+wWNmlyPbPvH$`+(RK7jv0&}9G6+H*yB=3p{Ic$unXshEU7ZpI%OohI zxM@$u2ks4j{x_QXX!z6f2s}tUQvuWxe(o2vvsF7+3E`VCS&`CuQ`udj4+v|>cP!qaXutX$rLaP?i}YDtKd zjuPJV>|*BFGH|pcdWqg$HkO-%4$FxvB-RJsj-UMI35gJO>~`1_xH2>d=bvUZHu->* z55+^UL;#Ql3jj*|Xh2ReaWUqIsQmm`X%Z5C8mXef4}bz*r$M2rGe}q)50#>mKnAM- zfImsBH~W>_95Z(%ZU{Tr8S8BDNpgTcrUk}aC7;kEX#UMnwHD*xQK-XiAF5NgmJQ-x zB7!0g;*vTuklXDtLXepF3P?+=M0N>VdTeXjt3vddi1XRnY>Jh1&oP7`iOGiY6$5s8 zDV{Fa^!N03pGJteWK+tsPB)<#Fr(x&!~~zKiVuF7139%J)W7Z~Yh7cqa^tUKdwHNg z8uv3rE)<$k?LTz70!;PZRDgDZNz6PrKj>ZBy`wd-l-qRfoX~_*u5^mZurtDcQJekK z(t3G>7mvs#0wY23gDzB^0$|2y|FG)pu4e_1m{{lwOa#DtZvW6e`6qjU)v+EC>nYxv zqI{Q;!!igwf?l0?jYQ@9sk)GOn&n~&g*YpJsYh4!-}SGW;CURJ z(TtRD@S9jjE**MBdxe>@!jr!1L)ZnA0Q(bQzVu!m|J{?cg|XLQSuCuWgk7Q_j%n6`^c}b^{ z6te^cXaWF*G@$k=sQcvJyUn|y&4Tj*Ld(TT7RVQVP9u(f&}lPK+GwkYMJKu zNl;bAbB38v6Z3P4Sky0^n4Yju$c#_R~%m9;2hY@bN}q*J@`DI)F#x9M45M|8mAI0>CY}1JA|6 zmWY^PktevRn^Ps6EKNd9)0n1!U7u9QpERaVf%1nlKNwdiBI@O5)4w3WOq}|7F5MDN z6DAJW=-Hfc8^uI8tyDlgUYW9k>?VPI03f$?{@YOYLkj%jmo+<+XRtqf{M^itCwlj!kTJX&8h{< zoIm@aP8`p_8^yCtM@f~i=h95D=dMdYyLJ60C2^S8}mO9il zMrGbt+!e%5zobBui0gMt3}cL+NW2leEG*Zguse2(iB(?cxD_vSSBQ0z`3Rz|-DIYi zfxSE_a$X^;1IP~!d_0w=Q$2j`B?YX^ImECs5#SewSCTkM@%#r02mQXnr9mPdv+xNL zA}tFsQ*|{g8}VpPBj&C_;$4GauB)Dbh;xnlC0T}|AJoK3)gC|NlIJkui`pDaECxGo zy`y3ZJz>0Jnin?UkDS%gfSgpROJ_^}DYje_iuFPFUp{UH$~bF12EdYt$P_01$_)N* z6@svA{Mow%R!ccn6!6T4)8POq?kFS`3nw}U4zE8Srg2aKrn(4(5+{goBSgFe(Lv!< z_u~Ht(DZCGdwiowTW`Pkzi8#nZROZ*8U4d*h=kN;+aPjVRwx+-Ot4vS zi$wh~G;U!_{bR!$wV5LPJc?ie32V> z>Ae`D!R!dHVaXCSDZuy@g^;X6Tv%jQ;_lc*l*^op;P3XIdZTLBht zbuF&{HqH0uIAeLEB>qOg>GMOYjev-4j%8CqlM^GrEH>EY=?%B5Jg$8G*9?@+@Ex{a zHf-Cu>Z`eVJw41wC>3v4pXw5K%_}^1KQ^qy%qQCAg-Kuv7FLOcAn(So-go=7;QGGf_A4Wu>fqv1ZjTqg?RbYg?(8E0C6d!L&H+3s z^oI-6e};jfX5Lzs-xucb7yw?Z&oP>@8vjs2{8nz2yc|b_vtUXp+YIb z&Y)j#W$vMI9+zj@E{h$0DpvK)3&Q_GLLECpukYV(>bR4)820quoj?1bd6xc=PIu%z zG}_vu<)RM8nr(r~G0b#wdN_6{FhV(q)p9|Q0(?Y=7n3+wT%MZzcavZpytjzA{ssENys!|}dFRP}vz$GZ>PWwWoY0&+_y2f^4J!9b7M)bOA~cqw zPlw>rdHowyUNNAH?x;>>j(Z+2c*hmX;T#`DS4srQV}bIEHuIf?x@$}_Sn!y3ph#Ze zIJ41=p4^lDo4-^NUk5}ebi{0hpl*r>zM`Q+n_Q`MsL>7x=bUtA-%O2(TpQ_kF*jNo zBdovVVjLR!*ZR(4e#$T9u-6A?C-Wm_yIf6G!#k}5><_T(SXdxaCrQ{hXxK$wF&>`7 z#7$u)kRUJVC_p5uYYC4BjrWW`?QKsUK~!w?gvPRZmTqd;!jU;Ntxs2kw^n;k=6; z>*wH%Okw;AlhDE5I&@hLspjL|jQP)W;UMjYI<{DY2r4E*{~56fQnTg{vzRD8iOYFn zjc|alI!7gECBU>i1@edlaiMd%EZ^%>z2D4)9+!9jy43i2$q;3yHhYklS`f90DP6_5 z3moNxR0=FqJ^mbo2bJ-!mC#dQrswXL1egXb9+sQgMXWAItg8vTWMCFb1ZSLi8tL!o zi{MZ!#EbegeDRGc-mj&krweEvl~XQzKhJQbFzB%QD^JYBi7W%!UF zp(L>S`eyfm4*5gDHgTDRa{H*>!hKAs>W-qV#PQmP1%*{R@?h!;hByuB$1o?$|a_n0S1=>e@ zde^&MB@J4yo0?LI=yCk#eJoqNc2y7&T1n;Z#|yYYI0W@j`ZO*gjoU^RzJt7Vaf^Zy zq)Fa?o~J?MJCWe+R?rjRd6mIqh36qKJ%~nOYJ0-fj(Am>CpWNz49p4AsHfNLq+gHr!*|n~M z-WValu^i3Os^SBwe(gv2Oo%W{u^bUdvs-5A33$eq$)sddl5c!6Xz}1pPUuj2;3m&e zD2M17f^$yaYt}|$j{r!ptYm<+?Y-2<| z`a16dHnN1$qL1M2pv8mL!7u4BTnYcUus}%NAAOqzflD(CWbcft(8}4j*NQLI3;kWL z6I!h+p7}e*k%`|Xm6$GTqv!z4aLK&{+IprZ@`xxn7s#5INLIZ_&LaxEln#?(;)nQMajBW`848}K@VrF6Fn<&cGvdwngvMutXKSRu6lIwdtMsn;Vh_Y*Kix%eT-QCLwC;oD6X$Zhab>pN8YS#=pWz&+&PG z)&5Q7zg+>Y_mYoy(jWN0r=q*7dCJ)&r@kx1uuSQ$SAU3c-Su1M>-&1?^2Uot-)NV2 zmS65%*ZO$%>52to!|4GqNLJmS07BV$AahH3quXuLCVU%tHEWoI0$ zW;k^|+%xWrx#)(f_Qc$;l6)YV@Ss|t?X)3YqO9ch-ZBLg&_w1uTwtasl zBYqFP|26+~Wk^Pw4iNQm_7(yj50s~5(oUCyaKIHdL1h*=zh(liOWV- zCYUFKs@3dP6rQQjMJif8-}N?+H8<98@M-n2h_P!3bhm30D^?G-68p*{=hqeRxyySX z4!P7BlHWbD%&#nO9e?Kd=r3HgnV5jpyHc^j-87>ZZA6O<>NKmec^3HXsQp%M4L!c87lSSnkjjT2vSkXvuBrby7Cg4B z`Bblk!}4OQK((qTk39bS;%qL7*|hNKNc1Wde4!@sB+)Q2$0)5fRl%#=*^b7j_~~rM%R@(U>mm$PIDZ zn>2N2x)cY5uNrB#44|TW6$bP9Q~bwfBFkwnMT1USM|Lt1pT^l|HJ=Tu^$6CF9?h6= z^rY{@gC?&G6kM3O`m{c9*1&}tG^HW!7c^k$^dNZna(u7Sg5xdOparX2f=bhRi!%F- z7U>T|!X-42_lTJMhd(CPR$j=z3;XzHe?h;>F>prfSSV;I>b$Ya_=Ep0HNA^`DRgh+ zj5jv>{r&6r)s{$QFFIDzf?hnI3qhH7Z9Wda%s6UH%=`EJGsfvmyA|2kG+dv*KJDm3 zHKPs!()OY*No;g|U;f#2&+5GEhZ!1IVmtml z6a7@}@Z-H7FMdrwO}|X8s}g#2G$TJL_50M&diXD^Pm8Pk_j#!HQK}b-IXe>o^m;k| z_eYpvofC7cRUhNek4WT>(|;%TXcV(4H=c1K(>h7(Z{k$Q$uWiXdO|-}t$(b{|1`*; z0~jd-HX%$2QnvLH-?o3e=1vJJ0y>D5OOI2LDb)>>IBjYMB%1h^a=IJniW;#eUav3Z zZb}%EIl?8G%ZPBdLx*um0V!@VCdi)6Ar3}vK&r2AnSkYpo>Ce)Ff=P#=tsgU&Fz5n z2Rmh_a_NXRERY-{Q!b239MP2u%t-Mq$4*MTVxLI$xl>;*CcmX`psyH?-6DlKuP0E%t5)H$C`P=fr?5QDGs? zF|zf}sN|(VsgRZwzk1iR@Z}Mskk;&mdUyHc<#C^oXT{&@J+~YLOR+S8vO1gudZ!}boPF0xDx?iqr>iX4aznKq$jU!NZorr?$;Rf z6#jP8=wA0+Lt}7L^4lGsdp&E2Z;ki*;O};mRH~Vn{x=ZscnZW%005^zHiPwl1KI1@ z@yP!_kUjGuJM(`7**nmH{|98BpUArWzk%!|^ccr^lm823TSl9vaj6CVUm&~kuKBqU zREt-iexjlnY@q%2?Dhi#>+ia)_?_(vn9BG5_He%|dvrU z^8jNBkBAefqT5KO1OdYgs#|K^D)n34uc$jZ%XOY~y{ebv$SF+_cuC&YTwvX+DRgq| z%*(7l+tMRtssYTOM$pxRX8MvY(c|T84p7B{@8ssO-77{|AqSQ zo#Pdl6D%M3^375BOa`j2&-i1Ux7ZX)bGLapSdZ&-UW8EOJp%gbZ)Nm7OErbl(7%-h z>otKaUydvmVi(Y{cB@85Kpu0KxN$yeKZ_C{R^J~cf9ZV5 z%x0?GTysn{pT--zAsO>{(QROc~tPm@HvzHSt~ar(JO9b{>D_*uTR16P0P$|FdzjpjkmecXp7`@gXKoh{a6N#NafQjFqstb4dkp zeP`GzKlEX}x5(ByDz8&o*u|H?!R+)mH#7r!CgTy`$<>+}9iqJcA`KR@OHX zdsfE~wKekU^6dcml`$*ND|3AsA~7ije3k{poE_Ad6mO;rHtfh6G~|(6`or;aB8*LL zJX`B!-!eBli7*fwep-p?IL%Yg@|9e|PpsW*m)ugys7c^Y3B4s}9nFFUH2!OjH;Zvt zp+&BQotU3m=mJ*<-3X(6E|PV6O&4Qrto3e2;`yBWOU*<|LzlPeK-*1$A(6Ugp}P=5 zm+N1j_R+X=TmIav{T#KUuWo%%%;Q*h|HZ$^P?*v*E3__{dw1Ze>)$>bdx!Q~l{fRb z$P{Pc{y8J%dy*p#-zyXRIIl}GVusQrWFzi#aaey=yWp9NEN#~H!jnatx)8!io^_Kt zX8dNkGDbx#C2Xd#`3(+H8M0enZ3z-ZQbgInMXxd-=1%uO;O2 zS1!X=J?6drh`Y=ual9tS(!B%Qpr21g{9<6#pVly& z{SOlNM8>{m7B?>^CIot{yq$B`X~irx4t9LJHZmJ$zxJzR(0Pm<8pPZG&LL2`*--+g zI<%ef{LBXYS)hC3qc_^5Fl z`eGBGnr4;+(USJQ+%?fJ&^7+jMI}pPgJjw67}2(Tzjv7dr6chbUD^9&uJyS)(;7-~ z=($3j{hb>%upEhX3*nu&Z*CVm=swDkW#}tSKvC7JWHzUr`?$Eo0pBh=yU#g;&Zddr zt$gCX`2lvhEz5!`A*X!-8uaJVydr#UiLJBQ^Zc1-Ccek!>h61C{;l0IyHg%}{cULUw9f{8|;>KO7z1O;fR^ zyq!0947-Wz>BOLX?0~nA_+C8QqVf=!5InE^;7=aMq8@wQ7avwt&PiT;P-$q`K1sHP$4%ET zWIvSW;Ld=uZ-k0w*sQ(aQY88OgOt7SO>37da~7nlfs|Ji`JVJYUbFrT;MR>O#SwM| z%$bX!*Mc&Eqn*)`)6thhZ;obzx;$fa6WB$s%4&@m;>=l$4`Qy3aF{^PnjPriGJ#LC zVyz|Eq19-j4Y#|OhVVxge$_bVrMT4~p0cpYWX zmP$fQSG+V{k>r)29^jR<$q~bt@nMd1{?`&4EoKf{Opq_Z4n`$9Mk=fhC(1ZW_N?O6JNn5b=GN><$&$C3)^e~&im(wY% zTjr9*@J|zx6kVkt8QO@4&F(6!;=HV2gJsb7uI!#q?1k*0DbF0$f}GY21V;(-Jq~dT z=Noq;Th2L0ah=SJ&oxZU4HokZ3gNgImSw}5mzwcE5+i#H@*MzihZ4tJz@B5s@qm>R zb(p8@o$IK5-+Rjp{L^Jz30+W=Z{3;$#0ynMAID&KC~; z5Y_cxVRg+p2R_8CCB&W1p2x>Qea_LMhK8vroh>bzQG47~6KYhQN892K^k#Q&#&Q)D zv*XEPjFw_4_994F)@7c@bI+g5^06!?KF(`HkCPt@J0n2r`HW`dB}ue>4f1#yxweZ0 zMrK0`9!VQMfeSwoiKIw4Kl!pHTR?llkyNBce=?rW*&k$-@BuMCRr2dO;+HLY-|#8d z9%71sp4mmcqZFQup7N{6_vkX_BUB((p39r!P5>hc(J&Z?hED-(oq{?7k(EpI?XZTJ zRMqM18BP}8UDSDgB!gUf{s=LNMNbgWQ~ssrYT3!!@WYy?D+J^$q0++$IYCF1`h%1+s~h9Oo47{SKsunPJlg)0~$SNa9yw` zvi4EnK;fDmI=pWeH9$lRHzO)3&@2LL{!|4l(wRsKm;KEpuMA(KJnh55tFf@hQ>>}G zsOTw3I1U<4I2A#`?i5H4m9>!o3nze$jMy)&u;1;b+_NLwl2kfNfXdXW%YbT9(v^iV zp#CljvIT||fY-LcNn_~3$Y7^tNNzK%0>>KB4B0tCMF61DIB47yG=GY<6bH-4K~n*& z;mx40tx0j{W~Mr5G>Mf;MKAl8Hd9&e10eppDF0pX9W2^i&DVDx)V7O!4M4VQ!+W&h z?Yr<(7j%?}m_#GT>2NaP^kCLWZRGH2^etXByn^OnByx_9nWz*(9$=wMneMjF`Zc(sto3SY(fXo*o~9(+nuy_87rl%DkTcnv58vqUW*bcXVVQ0gfF7`%>$4 z_?*vs*c;Pfle?Wu&B$d!U{De6+ptkGf_(urnuLx#M%ms+A3WE~t3?mu`dAbYzcdiQ zl1>O7G1dHhjgDkYy|5kyyElWO1=gQRvhAsezFqh{0XYLe&SH^sSY$!Z=^J=HI08C(iLexxI)6sR=;lDms|Ph@+03dEw3oHEE$DRzzkqhXOGG)TR+Ola>V zbIZ$opU&t%F9TV-JT(yoM<^Pl4^+}=Uw{NUvs#eI6-K@vTOqG0@E+ojbuaSm6!PEb ziwOn}Ue*lqM_$JoXoh{;iFA zM1{E0LArGfOVBTZ8G*%~0NH~0c!aS; zW05U5=u;AFE{Qdt)YQ|AT%(+xJnZ2vsJr?3GJ(|?-N+??iQfh@u;9lhY&gL&c^Py~ z@$}#3>6!=V$`jNdZB!tAtogx{BDL3(pVN}G5j6kiJ{**!4c{cPePR&VX6Z2IlF1}M zW-|`?)E@*g(fKCLQAdZV{?$6=dKps?NC_m*0aihT=?lSIaqwqTEkeied>kmtADv5{ zEjdDMrM$YN25$@~%TQsdAR{ZuAQnj_iDqVg3Y6(m<^2=zG+=6l%IYi0kyp>FbAs|F zu`KM4DxRPOQkN*4D71DeHnkdsq02R+TLyC^Cd{+tA> zrn2S|S*wYNS!xa<0CyGlW`#WA(om}U5CkrK6wcV8lF6Vu1gb4yMPds2j*N6rVpQhbygek-HUaQILu8$d?KzvThhla zAm_A^km(mo*a`+3UZGv{jL=cx&r*zgx@ucltKwUYrL0VCtW3RVdI5rLRT2QK)Jsq^ zD%gV$q_7M8;y85uCM$u&I^8_9L}mS@`~HvLd-jQft1a(20!H1*kS2e`qBdIyTkrjs zUmm>s@`$Z>gMxU21)pnJK0~uQW@PZ{?ShHTGY7`4S(KH+W7JwR+z|k|r`F<61(S%S zNhH?P8urPlm6urb2M6@tYr~~ocqI{b+F5!@hI=@|MsYC4E;97NTV~<6tQl6ujqgmq zKV7FHZykY?>dIQN$O#%8 z)X}D<-R>JDusTt}Lk?SMC*@dHNcb*l6o(upBdlxLna2^I>@A9pQPDly6?E90V|Ys= z{Lf0x`0fTsnEHZoQ>vQ$jy92Vx2C}t3%Sz_j;13d;FE(#1xjR~#4hW4^YbOj>DlkS z#z7_gSvDS_4}`woxWo1NGW+P)hTDWy>*YW8^iv=k?2H4SiZ-sK_s(c=f)Ds65$ykC z|Mm}%8)3#Tt@z*eMbOU$o z9;s}Kb{K!o0L*t2Yoz+%?G$)1@vH1@_CxDm)OQ;vHKjStp!?XiaRLKc5phZLhQ2KLz6j|4vUrMsNMKPyahw z2ijts0dG}-))*k*_1#b{A!uJ$oHio;-+ySWE{?t}78=+d-D!K&DIomInFA2SN@38S z0`}4cI&ZHvTMq31a8mZ6Is82a?JdeX_1xX+cT2+HJXg3Lu^cKGk4TG^)&I=BwrZ5l z=7 z^NL&-9fv%=>bqPn?_Xv z-}~0;=9Ay#_3rhf#LQ1)eTQP#N^gwLl>O)TR{f7;bgtKv438YSa`j!ffKO-%*Bx}N z2U#*(O17Zt^YI6n=GGNlJ)4T4uXHT*I9~T{t@-PEF3WS$dYvn!b%WI1{^az|e*quM zlrH~_N{I*&G^^tr6$yY##6dqK$d6&p<tSAPdEe>)}k}xauHk4n&u@P3=RAKc7%=Q ztNg=xXnX4~UzwI$7%7btBs9kqy{=srJsrt#9lpXS+s^lI?Kld7wJi;ArYBE_4`2<>9T=cn#6%U4d#%w|MS5h-Gr!{~F!Q=h4GX6+ZmXOt&*_Xi zmj!{wLYB>?3&&wdA7}+;QHkQbjt?Y%@Deru4wXh&8GgR_-<5uG%LBWLBL>Xo*KE2~ zPPHvC%bgM_&TraExC_T6CD6bwoh9IBm%0fXd^4HLA8p%BblK}=>OLLY`99xP-Q~Q1 zC?nFY?}#LcCXrl{<^KUH+a-=0G6kF}H+|_cw58~LpMIHd{;`in|7#)6q{#5OgdD~f zr0T^Bb!mh}lQ6!yYHxWx%ALpfJn|K|g?-!BlZpr zX&R*8$e}dH%G!f3wMV~|yqzTZD8YHjsLQ*D|57C; zW~~_C$!)TJTk0t3Ggp^3*r(C%?7G#?IU7u$CEDN3XqvZ`9wV&E#6Y+&>1=RuRLE`O z`SV)@KQB?ValOL4bCh8cCZx+&HwH6o0JeBif-XMM;eYaVn8kTf0KftOh#$nMFHEO} zbd?DiyNPfvD(D5@m`*bCy^4E8jEbNTLGs!(c&js;FXjsGazfmNCrqi8Xy7&K(!28> zEd%>E+#fiRq7HW!L5?Rn52X*|l~=AxU$g?ApESt5(c#a+zli|lEDb9WyTJSi7wu~` z_FQZ>xyT$h*i#mFi9egQgj|knk7Nqk^10F4X_;Ni{|es%Hr~nLHiw0s{>93S{&CqU z?m6->shBAB~R!z?Y(_ao~0h`!>&l8h@6mBx_Jlcls2&duq&@*B_d zZ(FoW-i-{lu}Hvr{}CTI5cQoT>)d#Wixp&XXHB1rQ!2-wTyHKyM+_jz>AaPD`lIUna6i)8=&u(;Jb#(EkUKfVjn;Nzesf^a|P%!FUBJ&yIfZ$u) z)ff^U>DjEnS1YQ&AL5*}crKd%4*xsj4m>$^z65TMN&LHWAy)pNRA6=FIu>#$PPF?S zPo%sT3DyUmrw}=o$g5hVL}p{T6q0C$d#(e2ZW=e!xpyy^-$kk4{5cU1(Hk)rDt2qD zP|opNJ>~YSs;RO!uJ98x*Yg)LL0;1?uK3?z0j*5wHz!QoJ>)k^&C^dKVm_Yz1obyC zaZi~UZ*_WO?HYcTIkpB*#a{ODCBvERj_xF1@Gi(IFB9R~#g2J75-S;nUx`)) za?h>DNV+hc(LOb0#3Z9{3m>H4@fR(X=KGGPaw*@?Wx@$Qq)p5zC;FVE@ewGE{ZBGd z)bp`0Mm{WY@K#Qq)hB3r+;4W%@>#K%yxu(VrhDTeV$3lL zq|wK*!m}8!NGr(+9k@;QhqL(ykaJum2}WK099h+|FCQ#*_=dg`fbm^b0XI0!O1S06 zD$HNCk@Xz`i1I$e1j+o1gk_t>LX_wtU>p`^_Mo4Ow`5386O`gi$HkBC3SFq&Lk5*! zXubTz<>jviw($jO@>P<)+Jey?hL?8ZNNg8o+pzlyzRbQ$4H**~rN415UWcys!*M!6UUeN3_D)BJYdT(?0Fp`m_iCo#kw6u% zGi!CR`jRcXWvPaKRz*Z;^r}ntWdpDWAkNMotaqU9x)fImh{F`gzcEX&ovKK;fz|r= z$mAz+Fr~`yN{TzBA@6@|8S}ZcU?H+Nt0EQ{ zZ>Pq)gYdo9gC=88OAp^C$+H+cB*e-y& zeNw#=_%n>+oXN3l772X7ME&X*bAOPvL7d;gb52R5*Aiw1Q1mT1E`rd%SOPmgmnY)@ zW?bZtyJZiuz+SfQV#`yAH6+EJ6|IuzYMmDy2tJ5ETU2UGkHmYisFI>YNz9p?T-zGV z=kud(*09_lgY3EtZ2eF31z_e^p!GpR&a+E5rlMEJBKez72}mYa4CKy1TtIc4prTxc zImW9wN16!4ZAP8N4(;8Fku`~P)Q)vHr6EIsncP*h4ul+hN@v&&7w0E&HZ6m zF+pwZEm%6P1@7+kyA^~lqq7jkN`sh=MHD=5P zY*!OUl!*4!Y=3h%mhDCYYMi&OOIFuDT7?+x$P!~i0pIbz5St%ov-Cd(F$3QmW9lF4 zAPg=UWQmYT4AgAP4`d!jOql0`TtW?!Md0tlI?`?8JgeiJ(6JHKEU_dOV?vC>$7Wg? z%;F&4ffN^$p8%1GHC&1wcLTDpKbQ9J`J5cZONx&0mkDT9d0;%M=l~ht1{x<6SVF57qPQuL^?v~R*0>yc`)YNksUBHbn8eaWE1lqmiK zW+GHPIa9!e6z%jpNq95sF`h|}1oj98`_kj?kRV|Paoz_Y69UV5A~~T3WUC!(cEDm% z&7!viRHM8(6j76yGA~jbm-CB~2h9$Sr;1QU??;XgsOe98*D$zFqBG4B483BsLV@(T z=r?XagF(^B>e#bGan9A(o*hH(48|NELA?QS=D3)M>RFYgs24WT|4vda*_;MiV8d=r zm;9I^rs(Vb;5x2^R_2%qdvNO!)LJ4|;#17^rS=F6i%9~g;wLo%-QWI8`*{Y~kxb?d zZ<9Qw=e@M9N@9)=A?L}B=_H``0Zxy^VzOkASjRTQ3MTq<$PI$6MIF9~>{-9v?=I5A_!bHGl*y#Tk*Jc&nK>DIC6-Coacv zmNr0x6UgaT@?;O>LYNmExxgtA?WTRj{xL|Omc$UjEfwl8=@3Uit8u~kkWep3FtL>q z$)Xk;#n#hejt2c7w(cvcsqKp&eR_Z-5PE1DdWX=9C<&oALob4cA_9UGK|v7$flvet zJs>Dunh>gpEujgB96(SIP>Og!Q4z~QMe@(@-f_ph5BDMOJ7cf4voqJ6pRWQm{d5U+ zD(mq{Igvo((6AbX22g@#xF6ZLqj2# zS3SGX%E5pBhpWmYslC2pOOvHXa7zMI2HUJ>xCCsw1#xHse;A@YUZEL)cpb~3yuED~ zPPCmFT&a!cQRXPTy5tYPVw$5m?IpZG zH7ZcxH0{CM7@#9rBGkL7*e3A9KcJh}hdr{65{h7M-a@#sLfNL&sOzb@27^ZxkHpho zT{`O(Psxm}ruputTLT>M42Z3*gafwRya{YoAaIxiQeiIsv2v`ureAeUzg$l0HuUxF z`5dGw*mways zYw)F|bO!7U1!~0@-)?;yfGUfW$?Od6W zl=M53M-_ng%^B(Dth*X2AQLQ%Ss-=42IjIQ`azR=lrn*#-08nRw!TJ--+z-5o#~bD ze>p2Np7GjW1=`sLW<)@2L(>V~Cr}grs4~wSJUXL{4LQu{QQ2B7g0&THD`6w*Vha+U@tIs2Kf9r~bYP@t=kzKOiRpd@`~!qYb^* z3t%BE8X5aqU6HX^44qsZBIo3ql0puzoUkPJJfb&nTp2VSwoLF~x)F{H_kqXyZXGS% zmZOF08D`R}l^=Pm|4U;w5ifETd!M94skpD@&Je%3E~|spQvsaAH8`4IBBJhgukj$*vE8W@6_nj4Dq*qtvF7sr1EYK7j z)uZt6zP`*eI9j52?UhF|jrhAs?~2L089$8Yuw$S=Oiy}|g>p=`eTHl}MeAm{TVZSJ zQA)bs7R!91CAo*V7wLuLEE>l%i2XI%1O%JaiXfj3r0Y-l8C)XCb-vLF+DGz4)VPU~hwecAE1sq?BW=?mqa0y`6**n#q z9B3zW#2DN@Z1e9~TNYCz4F^j10nip(@c9iTaVn7~Jb8XKwuxU3jh76M%z_2kX4s;s z@|03#JP=5xa8~~P`{qBu8_qQtPx9K^zi*8W*Ute2cPTg?Fm^maR_-%Bz{dGzwuw6_ z5|??2tC*esHFqW^Ci$D!A&-xed{*%fuRm~n)04yDuUd&(;Q-!!^U`1Dr4fvbI>~0^ zFkXUC{W_2*V&m|yy3uEe`uHs|T}zu?S;9pj`3h=iC;5J?IBzoI-%fIW%5uM8kk}`Q zp2!u$_F?1CH}5f49>y#+YAzW@%rkYUhItsB>?acjevHp5vvD6vbt6B-$;>smEcKpx zH6`PD*}ZlBTgl`b)3#5Ok*%JQl9u7&t<5Wj;ja1-;q!+}*`F@-MR4}sY?kggl^L8$ zK=KZbd$(~Smk$Gm?mKl3B)D_zG6wYhXR@6oXuXmG{#{OS&Ib;pYRdMDJJ6;J{s2PS zLbF?IzCWHtH4Pl2FK+!Y+Fc#Y6xMzm^Sn%hw1DjDaqu;X|F}MK5#B4qzWcH3!Jo3; zKjsOa-_@Ldh+4lFmhxt9rrU=9W{ST?SnJP|ny)i2{^#~b*+~rhV&R^r?@vK}5@Ex* zh~$EZRB*B4Sni*)mL%x&(>4-BT#f&&QM|6MtSOvlxNs0s>hq$hU(7(QMFpilV_WB> z*;^enMM6oIxVt+48goDE8fl>5b$an)$+55XLwVU^HKAt=7K_vDuf!9=$fu3My3d|o z(EvXc<3u56$BsBegOEyjYb8$Eud9Rn-8tm4dGin0UXio!qr1;$pSSxqsXIDXIH}uL z%smv53a$=?N!ZexYK1gR!|HMk?YW_QC$Ln^gCAnFn3^0@wdTP`>`_q)qYz=R8QLpD zUpU?)dR8FyT!8tEJj;WPkJHHz(q;jO2)%V|ip2Bey!j&LiGULk9jqrwhj}-OZ3ld$893 zSVK5py$F|Gs?QqHKj!#$;Yj|rMEN%-)28ZLZ5LDBcVC_W5N0JF#P*y#$-ccC=TI2MecompR@YO|K#gq5#G?>$qC^$Qp}!ud5+ z!=rJ3czr@6T!)*PHz?Y;m98kF!-L0>1WU)#mEC8q`y=H=T>)%Zn^G_8!Y3nP25X)N zWFdHZ6?_!K=9$9Mbdtg&wUPo}zYgKc?BB4qPaV4yk})*lXX%O1gLhzEOZ^?Wd1I7e z?Mp71+SBl$q0Tq@A~8D3ze6ta#*Qkqdx&J=Lyha7joot;Z=X9}Csj+abV}QodXXJN zl$5l|7@axhWedTuh2P|7!I=%x+P1GdGqq@6A6{aCWgdsm66I)lk&HC4#UjkwPu&i? z-xChx7Aup&PMUgL4Z^00!1H_eM!;5@uuB3#>fS3z%n=8%+PDAxrsYa zGR_9mw8(Op7x>J$-5!}H@A?~%fOD(w6a=u=h1j`$E5%h3%nGm}ewA_3C--8finELH z3wyL)SHD$`?U=>jufXjE<57MfQ8Gk-*wH$$dn965K4K2-6tbR|5~m=&f`_Y-3B|#V zh#QITW^VjedGS~$3bRMTm~Ca-rm4hAH8HFlq&-jC?~Q0jZ-KCuUj+=gQxR7CM6F9M zh#;Ii<_Qm0=awMqW@4TE+XX-GJ(|QrgW|ZgtbEg!PK5I^hk%d|1;G1W_O1z zk(+_Rw$^6@gfpq;dck`At-@er+3L?St)w+RpM4N!flehXOiA&7w6=R8EAearr6;7C z8A*h%O_v8rzqhq9q62e|eP2TaJyflIp)UGM6kyRx3x)FPECFDlA2K z^W-s&O?R!DO86s|vyA!A$`dND55zL0!zK&)@PXn{wToE5v3Ic zHGALgdAeNbzn@+|_o$bCjDa$acAZ59tV?X+=~fS+qlmLxvf*N{jC%;k%B(;!Q7xY4 zz_eS8q#@~X9+*pMj1fY3;LO`idFp>EFUtPPNqp<)lO1=JOB_F?_3yUj*j}vQmAj7f zirhj^ZpbH($pcLJIR8 zw>=o(PdjPfr` zE_ZIkB6H|EmC7d+Cp zMAC_?`LbC@ws|Y>c|$51IOQL#{BRLOW89D&A;5O}jV)pLmW%k)5)tu1hyjk8!r(qw zKwP&}mpo*9mzvN&u!2~E{OgS7-Fba7NYJkik6%Pxaz;y839g8l36tmFbf8bcjxu4wVc^l1!# z)wDDr5jBw@DMz+g8@sUAX-Q+g8Gz->sDeRH0oxg!%?ouJOA>Sf#2Ksmc>3ktrS%Ac zOxB>*m|*ay=Wj_?W?4%=xsWYmPz68Oys&Q00+M%9jnctRq3#B@RBo>n1;a0S2*RjX zcnA`8%{UM}1+Wfe$Q(edi5CRBDZm0{Da^Rkn>K(#95f$3kxbmHRXr9}sguB$cw! z5AmoripE?<5YyMu5R$G5z4?4lfs*>N1SoB`X!Lr${l{zRbOz`*jk%%-s*r)(KIfv^ zU4Ow6#lQfix_|*vzyy1s{3u4>0@t5w#v0PM7#<|c-;5jL($J?S&JIKt%BgUyd_2Lp z=^)+JB3Z!TQ9#-WRg&s~9S$F?kDu@cBt8ho0xl#0anWz)I$?Bk3_1W#(I0R6gdfKkOX!fg9HW82+_;RWW^NdCVHABP|eav8X8$1HY8tiC; zG}~RV9tNXPM-1t2k30k>NpF~svBkVWL7ViddZMvA^-((5kO{<~Wi-ZFyxj9Lm6> zw%E$SqWW80AUaJQlP0TTaTEd+;4<+CM0gwpd;sQF>hEd+0G0shEqT2IULC-Y))w~~ zK+;?nnK2l+!`tF9q!L}VJ{>6bovm2GSx=mHB7S;f+&?Iah0mn21s(zfs<*B!SY01| zmrz4BLQ@sDfcbaXc_CF+TcO6Y4S@WdMIARD8R5C__&fCkiPfz_T3b`Z$_fEOzP}`- z0mPC)gzBLnsB>w>n2`eYh;f9`N(5O`5a$?VI#+6F`6>u9RQQNZ9EMBBopD}(`|hyK zBY;@Eg=)WrX0gMU<3wCK%i0(KApuHuhK+DwC5@ralW#J}Egu@nKlOYR(IDtDh$g3p zn~w0z#nU{pyiAhjl^K*oEeiPE2kYq%=4kxtArZjyxgEp;9Z>J8u|Sn~VgLXj10XeK zf!i6>_R}IAfN&2RwaFX{jZo?jCT~&J;7uW=2dP{dcAcZpqFOwt9|528E;E@Pj76@f zK?z96jz+?e^S=Fc!*uQ;r$*0n5eh-3|7O0RX8yXyw|2I~Lqdljflr069zRj5F!94R z3YLop*OLCbr2SuP2gDYDwgqC+2?056zemvol`rB4V3CLHBY2R$`|zdj8iuCGU-LWW z`ca$^pdoG&Uds(O82o1}O@nMfp5G!q1kQed1d)dn7@#_#VOiQ{%_R_wr#;G;rOnMz za3`v^v5rO$4a%%F_*yoe7&e+_nH%GIyg~ZkZ61F26FsEntfuQde4kpHrdcqKu%*gJFKb9KQjaF2icbOoAo5=FhO2hGos{a4F@pOB(ETkzHVb$pI#qgj z53?MhnG*jxDFRvxs^h2X#ZmQ1L$`Lc$9#t+cT%^ii?kW~#uj_T9wD{rn(sSgRfZ#F z#ec=Al_;Fa%WzPJu+24qO2zVgZ*i9C4mQ_@jtPIZ!o?AyzP6k803$d*Lxdq>DMe>9 z?b`zZ6wUdUf+6IYTI0qgSCEC`^sK_NKV%}tsQ39aNKDDnW+!LqsD6oqI2*A5$Vny| zV7yh`)3kVajBKgW=^I7Q`}|;;Mkd+-NdrKBsyx*m!(?B&PI$TPjmZK^)u%?@NzHE{ zNPd4Sm79v0#xT+hlFD*4a6>qi2=O@}*3Z`h;=O{I8HnF)N*o3{?>i+T4!(2=T&?Gr`6*5_cBupYh>`&t2_%YpUOFtph}} zvd;{YsRpny)eQNB@E3teb4}ap3pRhOBR?*@e8kp6zFsNiP`Q$*n_!jOBLJ$JmGsHT zaE>67n--KnJQ}>&T#o_>LGngoT~mU->2_!;efd_H_-X{Mp&Xyo@he8;W&X*1shvSx z2$7pN$jVR`zzzB`r?^yNAb$s90?5| z!P~+R;`KTg%y&S{?fzx7_+!tLyyrWtaVDJv7L$q~s4jR;g^smaOsS=^(ZhJ;Ly9(T z+{hR#b2BYIl4>-)rKuMdDSlUzmdLoMbdF}yq`Yxe_$d?oGym;+HH50Okf;X-8&y~6 zBS9Fmw!Ac7Tw75bPw>p~2Qkt?zYF;w#z2BGhakudxBIc$ln%Lb^-A{;nskG2AhU-= zB^-?ys(u79Wemm^msX0g?{1j>xHhE6LsP|Im|xgWe_nljCaK$D>E_9ON%vzqjI`cy zATHuh?A2ra!s+7*)JHTZE&@pQA@>yJj0o635Af{-wutnHl~Q}r3c%waGpNup2H%f? zM+C9CG>dmg(|3d7ZBpUlK-5D#lIw1V4jI`F%@kW0nbAtT%%)S0FBoZa63x_h%cLPk z@7;X3S8H}Plxnf;WP%wKYr|R&n>}gG1CsD44YsHyTWCKmy3qa~j@iP~>Bo1jP741G z`$#ZBnuR9yY$vk?<^ZTR)`ws!?*$H9B=q>J7bM_rLSsyj5+Jm?`>S)Svu1c5Eudf1o5;xB7AF7tqJD zhaZXQ<8cL(<^XwEUhrDqwW7YW z4$V=^eTgq#oDFek_38|nA1L9R_e$07_B`7i;?YGO_d6T#&ARMf#B%+Q^l#Q!e`6m~ z!=F2!-*#z7ji!}I6sZSv@IkeBzOM5~<7xKe6+fc9ds60@VH-a+mq%0H_GJ)(v**KJ z_^d=jO*?)u8>ji~s&pV-KU3&kuu3p)x{@Cr8fA2Mv9*h6@(g#Gm{5-s4@}vM3hob<&d=NFg%^_5$?D4l%yBmP_)^i zJ`pokg;>9#0dAr~ORn!j&UHlYeOMtlUpFgNStg-nTfX<@X-C&_#rv^Q_3{PM4vnt{ zaE&q-XS1PAnx#!O_rycVA<}3o4d~67LEeA!g`59h9B@gy%+b+ z1#7Y}y&>^!axK_qduv&ZlESZ{La|2q>MNvLq`6NyxKMQs7G9sKLs-q)ovR9N-w(_= z8ki8EqEbyzt8Cy7b4y-$sH%KjveJ9Q$uaTMyosoj8r9U$Q5N>VBVzg61DT<##C&a} z&K;S{w}3=`RxNS%RpfmuyB9Bwt9VrcXJeErR41a-;Mx~4>v^HKu88JpnKqA<_?Fsf z8I{98eM>38H!Zo^A)Kx$#<@VdzMBz!*|3KLt6L!9@6&7V5c6Fq@1PeN$M5#aKauP^ zZrH~NmWl8C`aMgU8+w*~a&TLzC-mk1IszY zD_XJgUZc*t=_9YA6>nW?2_W)Uq<^k>1=hsJVI#c4wXKYq_q*Q91!e_grOL9EPKSQj zm*aD&*MpM}R7B|Mj%g>hRdVdHkj(Jntc<21vrlgO)t1j>o-PO>j z-G9m;H?0P$lj`_!q!@UWU1PN@k4oQp?eds@iE|a2w5-~~a}x#D;`o78@$YL?t&JSh z7GRK;#M# z&e!mhlPz=O$>*eAOj{d|3Ov3(g929;z*6tm3Fa4Kv2r_n61;L4R(&JCyzf)}(wV$)vOKq6)Y_EP=K>Q+%ztK1}V63!$977MeVY7SX`rY3^LQONhj}uLY>GbI!!w1ot3|HcTpgu z;o_V6ijo5!(T^%m^;%?6;YoGUo3?HyPdbs_-`R2f_3w|}*F6z21I2~Tft7<(^QJ=I zNxfOHHf*Uug+S_LhE#|$tJQW1pqV0`iN-OtS3Kc6gXom~AqDbRL=Z+^Vk*H}H!dLO zxaGGBgn_D^y{Vz`7J)sNuIJ2#ysT*`o8DLN?It%+RE zm0)5+ck4titSojv)4!%UbE<@`9E;!b8_V*z=jz71`mj|_sfLG$3`D1FoxTC{Twtel z1X;wtP+6Hfk^BhAUwjI2&hCSAn(d{on<5bj$(B|)9DmWJ4C>5*{p;DOm+Jj(mB-FF zoLb3$snGu@V)H;jsP0o~|3YzOOaa2UG)t^uJpKY9?Ns5$iU01$Y3{@|-}L`<;qs09 zo1ZVUrA~Js?>$&I_>wrIUih`Z=+US6FNt}hZ~mJqdpuX%;qm#@nZKXK(|>J#Nq+R_ z+?hWYMxKDQE~KIktROdo*}Ru_saNO8g|?VM&$AaYQZeKeplAnUMDxjBb168|tp4f?+3#Z(5#d|^C2{`2dNROw(@f$}jc!@U9nPaifE z^8dAGPIK*<=l?(UOwCXx`v0|OBrA2T>Ym=f5_6>Oy6VS^{%6maFoT|^kOD`8?YjRT zdq!AMB$ZUksjUsXieh9;6N8O$@I;!+X5GVwoq#`?Ax@1VRbJ;f~H zfLS5hwsa5cKUn2(`K+UI(2Ew$guc*~CltNd;H=*0C6+P*p`U9k`}CaO=~NaRx0aX*b@1D&!4pJW=HgvLAkch5$o;bpSp+N31cwlj;avYd6TwtZ z&$Dz7%Yp5)gs{WzmkGfyOGeDSGzt`a69eD9%lCWTtU^feP?@fQ$`q{CiYb~(5zebF z{CleDlghMEu&Pg!71{7VY{Mn%9|9>v{J;nELJLl|8quq#WT@ppLZR{M#hRC@r-ONe zS8Zh4|E+B6o)Gu(e6smlg>cR!C!z~JZ%QiS^@!K-n}-?%6yht~JuW^zO}I<@lI>Av z5i(H+5f2jp0S~w`oUoer*i$n+*r-6dGOxz zdITTGm~@nh?G@-#nG`dK$onIGckN}MitblWdf55IURg11vA3}-uo9E!Jd_HD^bK_X zlVsAWQ$1%2Y^S?nQ8NNoPO?pSi}2s1`y3&T$j=dc`Ta7y_{)TK_SHzI*}JV;1tVf9 z*JXU~UOtAnyXo!w+0uq=^Z9-9l}icgF8?KKLE`fz*~v`R9w{R_}8U9&nQpFA>GI2+{%N}dgh;&itz3m zmyW(MZYjCC1+Pod+*RFPihnzLwGWbksCn*1a0rI>;iu1gtG_oM5VVAqow%{4>9FIH zb-xSE%zYlEHkp_stm`TDqCr45M~^qZ6!2u31knGN5@tyaJQ(vyL9N*c62% z3ZIuC$d#g9=IPf=RIiVjVI*yiD+FpmiaR(1#VRO^JEonfg7CyGiK8bJvY^{%())yu zILd5lh^J2rl`mkFPsGS3ubsJ({!&&fwm`v|zAnLDxB9UlAnV0gF?UpXx*ct+Y3x^L zoyO8X4r5!RL++jVXvk0FJ8r4# zsfNVDX5%+{J_foWhY9*qjRzNP2;zpr# z-^oU8*WDjis1CNA3wW+4^#G{`-YjzY>00=B=INZ|gE4p2+W}Upyb~ z@gSr6>-m6~YrLp$KU(A$e)ehmo{b)pM^F9!r@N|V$*mDR|6a22-lo5nVh4Ku>D|kh z$XB!LjCpTmyb*mcP<|oBvw3M!zw4f$u9HaG?i9C)_i?Vn7GKd2yZX|-LcpbuvTxM_ zypHT)ZLfq7KHO}c^%i?_{1<9XF3>Pr;#*j8OId`f1zAzi0@|R0SgF>AV zHkg6+FU2EjM-FjW7rXlSlHd97bZ)g(IFN6=YcpJQXmPLjK^HJk;Mp1ZYTssm20ap< zO1w0I@6vrD@6eK!Gckx3i71f9uW=A5a?^SG8Z$SKKpd?{y7D3ejZ_{BkIA6EIg#9| zbk8ezt~9(9xgsrSl)@gOfR<#=hm9otnvx}8J4!veOfN}%dYEQtABTv1cl~?JX~7>^ zb&H6#vY(0Awe6VP8skS;%Yc6jx8vv(jd!Gv^^bnktfs5E)|~P(_5s5*iOb7SMMUS_ zi02@Y@M7g>4_i%a{bD*TXy+?PRz8%*d6?KdRCkw0f5&+v;)+b5^RWCJmi561Z zhIR6v?L}^ zgv|@Rcz7;<({Hlk+>1ev@YhN)oLtaZ)^UZOYJTdcs%PD4nu3BGe-`I*(r8g>e$qxC zTm^^i!v^w%=HhA^OHYH?XC8}?g?ZKmRdY&<&v({6*V_nk9(Snef_$+^cpa$-Hg|GJWe`XlHN)?b0 z8p|YB?2iaG@ZT4I;52HIjy{wRJd^l1VFmg~{Dd;#M0#KMPWy_# zd{NRPyCbhMo**2szJKVeR=2M#rW`7yd@$2c-}*v?NqSto`@Uh&R+#i}usNJqbSt#y zzU7_6|7tHqx!=EqmiKy6sP|))Q(Gd?szq=voiSoOo@H$11wC0_y&=U14}5nZ!||&= zHFj*q?Do^m+t|>q$n}?=pZ`lXCD=WW*Z<~~e7lR7{5?fdTrow?0VYUkUBB|_as(_v zINtp z47)L*3CmE4Z>n|obYlK>(w>2mvDT4+S2F@5Z5Vce#x#i;Dxx#Jk)7ZZa8z`|De#AT z&iXOq;bSkYD3+O-Coqv{j;tqV&+STZ4CjzsyWjKyp}zXrPjNU-NhqUkdebq z&|)P7b%la$aJl1S#Ajo<71-V{c3dp}zwH@UlM;8I zlB!g?XL*T#O)+v&sj|NS!EI(YDGl~14M{A;WS5>|Cn**bs!Gt^>=5KtS4d59)R?G! zws4{uN6VU96;*mrs`8d;keLR{(9@6_}({@qI-O{z8v3(aSjW zB8N-v0N|h*Xi#~js%$yA=GL?A%3Xi;FQad9rcqA- zu!ueAhcKanUlqK+MZZYgMypj#my0}EkV&i&i^g4MZp$f#&YShg_Yb+vE7&2EXB zU0zs2V)^kISwkGOX;*-Yp`bgFk}ZP33Dgpre~4rkL4u8Tm-U*|TKd*o=2QnR`kkt- zb&3%qM^`=mg*2Q%kM9b2T&d&JY2YoW1G5>d-OzEL+Z=pt4yZ!Sv{ZGwBATYxIMW#M zyYYgry2(WijT~Xv=!UndO*}x< z@;G{tj-pl6t&sS~$+tMzX3O8LJ0>zklBI=qr5CNxCzx%MuiK`6w@rTlo08AltjXxR z!aC8YCP`FJMGF__IOJ{T(kdK$-5s@7(VEt`X#O=E{|1Sl3xhl+!OoCiEMJ(UPldWm z8{b3+Z%kRJsn>XnyaqQV;VP5oCX=s~sX=0DkaP4xWJP9WL|*ZZqmfSlNXgdDAv}@` z!8{|^HB9rAka;;QUKf*MWI-8VG>HqZ%;1raxd_QFZwUv-o5N*xrs2_Ccz^|q+J#YZ zyp=ef2v+?!V6%u$>4x}u4`!R;D%g+&bvf1RdbQWmt+!X9_tZzQ`$w=79qPXdJx#hJ zM>rMc4lg3{-3IW)GT|v)Jg1t6PU>Q?cyE*VuBh{ID7nL=SQlkGKkeU8V50 zk`NM7$YFF>X9aQqhnNK*$kT~<&K1ESfZ)q3C+|+&nWDF#1Y3pHS|gY+n2WOy9v`0198mw@P)pOO(P`dmOc(`+oZm$baQUHaR+|(Q zc8dLrDe#xGEAW>&c71XzZ)dE)Y@GW)_HcTv%u!&c8lJRTal=$_fMqAy(b?ZkqUV>eaDx(5bcq} z0OUk&q6-Q31dr-PbN3$V1s(;w^6Z{HYJkF*LV_^pPq-LTe0AXkP(7IrI|Tq|Jrtn( zjqgd1m-+nzUlUN6ge8*tKKcow&6qDect@Ei3X=Cc3Esd$eXQnx59r`pMK91OLrEk9 zhn%YBIYsVZn+g4UEVvbbXs4j7xW*8AmO|<3&8eECKQ@8IB75L0G^%!$kLz0?xXes1 zmubPFR#>QcCZY-ezsf|K-9-R-**S%R3>{ zGM7oBa|J2@@);V5xyv(&M+yApby;Q%^1<8Ds0I%C6*(Hppa`C6i`EZs50IYautqrC zV^$Zg5yBgkBlu(Sv-BEOhnTkXeIL*<|}H`A8q~I!%E}UEFIbDi{QFC zAi+8Z>|02{GoI8bu;Amjr>@45_}*xYJhcP&&Mks{5o7?gozC3|)wlMZT^j5_pMag4 zhKA62vRC1hcHRm)PsZu3Yz~Dd{nl1)K2H{Fi^5HeJG~XgT-Qu~EnJh<70^N1MSQG6 zKB3IeaVV=wR4Wr^j_8TNjxhkJSrV@onRoSy;1j#L$8@xB?wQB*dz@YFLsg)M+(S3tX9A~ z!U^=`-_aflZ^s8gnd6T4uAmpOx8|ciLOKzjoo1)dm7p3FpiS@@<%1mW`H64! zd4)M1tV4oKawrvZ7giVTk+W!o2?@ON`4eyF=P>NrX~5EHTw?&f&z2()#DWE~V2*DY zf~UU-X`!udd=J7kj%W(Wx0s%rfhJXc9L4QIPkxvuf8aAmM*(0Iu4KhT4l(Zt3kX_i z?4313U#+%@u6%ywBnk|C%RyJx?F#trAf9NUt629u&4k{PUU5kO7kk4*%wSOrI`lm0 zJ%I$)UWLryzx9&8&Ek-gWIlBg`0rztV7~8y`PDbnKHGABhhfp3+FYXG4~PEQ7Y)1L z0S$UE)xOekc^h)B6PmQM%|`!(MD1GTqIkc22M64WCm{s?BHMBV7fHkMx6z9ovH%Vm zAW&0BGyMcAXj-a%lBA7(g06e8JCe>3@I4f0V7^h!vlB_J*!{SFWtDFdi~0w^3+QZ^ ze4>3O?cnN+RmHuOmGEn+Lg!zbpKJ8o1$>Jlm#1>fk|7eV?`#X@kCh(4mE`S4-mQwHi5&Ip5J&FpUHz6+aL^92mpX` zq&2)(@m;|@B8_9UC5d7h-tB%hY9;F23690Xkq_Tz%Cv8AnVjF5&2vxA%yN(dhofO9 ztBi`0{}%O4PK)8r@bG5~%ID}`Sa>+|TL}7c_*{c0WUaq3_ouEzRgSyF>4&og>Oqgq z5)Xg=zVVj$^1Ce!>0G(zUl?^;sm`UA82@4T#_>XTwWjMSl`3hO>Jv>ljDSL3>jDjt z8kkggKcV5e(Mxh&o6#GUI+3u2*pPDido`p~q@zYyN6PQLk4O7sB}NUIkYSyt4FDVq zh$JPfW!|Zb2JxxXGUWJFARht=#;h?pgi3-fe}<-I3=HSx`RgpE7^gE*7upxVo1@P2 z0;cffLsMOGa5Zmxe(^x{w@mTV-hq;{k87a0Dt_f5CDSq-V5oMEF; zBpbWU?v4}oo2TMtaIA%5m6F2WPZ4%LziY2I(^dm=v?Y_GF;4y zoe*JX)3tPAmlH0pMBJ2q$zR9D_IK07fAYYJypt9;jcz3Uf@0_giV-aZjk{Z|g-Tbz z^zF**(XuXkgA!VbCnHeuLeH=mHa%ZSdrT}{I=l@St@#EDIRv%(_fqb)bSjGfSTGoguP%RIelES_D`$~G6*Mjn3P_5nE8pN z7fxH8&9ghWq9p0fw_JN&g|rXPkgwkkxfvavJxHT-B!1mC=+R5WGPdhZy1YE|M0>{S zc%Vtd5}|f+X34?y`}N#>Wz-j=VqDtt%T*&r^!LF0HJTR zv_4y*d-sJoQi;o(xF{^{(sT})$i8T%un&M(R86LePOn1U65L8jU(+yifs*0fQ)t6r zQ^`Jv^76K<&2Z7A%+!VacMsO|>|ALYNH)x$<4rwMvDF=nm*b<*VTQ%`a@2!6vyT1( zaq}pSe~1^*Hq{+{ePULzf6Og!dDq%_;%i4(>ab`xHk*zQOijUaEf*Z#7R0=jp{uBa zbzy-H1=INBYNU6+*_!^u2oW#!$b39yW0oabf2_Qke*^bazA7NwH#9ojBdGLAJs~%` zB~)se6*d_Am8Mr7j__jGi;2}EE(8;$mKfE_#|QJooj1Iu6RhPM(GH0#<1lTCMRpc2 z&t=zDd~V-H-##@>7F~}FHW}CN?$-a*=BT*jBl+Up>zWtyy^NXS#@^iuFFJk=ZmuPZ?lJddEQxupLe!Vo{T5zOF?TFf;3!n2roe+lv!G6bP8dWRQ9F=7`NaIse zLIF?%ozF)+UUa zEI$Z5_o9x*`C2363+@{dPZ(C3Av&u*(d#HTZwrz3X$3kfRc!w|Px)cZ+|3g~;^YjN zeio2NWq6OzOl3_V0hi8=ypn9pN=2#M&kf5OgcwqYo9_Uy{#$xyjceS*`_PI<5I^|L zVX-$dCWElzzYqrR&KLg6Nyt#-*&d6>wgr>{vxjx>NWO{A2$KC+ps8YUMETrJbWOMdYH9u z$@OQiSc)-zJyi?YShAiA;C0{up-9s}gnKpUh~S6{x%0X&%UWA!{ml;sFfZ!6pu*bU zELl5{YofwNi_-p(@nC?_1qM}uvH-0+t1k{atQ8s9Mc~qE5N-$D55=P3Wi^jWw1wbR z%9u#4$e@9Dp!oDO%=uOSC{GkvlAZM$cDXZ?KPrIN>sqR26{YQ5Rv=XE=a`Meg z!YA^glH{dN-nQ;CTNfk#(>LvPG+XabaEY!W%KbK@md?Yy1#$ln6vLW<{-3xw@&6kHGu~y$REW$t$)97W6}uZ?w#WjUNugdCG&TM1ObIP1D=Q$rzHgk+LQBh<>4v|BYj%J&g^F%__ z2oZ@$4y7@KR0tuJLrUlA^d_?J_4(ayzuWir-G8uauh(AJbv>WY`@{d!a6%a=SlsEX zO`rHlXol#&`1E(L#LsEPa)Ce>P{zLO5cwyKFn>;3KyBKgweBQM>zfb*;d*+QFe{AL8Qfvl zpe250)^1!$T16~l`Vzc(11Y6lgzZDsUA;{{438wHx1GC}li8J0yra|LPVyQ|76eVg zrIR!OZ4(xVwDBxvsefTQ5Lx^D*inP*XFcpt5IYEogG;dYf>=8N*n%cYs)bmsfpw7# z^(L{ypI9*~WjFq&TaLq{Yt3KLWe*Y{I;CLIp~dQYeFl1In->R6^kd?Ii0xW2Wh4U^ z#{kt^c||}Cd`nMO=IN|)-uZO*(7K%x8Qz)QZhg|Bf77k8y#Tqe!;tAffE_~qZ_0gN zJ2-BU4VWB1DGvEu$RXs8d0hTycliA^&ak+6^$gRU&U*Xzq5BGyZflsiCZV5cbkv;n zLK*73rr=e~0<@Sn%9i?>oqnx$5@>P%P`FfpigSy(zFBo%#G|H6w#(srVIVfhDQ!Oo z<~MqqIAi294~(dj6Q^slW$q}dX5{JLIU`K7tcCfkF#RR|$K=4wFG2JegcWd<0n8r+ zM}B0v<5;_Z>2(@+KMyX7YHEq7Wk=P*NH&@(Yw60hsW@z!MZDb!9y@x)B#NW@N+{n< z%r#mQlbsja)^tUas)Cd&3U^~4T45OptqHtT`F8N3wKO7G(G%yilg_-0-=0gCaPsZ* z(8}JvmcHEvT;IA|cLi)FWMp%t+~uBB+uY3NLMRa|byb!fj#D$n1^gHPT2?IBT5IGg z#@*qCUfO{~XJovz@kY8aCu8xDrf)4f7H4fG!CnABh6op*X_!!q4GiIv2}o^nF+>UY zp6P@^h8dORjf2tVNwqQxLh{oT8a$kz>6c6hpcV8JDu75Dx;46Qps<3%t?2;d32aCCj&PrJAAy>I=o?{vln7K@dTLjcu zm=;0JPseXpIma|vgZ2;}o`nF&g=P)`Nfcu90M!YXCRfUC*HH7s4vO>ufq$MIR}9n% zS-|K&@DLxF5A)-|+*Q(KZbLmHSi7OD-So6p4U0^q!u=*v-XJl8kY+dSnQ@p=hab%= z25)@!thFgH8HG^V_e{51ITNAf=j?q*Fkd3<;2KOYp83cQ>`6#(XYL?p-diobm&Z^~ z#%rJEkWbRnlDLTf*3*-@>A^YaXPOY_xQLJ#MB)nEXN93Z1HKPJ%dfKoN0~Z2MP;6t z3Ndx>3j7eCWw~}8OHB2ug$E5a&DTP8DoqK~j;v%cT_il5$iDL#z7~l{j!RFXB2Lc3 zY19ErI>dU3wYRp-oygin+kMxMSto4QjRWI$GDM2^rgb71*-xkQBEWkd7B>0bZJqVj zka=M@$|Uc+LTZ3gKrG!eZH8DIXFNN8elp6f;KxK-Teg~2GK5HFg@fwH&)H*xAsW9% zwd$R1u&`)?vtd89md^0v!Ml#9C(d^{kkZMe&sH{(4u2aH=DP}7xnn$dEm-~7=wKur zmQ(_T=nZPG&b+N>8rU#))mBE$^CFtAg$}0q2@m_vv*Y6|6Y<*QeTW>pxn0Ut`&Q^? zwa|l{$@`Q5fn`8P{f={+oS&8I$@2%#6A`b+CnJVjR1t11Rn-O@!m+I_)gxg&cSH+Raqe<{U~!|p(NuM= znf9iCdIBH5=nDn#7>!UD4?1*Vcj@+2o-Xli)*DLZP$p_gH(Wt{zRjCUkG1Dm#Xheuj?-Q$tt|vwzINB%3R8X%L$ghF$S!UK56f zgDTfE-LWtd|FYCNHXs<{1ro%8(J}L^rNdw^4!g|#6!|T=(>E_f z%}1{393rGy3frL+oR(>~)*ypSNZSXT?;xmy<8%E#oSi>82Pg>s#=-@#J%1zJL~_Yx zFm*58^W^9a(NJ~3q1*dMjPCqQxc(;+afYZ2&^n1tJJ6Qt34;KR4nN6PPbQ|vjk5Qx zFitq98q?wNvxCt{#6cUz!{*ddd$3J0)Pul`ILXi`W@XIdmvq=KqMiW%i#s>fb#d@( z*>CJCkEB%3r9@m$`P#B?I%ntfK4&V6yvEc@Yae}q8#f#UgivPAeb`)?zsK>a~ zK?UtWIc^#Jzf97-Js!n5UbU=U1g0?nlK8QYWTnHl(nIcDpKx~1SuM`+2a4@X6F&&8 zR+Hp2P2($qYuS?zM zy_TwB!_XUSu8Zhs`|)YdEbrqP;G~2pAGfvg1D|jfQ^tXbgRo=8X`w>+$FH@+&JpEa z=@$YK_2q0D7DjPX-nqskgP>L`HoC%P-9g`wDL*YCa_9tDYtZjW_m`2zFHhT|wTO(c z?M#hZK@rC?$KaaZ_Osq@ye;_#u_gL@A=&5C5TWJiHK!08`RO4#?_x$@iK1&^U$nM! zgBs0>#1#@{3 zK&^&vkgonmD|QebF%5H@W)`6|7{#ow32AYhWKXZTAXmFBjt$ zF=9txq>{ck2%kBuFn7|JWTJE%w=|^|erS;KUX1DHRXGY`htb&*dO7w#UiOA9kz}fN zCRmogS&ZYsg9w0C!;~Bf&ovKQPuQoU*Lu)~fQKfVH3IsbV5q}y=cl~qytLxyIum=#vKZvwtoUq6=m!_sAC z`&&ZH+r@m*!CeqIl?uJi{5jylNWqIq3qdlR_2Mh*rFYg#9nCjSC9nm>`fp8znwvUxTrn`9YJ zA*rbn9*JZJAaMc-cCheLC?QRJ9d_(FEQo5=7w;J4$ByGZPHFmG_AF`jRM(NmfAZbF z_leT=B@r+GA_^_oUewNTKe*mTL*)1GKaFFJy*B?l+Zj#5=M^7HqU8!;v3a_u&uxB0 zy6UM-MP`>CjRe6jF2DSrVZ&`oq2`P7M&UO;9Sx7T8;Y0Jcr%!T?vm3i$nxBXCIU}B z|58L? zPKp>eBjq9SnS44jmLE0dsap>TtL4*+B%aTwuv-hi6=rxnkacn3S1}j-5z2oO2 z;gZF6wTxi%mnW{-pZ+RwYx9HTwg<^VbZ_=S>XDA9nOpw~{>09h2c82&55a0sxnaRw z@1^xS$`er&GG3Eb^&|Mm*_y25$ZvAF92XJOp=ig8Tm`bp8ueJRC8 z+vPbOn$0Zsq?;5H9|vM0+yLZ7(vHx>l-@^JU@9FWXn-+sJ!#GwnbV^bt8Pi5PkW`G z#f#7u3@=q8s)&4GpZU`(`@A8(7O&8dEV~t(7f(w>%LtX4dL1W~o9NfY*tp)O?_}&h zofoK4CZlE1+CdthIH^4^zB^*WYD3K07(G07bjN2W zyO;FR3oRHcs(XQ_S>L8(mO*3HrQLe9(TsF7CRF$wD1i{gy1sUP{?@tbg}>9O9y$+J z^eYY?$oS{zl>bPK^2;AW4wk=g9ZtV7E(XEfK)2pZ~jFY2I?wSe9{;KG%IrSE&? zt7YJa-E$+yyqr|9=ZZ+;^5$L}(7t1w5{b#1+mA#a`1StC^Uan$W;HexjD<+LBhaJRN3{aQ zvbbxev!S`|=Z&I^$E9a>-Q%idU|qj*5VMDR+fIB5)!65~pGY0MoZoR1f11L16Cj;N zCTS^Mh;x)QQEzsY(h~97hfqDmSzA&i9C)TYGGBeiiUA92M`b^*I3S z?-Mf6u|F-K0uF{znHSQRn<|m0*mde@eqhTI2(g`?nsS~FxvZl=lh)5-py=o( zmPzaCl~eNxPFEg;=2=9V`p0M~cho{vr)kKbiAt%1O{_tece>#mN9CaWo0xk(Ifvee zVz0*z>7;zBEZWLJ(lL4n3&v`ho#74DIXXHVtTN3YwlpzQ3GJ2L)pQP zqPLjL%Q5=a<~yw7?2^<7+SMMjsa{Flh8kK+E@pP#n3#q(_Ug#1gIn5}1{0|YLv$wv zeq0*CDHR@A+z+TmS!A>+%9YS7#UR3LqRCpBd}yNUf<$1%FU2mQGm%3^A0t)kwS;(B zR*j(yqWOV$C|Agdc5c5H3pJF8p+dIn#QOM4JdN(CW|u0VwA0MtY2`NYJ?%2ve#3QJ z>^PG}V;l!QS*nPXrZL4$+s)eV^p!b4XuVtR_pl-Kc+Qi5Z55pRRn>hWM1GCP@W&N- zQ9nNR?q?cLEIS4ZksMe;Z;LWYL1Y1Bz9ph4O7AH=-?fSVOCED&+JR)=^El<0cTIFZ#Xh;<&jjDORQi>hSt)(1?&nyUg{ z!|bLU>vP)Tv%y;LsVrOAm&1+A70u1*qQT$BrTJ;b%DS47qO{qx=0D~N;o0tvMW)Ljx_Nyt^KvsZ(KD@fSuW|GEw+OKXLk zRx>=>HhJz?b zBx#V?w)U^nj)jLEku!i7V+KWDzCBPOt?cAwsC0W(C^u=es~?l){|*K za8z_6M`G^%idn@Z#zO~yM=SV`-AySJ<5rPZcZ*Z6!s|4CGj@- zc7`JbYECCs;P(8|hM31^p>vHnvkr!f@)ivLWHm-c31&A%9RwBydcK?-zP&kOO|7uy z@&eahI{;|M;OoG9#g5Z~j)egA!nA$&+A5hDCf8R6n#ohzW&~%`{058^ob=^$$iWc9 z39xzcWBE7imcgrGkqXw4yJu*ba*gbFwolYuC}ypcc&NCYy)otrMSo~8I zUto)Our#Jdt%ytltrySABlCMGUOn0@iZ$1{!qCO1Okp66Iib{RhK87G&zPx>nFYwc zH_FYhK;4Qym6uwV(Yr(F&eLN4~HOpiRiAXj>UBvs!pm`$Ft(1zTsr2xc;aw1tW z!O_f9U}N>vVnqbrPUzhhnwkab?NQA)#Zrz&3obx8tvrEYXpf-dn)mN1eM5)^X!z@y zMPsGeir;w`bed%?0;t$EedwoNg7Vy}7G(8cL=f$#GRzhH(uh6qS>3K$^saTXVr z&2FcgHaME$1ZJUvj@Oz{@dHM?e4uH9tcS()M2{n5y#zn7DwM1+O@iTB;%;R+g>dx)Gx9BxG-x_O`w}>E00pu zF17uOm|VNM>WT2$hhisp=_=Cs9mQ_dNw?0Pi4xlssI~`XB;Tz2gGyF_p8m9?z$fcL zDb}sw9>@^;2fE*qm=+egD)!LlUrSY;#PkOdf->i#P7FTue`w3GZ=W3E7*_8-9$azK zOB7T2LS{|%8si{gamPa6GmO9V8gKTRIWftTz4|NYU`Fj=2M+3j&sIB-7f&JLL`(x( zZ+Nl`u*V#!1HodWWvU7}5*)ikhAfZaa=}qit_NU)ARs^v5`cgYo&{zBtVyZ{-%;it z#L8-q*=Da{AJ}NVN@K7`4p2$}#)C&fQbABBkVGO`YoeEE$TY_>joTS|*YbwC9B|TBG|C z@m5PR#5AsV8^>$2PQRKxtMov9v$-dIkR;LS^*NjVdhsiK{wwmA(VJn?+hP8jT+lq+ zcwv~1E~Lv9iz#KNk_$i8xtwq=40Ts|3Xa&q~nE z8D(7Pjp>F`+mTA6V@#dGp2@G;Dv4lzg@hHyQM&htj$EG!_j3RoA^~VNXu6mo9rC~s zPUXw-mXES1%pYli8MR&A1|uUw7Od?T*ZsJ*)P+>GHD1AS-;G?=QoBONupJ2CO$0J@ zGL%I2{Nlim{WpAvJpFw`nGXJSN3AMMI6Ty(POqu_r$HeUmqLLo#nbL(qV z-PD3^#Nw$?Acz5oSge0)HDERYHXP}7pz-^_B#@h-;{&meX8m|4zz>2f)rL5>A9p#a8RED zOAHO7xEY#3_#nd;QVw!-!$BNu)b9B$x z%_%#H;j#reo-xf|Zf(Fs<=dwCQ+LHql>v#doXU$3(-DU17m3{oPKtsBM}83QE*S?H zI2O99Yho&EJ<9E=>Rd9Vpyz*bOfmW7v0p0fJt}Kr6ct!PW{;9hqaqHvEvk8U9`gB2 z@HWi_eVV|URcT)fso=saTUW__ZxtShJ&qi{l_S8PC*RERB0nJ4?S`rr_x5{2EF%zd zLylwu*p+%5q1tB-ISE43|IM0c&%Log_exEOSs3CUq!A1*CgfhG7~21E@C8Z8^+= zz6vqF%p{aWUoVo}d6llZ zDH0#qoUzG{Eyp=Z7K$b0&Z>P&boLB=<)yZ9`J@uJM>%3$>ah{z{`mNkd|7Z(>!^e!>EQIfg80aY40^mzi!7?>@#yU z1BKsXx!&ibpK`&rE?ZS9Ur3#_gT|(`6(q7$qf?DN>$bZF8y7rWlsb)@=+pEmBEBDn^)|%S$x}?r^UFrIz#EQ?)?@ChbXGiq9MBqbQ^8UZv-q?K`~1z!UJnGw*w)?fX_X^;)iy zbfC*;NeubGIYWIg?!P~`QSu#%|6Vz=Zs$F4+y3y8@0q5q-UqS}LyJ(kku!e26t%%4 zkFsXvN5S@e{YvSS*>R0O@+?7~Tc0sV)~H8jlZgR=tv1UKp50{p=LhRG2{E|vh-0(+ z#g&ruSp_WfqT_8-CvpbsnS37!Q%u)6&$c7?Dx$&EE&Isr&=;R~zP~Bzco8l(5q{7x z^n&aK!F68`_0iBKjlbO$rE#d z?TUUA-p%1851%`v*4QII*#3_NvGWxatSl*mq9lv?x@7_Wn@`o(Ht!wWr1y^wZ*apiLcXSR){@yZ z?FS`4DY<$(+rB*bp=+45GH}`8CgIZ~%Rt8HT6*P+_7koudSRVURebBDAbASA%92+X zg2LHqhfhr#?hGoM_{;u!ds|0her#l@SKxn%IedQIMqJ#>`9oqLKkTA&N$C4+y(xpE z!R=3a;1O2ckKTQFtM=q`L$-CdALMG1^6n1>gg2lY*#-$b4Mb({4Et&fJ{63u$yL_A z1wt+D?UQ!zljyrOP0eixX4g6AnpEQ1D$(t!@3YL}L=E-ThE#vo^2FJSnq13nq<7QP z=}}(&uPuK*OXp8hpPVlhcqtcIQvz4H-(6y;nXzRWj?1;t9~)tBqTE|$?;V2V>IK+- zy`JQhT1j4s;Pt>O2b$xqy7O>-DzWV!k8ueBS3iw7E5%qC$X^LIRkWdb9#c`iJ`{pc z1^Q@FM`zu`)e=3|9VPjLM~CcnY*8e!TsbO9D_w4dKP5@!EOH2$wagsy)V`yE{1W~zzL)Wc;_m&0GWzrSwQ z$&M*sjS@j+n3D04N6geoO*{RT9KF1JBji(i^WR zv5`8Gd@11UjjX+wI@T3!hu3%Gw7{97?!xL^^S-n95qe(gGiDD!0(J_uE}>7E7Ri%`_)$#Zk(imuXP@GcVFt)BZS! z(%r^KpT-{bp}$+Uw7qFj(rUJ?mDq3QmM-BuQ6X8(+h@!$6~E?5maC_y5$rPdocZwq zbMg#DkC%^$@*EBTgdEeN_#GtREetG>qGs2glT;jnx>P@BuW_qMZt?}=IKkPz#yjhA zv{vqPG2F6AtUsE_l*M!es~IbJUseeBq2rwOY*NJ;J;5>}T))Hah0MK)l^R`i7t2bG z%reiAh^c^&-l8tJV+mCT`)SR^xSb3bJ2yOz=(}3c$B-rYs}*j)qxSncUOu};v@fiO z=$~51j`dB-jV)nYRV`#D;4)(mZ+;4VuH9mZ2CFS_U2JH2k5d{f1Kt+1jpa1b?apKG zq>EjZE@Hs0s8tKRO$C%Md$6!__mkQItGnbI zu>eeF%GEh?qaKARBPOc314)0Ed(bdbBT z(KxAS=O~6!^5AA(}Ju;_ndEayCyXE?J#Li8MbkUlt7LWj#;^w8J*7lisTB&=? z_lHLCQ=|RIT--e**O;^tLtF|Z@C~E*ioR0QUgM%lIp!GCtR`Np;()5m@vzEO=wjZ^ znOC{E8Lb=6KMJe`G{RonSj_f}yt=aGTsQwGz6zf`+ULTs>HZ^O7m)?(Sz+dPN}lHa z%PYM5i(7$L z@6{Y^1}{i%dOPX9>Pr6k>7T96?!t%K6^44fzQ*$cj;ul3+QIqD2H=~bLD4O8F-n)*C={uJsS15?$=8!TS=}@rr&5v{lf3yLRzX^Y2Wn}aSWN3rlV$~ zLH<57spQIcy;?ST=$xsqt&SAhxMX`N{&nGJBM@KuC@6P_p~{( zs%hs$Y=U&urILK$w$ja`@K%1PT~A$AcA>Gz_pQvOekHk-eeQp*&^#XQe|xZaRc=z= zzxHo=HAt$uLW?HyWw#YeSy+e42B65bccUv@W=&~MIN3Nlk$W#)cMlh?2AuJ~NwbMBOH zL)Sn|{`b3z_x?WbcTl(*TRe*~RcR1+E@omJ4D?Xu@5lj(l+O zJy;<3#>+o)?-@RNneoT-CJVjhu8gj1M4*yL}#S-s64Xp&ZaIH05hsZ__Vx(xVt66{Er~XTQ^^vIuom zGyUds?o+*-S6!NN16eZNasvBi;j2=X*5q%+2PWP2p^laM+RNmxI=`mn6=nV$Xu4v# z--aBrXZp;6+01QvbW3${=W_p#MiHND^2tH9eE6Qp6MvV#cNlLTd}Hz2p&#+BINTdsGZ_=rGxC173@do-x$F0Z z+<(vn-4J=F$SijiMq@&IB&G)rwnO<`?0?WbCc!|wWsA#P zLb11me-XDw(hC}?aegdunA!29Tz9_@XdzV8Nq^MlT^&Fk9qHyc*5D_?EXWUfWk!BK z%m-3V_4OGF=ZeY3lOwdOj|{o2?Q%*pJZ~%2p_4Vfx`g>?R9xY#oYa4L`bVIVe+3~I z-I8U`>Wt*Q$9$WCl4NVB;Z9WBKgDfJw`RvUe(Kt3Ul-fsSAi6v?Od;PHDyp4PF z>mTY3Wl!OIsyv*nSjLRL>dR|2{k4e;sJC^w=DL*a&B#Gj_#LHF?~AJ=q~AH9#>hFX!B=8tekpn zMWaHtpi15OLV}t2FU-AT;oRnXS-dz^m1a(wx%1A#oxd(UbJsYly0PcOo{US`VRkR> zSR3~hKW3qI$frz`_oO+m+YcTr!|g3Pv21_AH^ZZjGUk?ml&B5muy5mnJ4qC~-bE&i;H$y9K{M?e5ZnKconcSQ|`0 zJjURv&bGdc6Mdg!Qo!Wde_^akj@SP6E$y;@YM@m&`|h;TzUiN>L*Bg4k<^KkM`m}Q z?xZxINU_(Gu9|9TCKYvJiqD?l-5}J=CI6S8=}Sh3C3_CtEk)UgFVxEP~mf5 z`AX4le`O``yh|5$XmTVKoPUs-{vHt4{j|6pyh8YaJ=JMB@W+S=A@ zCa&Ie;Y46R>o*kb)6ml{*|?;~@fL;1-ddLP^jy9j(6C*)s438HU$D(C$-Q-@UmRCt z(qK1O#jPF@Q%onI zp>}ZFidX5=%QeGw+>C|vh`WJR(z>Lau-oKd7{yXWLH zAFERhhs_#255|~FvaiW%W{tc4ahiqYzRUb@YyLmev$MQr(;7|435l5CSI-j{-3$_8 zVS?Nv&mc2}W4A9GmrW!tpSwSzTsb6H7q0OwNxypi!sYl+FY#25pofS5W7dqndK0@R zc^cO!A7HM%DD$|TeE!8=`KN3uSoDqX`0J+PagTK0r7lNlDqL;%&bzNO;u+G?<9BIy zHVr?;7`jF6R46_fi=uMWhBi*ho?HC&(Xi)?%P;5JaF2f4twy&`ctbAQ9zw8J9&UoEncU5HFRXWRZUj(fCETGwmC!@paFZKPxB_l%LF zTN{U-?RpJKbN z+1}au{UXp0yH9Fk*25fOY2#=U^ZZ=E4?3KCI_!J8dat13+S=gr;76C9pI=)A4F*nM z_<7UBer2Ql@AT;_Lrob^znoJ)`uWn9=)cDfdj_|T7D4pv*I(wD{OJqck&e+u8LwR#C^5_v5K}u9qw9w_Oy8sK#*Alr zDz2gJZDatyB)SRuvXx2nQ+Fpjk=CR}uq@>s%-lStEADh42u}4=A=4nHO|WJ>lj}5{bb%^(aKtgSfP|3 z(!rG{Ye`WpC9CF&);Qc1#TQl#pR4eK9A9n$UeB z5_*7JARwaqxac7wQ;UEtqKk`Yg_ua}8#-o;k0$%0YJ~tGBA(dCi=o3Kgi`7qGR?B`VMJu{s5qMskN*D* z5$7TCa=b(}fP*wih=>wJcvPbhu}|*QsD*iYli|R0_pw<|Uem zs74~Hn~G|oi6?>J#avV$5e+2s*d}vMuWJFS%Fr5Q2NC;}hUqzjnWB~roGBa3DC?O) zk0_P(&Y;ip5#Z*$1JJ!eqsY!C^w2zt4WJiv@w-A4Nu*TxT!y0 z62QC6w@sL7DrOwdMfhW;=Oy}t=r~X)q&feKbuKs$PCeFWycwr2NN(Z5&fEk=_ZN?0x%I3Sj>_DD?=Ktej$_stdtu< z)Fe@y%4hs6KED@PIKV|y^|5_KY|Ctx5_zBhJhZ%t+XceR0c-~y^SKt|REn7tqH3EE z&P4HXDhAL%;z;GL;}?!#VP+?9(uc8(v)EVqSe;U2hEVFre2sxO$s2@x!~;YYR9O?; zpD+G;UQ$Gt6bb)li;Q8p*Xoe1O_<^)Xsp`>00F7NOCVDv?h%p5-7-5ZVaJ82=Xi-$ z61o)+xF6^q8hS=pH#?6irXrYJ)HEMcD}?3U(mzClp31x_J|?vVYEdn{X}SaZR%C}= zuxmV}SES>8a?TVM3qp3$(0nYq3xvEtL@f~|-wLJrXyWBG@dCQIZx_6Vj;V=*sfgd{ zyNQ4|XTZoPutr-gfZEWcJ1dx)Nw7E?Ktv!Y{Hy*nh}jF+3v9z{A>E&Z0mzTHGzn*X zY63Vlm=9t4^uEaTPh|Ds<0QD(hpjT?=RL&IJ{f5-tO)~7{VuCXzEJ3i-LoKd%^N&(9PSD|JXz;O* z@blFEV_d|E`TmHe{@~62NMZlj5aJBBJhBXNMkp0RYBXBS_vXWsu&5Px^b?S{4-fGS zphI|=CVEdaDDyZ7QQd`}p-Z@ltR(~2`gV`fTn?^?FMvh|PqlWN9^8*uKI*t(GhSJy7R?i>DBbq?feS9=G4wf{JekFW- zms{swayhOEeil%FIuS)w=A+}-yL1n$HK_?2^Gb&Ve;x%ePa-a=h$cROMI+s@>(SEN z30Ry`=7S-44exm;7j|L|MvjJVqdX|eh{7>ovZ^*+OgfP7Y4W61KV7rKD5f61@52`dI(NW2@ys!*xCYIwX8MWA-EpHmjf0yth=qrNF3c=v-c7H4VfYU=ie3l?E%=fHye42yJFhO-i~CTYeHq5wGkoRm&j}QY-;luU zT`5#Dz2#L}(ES>LZ63WQ1{#dPhCT#=Q7w-JI1vdr7vp@i&ET6r(smOnTuiy<-n`4&h2@QM zeV?6^VYusB&G}fu3^-T*%(WLisuM>^@F$+wNYXsSbU}LC0!$=1PZ+x}ZK2Y6@Nvt! z)Dx<>n%B$I8z_JJ9cGls1&_VLR?LZr_0X}`;NWEuf9mFu*D^cU17aWv zkQmVBV2brs*T5a5a=b@jKL1V({{b5`fsZ#yl}BexZAvjfo87NRM&nHa zfEFzpq?#ta%LLUR`E}3(JNZ<+22?$HQQ9yi7v_zKYeIC576Ry)&@DM76$ogDHb+l) zf#BX)l*OlSn;7_^lFR7)@4vmU2`2v$+ZdBsT6rfP_dY}ygH}g)m>2UHIjPC3Tfj6U zVt|BsPG3|LRq3yyRE}enRe&tPr7|&45D~KnhgLa`Uev1+^S@R-eB(cNOfmisK`7O~ zC1rs{E#MKEbj-b5pSpKqyM^MlM5fR4QTXay_2{!=8hXPHQ%{8Xxf#~&`{qo-^!&wi zb2+WVTjM;W1{M0lX7YCFg@YnwCaiGH<=$V^Fv6sRMrZCf&t!X}Y#h6jb_aa2aMm`bQC#=c{K8p(k`NojVEG`B=O@vzN{aQ1Q$45P3mu28V*}LW2wTBU%@Tp_F`2vfccGuo?D1*g z?OMt%m>MyB9eM0YBUP6iLLo|PA@>~8B7}8@D*aeY!^nAG`zQD|?37Qte2?wN;F(Qx zP=~mP*WWwJZjI3d9dIfK#6VLA z#gIfEUSSIU_i=fGvaRurcjF5KDkrupg()*?u8QM)&&U7VHL*4G{&9+LeHzbL^^0U( zVcQs7MW;pOxk%+`TQTfWcx4G3t2@`FiI6*j>t*9vyWyq#sD2Dw18?RNQbOdf<m+aWB$6NXVb!U%}Su%ekVLKR0g1SstQvA;?3`O%KQ!ICFrj|9@#$< zX{LI@_}Y6V8_|q)aSEfS=Fy3^e0E8|c`+BoponIt20~f!qQv3IzigF~UlZxw{ ziSWCZj*0Sg=1x{FtRJz_R0_}TdzWU&NIh2a+jBZZ>h3RG7HNNMDc}^9al5{Cl=EL@ z=x}nuncX))_L+KrPc3pZBuy$ghEoI&zsKt7s@cYs1kLpN86vDHs7OgC(=L0Vrc|Me zYgKK==Q5)<%Vw-}{Gs~^s5J1q&?|=$;`?KA{T;6|PJh~+G&1JUonU0U| zRbs0a@_7j*!C8OX-8QSA{~yBcGc4);e*->y2qxZf)VHw5+tO%Z699tt@VS|0nnT?B*fI!S@m0_4&Nd*BPBO zv7x5G1nDZm=j7=_Fa$oHQ5$?=XMlv(}ftAr;i{ zB()P$Rb*OX$))8Mzlm{g)9+N41)u|Ukj6Cr3zQE90%Z!`jpS|59rPHfo;veVA6r<6 z%DR^!E{j9f>W~&zkMLpqUkx@bbfmn?5%Z-icsWdPYnj(PXt& z9KS&A6T&GQJP}9X(@QM8GIbs030c;G9{a2p#R?^O%-(gbs{SIKu(hk`)*K+rI;zk* zkdE~Ju!IS;7<$T2_3jG{DKRrkQa{CInUqYOGcCXK_OAy%eTjt;M6qqyHsw*={kW$* zwj-xXv%F0*Kf!Xum)9L2c^6I}%mmmy_Pzj>xpJ0b#r}W4#&T?r$F9lUW33aO{U-s5eIWr0LHaYA$mk(m<`{1`r0SV zcE({+|FFO@sEn`#d|zG<(Vyg_$g$dy^3YL}E{BlIYBVN__(&6(*S>@OG8$`!0W zO*^Z?>Xf_WU?mllj@2({4k!uB4))rOX)e{R6KHdOj@ef$m%Rpou;q&o6W7F&9c4*s zr&hcyjsr21TxR8==F!~$x*uH~xUL;?!Kdt1gJtT%0h9akfW#pWR3v{;eZh0Yy+8Uz zh&&gS&k7(OmDSuni1ymBii5kPHFKPn`3QC_8Cs*lH?vs6JU=k9tu92t575%Zf97d? zh^{_`S5nWR4l1Qfm2_tLuw$P`o%)u_-LiM(3^ z<4KmF>drEgY+feCaP%P_X8H>c-x7sxbPtq|+Ua``j1;Mny@RQd7}%C@vc^r)uHapd z>SU_jOgvXGoTUFrDd6jVd3lYu8EJKQ5?7^C2=%etW>ZXUNk1baYI`KZKN~OeLvEkD zQ~h*m*+e$v_zEz*7x<~j!-%IkfFHHr@JA^l*zj=RuOgSpDolpgZk1LH9r+z!uKMez z&eAwbk52(>6I)^S|6^xF6iUo_gDk{ZqYwmok3-SAjnN#wN&P3q-+lY9N1Bme@! zep5L9l$WY?v|)VRILzfPVmUaf(7?oo6YV?{JW31c+WQ$sB)lA0vkWm)^RNjIl!0u= zcX{T9O>>g-h8C=!v(3|~&O!SOb^Y(WwbFR65Whm!=pe8NYVW8O?vY9~nwQxj8}x=- zceVaKGjZ^P{mp{>#AiS6C;da{W#xxS8HE5ZPG^EbAo?kmErf6k5#dBu%-pp^D$9L> z?nHzoeC8GS6(PKC^hFiriOTb+@PAT^4)b8~v?4a1lNW_hZYshy6&)lM<*a}Sd30P9 z-CBgspkBVfEi{x<0uEAAtP`8*%&3Ksi9AlTAm?3k_9dZh1$i9iAR&;CKTj3#35q#NgmIALN@36%OHKeE2v#}p+spAtL@3;XXQzuguRdW( zk_ugeA*3~i6^=W$R^&m1W%0^p#$oYM@?lL72>{C_A`TMa2S_BfG7>{n4woaljUxrP zqAcD?rv{jo5#fC{d-*Us0tXEPKqmc52!I<-_!^(QLaYKZqNR0m@}hiYCXB>#(}5ot zFHZoeGW?33jbk$871;u1xUMgV^Sd@_t&TX_wt1^f!bbQ(G&trxbUbIB$rv{chqzyI4fefRrx_V9atuP$8 zU^3`T!5SodMOYwpHGwcgdoLUm!5Lim0TGN`)t)TvD_G%{86f;E!0`fDMy&Z>9+Lws z+`8swqTm#+k0AN6seHEP5NtnyZA@d}SHSVTXA)HWhSK5L?WhGj=eIs5p`D#dVSiX+ zS~xQX^bvfECW94_-iu6IJU zsFrf$2B+x7IO*_;wG6XxiEm!CpE7|}t4W9x`RWbN@CgDbik&TjX{l+(BN%1~hP$&D z3+qSWu!fTZZ}LVS#%*WFiH|%s1;^U50=o4R-gmggVugWv2~oVs2<_dNMMK4xg*I?R zvScD8jK+%Mv!BUnqg&oA%8kR!QgjCVFqIuWE+YPf=Mmv)h$4S5EE6j}h})jE25u!V zjByYO-&jDz1c~ljFg7W?+W|^E;jaaYV8D*%$PI(10n z$-c}|2SFifA9EYW#1CP*I?Rk0vE`}3?rh@L96~K0FV{buh{rO8lNNsd1 zCc0fjt51T6e11Xj#V*p2r2w2DW&f6-Q#q`^cNsgq;ZOa<**KUiiX@K9K*a|l#{$E4 z#ofymdQq?}cV3k{s7cNW%^M*C<`lb~@69xYm1k~0U=QCTfW~uJp#tbsSA^>+k$HcZ zTW0BVE_@G%bzpe#cN~0?3O~B&ay}EjXAoBU1ndcb{ELNFzl8)6pq}HUt{lde@tdv! z@D^gM+?MhgFUhZhX<4%Daw@HxWRf&3m=keK-^#<&*~8_{hU^Fq zbF1?;YXsPG4Q|QD+fhNO>;AWaO}on(rnn|ksm_hJjrX_gWbqm9;z#>Vb!Hl?dar?< zNt;PnsGOlbhzL2n23KAu(bPhWRs%A|S-x)zW!stHl@c#U0rP4@nHxiH-q-s?^-^{_ zZ+hiL5$oB`PqBgG;{lUa$A;QI)=ZCfqT5Q znH7y-_fJM$r%i9sVrTv?di9f)%8jbL5Vjc;(|oF!85Oh0g{R@56XddK5*(e(NfF6c zci|q}+ae^a_^9HbORUv;*82m{54#I>5x5uu>*on*^cwuXDHi$0tqB1;1TQ&D1?h3< zTS(AUDeV5ZVl+nUSN}cz|3(ZH`{GvFauGQs6|%Z+z`_ER*5FEbpb|gH>~s=K^wP5K zrBx781<#oMeGhFBjtv2Pi zGF6Cg=bwh(18U#P$(#PT;hxL(qMW?bH+MsD!5mO90*FV@U@HZ<6~^Da482$TGSR+j zrdP_Wwh&keBADy|qJlWF5d*1V1IDosaRIj|cP&JQG3+{} z?cV_8={%chzF9^pJVS&|_&c94Fw;w&V3IgW3%+bTEM2(xBC05R?v7?@Nh9{u;ds`v z`0Rja4vqRbsU|vvsw=k5<5EFz;XO1c2ug!6YFwhQp@j+0q~tg*>F} zBwCe=3_ltuzhM^j!=`8XY~D=J#j+0THEuM z434GbFmOODHPe<2u4*sb#)0lZ6d4bZStQ$M{VVk}_=55NS9{)Oa$vG+i8^BqImEpE z_i68YPw$`l$&87rI#KujzdeCc%*W0F%-ED%vtp++PO9HINp||0ua8(LCH8JZHU+7i zpfmTEm&_`Ltep{#!oF%UnDD?fjXDfGa>6rmLsJ($|=K`W*DMnJt%`!k!$H?}8X zq;Y{c4idQtaiQ*CIbG~DhHNuu#f`&mwPv}UnUh}KYq}v_*0=U01@ZOPtxmV}r)7`V z_O=zf1=N53!`{Y${j>NEa4q-1@K<4wi`$8t+t$CLtp4k-doPgQ2_3J=4MIj_eeLX# z8V5tF34VIc-du%2)fg_OOhYVg+n(76dI&5V@S}lF32fe=GNXAlBBRL&Y-Oy zY=`}APGab+!I9$tL)oXsMOs1XQPvtjv6m*lZuNB@Wh?@2UjLr+(TXUPUwUsOkYk?C z-D40@d9tv|io$%!oZX0uBmo=aS%00A+mGSpUWoK>n> zr0taRVdazIIM=}CN+NjtVGniX(S@)dS^U92>b2XuLxqUvY zl-FWaa4zk=%jXx@B5w9X{Ej@a`)cNjI_TrKZ8G{I>Y?_ukj(K>5{Z#@)HK2E*L4dJf~j`>J20%jPqXItgFJY7RU6yUWc7 zGKOX%bW#rTB1O!Db_PB>-We~J}rlNZjBh)Zh4kEgxR62==Fy5B%}MDbBRS4 zO!ug0YD7Cot&6Q&BKdrWzypAa^o{|N#__ybgA%ju4=Q)9>bzC&*@uRPVH}@QXSO@% zoiH?XeUl$nX0%c5oaC^QaZeTbzwGd-@~cmdyeFm9ej0VBB#U2|GB5A0@rCan#=BW( ze%ax;IWcUz<3j>y)IDXr8y-SgQO2;c+UBMl1-#yw>x!2N!7i@>cBN4fhgd<*Df7I# z_{|kj0UO=_s-_?FI}-Nzyz9>0$lAuf<^SAET$rx|V*bvA22>XJD7xJYRDB?EYXFq8(qK>sEJtyPgr` zstg~mmXNX{>I5$+c4%`pC3~p7%dr-F`NP4lz{|Zy{(Q^NqJ_Y6=zW9t0zRo-o=P6; zt4Wz?^9a~(I9pfs!aZr|6PlHr^Uh)synP5`5r(Wyawv8>cOu{o|4XUGd*`i&eP*34 z+jJ z_Fn07^AiO|rbKyOeZGi(lQ^;|^6&;bXJvH7F>@~&PyW_Ark-o@O7opS`89R6W?Q)7 z0gBF;Q(0B{ezd}dv+qhG4Zd_1VC3DqfQL@UyD$d=J#|+7Vv#ML!#2cjYO zP+9un?a_MOM^rraLv|wzcoNN%BUP^xhjh6#5bm0UWxc!?;h8sjrS585W~!m?``{>F z#jv{E@{7991#EM*Pi*rH;EsOKAZg`a?03rQaTL-Y)+@Qa{d*+_H@xV+^#Y(=&C=^7qUPP8W|8!@--|i6y&JCL zJNGkb@dhYR^!Kdo6DsmiZ+~(2A9z)t6afZ-T85E z!(}4Nd>yQqf*8`$yKtKuz6?VC1pGx0a(5<*(M|pDB5YDGTlQzDbO>NOo{6gq?hZ%6 z8LwTPA6-bRl_jZ^;7d$B%!+Jv~zyJ?{Au7#TyyoCZa}dA=Puq z_*vXAZ`2MxsGgY=X8lk!Y_ILx$)z5!zDpbR4RJ2d)u=M`S}5iA78~6Pw(A=9v#@iu zVVbQ2v9y)pkaOa4>7TPE<>mpaF=qDWi8I;AS0&L!P0$qy4A{GpMv7ZL4v%-E7g8A43V@)@E26;#xt}Euu{K28@^sL?5I=9VE(1jifi3 zG7Q}}=FC`mdN>HJaX-bX^cTyO_;&Bmc3&rk$8%|Ii);BB96u>6dbiHd9!883t3Opn zqhBf&ra~-7eUst;pe)euD39 zwl$Gs;kA?!Pk{C)UcV9{iNHT<0O?@oRQKl>>b%a2z0m&|b3l@$kgV!=oFNaXiO4)q zwgX=2EN;v=Q|B&mWFucP9y}l(lo2Mh+WWBnhnV{4!w(A8ZGoBlhGTGlWsY-6AN==r zHlu=g!&WU-ih0B%r8PGuT(2!fx}>O+v3w_7T>O@RaDg z2S#Lni_TljHdm&9t&K@aQtYG->E5Q1Gv6R!M2keI3?atL`otkSy3jt3pa#hsc~o(I zw?Y=Jkaes4qaBeKDZ|krFk1$uZ1I~;-j@GT5`I7ac>G82Mvv9K0A_08&9z-K7p-)z zuna}wO9A#8(IcC(TuvcWZ?`;}v+8BLwu{vw3;YM;rf+>*5@@8*3Q3a6Ut5VyySMnm zbe6~29&!l3iwLu?lj~6VWFRbx2C|?%IY>hAXh=STn?K}C@wBx+9dy`hG8}Mg!VI z0P8P6Ul&2COb~&DIpPIv_s}3QVvQd8M92#5-8|(yjdiX(&Q0d;rKScAbYh9I?H2k zkr2X#(eX8QR?FlGYhTJp2T(Xn3%jVpKg^ox6!C@ zhH&4}VhGP;SQ*XRdCl56gKgHywiFQB^%UCC3o<+Cj)=3$1)8kPDjlrz<-Q{EJU0?Z z@?t2n_343gI}4T)hjP7lQDmNOAw#y5ILlhH8Mcr>ql4GM=yZsqBFRy~3xI$Cm-&A7 z8-VC!fMn6#$msa2hv6{~jd70+A3WquXh!SvR(BcJe91&R+CoUbm2$>YQdR0APr!S= zVuDZQg7F#pcO_M-|I4zIOzq=#N~bnh?JAFZ=Ik|O5d{L?0(SCWbh|YA(5i8SR$O4K z?gAaRJ`_<+-`N4w5_!Boby`bA*SbsBuSkj3VFt#i%D?L0-qDb%-g)>Y}!j?jdWl&opL;r(VFFXLT z9DN!CKo80&iZLW&ZlyJ^(X4g|KM@?mJ4@mh-ZD0V@BvE8a-V5XuOEo_I%(cMxT%*M z_D19`5n(ghpcbcq1QE%|$WuEx$A>+G0eC+e(-Z-5{bF`@l;&OKyBRO?mW-wC$i>X& zZO@+)w(96+0B!DqC(Znw?a69XUOpYD)-DSAe(sB~c+0m)`3vnPDp`{seq2OO#3gaQWwLv>=&-pO7m^p+$p%glJ-b@hN{%5!_j`v`&{UGbnIi2TRX3QcAl14;8nO*7~RwciomggQ2@ zApRCw<!$hU zfn6=kYJ-eweT;Gq&Rq#jc1$w6&c1m4btpYaLKnCC1U~mAv>tpU)`7@8uPo2DUnVOL zzmU^AxP`RS#~CwJPx=4TmZV#gI;4|)F6p?6ui6TU^U^)_HRF~?XhgeDEo2m?*Vgvh zU63L;{^74sACCpwNMH6i1C69+skpH2Z>^->*JYnZqC}p~kopk%uq+DI5))ARIYTQ~ zLl{c zRIn2zu{)(bc0b*q*Nh$&Z{Ss1tXJ9dmmN*`_82E za|!c>b|J~gTZ6z5X?2(f?tPhLp&KVANYw(URR-aerB5aw_^?4dnyTOGDI?F7H_%_p z92nWs)eCsT%K8O4<9iNhYB}5`xKKHXOFVs9ez7p4ME@X=mD?G+)H*M@dX-Lh$|t-T zz`?^dwFb#zO&obC$Mc(lAa?MQZXEDtTzuj>=wd|X<+6|Y7V?Ev54AuK<$kf9=+5t; zuwQPgu2tddZU2F-KbDRJY6K6V}@ z5P#tpt3rb~k29x`--1lviOoAR=+?{KT_%yK zkR3vey&hTshUPvZ?jPxpk7uBu#V#4B7R>!yXK^%JkM9# z#q0a8#3x@l)<1Vpd(cU3bVJ|yIht5)4q(^_Fr{c+!VD_mDRv=Xoun(of9y=V#d^WJ ziNv9{6CN9xeqn2G=m)9(W!oKe$6ae>j7*-qt@86R91T1yGRhsZzz*3_6o$3-r$eWX zTs=8^qaJ%#%{C?d-eH_p{?UNeY_>DYb|YLQLA61OYT%|E<#4j-2vU2p(rZmgROH2KiH`R<^0#Zw=*Z+`8-pvT*Y1rX1+Z>BN0;jK@HAA;O? zo}1A_>g{3;XF6tmXlJ8{FfL2J^vy$=$FO!<(BwZ+GrX4eaYx89gT%FqyJT;+aZWo= zD&OULmF~G=&PRs$e%bld6_b4!5C8+a4(wmVp1$^}_@$}-oF3CNz-UM&LN`@B3$pu4w$oE6~ZgX`$;SCN>cq*S2X$Nf=^|ava^dEY6u)sAnPP)s}1_L+*Sv z{g*!q{>d9M;f1Uhx+@JXzx8mNKyC^*?SE4)hsA6-51o28bn1Tmgt=DqPp{2bRKjt( z0l#o_zNfB-hvFOnqbn1uP|41I+`vb`rR`)3tfwu1P%rpSdF0RhvU@tS9_Pl%mhyqH z)*e#+{SIe>?yQFvr7-Ft!wjk?6VhQ(E=`-6Nz*5aTZT5q(N%{<3UeZjWzi-JzG%Pa zh7a%c*5OVTLq-|mj*Q{a(HmzA#2Tb|i(#?>u*AC=>zEe?FZ~pE(9^BVbNiu-tbrS6 z#}4~1hibMD25=a+pkfu_XH5%lrtg}LF5TPGQ|=gA5g08e`#KLWJ4p=of3Qut;^9By z#pGYsE3qf{xHwmOx~&hYBUU1+eswlFmbN2`Mu&3Ozv3E7fA82c&Rf0)(2YMu=QMFNCWtO*-%NET2GUoZQ!8H zUggKs0ZHV~jwpsX|9{dQETxUW2mM239L!}9))=w1gI437#Nqwh52#2IZV{Dky|-D{ z&Ih?kxla8R<8S>0wVv{Ztc!zm-Q=4KFV<+++BSe_Zpy_8-zdeT}>C4Yov+>%)HkyZINb<4fD%b$uQ~1?bNV zL)b$Gic1)}{aY5sjyn|%;C$a1E$D}yWtdxd?zBf;N&!!8*rt78>!+i6&%R9ZWx!2D z@X<-Gi?DdFm#1@2p}yMI&)+NmO}Gu#xxHdoq8GeZ1GgC;$S}?wbeEG?Wgw$|D^mYY zCoaXK5Uy+z-pft&EK<_k|4p_t;Q1CgQRzb>PJ2lU6(HZBjtr(yp}zI)kFMy;rX7PaG;zx>E~Y z+sJc(&}}p4uUS6p<=E_fl>hjR&V>e#B8_MDi+kB;Tq<|oYB;!a@N(i<9mXXw)&AunMo;q^y{mql#2ZEgN|6ipbPOcP) z|9_PNjV4>~vtyNb&yxRFDe&j+_N^oCo^0~(ZoAj$967KKXYGB^^nXf0k07Kagl`f3 zGI_k}jPKcPr{qdOL`zT|dj8j|B9TE*N6ChOYwh#h&{Mivp9_7T7VIj3AWN@xJd-O0 z6&c#gmpyLm_@dlZYilv+y0^3mM^;+eXWdRp+GuNM}kWBDZu|9-5$ML>% zGOWPs8L|7_WBV<#*y_2?p^ct(z3g%AYaeT_6f`nlo^!5UME`U8Tl>{Zt3@7lhz~!j z?FOF@cAJJDr~b2d)$qKUEc^W-zuX7om>g@J5&x>|Wu`B!a+W!{^!KrE;13G;KPCac z;Pv}u-%LYuzdif$;&_sWeoQ_-(TU51eI7ftH;m#J8RhA=bICsz^J&L^RLe*lwxl@M zi?;C^Poi#d?fPtq!I5t}()9XLrcoO9_v}sssdJKj zc70oUQWff*%_?(W<_@`gs<^bMMg`SxNU<_=cv*h`;K8$DGQYGpC0y{AC1ZRLfhL+)}Hfc4S-nTyvQ2 zyZTUl12tw?a*4w9MHjZLL@hf8SfWyKrO$P4PcZi6+{JQ@o^<8Dw+bPA=#BZrbG~Nk zG2DcXaBYE1l-i!9wZ|a|tI)i*3dzRUC8am8clWI5^+5u!#+5?Fbyc{^`-2DzklU3Yl+0)$B?h z8O0^3LQ;8pLk@c`810a4$EC)G^t^MgNK1Ru=8IB`zo$5I5h)dGq75Is78E@)L{GfMb@%o?Uyz)fdM2>hO}^3) z-V_>n)LTR0mJ*w* z^h5q3h8y@<25YklCsJlVdS>>aggyW1Q3iL|reSe3RW+ASE#bEs8rT%?%Lzdx4xTmE z75n`9f>HO(^ERr=K&3EGJ->VY)MUJMIrT$x#I>&@&G<}C1Te{a(>EXIUsapNH?-r@(*6C1RGsLpk@=pd(*^~~zIqR87yTc4^ullVCpV*_od^F=E>z=b zZFHNofHW8sTGbqa&tWRr>AVbZ0ex{IOfM(EOdTRdha2JgyPNvgP7f?IZSof0czYG; z{HAS7jwkKb=szsm{?@J1@7cOZwG@sMEPJ1cjR}3WC&{mFk!^O`<+(=34eaut;XRp8 zT2AGBv8NkM#LkeHPQw`eW_Ta3&u*oSO=ck(+Dbkv7MyWD!}?cytAU3zqb})Ph?GBG zP3Dfz&nRTuo=3kjOH}Er zW4&SJ1YKxzI_fvYM1R|87^??Dg4D|urpyTjs-K6SM9eV{cAWdJ{Y`_WcF92}e>xhtI1g%mM>_p8 zI@SUA(8d-lLVyp>?ep7=h)G+k1X|}AZ_%&!*SARg{XxjHEFm8=oNhJ92j0S!g&oy5 z(9G5w_Azq&RQ&d_S>fD{^H#@g0=^p0rf;V+afh=gRgsA{>5uVS_rFWKE@2U}cSa1S zD|)&bUD23<$P`%Ke)}QjubY@e&-YiyB}cBrXjYjUx*)y)pXHOnD-Imussn{Mn z9c8uWb%Dr#MxE-xRbjIYUy2gd3BS~K<=Sn)XmVOlY@}MA;gC1 z&)#ph-AP7;joWzzs%r1wK%YF&$DmtJ*BNjd42ac&vnbGmPD}63jy=fFiLFeQEyw_}0P{>(1JH7oO-TXu}ZLdhcczLtIQtG>o5bQ)QL^(?p0S_IPq0PQC0&?_k-+`mT)mnf}>f ztT5oOw7cVac~z(9_CLN`Hy%GwU*`H41Jpdmj%}*gwGS1Nn&ZhJN>AiQ8~areyo$b#4pCQkF5JQZmkqNfHT0T5hQ2Fc4 zl;yJ!w`_yQKg!6nPmZmaZ_%Hr{P0dL{#eqQ&z(FoK{MSZ`!!Qw5G>!Ws1pwAuV0yb zz4!R%z1Rb$i7(C`KQJA0YA2SgPGiyIPpBP%?}Vi0ZdWAG?8T;_D)n!P8=p5HTLdzW zcqAw;8|&33MzHB&OWU=k&3lc4HT`f221%0#kJ<zM~lxyGihgxG$OuM`$lC%d;N7advibrVA3NkvC-9D`xpzm9B19%tiAV@Iq; zZxN?LM%YxcQXrE;6QrDY1jot+>x1jg2Tdm#3AfpAgU)5cQDvifW#hcENlqaJ5b5-zNUju2 zJD1Pk)EBRo;Xk1$#I&ucxcJ~=zvTEi0rn{t{gk)kRjRT*&FulV!hnvE0nq#K72`a+ z&>u>xJoJPR`(&{KJ5?!@qOv6Aw|Pk*APV#eeTR>|zgVeC$Gjk-Qx?mf04u0QM!{F0 z9eC{BMXp>;kcUNM`6YVuMxQ*uDH<4TSEcb!?DJskKB*dF(l}Rvo7e(r~jf)6a0Z%)wSUHxY*GAahHnnp{ z8W!`m22AH=9mYQ8WAHzf09uM-l3R>Ca@zyDN6-OANOyi#BI1{IL74;Ins z^=Nrae>xb;y1|1h*UH_B|H%wQMR}TjLLN3mz-ke&kCF9NUG<7p_28uwnaY|5Vo-pY z%13p`|3a}qSO)-ehu`qH9z9AsC0j&4pr8drq);}GU65j)24iN4m>Dj50FSy9tZ+gK z&%wj9NLZ@;&;Z1bD8i^qF}_WC8y9|9sIseSXS^I(PMNwFp(1I#X_Be>@c_T0{>oqU1h90bZed5j8BAB}A?A zl(I;Qn&6}4j=~utH1%sa1>a-@L?i@*$uEs_E`|+oywc4wsVui=fcjxc#T|JTQc^KZ z#LRIqPf3jrX$mwvoGVuFf3AX7WC;XbykVjaN*CQQscJ&AqEY>7fhGbL*y_7 z7Ck3Ki{vr|0MR8yzrKN)m!k>*%v~Y(p$OfF$8-?WRDP73bycRhv=8-hU*P?Rh_n-3 z&>k9QK_0m#w#bo(8PcU`l04*$d5TqhKvAGcVTD5UoD|(5gb`n!-SSWg*{sxjQDv8y zSSLiklA;Hs@aSN8w*>P>s`4~dvZTIhjbC}_kdv}-+vi{vV0LyuCBx25PySoEkArFIj2pNpO&oqSDD zI4Xg62Vf}y1?mckl|reKR=JLFH5gtaM864cd`?6)iI7S$$Yc03 zVkx@)7c2$V#Pn6}pebCUGz(ETFVVb?QL*3Vv2u{$k_g6@Dsd@To>b`!QQ@C$*kk@7 za}n?f0ER||?i0#~NsHy${&PO&fdV{5gnq`yJQFGe0ownOHD3+s`k$ilm)rYmQR%N# z@vB6kfqzaWI=692&+s!iRtU=pz9HgQ(j?HcG|cp3=P>|uVE*iuC(zp@OieH>hvt)j zh4KK`45#2U3H%6Ee1wSAD)TB#$973k*iTS%vc(1hc89Wt_1kL)iWMR~i|&Dum7C=C zny^s#DFPNew1_#@i2e;hKM~!!vdD(%-;UHD@ST#U-O>K*N`C7~gNtz6G?kyV2Rymp zSP_hhMJtw`J&J`k$~vChsB8xq*14D+0e zCbyz``Y=}(ae>>0z4O(}8{w(K$xG`>sUkRK5q9h(I8q9uN>Os;CE+4GfQEcZ5=;}3 zk?Z|(;YN-PloJJoi~V7wtJ!YKm>VdV4f^P!!fgs#&Y=v6u0538lS#V(;TT9rMIB!G z{x-}NA?#r-=}m4sT;G=Z9zDlL9l3BaRtla<0}o3uP5o%{Yt$M7a|+9jOPf3&r@mVb zGGJlo4Y1w(bBEI;+9AahfL(|bmL)~S{%SocxpTWrPMRR?`eCTjTMn_94k;{>j|jb} z{E&7Hri?yDLWyKVYzF`}AA{M5syzO|X~hgXO_D?2w_^cT4h8u8vw17-g(HyG*NFKmpwb1 zB`Fh2doGEPzXWrd&6o$mF36|a+e8HS7E0~Xh?u5ug?qXD7WQS6CIFzE^Ogsh!sJ9_ zyX0Dg5H;P7>f@py%IHpitm}qZzkByp$xq7uRLkXqgHole;Qt{s52OMvE#`+V*qQ?F zyLW4#Ty$*`T|)!qCW`KDP)WIkE!d)ZZ>|??1KS-8OI&>AwiT8vdIkC<*YxOapk)Pq3WpG@qr{{V7XE!1Hcn7g8K8n-@8_~EV|%;7B*`A10_pi+-)3f)Rf z0l;rkUk?)zA;HK6$-Q}^LNxasD)w$XO<|5-?P`V%+M;|^5iyOH9MbC=5~9%08(yqq zj|FJ}ga9lSWE~8?P@}blZW9J*kCc?9P)1{eA&w-l2^U;~MfXXNmjHtUi>PWVEYhmK ziCBMEGSfJKO=Bpm2Yv>1{g3w%V{69xp%$_Y7>N{p5YVpv2V^e$*{0{f=3d)Rf0$Ham=Qu zCRAKsYatOz<74K9SK5S7DrpETh9&S3Gr^ZO|5RG}^M<%V`QoWcsuflgd=q2UrTiP! z1DJ2Phb^1>7y$%q;7a#ldubAcjE|@xBI|;Yvf%r2EI2LGaZ096%)1+1dZNRiI2pV7^(S=|a|S=fpRxqJloHhb1B6-)_HhZ6Se`l)0s z|Lwr7xMR=+3VL%II!7jauln}UeoO4O+t}?1e?t>uo&G|Hb)oV$U#BOn6MRG@5m9#Q zihv3|umhU`fU$*WK#1iN_q}(jjeq~BoO9oe+_062P;PYGi#Ggz;Wc+om?(BTvi{9H zQdlq(*l@1S_T{!Z%lHANJm!3Xu0V&z`dQ3h*?U*lr_tncOmEf#d-d=qYag;Up=A9i ztZ42^ypfB~y2C{^@}Bu5a+8WAa`#&q~P4+)~_1lCQn#K)-^?c*>nHYmVd0e_h3?-vjzteJxh5u zr?^+plRL{B9K$1Ji^9X>Z|;0<_@6i%)O9g7-`R~%Zh0=!Ct(mmVn(YUU-K`Pw<8R#Hrp-> zSp7;YPY&;){fvozN%fZso_{J3#!J+#-lHw;nQv>%V*g&=7#lpIU-wB}qYVCtu7~FNqqhPi`q5 zVG{VwQ#^;Hb$FS>bL{1@5i7&%=rNj?Q~bf(Dw#b6&!a3R9Fjlf@KT632C;+-Z+(WJ z8ay$mOXpX?VxcnsHvQ7z`h%?mgO=2L4h~n6>k@Q7`)j8U{~l{B7)bQdj8VCmq8?6> z2mXVIUFVctS{9d}YJY8-!6*Wi0)(Rd2sAPrN0FR1Rt;Y{0VAn}6sfK41;PnJ084Y1 zh%E~}*l|2{!?x%reWwn+`D9XBu!|#R8VEg1b#oc?VXZWtKemOk^8&G#>AcgbIsP3r z2^D>l_pPMJdUQ`?agWQL=Ka_sg*E9-^fy}R79k%>jjJy%6=_y*9JNw|59^mCD{S*o zQf(6$F4(f;c8}fsJ8y7kK1FsOC3-xv<)4M8P|uywXGNI0Bd3;qdEnb@(HD( z7pr_4l->}FnG)d4MV3 z>s5ChXF*iZ@#|pR?Ky9==R~H^LSG>)FJA4ds7&LCMc|8Uj#G6N%K^PR>VaU?s7`Xz z5b$oJ3rCq;*HyNyUH*Wa_tZ}N6Xr9Hy(>-)*=o zkNQsaCgJ`c!tOns>Hm)(|IT9vhB>Q7%H+_T4=Hmdho+)AWzL7FIYyD$*pS0=YC?@7 zO0^scsWwAMHA0k%s8s4b9aXa5KELbwUDxmW{`38Jf4=s79j@o|alhR)b6xctsdkCd zrpWf0{`<+_pziKpwu}ShezYxO6l`=254gKyi}bwPLwWZh91ObFFc zA)HB)sVJA8H+hAvUarF-vhX&*QLz1t% zrB7WoY$$%MWd?oF*1z?erVAF3i%vLrQS+u^lhX`<>7dKda8P%57&wc`>wBzCzxpzK zUJQ4qG%6MG<`gze@)SR4t2AR=B>LgL(k+RtC#C=wt=IwM(YD`k^`8^c&UP^4d998VJ36Sk>8|c_d*O)x=iMVVvjiDP+ zBD7>p+*-<|U!!URT@ultUG9Qs!1{kmC2A1dPcf{Iw;&Jee5kylm~U_?RrU}bWYRAv zc{|n_F<||XsH0j!8P-OIcK2gAe&84f2aVlHuG?ZU5aRNJjQubW9Xp?=I@zGovIg0X zZGdN7GY+;Ly#l{4RX{r;*|I>V*pDQZ=_NH3PZUi!zgmd@-k>qV8M2IB&F>!VlDlvH zIc+%x6V-kR8N{pqd`kj=S+}XBhlm*4NWMim-8yPrYWaveo+xRYQ0FPPd0$%x%I{Ql z4HtSXc9-YfSig>Q(70%qMg{cb-m=FN98T)jo)?}U)pagR#o0^%gIO|XkDM)PcvfT} z%FF^INXszWdnP53%l*n-fPpRk%tBXUqhgVo3nBVj$Bpa;7 z=dpHYg&{nL1@;>ZI;E4X8Ph{DMERnvl#Zw#>Go84&S7YX=Ak6cI|m99)$~zXmr6}P zydg#grqY!z^76C?{xVaN(#*7nK6-Kvg{NP>nr5`&cm})58t2zaaR?VvURaUAOoryf zu&YtVI!D5yA%|ObZ>zlqKQp`@as3Fu*%4qO<1|x#Vu*OryfaKO&Tw(`g4zHMn_HMy zpcB>1Z<3bLqT>6|+7rJG&qci&i>v?2hX@}Nn-|_z)^?FxZy^a z^x)%-(yK26dak~5t_}kt1MTZhMOT;8BCnu&0Iu8kY_RM8)#nnbBc>6MpH=u~ONZK! zS?a2+3yN-&EfQ|lSmnkLo~ln#p<0b%MvnQB1i>29>Yj<*v5bpa3*r=fVIAbH zzo5K&(pt>ELA}>AL)OpF$Q>hIRB2XoR*40`4-U{(t`qa|kXRzsgn8AoK(@CFp_KAN za_{B+U&Rs5iyW034)RRSfIZ4YW1QC@RU!v;Nz!_Z1YgUU;X&2mli@631L}_0+v9pi zaiSc2ZAk3hvbe128anc~3iH%c@P{n3lQ99k0~7^KGm zSrQ;sL9i9x_4=>6S!1la(Jtq(76FE0;O2l1NE8$PGUG|BfnlOG(*FXu2j-fSn& z=e7QUr`WUy_JDMSeMSV`qbtUZE3o`}6$o0kBx> zYsk2U<V5qLS`6vsdGR^V6~Y^YyWGH_W|TdOffqtYv|aS zon+~#4$lcs(re1FET_P}%#@~bE7Pcz$1<3q_ zyJtmrUmhvkx=c6AkTJ!9=amM}lIpQ3_jZztmpk%uVr%Si=;S*(x_=qI)O=q6GiDej zO*NVl(J2w&3=^nTrcAgrt8IPHN1X3VX7rLbv4kZSGL41ZCjYHL_2zSRDBuG#ut80E zy&d^8=kfz-`F?n4%VMW%3xr54u@K$awuhw4EGyhJT4myCP(bjV%RID=G#wv) zBeKUXaJ3fu7f$3snp5&aT3pJn-f`eSb_78WQK4iRm?TjH=A}j-^UX^pu<|k*R8Ppd z9O&G;dM*PGPirYtI|sMxEn~4+e=M8?X>t%{jc65PQH-u8QM>O3>D0O~cv@cP7X zB@cLTtW+5F`ZN#=W0G0}GE*DuTQ3S-*`%n?*xiy>RcPzUfmA*R;W>1RHE>`ClUe{j zNq}3&86=AHMawFq1Xb2wkTh~v(OpU(*FDw>b|*kx$n=yr`}ehZF=A#cml@xEGZatn z`g=1qwk!=}9$o-FF5}6iQGF_pDjvLNZrLB*+yK z-P213A4}JJOHOSlKAI`8T4N{%Iv+9^vl^z`ujNI~Gm{J8SsYdzT9mbUD;@gSA~IY`Xkv&>QX!y&}m9b0DJ-PZY9_eID* zcq$p5LWR0m_XgsEBC4=|y{4hCwL=rWC5V(bZe9>{mcNysY>lkBW~0!2Y~=iKl`F*69W2 z&?cvR54P{%Nqj*@izaNYN@juY$4bH!26Nh@I7})Pd#3ZrU#*d|%e@lk>udk6Nv}&B zl$peVXT-9oYVdFhSl=RV4=FF{9OSlHkCgkSB+(_~sGWhIq)!^~ZZ^XK2WyzR5#Oyw zeonU_wM@Uv|NW-)zZuuP=(#HL;rH2x4-bw<6+k^{i)I{Z%wMEK#^Mct~5r@O#bb^teJDnfu{>OGOX-(F?W8va43~2tAk}} zGzZSWmK?)bvB6RK!Hn`ZnJv&sBU#DUWoERuOvbX2e>yw`&x#@D2a_EGIr+f_`8#U! z5rt4P0cx26^i^YSn}de5g(9r>Nr9y0=1l zK|uagAX+)R>QyWk>cjU@!GLu!xjAB59xnIVmybDXA8$NHDTwGk>6fgs9khXGr_L~T zud$?PhXJ19Q2>oygB>pj08eTB^OA{4D=^(AUq)tzTEE*%zB!RmU@@QfY^A6EVrSS| zn}&7=gOhK?W&~5Zg1hx7V(8d*Sk`lBr|+xxjs?`};=|q_71Ikzzu~_PSw~x#k;{3< z+hodT`tPI_-p{}8?Ghu&eg%s+J2)Tx_cSCVq zp~#Awuduz|AE#mBX_cUFs373$_x!hh$8d-B37=q3P}*^(86WCj5b^>j%p`aCKkMsj zB@Mp|$}}eA3kV1P{XWus-m^q+-p4045Lk&au%rCu__gz8BMU~q9(lV& zzR$L66m$MtU`k3E%sbDasRi)37L7A?*dJOWZ?9|9+Z)#S@`nzO(D$>#>irE5vl7Wn zwd1luhnWs+s8v~D>FVmaud8B={83ImtB{_9&fTL1^Pxdg#LPdv?9Kx1KUr_mx!Ap% zI**{MLXpYer{_xM3qppW9uzTzs0vww8?V8wsN&5Z?v8aTrT`hNaj**>8cwWTtM}jU zW}bhq()P(W%x!IQebSG|;~s5{&NlGZk02LXdCMa?4OYP&x_1l*vh!t60aa<0Z|ITc zr+aqtEct5zDN!NkYr(SI!-+YMwUSSmuWx6hr)zUZXG(M5J8p?Fm|fmHo1xXiWya$3 zlc{h?Y(`32x2?6?Q4YZI*YK0v_}FzaE0pr>VTtsq3tI)uSJAwW;$WWqHjNmAQj^mx zPHXUYSm1K274I~T{K#V-BHy~|GYUHzTe^ zcE-}Tb3ocN0NHLD^8a-uHuV57?gglsG&jdvhQ#N=99SyZLtPQy7L@MHkpCwtJEyg} z;x030%ETI=_q_nWoKOGpPK{b7131szrv`iUBfU_qERj9=J`fff%Q}9%aNEAmnU{Z^ z*e5es+pM`&IiBrw@I-;FlXZ3Mx)>%urU8#z%cD|R^-jw-yu+6cFIUa1l^m0mj6gFD zw~I1}aGF7C(Ba>4)~6Sb7Yry=5PriBQb9Ic7h=o&KD9eqYLE}(`aa7bPr#X2{xc&A zN5}VpF`i*W*{R#Ae5}UdVfr33zNgw6OU1oFmMgijPv(aF$tO~E!TPTosKAtQDKqH3 zPknFd#|?ew?k}Ntaul~+4|?|H&3)GY_7GKfzPg|Bb=0q-z&qR`@gcVAcX`x)ql3x! z@X!6xFFY!hj(@59`Jd9wggu!)b^(c+y;5GGCg|POko}EzvznnSG($Zhhd>4ZN@>DSj|G82V%iMb!t!}(t%U$c6 zme&$>9Q$u$_xjrV*{qsMIjU`H{x7{f!6p&ms{d}EaodvZT<(F7Q}XsYmTEG*Q-GSt z*NI&)_w^`hwJ5b)|Rqcddz%~VcqgPXYHv6;9e9Z41Jn(3u`l1dS@al1t|e`@4PC!eVktwpsgf=RQe;! znaGrAdSLxX3Esks?qgFFndFQ3@`SAR@j2iSHrhN4hT6rY_RA`|6UL!R?8{d&KY8;upVZ1CV%15{PZ(S$ zwXe$OcO)p4+KMC1+x*KsbmwVWX}XGZ$x`a1SywlxUZ-oU9iDHQJA6KHs?xOBdnO@h z(%#Kwu+ro{(FN;w;KSw6)5begE)|FU>v&{NT~{o%O8Ncwku&wKg`5DYX(#9V?`V^p zNp)UFsrl@8w;3O#k@yA>=P=;F8c9=A`ou`^^?*@K zvf5U(uCJHxkctzB%ewf)%WMRZT)AIX%Z5t?V-FDL+Z?dpXRGm#eT4gM7hfNg z@Qr=%h=*#YoV&k47JX!%tc}?}cL&2w7H76C-rqIVm1Uj$=tr5=OX|~OR<8%>BUT@X z7avtBJt`FqV$&`hvHP$VUK({8Xn4-IVR5pC^CBT7F#hpSR)C-OhfalK8=hs#r@xI=ux(d-@M7e& zOK+{rf4Yu@o?@Z;n3MvL?z8r;oWV;#GntLQRF19--Hyq+5u6v$X?Bd0$0zqH0rPGb z3|!ReAwGzhUPVtV>pDMv4g)<5+uj-+Yko<;#PU{dkwlvBm$K(Rs--mgK3ym4Cj?gl zQvnr9U}z+0D_Qjex2E)sYkhw1acbVYG`U!)DcxJty~N8saJNKHi@#uh?{}_j@d2Hs zO81vpEsxWNSZK$#xAyC-!g!7lcf-leQSP$x@fGKy$I1SC&#$sf`@&d9sP9z)NfrLh zt-a0d6zbR*1{(Z};&fY^O4!K8TblFpQw{P1O zpZ?4eY64F`w0{-;^k`*-M%S{d?T*$`ZH4@Br6l*EON#e?^0#XBwiFLLdo=r>^EmaK zT5Z{HE*p+&I`#8~hv9$Q#tl*%szaAUu_P{XFUDIlRT;s$piG#pxODHfOHpURU1%+lUq?7oOQGdoPpI>FmnV46jz_ zuPqN8jUzM`IIjBllHBIsj5aH_>XUg6sG}UP#!H&p!RL(0)!Dt9zR0k4?qJ+J#xAV9 zDsYXX>eyGggvpCIul>|p)vl(4m4h&pcRIVE*fE_nyK`G~yaR)KPc*TE^dDGV%0)Qw z8jz7}29_gLtt;J_fhGyoa80YB^6ml2{@DiSS3OtZwhnR^W#;B}!@Iv#$`?l$4Vlr$ zrGM8q^s$zxEyId^S2q|M(YENaE5Fe3U$l`UJa*0VXHDzd21^pNqAeZ(Plqh&86c-O z{g-!XV)yo~8gIEn*>}hL?wo(mmYv@Ftxp@<6$>tJX*pahTE*zAD_>xGd^}lwPT|`r zu-Y;WZf`~}p%^mMB$!e&?m{u~pOZ$_t9%LF1nqf1II(9o)#H}Q-JF_m1Yo0Il~2uA zWgAx?Qtq-;%$k@pQM>V$yLTiWC~F-VhCH;+Qr{5dDM*b%=?RUqU4qZ;ka^x)FFzZ5 z5iN(Bi;QfkD(tvBqkP;UCL1r2vK?ni3tAY|UAf^U7yHmL2g5NZFpWhE1SR4+;>OSm zSM%+kA9(CSXgtk;9j^wWqwOxv>sGp(ZiE%P?OP1l-c)pU(Z$=f*HJaZpXyOzpu2P> zRj2x$xus6?JFBholr-(%_AANHj(J6>OWa|C3*$1HSqodT0eSe;GsSU{$2Q^4c-<-f zbAFw)WP)_KVYAj(8U<)X{ktl}lmE!a+Bs=F<+^O!vC1;&3&Sw^1B3z~ilW9)7Yz?- zot>x(`F>2Nb;AvPDNL@msP{|3`d5Z5Q@Q$6KPHO(Sb2fUG=l``YykkX-lfkRGd(rn z90pb=wS6A>#zPU;-5exfwEXP|t7U$ZI_K1Oei*9S zb!NBa4b55HkYV2a;`kPVV7f{sm~+{!5r=XOJnv#EE!8_{?x;Yr?#KGi0}25|;HH9p zRSM`+OMp8mZ;AcDx_FI?f*Pn}=FKxyS0}W9^>$SNm zFOS}Orlndx_R_03Z^)-KpdM~$P=;y4^RFoen?&Xs4Jv7g9&8~9t%*Js1O|92ce5dj zDtcbPg3SfubN`mqG$N>Vw!9o zQ3fKl1B6oI!(x5Hc&s1q)o%}QRPhqn6LYsM$y<$;t@HaeXC_|tIjF2Sw7orOn=S$K z>>y_OV5?%GS!Awr@P%^!N-pL{Rh3x&TTPsH|}?g9|EA zWnC!a1z{!f?XjBf8$$OX7Lv`k9}}otk9B>SH zyusIjVDhsNg{m-Ipfgv9?<2~j^6m3zP(vCJ1=t6mIb(>?$&z>Q?>J44J$7`wy44)xVW z*+6U`5#7h%JU>u4|NcV@Ino-IjeEOQ_a z0ye_;tGc_XAqGs+3-^8(;6;uzP(-N>!x`hGZwQEu&)3dlm?wbEhkSgG6YCTem*D`3V;9r zC}PouQ?*q2SO)_KSkYgcrN3}Kx~lR8nh8M7V4!9y9EaPoy`bN49b~iwa<+N+eVDGb zcG2ixy~}glWnOM~4K|tXvNbFBI4n|nflyokj;v%6DYT3Q_oF^&HVNlUoQ&{v|K0;? zn=Ac!=d;^i9W4-SD#+EUysXXvE<6%QeG2uK$ZN3LYZLK%&*%1eIIC<3Z%ka~y?L~& zBqr4kqqanEdgW%D3a%kH)mgJi8$vmomzI4#wuCL0r-2tOV~k2JdzR{1nu1SOK`dgy zX3~s`h^|is>CV+@@db*(k`MN=+W{HxIC~-IlAG}>1?DTcXaL=kpmaET%f7kgv>NHt zq8Ug8NGgG;qD#|l^qq!IGB!=pxUT9FKz<#7PNl&}G$1t^Aii++gg&q`E~|3IIkoj# zEZ;sdSFu`fR6M34-uo^%c9R!~`e(SQxz3O;$oIK=ke92KATXps%rY5P93g(iOEvZt zR+`M_@Ns}K52{mrqDy);<8mO~-}Rc}{;Qd#mzQLt=o`W=R%w0L4b#8j| zGTqruXgJv~_gJ1obOZ++)+*njnFXd`hqApG2a62i>y2g=V@-=0)1zb3;Oyqk2-j1& zy9BvPD_cf(NSM*aG{X!h^JRgeR<2H`dvVsAFUxNQUU^oP!ku}o5BIv%R7anzYy(EV z1MpT}ijA)?T~6&2#MNIpXsoRX=*Q5ZcNK}FAez#rBZ_(^58GF&6DO%QFQp32CM7`h zSBT|(H>IK-@!J|^zjVyXowt{y=sI-}Upy-MptYT0giUR)$q?#NcyB*{GxF=#-*OtC znyXUA%bM&6FHV3Ef!K8?tf6!{f%0Bfg(#T$s;7LTN}UkK&c|Pf?~7I&S=mREPU^F+Cyh)eTY^y0%Wd+{Ry2o(uN3Y{2jkXh_&lc#JK^}fuXy>Zt`9o>q&4Z!`c1XI zt5^&4tkW!|fgH)EzlU=T@DNJ3&~h1A)bW% zWi5fS9mBRS9P{Euh{-<6{qJ$_(R=QgUSGke1#XT^6S{jpwfYWJn5AH)P(>a95v) z9((->bWn<7I4Gp%n#W!?7}ZHpomjQ|mF4*>=fJP9*T?Mc#%-FIvL5#MC@WGZu(FMD zvCabHr1xUR&ve@Y&!YFb4}UQuR;AR7l1g{iiCZe)YgSb9~tIqRT-COfSFR`(=Xx%KH#-MY1gjCV=^uZYy>)a>tu21HE?b za(M9PPm!J`)z`Ay$);OqINSzUz@`Jkj8hB;+i z#Th8oOEOq|U0j-lem}OYKghx9!IQ*{z_hrheY|Kx%`s4gDZ`)}f=lqQ$YU6;1=7DD zv^YO<5}bDRuG3ByDcvd)j%2Up^nV|PboO9Y7#x!eI~-K z@W>1e$k@TTL8%|j0_rAe-lEhr62}n`iE7NXV>sJ6dhf(HHh&`{&Rz_?+hKtM8CLHAOG( zB1y!Tuh!7)(B|KI8i($Qk745aJgBPHk$Yu}E!sKGn^FnDi^a`=Jc9wChvCf@128oqfIIl+?Ix2i5bId6~$NQKaf0Yk^}fvsoe-1RMQt$_u#ivSVV)y$QO_PgGHMSO8*sWvO zAxyzL&7-{^-fcO0MeswDQeMci&wpGuHWe{4I5uUqgl8zFO@uW+yMFJ3Ujy}CVRW^_ z(sJQc@^6dE?N97Jd6hcsmCU--QkU+kXa;ww57`}@CQrxs9jZiv9IJ`UJ9`h6J0eB8m&H*A{}2R;em_Xa_48`T;IhWuKv zh(BWVRM~d3&eHLxw6*uShe1z{Ew{cmy7O2iS#IuQ&wa18FM{`pGvbk*uh&1O{M}gp zF?;Mn=#Q6W_wPJ?d&BrilTh zbCJE|$$dWJ?WD>y;{hyfkFoB1lJEBdZoHlDxu^1OlUA7e?CUO?rF*`rw>ls-8!kxXo)y|P|?Iz z_Z8;F_~e43Ti>?xWQx%c`Kl?jTcbV5`s4l^<?h*$E z1uq15zd4-1ZiU;MJ0CC*V9#ds=oe}FIS?0k4_G z)}+EtVcXQ%rTxcO73{WFHaSyADmwyfu)dw+{w}Lk4-SamZJtK^Wn0WNl{`|H|6cwN zGaetR%z5zV)@RXh^uxqoFQruV@wfvoC4E+hv>D%>6nrQD{R(rlCSS-_Ow9dMHYumP z=H@UQzqY_E9BI7u?Z+SC2^*fS!qx7BJ4J4&w;gDY6ST$gv|c( zm^Odn&)N6>@PM+O^W`!_MbOSm;Lk#923Iep&1-~;#-?iS<+j?1GX|^389_UD5JTZUA?j|7Ny<~7g`T| z>_+bVzFHLSZ)umCw-X6VDA0r|I{x=hnDf+;Lu5l-_w3p3bu#I245()ZH&(1|_wC6a z*MRc(%UAuLm@Z*=#Ep!d@l2wAAIqNmI#S?{Dnqt5Iqi9Nn_;N9^<$x`U_(b4dCSx& z{KTgBUJ+hQLJ`}vP{-SJNC9=8WPD;*v{%N(%jFbBKiLUvLUW4(tzq=|4%zMs9L!4wpI^cWcBY~kUy$X42#D?I?jnyG{E& zB6fduhg*5`Qduw1%eg^yOA#Vo`)1wJWa{Pa+NizS_Ua$J)GUY>t_GxCy>A(MRFufSKY<~$s)Z-_$`J)T{zggo7PhqalB|EB`e)Xeg9BFuKa@B_g zI;-9Gm6o*aA&2j1&D*xOOmDTQ`})&oU7NSrc(x>jceUq@apHISa+RmqQ31ugr^n)U zEc?2@&#S$e*0D+OsU}0sFj7*e5`E$1*1dgEx1KdeTKQ7v4okFyW{Q?69 zkWA!iKyH$Qyp-Oahh*C4Y#=J&$@d4M44lQo}Yi+L;_nf^LZlkO^Q~+CjqFg8Lq!T_~EKY6b zpc_qe@(ZoZj;w@CK6qy-^piyU9q~{wUjwHrWQ=7PyZfudVP{d@BT-@7{$^YxBpWTk z$3s48sXkhE-PJq(&1L89#@mO$AX_8)t0T0ZtsOX=cp_6yR&IBC$goTxuI{iqhPWxd zd~(P5wPugTBHCN>f05(-+s_(p(J=cvJ8{jT z^YXuQfGFnFL9pgc~lc`>J}EulX?{`gz{YrB`) z7cy^zi&LIJ>b3PA1fk;J7B}wNy>;Ak=;`GznERE-5bd-f`*S`&9*NeeZ#5svAFW2k zQ15;^_xps?)T23&Vt0;xg0qi%;Uh{=QuM3d-eYt0$GYTW#EA8uD|EPaM;9 zwb4Px#O@ZOXNT-{|3imPIxG-9?B?eFGK{<5Yu1T$f0vIreSNvcl&nF+<#JaXZc(iN_;T)F0(zIh3|fGhu_oxb*QeCiVwkg= z$|O1FZ?;s=r)s}LOK8#@A6lA|ml^;a7-SkPB!v`+*x;N(F4jBP1eOa2TR~9&uGH&yi-S0W#O6 zz1J8dl?`pXd}8>g3qz_Guu%f8Ob`!#fsGsxqXIKdK9Q#A38)b4&H@;t&a6+8K_1$UZ3`po0#boS@O36EfyV$Q%+pP1^P@)d5KG1LC9=H>E;%)tH%- zJ(9Bu9H=y}j(iG03n{WuB6yRu3>_o)f=V05W$)KRPmqvL#K=&buXpDm&*5W3Vw6&Y zOT{m=w9x$)84Wf;zi>m(ish$pNU6X;;YwWyI=&Pl}OMR4A2%n4`%_ z#OQm=r=JqgnRv8x#`Xz7h9rhsJuS+3cT(K}mCiwT4`XilV?#;Ex4bky55+iy{+w}Q zl92frgJcsR0RYtOJcRPigc)3>T!Za#DZ;_Fz5HPZ=CpU${W*Xl_%uuBG8N6XO=Hjh@`$PT5EC&-n}CpJuP@BN?MaB0HTfZ8DLkw+qe3Qvn=JMF zd;#!E50n7FWCNfyS{V$F2$1k#AOS4(7qo&}6e|l0r3U%q0A#!qdTJic*Tag;px31a0zt-JaKU8$LKBg8VGZs? zLEM5PsST&DO~<@Rflx)zc3No#50cGpkWdg(rC@X5acLYjnTVPqpiUA?Ic(HFD@CCg z-X*epGLL8!XIiYnq!VZ>>Clsa<4?Ho1C%%yF~|}FYQk`505VSV2+@2-3kht;a z7>SKpf*9ICE3F1VPqG_k0mzW~23?zSKEFg7(2tr&(o`?#D4=p^<&ogib$q20+_Ouq zDHnMqBLJA_z=bRgP%}ZUf`w*~AUC;b6Ewt5uICW}=d0j+C>0X*`_f(2>Z(BWBoE!r zZ_w>&3Lzk;aOj5snG1xAx;N2$icHJLO+X&T`8EbZ#xwztcSwpxCK+gj%hF8t5C;8} z)*6CwcERLqryAaV zl&4(u%si?^B-;Z(^@`V|Ldd| z!=7-_lQi@_p76yk%o-9kdm?Aq{hne2`h9JMEU;E61!f3?XC9uBkdPk?Fnd zmaRQ$Al>4tAOZThLnXRONqrg3SFh?%j(=6ui7pL+l5T@pA)&hn;<+fmRnFNwicT;3_~~0+5%E;r82&txB(>A!g7{ zUV@STf|LKigKHCa?&N{+1eAn`E}1`rzpB&$fJzmeA`E&n>K>I~U@8Rn)PlETkW+x+ zaVi8)JUPE6Yrxg3oQqGO^np8JO*CP%7=d^=fA5K@UzliJOxaoK-`Fkd zJ3fv>_qCv35ag0G9=MSa*Kx>ZQkSasgfb8y;{cG)1>K*Q1K*V6l+2=%CXD{cKS=`1LK<*>3ugEzlJMRTs4&1N+8lOcbO$;T-F+{-0Vo>iPxxdTE=T{m90OW<+ zr~w{JyB5{M??fgQczI^Y-h@yn2)p0%PjLt>2LnrDzk~=L+>L&eh;pHUt`gDS&txsw zmszp0Cy2-I4V@oIgW6-D#GaR9B;h#n%c zMJ#)PFWbnMJraOqEw?~IKb&vph+)k* z#D9BaITC;@2Zu~|pJB-^q8s4Z#PdElRddm0dwdqe0qMp=zIZQqD29_nF;dEFCm$RT zGzZB2{Msz`$rX=p`El|bZ3%Z~?d!3#`d$)iZ;kK!7F|m>?LGxj-@oKuzRml*bItxH z4@(-#XmV|k-I61?^7haEX!YB1ljYYkh0)$_)}j7k6}LvP8?O;SFd$o#Cq!Y>cwGsJ-LQ;%{P&V z%H0C=R%mXxMmlBYqDBn3sqyK`T<;KCIHQs77TvfCmlZhg#w$ zZ(R@Rr9L^;aOHq5QqQ+Nx@X5=Yvb_Nlb>HdxDYDYD2+0w|Av>^Zy%Sz5JvHg5@Vg` z7ZqHl$q}k?yw>eC+zs{kt(HZmP3PjQH4Hdm1z|g`7+;sh)k@|?GF6E@g_d(U&8^l;;8!^YTa%oP&VMI*dr;oXJAQD41HX_Eo)dexi{OC=UK^}LGx zcHw92kKKn_%~dHzE^d*Gu7Qf3wOb(-r?In(r@4HZW3Lr9;O*I*Qvt5rsE=x+_UHvb zgkr31IZVar57|lKU~$sh(^%GyUl)=?Wc6y}@B_?q_VF@0r;E$qwkRE<)ihO;z4YHI z`53lC*t<6Xtr8q(Hzrj*Db{A>Nsv$Ffz z$s@k-3wiVXi_5?Vb@0)x4~l78?zK5{ti1iJ##*%XjStg=OwOEM+pb{aTFQ>KL72+M zM=FLOEokB=L`9zcnAe1(vsF78P|e<(b4^-DHpYq{?Qrt@a4sP;aN(ju8#fy3XWs9l zV1I+xYFAR&wmWPt-(P72srB#X;p~K%+Om4Sh}D+Uw0kjl*mhQ? zHGA9DkldFXC)=N;sae-FiE{UCZ^&SxeIQcJfCRLSJy`ERZWP8H@h0hw2;uKvj}8oW zGtO;qvQHRNZNLtj?64{fN=`DWS>f1{DGaaldd+voo*mlgEE^vh)cMZ6?{y`x=(G@$ zs@a3y_HsqxpV~G}Mmz>{hzv3P>+bbvX;2|iuzCItNZvM3wmeD#(Hx~~!k>)VG|>u6 z%&+gW8a<7Sw<@_zVPsuq@V#tV@;mAbLp8F7J(neHhtK)}43WDU-KcRs`*Fp^^+zj4 zFqorI#v*v0Y3l5%Oq!lUxZ^w$Zt4S=@1X7q5AJ-W4kMQkt#O<)O5Yn}MZ6QKKFwwS z;Wu(D1#`#FJ7RE~n-uFLTePjE4@RIJQ~BbUexGUjw?qnt(B5ij@#KAZ< zZm*pm(@y7ck7!Nju&v_CP$2>u+|&KBSE#Zqkpfn&ZiZm?Tb<6#8q!u^Ex8}4KTWwq z!G^yaQ9EB%el$6wKs(`n?9J|*@e|-8%@A)Vqu||H-Ghaac!E7_`Hf7Gcw znq@mJM3x>C4(c43h?UykTro<k8L(vce9&isIg_U zw>8g7!P4GVtD+k$mqV?y*I+okAb4BwNely(I#kDPu-3w?Ke4vCS35G`{iZ3+54(Qq zZCM3xKGi-QpX(j67+-C$@7nwmI~5(msTGI%m7*ZDoBW=&{2}efWt(0-z3-xiWS+hS zb7~yM=A{hjiGlwuPJ8RsKAf!IzF=j4=Fo~>kFAk@$4c?`T9o^hr<`v)S6<{9v0AFQ zaq1f~>@4Ja(vvZ|Ho3pT*TPVPAyC6Pm(5IeI?~RpS)@NVRhrLitP8ie@7OJ4ihfDttfB4-!P}`>hGVQSuRtZR2zZ%Y0Yh#*NuVKy$yEM!K~<~NCrKyM zwa3=;oo^v^pe{?BVMqbre#58SFdu&Eb~v$HI=k#b*GWF&h|+mK>t($^5Lpu*iSSH! zD?JB-NN<5(%(}3-!;%B}u0V;WwRS-DhrlR~@2wV}KO=eUu#6JtlztWQ0$Xng9WF7-;_(@b>T}Dej_I>TgsyvEk{*eQDRW z8U&RH|4|~kZM74$YnZ%@)*2G#t48=^4)8+NyLb~ZLqC3QsWUiA1$kM-yB39vg4H5I zJ(rwsw8vJCx3(Pb*Yc_>N=ZL(H9q3mHan%X9KXG93f}m*k1Hkym$>hF8|-D_I0eTg zOZ!n4jyaO8$i;=Rwy-oVL)ZT{n@}04RQKI$>!Qr9Nzihm=3B%`ms9;QplFRDZmAoX z`HpBdfS*oZ`-f+Rj+T9>;qO#zl{=NcMF_^-9%WgcQbgbU*8ta}!4AX2j>O}$5cwG- zR#U^}%M9nr^zEl{`57X_%o9Ya5LTg7{4-iPL1an(F5K;oM1E!;roa+&%Ch3~)6&^T zA!p3p;A!IK?Jqc@RcN#TUUvL;Dc8JY6-6S_3Y%e|Wdu!(z_q|qsW5vn{h@|HQ^*V< zK>^+26RnHMKdgm(o-84jg{?7bNv9+&+3dVxwq6ejOkqn1gxumgz zEm%1pJ}aK2)xAQnl&iD|((0LV{3qSC%NI@)!BWMrlyaEoQZ)$K;k>HH#k8+P9-+bc-&B2e)cT;Fy3^XF^V7g)VnV?`;ich{YJICB&!0t3w;rId~HmhY^bP2Zx zch|mY-OQ+&Vzdw-jwBcTMlQFxNMlYmM8x*_f%pL_&0H$Z!kg^%Dcs>Sya$cEK98_4 zLLP`|4i~C~@S%xIHHl)c08`Zxq2(?cr1c4QEEb*ITzqtit*Widl|=>@<)5m7_t+F9 z^Vz;Rg(klz#9W`|&hP#F=ctVaXv1PZ&O$Dz}v^e==R)_f;~z*=f& z=Ko>r5HakUOSi;>4aM4qz{hz3w~7d0c-)W zFKn30yLCM1L74bb2o@UST(L-neE_v45O-TEBSD+1I#KXcArpw+EBLmjD{9?X=N#qc zpDHk@0$S>1W~5LhsAXrO_Q1DzO@Gl{>m|BtGem_Xqqz!A2xcFqvhV;c&VdaJWL3mH z#yqe|cdOhCq9XbpynNLdE89@m&9-gvxxEl_#f{ z9{Cd4F(Co8;JsYQxnK>torIN`&RR6B)x-+IXYq%5P^(bZVV;*KNrp7q<3fVE6AGP- zjGKDsKyKHH#|RFeDiP7OxKzw)KB{{v{58rR#MqGoGk;a_&tpW?`FNcxCaJm_IvBx_;x%^H|ja5q8?8&IAlCNJ#hdZ1pQ4iw)M< zF`y}FLVSK`H@%-$r;4CQP}yZyS=y^Iz&UfA2ul1-D}H?j`MQrX%JNnOBr(-K99a_g zX&#l9hjY{<&~#VxVIoBMYlP-sxI8DY;r-LbF5H!1h@YbxDFOeF_5Rb_o*9Qe8z*>x zpYp=^tQ}Zx@F>d_#Bi28D}VKvI|@s!YVBzCGczIu+Opz>q4oa5Tem+cBON%#5F*y| z!^B=uOALt0;AxR%#ClsfVe27u*E0>Kp*1Hs+Nca6rtiC621o&X*ol0t{|ezp`0Sn^ z2vDzykI&w3bC+Ivgqt>s&9JOk63Y@nHxo7HA;1w-*kN9Mo*OiT$21S7N!1Z_OM<4) zF_j3%`=OMHbIL$%p6QBXCZL!kimcbH?0z5CAr3?p`!cUNu*C6Y!@kf<50M|{3WJ60 zqDqrVAA^`LKCgc_bCo=%K;fKLc2Kju_D5MyANA{|$n&odDcoX@g~u{SXJFqtyLC+K zK3`d8-h!zWxQ`z!#b3^AW})PO-z1w{K^l17S-HecB@Ko7S0{=X*N?qIY&3G6AO4;0 z&J;hMtt@+gjqOW0ZQv39{xdtq5is!3pT4A9^1!;YGP9nn*qjhQ0nLzLjLoJmqU6qB zW$q1S1>sn`C4POib+ID6!dO$vXj`5DsxAiAeK}OJ3MwUrO63u6we~qxZB^-8)`KVR z!n^IS>^)GbU73v_TMol~R_V?JhJy&=Bq?>sVJ8ommW$cp0P(iw*?Ds2xaRYC@;D;Y z3jS=SN=(USRfUNGfe&kk$aD91go1g&*IpI>kCxBZ7}wX}iOn%pIn|TR_bP;4IZIk@ zisv#p;?p^03C+wjpRKI(5kVoHhPb9YKr49#67fGD5-Fq`6Uc!^fY=dum~9KYU3oAA zJ9unQ%Zad-K)+6p4&h!d6TLbS7W?7!(iCTLgQ(nJFz|lZl=(c3 z0FU6ovK?c(>k=!P6O0q{BZTZ6@)qeog!}}b>L8@3NBg4sF$h7-l5;LdCMcK$pLHLj zn{#9WR@phbZnq}RQfzFwiyX+S*-Qy69??rA2U-HO!_PO|)i*iM5RI%4?T3=^=b8#l z)rn%T2?6523Qb+Dn8sd;V?$JygOr zY8}T_8zc+eyfU}P*dF#I^{V~({C5>t2&;Z+Y%Sp|H+-F4pM?qeutZ#bEFc1UG28OD zZe|g&EL$*%fF*O`t5Ew0AK2aaJ{k@YKUx(dW|+?!rYR3R`W+U#GF&2xEQ!}_3UTxA z{#GK|e8qi_Qt9^A$x3O4kR3{7wv2*_prr4o(tiBnXnf&xZVK&u!|8nXJ*InkfXBgA3`tUyD{|d|D1%|D4NkiK+(WU0pZ z67BKte3x0-&6^7z=3L$}mGN*Dy|T(mL zzJX#l^I$Vq57-pyU0I^*y`ifTSQ$%0I_U3Z@dWl2lblcNaivXfq48jin~>8(4jm8Z9-6HNVrA%9HO*Ijc;X2Iq;IqT_ZB{@_lJfz6QvG{<~X%IsS zP9ADh?#T%~g6P!q}1A9YO*APC9PHp&xD%PB)2XTY~|TL_yX(d1KmnFt2M zb(KjW3euO9(|l|NR9N!pa0<>Vb(Mkta>dpd`E^s+u@h`y^$wM=K1Y4I4(H^(>i%mM z4>Z)$q2pCsIjL%uzFnEESN0I$Fs7!%hTr8$ZF}HM)Z&k)*?x-vsyqxypO1j+N`I_d zd7@|fV(ul@{eJEfs6hycbNjT3JOdo2{YYMWob~X`mZ^~xo6(0_y?G(hl25-<4xTrU z*hn$e8umh~gkRWK@hffSW*WwB^6zs|m@TDxA?zdg!$Uw!j4rqOo^~21-3&9vzapnI z-zjRFXeIYApx;lNbvW|%^V*TPej4UR$ai*$vdKx}U(I~W3%9eS&$Zi{+No8^TIJA{Vh||P`!A_Oh;)+U#*J#;L*Bd>` z3dvuZD^M5$lQQ6fa}+Ad)b#)N2#mtT2wlI$j*O^=1eXI244?0>T^

(3=_PZ)jK8 zNo9YXz~nMd^@uFmm`jiB9x`#$UwXj)MZ)whr>dC#5ts0+_F)&P{T=Fn(l~bSF4xHy zT_VSnvla5rGwXCD6T~{y~hwb5PL7yP8#qCoUAKqFM-`y1nnh2p&M1-(FJkvvvI2@X-Dp z`ulwq-`@vEH2d{`cw&c!qPY&Q8r@MUFsJt(7~A!VVO!~pKSS9*@upLNBP8>Cv00jj zl~_}n-otK0$Sikg#1-q0Xv9slcScHa)mf1N(fhfN1N7p=+U&8qDIE9sUpsN}uP{+U z;4a!uyBS`?oMVC%a>X<-CTuxA&9TgXYsgb}z}C>}x{N;3yUnk3yFQ0v?6&M??6mCZ z{#Ia|w;Ft3_W)V48}vsLuLpwV9IA(s;s%SA-9a4@hhJt+KXmRlm89rp3)|0{wq0`@ zw;mJRLU*3i;Qs3hSwL-zuZf-{z|w4u?*}tZmO**P?pYzsH6&+t@XnIxPWA#?lAbkP`D(4p5jD=t&2E*CJ+5N9dD9 zp(2#sN|Vp!L#!4%^6o^c_2bw!x%%d>V<1|uNy9*cw|lB~S>p?l<2}$`-oBPh)%?gX zADF}ZyBDI>CT3`Z2=HQ>%;tjvsw<3NmTUJ3PRjI3ZzC4BYR6c<2p#RQAHZY_Wk7$< z7Gt-5pvvbqdC1~P9d|Zu^S-OUxjfYU(GS}eyJ?zo1J%RCA0XNNqf!T)M#bG(n%l$X z)FoJvqrk1$fZFdDPIp6Z(C8L>8Cp-5*bV|$E~qYAqiYHBedAZn!S{;s)N+XSEVnbS zwl0Y$GcDu0cA4RiiI1Y<&7)2Iq|AvZjiFWe<{RlO-*`iZw_HyZF%ef>XGIJbdTre{ zulNtB0lhV5E@pv`2%n~_b;g&QW{zHZTN!sQ0u+TEOyGiEeS(XrBdVuCEDOQmU5GKY zZ6-Fu&RM5xBeorKg@LHV0CsJp(Fd6xxyD{Eil3Gdrybv zA?pQKG8vYbZm9KEGU6~0cp6j{jRhP>ppNeylik=7#ghphbu9%jYY9An79uRJ+V zU);YV++BTtS@BQNJnBHspe^DXCL-C@cA#e;1(=WehyO103jt1^O(#F#E1vzkdC;v$ zgLffg>d?bbH)0!+X^NK0$WKTfb-!^sW3L|*_LjhLUNRk;0PW^)OTo)H9r2nJVB=rX zV6|%BN_PB!`bYa3$%%<2xBfyjtBIa=DoUrlJR%K6=+7}Cj>$#eD@{$i-bd`Y`f}HA zmFR;+PiuA=Iy6fkmCj=aR+dAj5U?u|IShyL@1;5G1}NxHwExxynMbk|(3TK4*Ln#o zKV^ZG@p?48%Ked9+tIE=o&@iEw>5T_xcMvwCr8Nc=i=^Apgt!7t&$bfCFZ8qJL1r! z&`)1<^j6_)oxL>=^4BD@rqxBA0@PMP7X0L;-FT1^9c#G{~je?ay8VhpOwoF^RsX0rfZ`=Eu1KO z0@6nesOE?eM}iB?GVZq3en`e{P5Rw;oZWoDrYS$o=%`Ku{)Z=uzGO$y&??cT8@v6w z`QVs+AkR{2-+g;L!9J@_Wem^0-8}?L0A`WyZqI(y#xL5Ze_!ha=+mvgev=^c*=L>z zb(*}}Jbkog67HL?y;nQ+U+3ik7|mThYVI_>(NH~*Q&^|a8ki9BC;Y{)NnKg?LiFxU zZ&5C55wx2|QT!9?$?=J{S?^N!loh8Z zg`b03NMpv^C{#{P>KWsw?vOWx)q4DwbQsS|tZ(mQt@WPcsYuLtetmkbxq1UV?{fXm z_5Qm`M;u1B9J&XKTR4w%Ud%l3_eRN`hwkd(c$=IfrJ2K902}3-zmVYvgbg`mG?kR^ zE&KL51OFSPTg)>XJyfOfpdY#2!)K{|3ov^>{NK{XuvV{x9lNky<0km6IGJW}ZI^T7 zppie#?crNj+vhGIAt+Z-22m!H8wgsLm&v&RzM%c8s=s2dD&AiPr{apid7wc9F&XYo z*W46I12#r1dx0y)pGob$i2iH#T=wm!)BFLqITlAEm%l+ttvBaa-2?$}X-l;Q#-N!3Db! zb2T?;GTJ}z)m9MgA86gP!1=kmb0=UlKBozr|KKa9AAl9bxTd!bnmD?uNvP{8{VoK$ zTRg*|(%qCKqlE)+o(5Y@58#u>viWuR(@_v43>W5VxH@3DPB#ar*gG^UBk{(onS@H% zNEXdpGG{N4(GJf4QD#8=x|d)eE0f{oEOfUR@&WKu`Ivs-Z9C$jfHi}F_S8uZ2Oc`8 z@?Z(F4GwNQ_xzMK7Y-1XX#3k`tg_r+`V8t7Lp9f?UDoMan;B-oQVs3(d56V!5X?K` zqOTs=eJjpgW1WOGcU7yD3HV5NV505jL-mq%>^{@0Wyuc94W2iqRdZ?P#6c}3B=4GQ z(`PSR5M6kuVYeq^YZikTxZruyX!p+sFIm8c;I_>XQcQBy$?8{Ghp42xdH)sT`6Pq| z!wt;1zCo;bQ0qk6e$xzs~Umk}3;GIKm=IL~Uuzn?=E8R^eywbO7GLEE|_VK~CvrNnB zezniF$I^M9Y z2#ePpn*1Uo2V)#*Y;uj??}~OeNq-ldG8E!=8GK=iqVib%nycQ>z!o2f(Md?|rePPd zyU|m(tuYY1r2a^`NuJVl&dH0($q@U`UT&SfcCwI)^}%Nzhx1_XC=VC4Ky<=_TU_iJ z(yI|$z*_-gY}*Ere;v(WFYSu;Iy&vDvu)6k2R7o-O+oJL#6jCvK6Y4!`Chu`9S)~_ z{ub-KZZ6#l|N3kt#5osYKNL1UF=#D#NXuRzRNS}}Cv??myqxgE|JbyvVfX#rB=9Ex z0bL6Gw0(=_*JeQBY(;V3@-t|Doo-4*n#j7_IFPBJwLC)v%ci&fA|7BNF@qR zL16XI#vdhrY13Y?k*%8{+D&J|bW1f&Xrx~M>o8%t#mk%^^K&BG zobWen3>4Nl06MHTJ~Vn*cepe&lgS^HhVklR@}{&IC6T?|K;W+jY*9tHB+ICR)0# zKCcQWMA!W80;1aSPp(wqj*gbZ68(Dt^cZnU=A1uGpn9C z+WxLnTlvUv%a4qQrdE2&Hz!^sEj&116wu>#_J>QG$?k8gOy=fSBEh+)3lqd6pSk4f zrK8|W|BbxpeD0O-_t(vpOZ|#oW66KI$MUxQxc4_BW-W7~<%?U!r#rWk>DsN{Qkmar zJ^vMZA3{wi#`sPf2KbcTD}R;jZ{iO7CO&ab`tZ?n%*eUm%WH?HRDiEdq_F3`DpR?k z#r{C5yX5{w8m_t$=Q{qgX+|*`TBeun@$}4`+p>?eWgKlz?uB zYSJH!kwKu{4i(Q+C{-EOvBa89FO-}na0?Z>rd`Z^;P-Z~lU%iBF1hdB+(-#4x47jI zd9d0k&|B+5ukXkHuOr>JEhbz(+?Nqt2VtzxP~;U=0FRAWw~14Ou6Tz zxgprRhmoJLXqSfrDoc8pGCYJemSVhz*S!T?gHnkib#9p5~tCZg9)PFGT8GThv!AYe{ zz4M^t_kk9wJxnooWK(Fg$}yb;atC4s8*z;EW*Xm&8JJPd^KLe?jDqSYCVQ+|1R9hy zI4OGEGW-3f^j>LDfyod)HZtQ5>&qpprawxy|Mneys`>0l!P;`z7-{*Z`8C;}Jje+r z!N_J0d6O7(Z{f`_?Yv>D;aL~aGjwLy9+Ky*=k@AmZ&m#q9}F_GorhX6K#RP=y%Tv7 zd&;_eAGza6_fJq38oTg`7vUA(&E%nX_arFqb zkCFO2nR|Jf%XrR&d~W5H&m?TahM_m^aw`y+vK;@Et*1m))p>TzS%%(ad$QW$$gp?r z0jbKhcd|VWB{!TorCTd`c=>nA0qvC=U)1)&*N^4vYR#wy7Qe74{sn#=J~(*d%xYN- zguTx5!bB2Z3taV1{*!3vOztkyzo;AJlKxzEQSUFM@xxm!wau?@JI7_HgdacmDX>!g zzx@@TpK$*8sQ2BUDBZQMZuIMeavVX{jB0=EnakeTO0#_*$qE&UzOZ1@J0^lAx2_{aZ6bn2m7`sX8vPVpPK%A(f_&ADP#jnP9WhRY+AKrlS%@s_e8IeoU{g3$s?j}^Y z*lnhXEUPglGK9Q}#8^Pi5T?!YrQ&lcecxDDl9NoYwe+PaKQLGmXn`(0L!5%tp%gt5h%yAlDGs>^~r!At|<4BKtgJwkz*Mcxr;-R$Q&L8&P z3iI+fba2|0;=pp=|Jdw@E0z;A$T#F$l|a@SNo`n5B|6hpucI+mfM`hRy1WHt^tRGD zy2U_HURHAOy~~cV2fC+koNTJRl&5Ly&1$wbTNsZ@{r2CP^CuPMl2w|92UH(2vuGs; zc;~%5i~?eHy@S_U-h>S#bPr}--ClIH!4UdwES1jO?3dHzq@yggPqZ8HyeF%j7TSVwoxzgMphzUF`}&cG?ji2 zP5b@(ju2exrqVo%xuiN3HXn8PhB!-K&b~_X*zr~2bD>!~1_{=@9$KLu^f|=h^{1d( z%C&E3FEaH!hq7C}=4-NRz50~;PDwQPmL{_rbzB_tQLcPQ+W4WM!bT~@?rQmI*^X_p zNDB{af?)EvcR@xgV)3!qv+2@q7nLJ=iEFUS0jZI<^!hLQU!4y6{Ozcb<)sg4+cO_` zwb0S^`4d0As{#TPTgBD>hA26P8@jVTl8_y^+HapTzGIs z^8CT>?-@>;;Kl{ZK?k^h9~%wt&JL=!);xS6%jWEJiw_=r>lu<30kwzQSZu$oLbJ$d z7*ZB#YVv8`>(fH-m+cR$Rm;0CE^r9xlVoM}-;h7OLr=0*zmoT)Bzpg&{N$?qS5jyR z<&EtPujOPFUI;yjODK*CkxRSY?vH(1byk1aY;!z9>C@M}TTTYV9}Vl2P1*A;>!ov9 zeVtzU?fS&lnUNO*Dq$zE#TU*UEu9w^4xrMq7(-(fGHw4{#Bj+5&=3~_vM6SxkwLaUAcg{-@ zRCm3z`1DWzHcCyG_qeD(fy;cqmd{DuulJ|hoc6T~?i+XHI!;$~;lCT+$j`KkswP=w zt47GoK8=F)8?*P;Gy*r=FDU$7HXET--r8`x*Yb;+f0~5F5PfoNjKD~UNTg0FxAR0a}R62`)Ouk%i4*0hvu{dae-xOKfKU``orAz1u0XoQ$ISwiaa>P6qkuT z9wLOv%D`eJhm2RDv9mPRef<7FJ3B1IiezUif!+qX!dOhtDmsTyFeXHkN6`WzQc6Wy zbTjrZ<-d_&rif^Wm0Tu}))c^E`RwUcSSC)CL%ik zD3XZk5}@vJQ8xr~O=P)#0Ar-ek!-f|&nVgxu^?)0xG4MFQUTD$o&FzUDc1zV7Rho_ zs+<6*Is=&GtX#E3A(QgIR&ys2F-PaT<(+VOl5>KH8V6zSfdGyM-YzPelqi%DSmPA5 zRDd1?fSE~w+($eA1Cm|D9L0V-wnU`Qu?#__UyY|ND5U1H^J|F$fHVQHWgn14 z1+lOGBnur|3V@4=Q7t`|54{_lVcn81eHU$YJr#mI+*8nd`#XP~X zbC%H4v*=@MsPy!m;grIs-7t+Z^fxxqoceYX+BI7srl6;|=tm?Bm{#zQ*4Sg^etx{fgVq<5znG3u+U^83ScUvMEQs{1s)DV_Ca4H zvQKaWbyf~t!JSicMGsLbMkwgVrsn}t=w-{vD>fnfe9@C2<|}|$m0~&X*A$*oF)xYe zCV;vWA%O04KL`nFIT<%}t_gouNR~?$K-+|vPki|$viwsCnwkJmP{0eLCy9tX66m!b z(2fwGLyPSLq5tziODX41Yp_Hg>_f<~Exqb01W`FfRGo!K|dC7FG~K0Kuz;JfM_oe>TSSTURhPxepc}kfNK!t zU{lOzA1JrKLz}qO=Oxfa9`xRG`~Gw$5U@TWfj$NbyzvM>5X?%Pd%IIM8Q)~2 z5fQCcnc~ED|1UGbr}qy zw~p|ss*hVK6rjK|=nkq}FBhY_6SEm*d?5jQt4K8)U{DI=T#kkBp+KxC9b*#AO-;0X z5_)nLJ>sl0j|>P<9tK}QBH(K z+ZQMT_4idy{U8zZN`NXPq5AkJ0Q(b46z-9MI}H}~NpA}fMklkRWEQ+u$op8;byayW z1lyRCQ6WJ;o<&y?j~(Db2Di$N&thgon10FK+BNhT7HTU91o`DQIr_i*gNzA2U&s|K z`(j>y5^z>w`##AbLyAvedz*?BU-G$663!2C3sP^R)=t!=o~yq>ksIM-{x!49RRl=| z|ARB-sl%dnR6n%^xPM8xsM=7}rzP|&E~bWqjM|31hsUN|Q&RNr0`lGzKD?h=FhN8x z7Bi#*u-UBaB(drZ7JUE&9|y5aq}mXr#7hZ?+(eE?vIsc@x;92e21?*hfc`cY(*c6b zk2fZc!uC**k7lcGgUVtZv2Z`d$KrdC)m002paz0tL(p7a}z-6)?gNn8=(8mF*(cvMJ?^Iw=vw_rpGwh{1u6rIJ#a1hq}VJEqW>7Kdf-}X6m028-2NVVUr49&OEx(eZ@xB zjQ=v?Av$Osz=we%{2e(BXz@0z*~IZ!{JjVubuNK52EwZO?UO{g2nl==SjL90piWv~ zpT=JvB4VZ}wb7#w*gzR4Sh2L{&Jlm?{okx~MbQ2*HE)2`6up&z6gIxdO9a>z^6Vor zr1kfG_lL;$WO*J%F3cC}Uh~2x5H%O{x&x2l5ing`kAk_UTd>o9LiA(o#k;xCI|#sa z2Q4mcc%R&p;&Ys{vydMKPo`K=xUa!0=s*-=9Lt%RMe)t=O`a@l;}+1rpjqKl$}4YF z$}l%~GU_SCut;=)HpYsgSQV}eBB?Cnu^+LEk*Bd=Bnn_l?3Y>j??SYT1Z>8AsgwTX zJw?72kFqMrzp-l$6^L2*i~VkaT|5TOmcXdo`^J`-FzN9OtEnsY0x%hiv0Fp`c7%$k z`9lKP-?@bi+UJx*j}=^D#ge;Hz5_Sdx@XIB6ajoJ{hF)pvd5bb5mcmz`esUa$Cl6= zo74KBpQreyOR^QsFJgBB`-qe_S9_(%w8`3u$&jn5I~7e&Zk5@rlraRZ~+ zE9g39dkoh9VbSS6Egl^}c~{RZGTwm+I-aps47MUcF8AN53YN2-m5sfP4wQh?1nd)( z_D4F$i;?#deKZ?&f$cym5TriNMZb`e&i2hNpZcpnAtEQqwRe0fv^Mt!!gX~5@8^ES zyuxE_N73V3KRqFzNi@USYcT7Meg2@qBBi~59x^sWt>_W--Jr^0))WBpxsZr(37hof zPv}S#RJp^_^a)t{glYR}p-6t|)PLaiukvM!UqA{|f|pKwnJ%jQJACaMyqwWitY*SC(r*8G8A`3w#3KXuEIa0v^^5uAx&UY zl$E_DaE%sJ2dM141Sybyk?We3>*Jy>@=*xQUelU_3v2nglW#N+p8s-n%6CfvL~%|^ z$q#d?oVc*sOq9Esh5$t(u)I9KQ+HPXd*tTE#sE?6)wCBK*{aW5261JPxAU}huADn# z?p2KKnqZl!e~q}cv+IH)V{Hr1E9%}()0f}2jQ4Fh@Oy9KQ2K+aygj|^jH;p+eF@U; z?XPcI9CV2CoZb8TKmV7{5>GVcj%EIcD8ZT46HhGqhnlK5CH7eVF!m|YlqPdBW5+~# zPD#%y*KT>eqYSVxdS11`D^VjQhDTp~i+y;;A{_s4{Ya{v^wukhxN5T5;&v?I!D&ZlS3lU{zA;Q_N=`q#Th{<}-3a{3)H&b8T z3_M~l79VAgl{>8m;6m*Zq+z!=K1{p_ibCfZ7r)0vbrvpL#%WJXMGs_4H&0f?apZH? z?w?~$xPCadJIr?!$Ii4GRsw6BHC780Xf~EQirN>xa{^AVuq zG@YYLL+jVP&n7g5z~pDDIddHCL&R~7_znG$N>`A~LZSBO-yaZ!OzfrVAm_CqCDM_8ufD)V-j#-51?%ZODwu)k((BvCNN)=C3ZiKEPW5Zi6` zfvS7k_bG>tZ2h-7Ro4#En1`tG~GA>kWCYYD_eh;}h;{r#AU+;!$>ftgi^% zkhxOsxtB;HGCKO0}Z^8RifbuG5a^%q$d>;4Fbv8O`bmBifaZ#o+}i+^Zqz55)iiydXNX&dL>YJQ1B z&J{>`mdx6HDfZ3L$T*GY>KZT2qx6X=;r4`&3*Fy5yn<^`rVQl|$)KyaIuKm)0NRW)qE2$Ek)=mrZlBRr{QQhKTzwl5*_Y zhs)BKsskHXtdEkl?4onO*iB=Bvcn#4todT~K5-e(v$hq`Xdl6wfb8-&mA382qJ081 z!JTcx)jIodp^J3(>RdjQH$`YD6$1uD%OfkhGMcX}@*FQ3cX$|qklmLni&NH=Q1 z^#nt$pP?-6S|KA(G^mAL=O7B^{< zrk2RAz<57ciAs2=*_+O?oOV_06u&gTTaAhSEVEnJV2=h#mUGzFSpR*^u-TiXm(rR zIvvPk1YV2kKv%!PSlAV^O@CooOzlXyOpvj=?6V2>ok&b^5Yv?SvouUpuTmS&)K{wK z?DnwI?@GrKdHtQ5j*;qLg$ja69`|ULT?r;5|NVwcsbF$Y`(u3m)|WViJ)iUSzfrxn zZCI7EC!%#0iNmV#0=hbHR^e&0mwjh@dB*5G#=Y4OJzCC)-3w7=bn8py`~~!=qhFj3 z_Im^$y#X~r>%)*^;N%Oml9cpl?dZ>{&U=gevMQrP`h-J=xU!t1GHx~D=>v+@*oP)V zSI_oAEqU6wN4$rDd5LDjUTH!34FVaZ_EDJg%SeUXMuyhw*&6%mb~tg=`~q@Lq*pxE z)l_MMJAs(c0!1Pl+Wd*xa{fBx{*wMTNx;QAq<8}hU8@Gbw(cZnet$s@zrp4117r6Q z&Ujw;vtx*1OZyw_lD_ka8k0z^&HjOMKG@i-K#rUG2DQp1Y|c!>Z>Da>f?((jM<|E(C$8iJs89QCXO%h)21(^n5&dZjriU6#+Wb<+K|dOz=7q{3cY z$hAzJq-{Ly(xZ(rDtnsyQP=Ko`EauEf3ps1hkEEZ5f$cw8zPvyV(q`rVur+3ww9<8 zUz{;&d*tZhQXx7D7kyv`;q8o_z#g%EsVx=8I)!~IUNNn=%@#wRJ|nW?b!oSxR5xY% z*2Eyg5qHYcK;Q%Wf}Ozz`n5iB>S78fNH$vQ6VTRP)K};^8|^ISvyc8KVOeL<#JW*~ z>I;0-vmacqOO7{ngPJ*(h{c3FQ%3IHeoW%F8>CC5DVGIGVMb?z%X{K|8;`(QPK=!) z;_FlTu_|s_Otj{NNNnlc-)TUi6`?ig%Ah%WsV6X_GnUiYpxCJBX%jpL&*UUN$zV=Z zMVUrVWRw}_FO--o)o+yCixSlB|LXdH*rcEl{ZD%1_h5_@U#ITO*k zp>fvRHuM#a#7BoT?DEp&A)`vV(^m?$niB z*w>&{i*Qq`CBqL?y0>EN^KEv@D0nJJH|g|APkI=f$39~>XpZN6R_D($bDk3QBgO_) zL1jZ;RDF&6DDPjWz1zOd1Q}yOS`(G&8S~OX?c>5BbMi{DzJtd*jH~tg9UB?L`CXC? zr#oX$^v|ajN8{w@IoUqQJ!G4fb6`J_jaH9y3RM=MF|cMOuc#0pd}o?o8B8+OGF3>x zvv&{+Ehr2^j*J#Cr7S2@C@k#%&3==_@ltm2vT^xt27kIaKZU~%UuC)=7^WgRF$WxA zC}-${Agsdmlfj0L1Kl=m`qyr6S}(U~sqp*=Nu)7dfaYH?W4ljZia=qIVK!c1X1*1h zJZm4#7q~372?_lFb|R#EcYu4F+k- zh6?U7dHu0V%p8gvUrh&6ENO zC0D2TanwWlW#2ioPS^?=40a%1f&8E*Rf$&+wz5~;UtRzkb z9|*~^5^9*?Jn{17oKBnMU{XxEDN90+cGTLe5q>5Q{tQ{vTbo5TM*;S%A0gUNF- zwz+jo$c%Ti6>7pO{=k!iVJEm|!=Kn8JZRJ^D_q1n$ehUIvx0fhP_hd#hqe#Lj==7k z`T^Zs4-IdIUHGU$dBP3_q2A$ibOo|Hn)%B)it1DBG>Ra1-TBmde#Ypyv^55C@WJ?@ z0rp`r)E_Tv1)}FsK#Hqyg;lr`H(KYI_Hf9>ParRiQ!YVNh-BlIBbZ%t=fye+=FBoAtk3 ztr$v)FQu$P!@Ij689SRj^1W+!>i#L81CJN*w8&9zT@JS^cz`dvN!EMfvH$-LnU6Pw-$CU_lxJCdz3{7PI@K z?lL(+QI2#x2o}EHz%Xbv9p2^rTQgM*-8)V<45nc@-qJuKEA#&mcJKd8|9{~BXD71* zlhd5fOvs!Mi7}@lO*s~sQ_hTtqRdX_lqs}ITFxERB!y065>bsPr$k4cDb?zw_IbW9 z-=Dsh&krAefL-kPbl>B4zb?b))@4=Zx4&eJs=w)jAHSyh7v4S%-}8-~&SUR&V(MT) zaPcG3_KMV(kBaHQdVAaFAci{u7CX(>Ic{FQSameKL~lFC1mb+pTu@+Uc^==9M20%G zLuT}E*IGlbWHm4)r@~o?G^a*4JZx%RL-?mDD&ZQ%<3<~^1YP^!_{eBcTK{D^*$f^h z@+6xoVP6`(lT;hZrU;yGcP`m+3$}7nK5ppS`My0Buuu;6;%`P~J;chdSSg7nn*@RqC+pHHTzbK#G%z8b zu|r@FF*Lt|towD5lgr|eZ=Z-#3`qnr(?;zQ=nw)38m3~DUWquBMhM2T(*4>?xW@~| z+1blgIg+VB#M7vXo@1-NuJ$F#`Rq0vES3uIkW92svmHOP6Q?+H@tmmNB~Gth2i7zz z{Mgi%ZU5;#Tj$(0^uM_OM+7Ha7Nia@NaEy#V>~7hHc+_F%bm~<6Nhr<#{R-70Ct3% zaioF$_248iV@EhES$wOgr=60&E1e2}x6ggrq25j#xLZS<7O@saj0buQizKiV;M)Pv z9;ir*hG|7Tv?3mDlT7jJ+?l=t#%ev2k`xNe-7s7BAz{GSgx4OT0@=j z43D0$K^{9jT=zo9?h=rS+W2hbgVBUVXr8bo=EpJLa>Uln*dzqph6zo?Y87>A?~g>c z8BaTX226TblAtPKWzNRnS@v_Mqj3lan|V?0-Ge-Mte|8#sATAyLuETW0|ED6zCIX_ zu=?9HmOH0$nswTf6`7>wAYq8*WSk|ZFUdfarWqYF?ItIg@u$(9-0r(v#^xT#79PWm z2eI`-SS`~{lE5ZOGOrJF-sDy&_#xgMURc~%=@`zQ+$J08IU&7tVey|+(}UjI_TLuR zpynX%ElUt{cROr^^rB&F#gANAaL>_S=^V*(_U|{lOM70dM^!jiBK{plyzr7u<1bLB z8FwtF*@83uxZ0&p(cZzbew@mjW#A7>5Z;^Ah3z~5>lOLUClla9TQoe_93^>ppoGtC zkEF3;Zg@B7;h2f-aBm6SFkgmozIY1_vpX581Y$npv!mK&9E8Y;RHlms=HMZS<)Vir zkzqk#SaM_S@B=1%I%ko#$@v{Yr`rV(;@e@*UmL4GBv+v7I&80Qf3p}PH&rqWPr+{| zE`ztUv*KycmRfkaU{1t?r}Ha`M?xgte9tdc(x;yB>j@QVk?5ityPRQm{4hJSrzv#) z^<2)LLF%~gqn2D8Gl41_Bww=E>`etCvXW?1RgRDkj7-UYGc=_-T8Xgzj}_SSrdT^Z zQfFFOYdV9eK+Ha!2T)ZKPrrbkA^JsFQS4E37Ij2OS30i(7mQ5{w6_S{;k^d;S zJzmIOZ%Jee5`P)aqcg&e{!BJ+Vc(c;bEmN)aGWh1I5TjJsZ;Tz1Ey9yKgf(ED_;8j zxh0$8RjyOkmhlkT02`mZ^ zdhTPXF6C{DK#`O$L*&DP#SFc08BKyU0nge!&59g`xt6iQxv=2&4gUE|Hw4s&!ek<# z7pz&^g|IyWFjkzp=>VeNWK}c_QWMe#8(P6-C*yC@T_nsXq03S3`x45l?HJW76JPND zC2AvS@2p|}O#+8uPrC3snFn^45IzIyb};2OKOG^=-c72zmVkwo*WKV;d>THOzWKTD zzub7&AL49oyi{!l65Z4JC9Wc|+xS%mBI970%W&Ed>ailClU364u)n5I$uBouO7Zu5+tXZ#okUWR-`Vxz72X8wQ%=Kt`L48 zCNrWs8R1R1*O?MI5dOHwQ}#Sjk9vh2h`-GHjkW3hIdyriB%`2_o}F(0`Nr93KY!Uo zAv7nC(|9E;WzqQill#_H{R6nUOPaF8!M-iw@VF_r0fgk`fwDFZ$1#`k2T`K$eDOkB z{)Ywsjt>!KU-$nLd+9|IGffw&}6=s9GGmAK5p>&Jv$^#6maW=u(5> zU!jquwZv<;P4`Q^foxt!>u}jWP1%fmb~puUg-@(Re7d`@LSZHM;@QoFo`F_HR)QFw zOAVuBaYBw>6}aP}*{*8Vtd|#lrk(mhvPyZ6oeh6p7bT(ZT!g!A`W@CXk^Do9H^rus-DoPm9Rs(yqkL z+rbj+*LUlViGt*Reg5`_I^WuF08KoHyQ$;6ep=X{^Zto6uuJvxANx)qt|&aC@GpEbAU+~o5g zj2>8;X3dWM`|p6=vitt`TB#Olmm|%RG^}@D`fJtfC%pxIX!9oN`)H(L zcyX(4ufyUwn@W<$L0Hx1&*+dE7c@qBYL~IYlzgy(k8z~k$XFNIbp>#N34`b^vd!b= z`((Sv>$d*dhh7g<*op%TF~`Q&4WC9C9<)7bL85hvRU--k<6$sAPMb6z|71E&`o;-5 z;b|FiV8%&4om62=jg+~kx^I2I?1q*os)w(VMNV;p#&)WVZ2sjTGGD2X|4tTTx1yjH z&t1}OuHNQi7I-7sj-}IxJFXZKbZ&VrGa7RP<1iCmQfZcbD~P@Su{Cr^a{`nU- zYt+hq(<_w4)iKX=+Z2=06NrWrkZU6-|kInicrE<@42T2b+8 zH0O}60Q*VaW{ji!zwdf!C%W780$)jL#ytCjca5qB-s+UqJ3bg&VK?vOGey>5If;od zMZ5IwWsrApNbo(sTGuJ4Qk9F&g*f?*1?cNTx}8MBhn_y$UX>Xf2W8*WkRD#o(zjcC zi{HL`IUc9(A|eJ2MMtH{3<0e#16Lr;X~OWNGJbFU>O6u29Uk=<+}Ef}F@mdfSGSr1 zC(>qvWGeoV*i$v94m->edjC95Ph0=~OrzdHDX?v4$dA+1_uRg{QC+mop&IF>ze5_i z)bAlX8$!Pa*iZY}R^r`@I`66e_p`dg_Myi20GqR*Z@#+Ru?>N);l{PfWe}MkUra}_ zAwfk>G0;u%)s?R>4x{T`Xj^IUtA_!%rd}&D40D@z`7XQKJ|KwyflG~d(PKz3GzL_x z6ooc;U@@Na>Zq%Yk4h}3VJA$>brs=QwZ%$Dp}~2|ixFsdw`b=AQ)xD6Xh|0fq zAgD4kxM@Sk2k<-}i|WQDZko@R^VWK47c2Rs8x=mRMyE0(*1l{$xH{w@ymk%r9%}HG zDC=0)S>_Y3k9=4x(sUVsPDo1Fg!jiWPg+IV-^kRoJ$`7lop7~Ay8bHpMKJBv(Hv@1 z@Y5L|%Ri=D`nSBpP;g#O8-5CYrws+qNrp_X61(jM#h4ItZ^t{GI_YGF=Ea@?%{34r zKuE`pw6neOT}rV4cs;k`)2AGZOj5q&uJt}NZ6M)h7QaceQ;%&M&{>f+{n|vzLj@`~ z>*akeF`SSL=)|5w?Zz1(q~V?jRV?Txnh!Ps6haqkv^0ZfsK4P)NfifJT?XKIQre(V zACaM(->h(`ooUsek4eIk)Vd^4BaO}yv-LP+6bI&*vGYtu07PlaNAShg754?uMA8zT z^HAsNvBVsiVzsph#gr9>VGmui(qGMy`>WdfI#Yka&&Lwo&&CIgq#s!FRM>0)b2h$q zPQIgZYF_osu0virA-|Ex(Vc4PUY%$PZ^Ok4KiL)m16pS`zHoW4dgfGNoC<{t(Ha|O z1H&BUxs{!}#jG;(fXiqG&&%|mBI=O(E8RX~KUj4Ugk%t@05n9j&M_)DYkX)31`@wtuiD*%~7ELjtZk zKCdLA0H4!@(qz~$`_Nn2p0hFvxm1RK%6oj`D0agBRt&11?B`NrP?Lpj@)2S`yHi%x z9SU>w(+I4+LpF68J+au!(=6>XiWuY7K#eh;w`}Bbn0-oI-az6{0oR8zpxjNdE}S9>chK}vnT(NWrvjMh;eD-|3W7tEQkYgReFOgwbtBcUQ)7>+$-bBg$v+CaxZR?B0?57Blv|sH0 zaff)~uwC=#*ypU^Ud2)2kYmlj!)xJfsuW>Y{zdp13qCkDJcxtm6Qj{rE2(J3Ol@-3 zt}nq&8nY|j7KQrdK@`t~vSpEbyDGhC%^n01T;!^OX+>-2EM6>n$rFl4GJ|*ls{dqN zDiq^o1;D(wOUg8lT&;>Bq~@VUJhg`lpuh$>SrY*Wu0@E0Srq6)al)hJXTBD^!feXWcZvORqI}rbIWT^i7#Ym-4TxF91&^0U1Ta*NUmG( zj=@cc-cDD8D%}@;x_`62Z&y)VY7-fQTC_`QxM!a1{dfqypJOLxG&m3_2Dm|jkIg>) zGF0^g%c3XFbF&A4d5Jv!BY&u^WA1vGXt(kV&No*uzAqNnD8Fw~7yUx-3DhdS)*<7j z4}vg9tuR0aE)F`{)P%J5dsY9n^R+>ssP&(6WmJH%^*#u|;}*>Py`FV9;gw`-M`guh zMSGHzf;;0=Gq9m99I?^o+-p|NcEgMUQot`kB{Sc7pgr8P&NS~Wu3pP{c3E-)_YFhg z&?{VXYwuYr^FDizs4ZirgS;(u#wXgy`j`U;Wg(UXcEUcwT)>7b&jk zVRmLgaQR0M<=!Av96+%2zJP{Qhr(eI4>ej;_+d zssIn{<;C@Coj@j>U&_8$DWiI9+`Ym>J>=o{keDAWe4N|vmGKk$IKUnz5!U-PgvGXY zijGDiRH&Bvb{T6S#D(d%na40Llv(mRH@h-Z6ONfYubpGmkcOj~<$x8Y&nQ(4Y43dZy!#X1{76A3&| zL#)WLdE5eD@0+CE0@WpeU%3xrt>s^t>KNwKE~#jrsa)@GGbSmei){Q#W^?*&Efhn0 z09RQit2%b&{Px`6_wQQLl$iBO@iGT{2A>F-Mxp%Ah~dM23=uz_WUNEhm1Stx=$q}Tpv+!AQy9av@qrdumd5kLcNiX=yh z$bmr8h8~@|**DHHtE_TnQd&d??phd zjL(EWaHDF4{e*myLmI=j!svY`MHN5b)XoUb7q!Wpy;r$(G>C{L_N#dHD@r_FJ~c=A z!AWHH4sc6&pi#IDQ?*WU2@5xZDvCzZo&zQoX6i|^t8_CB=V9z?HDD*(f`(B@T zx7Jj+cEoN)AJq^78jM?O+LJA^9d1#Uk5dh%d&V1j?c6^3qXh>BWy=$xw`fX44`np4 zypQWksEl7$iu?Ckc)NAxnn^mfO}Ve~O>RHFhQS1w?KPPlW|7LTK^R`WSp}&t2coA8 zaIJ40sm4K9TMv9`6W`mX4gy>=PhYyS?6Q~%eY*2U;(rg@m*19JXE69RQ-^V?GO z+Q4KXN~>Q}G8|~I17@Ibt5D=L9CzSbV)~_>GM=YAMxwPZHB3;zKvwxitKah$O|FN& zuaM-h-mf_M4ss6cSl7U6Y_Entzpy4P?!rY868bmsVf2mo_n&9x#PpJ8H3IK>&5>7L z8$d9NV&hK(Hu$X(`H-zND5q?z58lr?fDxzjKCOK@@sqeYSwH92tY(0R<)?EYS-?%+ zQ+_Q(O$t$bkj1AY`!yM5Eg!d9u;ZQATL#WIw^GobJ+9i78{;E4aii@f0r%q6RJ_Ng ze80^#A|r`@zJn~VVXIx{C21TN^A`eD=F6=R6?6JECp{kUJS|>>tyko20~qGRr%eMl z2DT@8Mx1b4IFB7y(<~&Nzd*7O$E!JcU@W}Qe3}J+5O{j(5It;?e4GnCm6@^C8s>f9 z$ml7V33ZW8{8P0_@b9fskq&M2d+RCXsagzJst|846ji8BmPxzs+tMxNect zVNOtOfROT9g*!a>K*I7|6xv*At;79`>r@BH=$Sq-Xd9h{T{STr z4ORP)PVxy5RqQL~HwxWXK$vy#jRU0qaZmdkkrS1USx=7M^zq4c%QOENIud&2I^^LW zh4VQid-Omw^OV?O>f3B{hboPA~+Nb4==)SF1!$CzrIBn-DtBm-7Tmj(% zJnZz?Bo}Fk`SQRQil@hsV)bEOG7To1Epw2709b!kKnCEj@+>Tn5oz>4un5JxP;G_wEhgfddC(-$qR zHi*1neQnd@3OeZ&a$}B+R5l#CwE(@-E2wmzUXY-R47y^?V@ibx&$>;4+*^L6-#g_m)hrn5?uVX`(V`A)nxtD$2b7sqGohy?Q`K^8VAE^A(;-qoDrao* z3ep~|acsJ5Zr$B3%&SZ%xYiu08o;>;APqRamT5BV#!Rq3@G*STBj^Y<0qtiq2_!U9{Qy z#0vB@OFI~B;UwD5Wd^2^deK;Gj+_a9Z{SzEzEgGz2Tiw+6l(H!QReP)s}hLae{QZ2HHWT49m~~po+E@)5RBT z;?LSgG+Zb79zf21MT&gT{o?vSYpuzC-LhxO$FqOAWn=BTQ*K&*u)MA%GoXXc)BPl~ zL~d1a{+8jck@@TA%%^U7xld_DKGrtoAEhbm1zT;$yu6zx zIbqA|E)Lpx%!tez2hZm9IoRhV>NJ~OE_BZ;6t!;Lm3QRg&p3sXalgJ7d?y!6^O}={ zN1|U88}?}5cWAcjVYo|}VNMwqOlI3P*6|!*UcLXt0cJsuW1hsO+{uX4Q^f5lefNWY z#p&yX9v@*(`PZEC$N6&)@+;fPPUXpX~4AHqZv9~VM`9$7thN*7z^RLza|AhK~NUHe%nNVv~{9j0_5w7LU zgA;`RA*nz@eVX9>a(<+%?eSS61AgY4Rhg10`Jc9#!L{>G+Q?1YFvx_h)fe551U!EL zB-B?ZN}<}vLd>fKKtdfgs`_SH&-Kyu{|`xpoYT@bSG)4!nu`?q_Cvhfi+;}S?D~No zYmdfK!?}6Q*S^umxyGs2r+dD?dWhdsChs~ecv^JAe;@qepP0lU_?8=PTmM`RYE9gA zvEiZSQf={-7&W85KF1+E`Iv8(MGq(8Ij_=RI#!?b`MpMw?cZO9!(4s;e?HQP4N&{B zm(z(#B^K+B{mt*KRF|ro{s{;C2ND~y&s+@r_V%9XV#e}ch-UWI2$**f#OC#&hj-yS zZRNXBOAEW-z@``3#@*0+LH?MmS`IvW85@7Tb}C9yd3U%$_}$9Hmle7lb&)ZOp$AS8 zEhd)5N8!17gV|&0x#x&MX?YXef#0}@YHte6%}jNV_j2^N(eFs5QibwS#nWj1K0t)u$q_F;9p6W4!T!fnBg%@JOyH z!@lD{bI8J(p~SN!Cu{Heve}TO?DT*8Luy}WuPwU!W*od%2>wemZbBMMFHFQf)d%22 z-xcM-^Jo4f=+oKSvllZ}ZQv{csYW)H>~Ap~bR>T21cbZ?jWW3qrl%HrPOkRCTV-!_ zGGB=ZKNm;ZWppC)xOuNjN@!Nppb7j)>3aLx#RQ>WQLM12y zn=oYb`Pz05{nXogdry4XiQIGkif5i@a-=Hx(@4~1xEhn-NfJAzw~or$W%)Trs#@K% z)Ah;>VjSHj9zr>fXCLAw+|#Z#P8}2}0L62PPtis@TaVQTd%g=oqNW7rTs4FD_MF=G zEVIAj)WyjWOhVEdceHNEWa6$HhjosIeH|koBxx<}zi>MJ)IDW?q4dz~jB0Z2xr;AY zXe%NXw&rP8}6k)BRblkdYSzwsakEUVNLKpN7PVW zg8NoWUe6={8-vdyf{UJIMywThecL#d_w=LN$(Fy~iz5qLVq^Ct=P8GA6!!g#Fe-K1 zwzbPczG46I(R|Y|{7B9ETi?6I%3qG`62I7OQDgaSeTT6wee^#+gKH0Pz+h+Q5nTHn z6K1orDZFffc`_BUU3r#ARWCazvk9EwMLI$jz&;9X-eC@yL4Tp~%8^F1H(%-xgB zhh?fKNH}>fy3d2q%h^dvnvtb&t6uc`m1nG!+;e)?ku_L#&p`{7to%lUUGun5=vg_V z3fuJunL;c~yRy?LblqcY*0^2uaJ9bUs5s%lfOct)>4C%mbgiJ-wnK4{Nj}Ff@8iNA zP`(}|Xd+BZUz+;OUeb$x>G6Di?Is&xh9n0VAu%sIjO0IiE6oq6O7@?QkJv}p>;k?$ zAQ=qa@VY8=|M9^)tpxo(B=SyhOR(oVZs>+)=E$eAf>Pij_o?Mpodb1GG2oya+FlJH>wU+1CNfH@zkm5?OuGw>_dr`t}BPX2a1 zux~lz>bk$ZS#DrAW$P~YYX~=`Y`0oVFKYUlkw?r`?R`gHlan--BULX5P;RiDN`L*b z>3YJe9vMyU=Z^WJY<86pwl<}`4~yC9bMJCZws9C0oFTd9yTVa!)l!-AKgPcM!pP1h zOt5Xoj_gzCLycPSOOqb0_XKbCb4^1pn)wJOFKzGKhl--oL;QE%>ie{c@cnyX+p(Xw zH<#A>ZgBQIl5_u7cOBCW)4wl(cV5NRYu9C~QRnhA+rCxmVnB-U&ypy6Y z*XY^iMLj!lTQ0sU_hLoQ`P8DpqbXZ7tN8ii1G&>erOR=gc=<5%BW%$*MVn7#ET zVQ^!VSL*Sf4Q6J@g;MdKkI|s-&E>iqsrgt=E6N*J!I3%9VleZfJ)Tn}?WO`VDjT@; zRRJpqS*|y#54~D8NcPZhzvvyOG8)g0SdNW6J5mi*VI8w88$g)OYtZbC3a?JKRh6f9 zx&Kl1l+}N@VPWJPZtuAclk%-)AunGSuU#X?HDvo<2y+XLa+VrA@&BIo=SB;gt)`zH zYU{I?*YZt~XHaM|T(XBj@zi{sOdsfKXxq%SjP$s&y@0b0zrB1i|ClHITu#eY&nx;$ z(A&U{42r$&9*COJtGH|c=3FUmvJCRFkIoN!(lb|1LnlpClPbfksY-n_e820$m9C&3^``)E2Y)AUnE5QD??_V6ZX`Qhwl8dx-rh2L=d{Npb zdUBc&@H6b?#clrE^%v2PB^B4QHFl)dn^Q7Oy6T^%J*|;SI(dLYcN##C}+gt_Ip_~m&rD_)3WJH zsNlzcat^ui+fvUITmRIb==}Gi9dY{;HYkib{^;lRn`hn(9=SRHF7Q|1+}|(xk8dvg zdi3kge}BKy6mBib?vM;<{#)6hzghJ7sAOpKzg6xDbDYVJ-^0E-x9T1jdb!@odywL0 z*b5@PdiM8sQQ9lr7fFR|Hr6N6scB8g`Sy~2=y`_4tDk}r&ZnY(3gb8b=5EeD?7`FL zCajAjycoaE%kaJF1V)|l~n$^ z7?ZRDw)kfVPvEiac%A5Hwub6MdPA$yrHXh9LsjnLVW}7cD5MKmp#H!>gOC6)Sp;;? zi9l=%kAGL-_DuV+3M`tB0NTq#E5M?D1)va?5>Z`T6cCKvCDWygNCCA7upYN&ZQNOs zKPSXI7Xn}!W`c}rryv_C$aXA%B%%Ne>Lws|fe=)IY&!*gXGJb`#rsa;5wjaMBrJ>~ zmJ@+6BNQZ{5jK)h{dyQN2=naOVJRS|o$VL9(?`lARLbw5|l{!G(aYm zk}*(g`NtHwTmk&Du;{W7zP6Lak$NBGh96WL*CtV6sd~r}GG>s5qyl6s2lGmZnE|4z z74+J(k}d5;45B{yX@M&5pz|1(=&?@^bA}dh^lh%9HF~$Nm6Ko5ARi^= z19x#H1X0!Mi|Nw)U%Go|5i>$SQYlAIhdL=YB8CK*AtH)~g|VrX?^05^0L-0G9+7EJ}t&{2_f}ld4R#|BbQc~s$6k0RM-HetiTuq^q&*x z7A~xSi=Lw%>Ry45-Tz<2n+bwf5->o$x{FX#lvB&YZ|D*rqw{R{x1*+j%2V%96xSR` z`VwfEc^YP65xI*dH?4af)YGAM8-{XGK4GQ*r*QHZ9+*h>NNk_?{_oLbOh90vd~8m5Z| z-hWNC*I6$*o)8U!dneb7l99dwI6DF}%|}%^V^gX1xmffQE;?{$TP0WH_XrDC2vg!BmiJ6agXT(?lRd5E9dONO6XU?dvN*dsLm00RhA*N)L+?2vGk)?h?^= z1*n^Rl#tK7#s~0Z)MEh#UXC5p*znB{tGfrADuDT)D!)uTaJvqI$3o1>axc}6)Kj6Y zQo_aKiydQX#X8BY=(hZc-?F`wrZEC4=?Cg-8Sv&I3-&lNf`A{Q@t>E-wSG{X#$pgM zXa$cd8V~16j+ZFvpmqYSyKE-$dL~E~b;{y(uWYvfW$lOk0vNr26!zcTz?r2bP>@qt zzyL+=$NNW+A^)pXFJhoQn0oR#F%~1{BN}F}L04fn4pM9WQ%G3xjuyyvanbjE>-K<9 zu4R}(vFvaJy!}5IRj+754^X{c&cr(R3`Ind$=9LVx%e8lk;h2vy7 z9`#l|P{-;a&j@KvD+*`Ha>kwza{(9}glrLBa}Sa|gJ=MboRapn9Q}F~j zeHR*U1yWC8KL+(?!b{EadI3fBQ8#Z!%HLKL zfcSNFz^UDkEKB0@Hre3FVq?Y@N`A}A5K|dKMLd_}T?nlrptYf!*FAkC8bB1kkf;99ipj3CYTF*Oo8Cl?EHJ+qYszK-;yn`9Hb+l>X>Rz%YHZKA9_k-S=!T5kA546#+9o(G@#qIRy@yN?LdbRMcq; z^7FT_B7f|1d$$0KqT$e9{}dh<)Gj6K9U}aXKs_vkfBCCWw@4QOZv12N{o58t0`+9G z`KV?DXF~6kC;JW%BFj9g+#4?Iz(<_rkCM3W!!O8Qqab-?IW}Q_F}d}XV%{Nku2yMp z!V2snrRn#(r9ywqi8Q%W=`X3k#heAUrDq7*30z|DbF_tNy}w4IAf#fs!(8QnEa;M) ztbl?%z9QF2M(r+O_u{cGyz;pdMN&b@@*V89z1W`nq6u30IQHu&H*7zks1i`69N_9u zv0wZZywp0uos#NJJso?vQ1LeO@Y{$pEAZ+=73;UaOT8j$r&K6+mqP!z9d(tAtOHgB zVCPE^@B*=HBzWT<>eV>9GO%F6@wbA^M?e~erb!8MW3=w}B&4eYjCc9H6|pus0Ilhd zYFv>`#X{{VkX=LwZ3XoUk336|qw!@uPTe@`lAyD7qT+nTleXm%J|cqOQS5}dbD1|# z*qlI-8za7-y*~lzM|VIDTKI6f;^ExkDa4D1$fA{{dhF05vhh9*Fjjed zME^(hJZJXsFj@#g(|YOMG&u%Yj!Ti_66DxoL;)EdM2xVaK!&)7X7m~txQF~fvfUIm zSRWHxbT^6$^ZYboPN|$affLmJ{~r4J`T5I}80zfVIX(TuPG1X|{$(itq?wopa*23*VlVa?^$lJ3i zTG?<_?=>z2>*qA`n`-SwS9nCq>{Cza`*WZ7{Z#gY#*ly@ z|IH;%iuY=Y2I%+n!{UD@o}lnfemIMgu8Q?{SI`Ab7JZVJD8kEI-_G7xIOe~p@>8F` z;q9MvS)IJM*~>Z!|B*dibakAq`Szcg@97J!r`nIk#~#Z$O{Etb zmFxa1J;zpK`?YGN(XA7z46i%I%I#_{elRxwb7i^AIK|1JyrtMGef5{hdl0U z?H7BP?%4m}AY8@&Pq@g1Wb!+4!`H>-Sfr>fKen`}!RZ&?xQ25jD(?l$ap9+Af6^V` ztT<_Co6Gyq>MeJsUm^*y7BF7sz{w9?X#(|@^4~(g<^CdJJ4p?tU6!IA_;37`uJ=Fn zx4Pkr7EKHG3%EgEW*xMa=aP+oS>_R{_~UG*(|@qqQ`uSgj!NxszZ5F}(3+K@rm?NY zP5hiBjYPNeBtLwgKB;q)MT!8sjcV zBLZ%_X@C3p_|`u;<%WDoo#~m|(ug+g;GfxkItSmLG}Sq{A#7c@aMt5~twjnI!7@I! zbcvsKXX`$$alq+zc-*z~2^*Y~B(gB&X~e#*woT`J)EvMli?Z=(K|eF-YS6c{89gyi zXZE#O-j^hIs}HFi(Z1AFRRofWud@HJDHB*F{^m}>*Snc{mE3>RKXs4%W_igkEG`=H zGUrPZ8;WM%ztzp~v^OrdH>$_I{Cfk-VqKu?2d6Eeq9_almmpM-*SUBTe?99^)#HBF zaSGbS1A0e1@VPawq`HsW<<2=F)Yg(9nvT1w*%@8vIHywe9qL0HBdxdWcZMQ&g^T<) zuCk4Z=j6Mo!&V1myew-QmCp#FH_-hRk6EJp_q|V)J@sz?SQ)_=Xhyzx^u6amlA=y& zdC3dO&l~ytIIT*Lhp2znu*Bx1oijLD+Yc0m8lPC{FkF1VONOI&i&z;Xfrjk+rjQg6 zry7Mo*Z+}JsSN5tk5hdtD^{H|YhL9)^4#le_x@5AB}HqV>SN(^jbhUzn{9V39@)+BQzo&Oq$Sz{G#ix=7OP!hw(*5ETys>I}2hPctG&8&d z>HZBB*`}4tBbNJ%pSll>SEdj}IMO=IJy&a1~Q>fLyj{y-PoDqu<1gYK#P;b+z7@rf%%e?Ky?zgdwRU&b-`6(y*=@2SXdH{8Lzs^reN7|@(A*3vMOb!?46Ygckyea1DE?-1k+-(EekBp!CG zphs0|scq@Y_5154)4Fl?P1&I=zinX}L&VM;)g#IB{!>AfN_7mJcUB2Mqp$4VAT6Un zkDb-nX%O-02kMZ-Q+<)oT|ldD7~vp8sKyvRbf3NhUj_p_iJldTL<_*@)~2mbx7T%F zdWG_C)Hed%U$+FKHvyWMUy8{$7LW*4MSc~>rz_#JS|MuMAQVkY! zhgXjd1buZgRI6Wx;8eSq2J3N{7CdTWY!EV#Ijx`kxw&9>#rs1J+f{FJ@0qG5IJ)(R zWxn@LE`YV1$RDITM=?t>UsbCWuCrPa)_u(G2ueJHH>WpA2JzPo%eGBND1tvijZCaF z`~wECra@ku3m%vQ1tuDG;#v1?|Iu}aJrrgC^X1%>dAV)h#GuqCs|rvHCOZZ)ltd(Gor_ai7%h zFIt2WuEog5|AJ-y{yTRl2jU=AY;|f%LU2 zTq@fU9*d<&2Cb4}uJ4X-(n>yTU$CiV&-3g>a?mZzkf*U zaYN1PJGh?A;aHUsf)9ahjn@BXpw>5hZ&Uo)K9yVgxWS$)J1eZw^Rm)c4uV=`k7gM} z6>#p;F27%gQjFYoC@x>nA6&W}o!WiCW^u`BdTC4VOHo0b=9J%%r9+JJhIJ7H*g5%o z)IIxW(c`@(25mkI;k*v|X5>E`!M+mCGy_{~mPf%)?;Bp^;kQ{bOH&3}pUE2nOXP$lh)f@etz z-)*eMNLDLvs$CiqB@?gYiw%UHT%tbc+yT|nhcCXLhQP6BiABNL~ z>=Z8iiUykkV(TAcZRapH;AuZe_kvxKPVE=*V%_Frti)w_|42D#P;;Okbv(QLkIW#e z+A^500Dy5W;RJ_e`tE7?Ohgrr3*RMSv{IW&xymJr@M*eT!8g5FPDu{&=C+Hbn)7x^ z#|Vt zy;kMke?SsA40fV91C4D`a!GE_@r+yEKUOqz2}1Ws)9H;Y3+zzQGUEaNYJ|j1rIU#A zDoe?4P3AGYR1?mZNS1XG@N)~JPfj5X`yy!?HE0Na0iWr`WAC6Bu zo5>-S=5Umk0-FA}qmd~!6GOb08RsWiA=C6NRB%*MTMCZt2x7$e5%=Mk_-V-KiUNU( zbv9!VBw))PV_PSPjYQT4SjCT1%u%ERRNG=u| z(9TLhl+fsPgZ2GKHk_vi%Ra2|akOLMc}mWUP=7HbG~Qoa(ea%RPou&E!r>M3UX?r_ z_nMlV<$Mdh&E~{Y+36g3KtA#kx2tu8c#Em9_5DLC4mO^q zHeqCTr1_R{$o4)SC$}AzBypQqYK4oQ1K=$?Xga0W(^{w3!BPL7)L| zR~iD+NnT+s`6(q2gOzy=_O$ASe9rOGyG1>WA|9lYaK~U;Mh{?3d9*b`@Gs%xA_?eU zPH>4{n~el|>iFgWn}DPxpUZa0#XikD5n{&)PWlQg!>l6^#12}nL}`zsw9RxF2MsyD=-7rgS@eK) z;^?Z962)m6I{$HzQ}B1-V*CwAz6aP=SmkqgvM!`!?j<|%cYorlr`6cx8fcSyaY-(< zyY+Yn&!R1L8}O>(hA+bZOd!x(kYOso*C1C^PChIZgeYxyjh$wtD+dtPht#%=Wk*&8 z+Nh?t!<}%gOYh-s%&L18gNHq3i5&RdVZ`^On@ua_)f1lSTdLew%aeyWn_Nh_V%T(Z zNcQ$>h6I-T{2@Cn%zBPA{fC{D&oGd{^2Dqn0LU1o8@9{nP+@hyS^79|ESH^-FE*fp zk7}_hR=AWERwVv(xF4+k5|c>fI7_kGh|X3V(;R1UDmxkEm7I+w3$`Dgo7| z&(xhUzi^(h6XCMC(=_1WWOS55ev+)ROlR&1MuZ4-N8b+}6(Ay2uO?Uf)492peYYS!NYE zF}>}PwU!ahxS2OUUX~&hc6C))P{HqG{0D+$r3KkRO~c#z&LBQ{SLZ#4$1Y!Yp)lMC zOw0<*A^xeBb?k?4)6K z5|?3@#ZfL-_|$c>6k)x*pOYzu?4y=sQrNGMV@DoD^wqlFp-k+)?tG`a9ot&m)G9onxHiBOlB|@Zk(a>nE0Yx-NpQx5!M8z)nkKOa-l0`QEO_(E(Uk zSbN_yZFWmOJVnetyq}aIf$yh!m2h|bs^^gGXI@SrUjBVq=;loLf=Dv14}TP~#|!Dy zTJyOBCiUwpk%-S0mx$QT} zaU&;B1i;-PEk8-hb$;pL`<5*_JmTAT`>`n;_KCD}b9>n5ae^G5&T9j1-QMOOG-cm4 z4J9wbwn}Kg*CJjj01~pdT4iRb`=h1X-V#d0;h(Xtxg4MH%9|Yq?xk@rCRtsdbW7fY z1N}mO`MroDu*!VOLK1G=i!%o%JHBp6(=t|4%jPUE-vPydIlJCBC)f8f7AW@ly? z`&g>64_U^(q>P65I$(5BwEbx`u^^7 z?sM*Q?*IJbILB}?*Y$qB9(w83f4DIH$mH8MI3=qY9d%c?`qUVdD$Y{O&&VeYDE>u! z<~go9=R1sG88ujEmtEHv>0mt8({DcE(fr^>)Mw^N5LAsI^YJQpuQsi0tbX-S%ZW~9 z7mw)AZBJ>TpN7#0kwIq2HrGIu%$pZeP^@Z11Z%iB^?Hg}+apo8fz$2Rx5h523@wMFc%G$Tf zo{SV3GEPmDI!R^rVIk=qv@PC=r&7lXC%+vs&MU|O8+FiwOdL~>hX%=|i&m37SA>BH zg@Oy4DJx)SP|qOLMd)zJ{#&`np013fYPBX&Y@fYiFhL_M=`RCy$8W7u&!udONUk(HImr>a-WYvZ# zBNV%lg-)<*uLQtP03avjKM8AHkx!6MC7Z9_f+c(*XLsRol;|mkAMQSUeEMj26R;*{8g68!ZLBZy^qL2>xso^aby zX9>5{1xG|C>e+(gF2?)j&X%5T4zEaIF}Ov*bp-3rV_$!dqN*0v{k?1M7`h;&9TY8m zRY~ZaZ@OhE%9Q|7e89 zmY9Mh5r6+qczV_+dQCk1s}MqN8H%Wo9%?wH+OhC+?$p73$J$@BpxX%DDNn}P!>aq$ zZZ^;-vGSjbw|7c!WS&)uzM&e+$Gyv;tQ=^0kIFH?NM*f{U>&6d+1{I-V_ zlJiQA4q&};kYFAt_Zrl56egge^!jCCTkpFoU{(tFOYhMuBQq_DOI z*LwN}o*Bk$veNoofZ}=PX{*Mm@S$hgF_olO4_&xMakCF|^a=6Tj8D#+*a{Tt4VCQI zS*shAjC*Gs_x|a*{U_>YT6pug+^e##-0|3M8w~i=(u=DpC#Tqwgmv0weNZ3n*506ncK0C;^ZHuXt#QMDsN|zh-E_! z>NlOr&6-vlj@+sF5@a05Z2K#IO%%-ywtp1c&2%ZN(28F}FL-_WpdY(3cqw`tZDJG$ zewK4&Gxq(nQ9kpT;R#pn&u6Yr1OrsF-g=*O<{LQ=Ved=>c<_t2-l$P*H(wsq5zXy> zw(o+C=%=lFdm?m9mDt)%qam4!Ih4ldBIXkJyDSvY0!YR+=#Q5Me5gK3vz!ou#0T0a zuvJEpJui$1gJM$0Dea=RDhujMH#{&oTV5VZMX$t<`-SN;Fb3Rph{0Pg@oD1^getPP zqd#NPsG~*CLB@}wIx2fS-&RVR-;W=K^ZE2r0m``nqP0kPZL8|l*m^&^l9MtInTqw~ zP}c)r{{C_^$$!%95`HMK)h{|+6T*#Ht11+aQcG0C%0+h!^x-=%Hsu)Qzc+G_;!`US z$|Xf$jZ*Z9r-@H;_Ez;oz*r=4k@H_s{jd|}ZuyXa-c zwLDRB-MyU(ZdUyZ96k^L*-=TiYsy{&^DY$Xv1kgMrSp;maft+5hOX&#vcO2yvA?t& zr`s8!%k>uwJ%~tdKF<&5p#Cw0K0kZQ&9u3c zk)udqeY$=8-*3$qW-B~egv~STsdUKMEAaMa!k?Tc3to@0sC-mfvlgP4d1!Iov&E_9mzMg~2$bNn0QEvcOp@ zk<#!6bU=jq#R5vLe=U8!VFNB7_}Oyag6Z7lsNUG}2xU0k()_~X!9@N&w?nPRODN$a z0Y{Sxt!9kbxTeCWw6L{%_Z?GbB_l)A7jLWlW*vSw9hS*Coj4d3smvVkE8yqJpXBJK z%N*luyp%cKW5NG(p**2)gunCYSxTwevs4`o;0~LAcql2Q3$FYWUtja{)4u8+(L+ ze6u9%Z@0fF52CD*D(J~w*w^g~7vYN<9QV43T%}n{CF0rAbwXgcZwI*UXPzW*{6WLZ z6V%+I{|0#+Q>X6t>!KpUcGyZ*P7`C)mEXGmpX2lN^YBa% zBlDnqAqIFTD>v6rySJ?R5FbP}zU7^{Kw3cZ<9kp4hU2mxeEQ%MNbJGe=r44KmGweViVkHew4OPMR=CDYNlnP4zDK#T;h86LS z(*%Y_a-2_3?hoEQfzE}9z@XJ%q0yJR{&?x9z@`b)Y(M*COVP&!NPne&+{oP zCA#&)Ds;iIqPFq2>x*f*wmG3QyI15*XB zv+DVxQuQQ;`r(Z{x6c)5q#-KU8IBODQsGAVk+g<&S^IEIsfhtUy;*ha=q2HR%aRWN zt&O*)TyDDR7U*gFqu_`pOh*edgW6W^%^3|yH#yBo>n7_}p0Kr)eQ$zMbo+rhMN|^< zBfl-Pl4DjihNErv(9~mvZil@}YPxbzJMqse!+V#4CCmeu+OHd6&S8df?+CDOxT$-D zid}FkESRv|h#{A049HEgjw8rA(9*^TgFe1_eSSoab}Lc-{CCl2TCrA1N_$ z38F-cl_;R%?hg~dRrd}S81#8G5tOx-bnQd@G>ZoL0P}jRK?(`mu&6*-0kVs!hl)X;&~)bg}~) zWD;i7Cy=c~Ss*Mq*xmTlA9h6l@wC}~{mLuB*|I|lsLY0XQa}RC@vMt}5T4IGEBPQd zMEht;`D~W-0Ww`ZCRosq!%Q0NF44ZKqH$cH3Ak*1+pS(o3RAaM8`f=!Z?={;Ckh@e zdGm=tMaV57nHbfLmV|Yz{@|=}pZ>9$tBwCF-kWvS*f7$J3%-d1e)MEWF3sD5Si>>vpC+Vbg!mLxaap*vojT> zdxC)wqiqDf=%&;;H5)w3)5&!E&f0zP-!r9*pIIil@k!<%QHOp%|G^Jg|Fz%wqueC! zxlS@D!zqV`t8-6iedBSauW2vwjxiy4qr>w z{lon4Qkh(Kg!9ca4t`G7@!^`p(CCf3(#;7<)uKm2GBAEq%mXa%9OK1LLe|^QQ85(o zND4&m<2p=4GvRg$R!NEXYv|LxdnwmatFIWx_2_GMQ$bylo0bTMjTT^_8n})7?!{+Y zn{m6%oV)ir2z?0r0H%O0BkAG+oo@fE)q1S7{(|*Qy7kSijf&DjzT9Z4ezPT7GT{~SuQV~H z6Kq70c1~Ta?hc*kL>Va_#eoE%9Cf3sTegP_gT>_fyW;C0sz5?0kxD{mTuz!bDuQT9 zSgM#?BfC3~kWA|%3D(4z)N_$`(wdg)JcwCyw;nNj zLq+K*Pti2DRPL#wrHs`EubUv>DFqeyJw}p3^V2k|;KoHXO_HTjPZt5m^yGog{H3W> zSWw+DzT@Dyx|JTTJAq&&(Jx@ggzCnm!i?r5R>qPjV6<$Neblx6B_g<_PQAKrGftOS zfPlzf8b%&qW+4el)_~foso5zO6R4-zt=VpQi{N+cQk8v;x9{IYe`>1a*RHoKUHif; z_Yfg7TGo5w?V^+4Nw1HZnM36II|Bt&e1yv??!qL3(@g8EwE|Mb|B@~uUuja_8PU6S zBsxXHMok>LGm|=1I*<7*haXE4u-~=Tth3q&718}WXXMK2SuiP}}2e$pvD3N|;f-h;DJakhe$q{e*)6S3X;@m>2|Qnka7 z8vUKC9M$-^Teo6TRj}4T0H|wVB}HZE*wFMHi8(UI3`FT(#TQT%8d*(VDE-==hX{*}KGVa*JK7>-(*#X#_QuS-wWE5LnZ zVeoYvL4TC)&xIJRfYk!V%WC%qp`$AF_MW_LyD#2K+bi!regqzFZHVhOi|O7QwwmC# zR;>uEV0X%Lz(i-OJrkXKNnTo@ZekrqchO26XSK&!qq;uo*kI~jij^Mw_AEBXfUKw+ zMl*M&y+m?qh3=>irY2qLmCFv3s!Nq0j@r{<`Dm~cvFyF&9_{l=1K$EB{_WDK%XwRB zrS#Xby^`OhbFqt5Fu&`3r?qijF6onDh1;WD$llxNj;LzV#H}-5@7V87#I1CerA0q% zgUe-CxowLi?$mTCDy@-td1Wy9i*>%(CAYQczVDwpnRR--^UuD*>DQ0%Huwx&R_-f^ z89u*gd0O+u>$;J~Ubm3XBVe_@n&RFy+mTu4v0Y8nZ_QV`HR2@$W7=91cCmVg?piv= z4#d?>_GwNY*LrhC>tk%}^YgLCLhep^e0rT0J6&`4?bm&87Z^r&?>;runt7@|^-#+< zZhU6>?rfvr+qZY0FMOFTsdxp~R{DMSYJVqOtbRfJ>rtHcRlN2`yZS}u=gidT1y}85 zxb|A}m$|Qwy-UZnSD0T%xV0-Kz|Ebnt2Om&yRg;z`cF^mNzK}yN4~BOYJZv4UU{qi z^{e)`t@>}f+UxLdnb+CtQuk)dR7pN+!Ka2aj<)V^H;K?kfP}Xr|NLl{wM6jon+^+6A0^9nu_rE>uH&mcsz!Qzu&(r#wc2di=3`M} zmRaoDisG$6@0)?{lNO!d&yB{~UTY1x*r|7^SLdyc`K^O zcEcJoZ^aQxqgq_;-*Uaw~?7sCWYA~|@i-;}DIdNd=x6pi&+-tu% z>~5FlYY9Jsu`O5DlD9sTum02sbH*<+^lTIz%Q-LWj& zskgzbtLNYkIt4=bCJ{Cc{OqHbWWQIxPqwc6wB<$qFgZrEl^=T;HE25jgOodg=7g-aO=bf6+Whl#a>Gc(iJF?R9efN}vi{Y>`Yq_U7zu*dMbmIE5_3b+_WL zqF=9hOZD=)MJ*l;jWpFAZD*_B@Y$5zF*DurnE&sRZ7W0P^7QCKvv#ZG1E()1T)zix z{yL+!^zWD4y#3`$e%(F`_v@i*s)tEOr*<QOIO(0J-BG;=#7e+G)CL*i48|eU&L~vG0h>{w#maw$xszfRJ%^S)y`fUF;=g zq!a6=ykNw$j0t!9M*?NybH;5-^yk?j!Na1J919Wm{7k_}%uGy@!)!xBetw4d-Mz{k z)g86SD~lh!%zx4Db$lz@c|7khRpaC(`=8~&`Jo5!2RJ_~73-9CE9r}3M0Lv-SNbxl z;vSxm`f1>x!=VdKY3McJuYD^tQh&qz3V%^S;!)$w!{Xv0Pu{z@=&I<~*!oK!pvR0W zI_o26kF)qrxyoZ_X4=#&jgGih8WiBu#RV@@TKCvK{G@%e_CH%_vvdYi8FBTmy@mVt z0hM*C8LA@8GT5V-CU*PCX?^i9lU9aRY?v1456|2}k*ne?s#XG7wXE0osKkk={II^= zCx5=!^4OS?Db7ktOuw=(tfvzBWYuLeoYo;jw>~JDN#FgEm!Up!0qu>e-8ALdi zuc7h^Qgru@4Wa#&n8t6&JFL!vHgWc2c#+z>+-^{zGj}eG#F+a@L|k z%nL76OFe)%s#&d-=w@!5E|C3aPqV&xcfT!8;Zf>0mbF;rRk4U}eOJM6nu8THUpYN9 zhKUklXXcnmB?lMfqHGs5h6g(kCC0DCMm_F`y|j6Ow>;zcIX<+Ka7N*&!|VV7^IcL> zT$x`j9g@(}mCbgmIjhn3(+%5wq_MEqi13>xRX!dg?pmL&XsR?M#&hoX&iSbe^6x)` zbSV>dTr%B+EOrbp68`9R3w#I{iGm7_bJozMooXY=L>h;fdZY< z9NoJKjeP-1UI)s*j7m7^N6ROwhDQu`9X;_VT4%=}zw~~TymT}s(CPR~xcX1;895_i z<9BKvlPeV>VzG}+&vqkLPdsQXfEmC0q($qiFh7SKKKZNaIX6IqcKAwJVstY8(=lV8 z`nfo_J3S-F69$fz$zgpX6SHSh$C-*}Tl$xT=PFcRO8iYOG*k_k7j%D=E#vw<86vz; z%s=w+HR+*3O3=&{O29Db*s&8${lI;VotBZaBc~4BYFmUjq8pUF5(WmAM|PgJhC$;b zt7#`E2rnJk&mcE0LEbIc-_Yw66{TGgH4MX5RuK$Ppq`dEUHTCJHjP4g{vWU3c;NoUo-a!UM=g(Vl#+H2NlP_oY z$-Yl{_pAL;MyVNJYz`5maN^KYhmeTBnFc{Sqd^(C$Lp}QE9Kit=XTwj_x;-!f;eFC z?GXQZuiNf-$hYZbxBnNYUC(>=e}P)1fsL(~Dda;0_T(o%AB3X<2S%X2RCqEK$)O4X z6UtN6tj%};sQs~MI)+bG5`e>2_FG~ho^wL4@Yo?rsv`1`#X1bIVu6NB!6a?({qvOd zG+abVi!N4w6aBISte6Z5~>@71`@~4 zb&&_`|K*`Cv1n5QHsIA^aB{|c2L`bF9^kWq#mu8}`QqpD->!>H&!NiK z5uPN}yAHInADkF*p=$ve*dh3G9rJB!Z_OO$D`3m5i)`^Q5*cYj6eQr)QrUK|Rk1dX zV%@%%eMqSH4Vd?M4B+^38ZZ-h46YO-G=TZAj`@g1R}+z^Dd<@;in>ngls5I@BD>lD zOGtA@VVNZK5?1&_1Evv(3MhglM8Ql75@;J=Q3bOrRE;+a6mlAh;Q=n9xB)XVAjp)wWQz@=QqX-wP9eVR6)}H;4-&lfGt#sf z_5hEmr)nE@T|%V_txCg=vQhKgw3iL=o(C{nDp>b_yZ8U=ZCBZ7C$ix391sQzYMf#4 z9zm_KwkiK}Nk#g|f|aG1cXK5iAk z4xTcusrzrA9|*CZgDxaOJAqt2m#lMTEWXdd~_;u`RZ*1H!SJ<|fKr(%q!1kb5sH`^Q_ z9ax#$7`>~QX?&9r|1m~Jy%;u+dQ8GTz=|iXiy%wW`()AMcmP&JtXSES8-TBec!w2! zPZn+^-$m`9MVzqvGOMcX(~X+p7aCBqD9jyV{W~t_KKbUPk99~}!(;<`jEp+pk=Z?$ z>#8B{lpzZ0kOT(XpcD`_8YBb)S(DJ+`0VsM_W`vy{S#`d4MUg`JiaC>T#SKs!T~)p zhL{d?)wFdqAI~}65q`7-pgBbdWW+4-)<+`h$N|jodP875BN~7IjPLogEdOvW;sN*m z7zpLw03YeVcpXM%nWYz<_jNhU9PSW2$wiKIlxuIGAQdbiLTv<^R6l9xx`+fIq4Ft^ z&kCxK@{KIl;fd_00HA&Tf6XlXxCc~+D7cv^1enX_e?&5Qz}rMoKqoC5Dh5*NYBJ{7 z8Y-M^vzC8ThXStsg8>-ndNQ<-jhW~`$FJA5sAItwA6NWJn@q1yB%%gLK*NPP3WE1g z@@7ak&pMNd`hv=8rNl0NY$9ctpS@1td`3s96l@JyIE9TGBDR7RviTtN*SCE;;n-?W`YH4DY7!7$i%iW4 zQHx+s>tH?>V#sd$z`ixp0jzZ)-%S_YT6NN$F%VyySD$%XQR*J-U1t zGr)d%21$dU;nh?Q_W&SUSJleD=q8SdyHseQ+Q1chRzp2FUrN zR7_30zaJ3_KR$QD?>BB46~#2P22ra|jy{(A zgYw!$t+k`~2*JU_G(WPSJqq)#1wAv}hzo8-2uzK)XV7yntnxG<{jKhpsv)6XUX=X0 zF7jzkcwc!h)kNN@sc3@VDYh{2`>Vgrt1N9wQ^ znOFQMLXsw!F%YJh>+H5?(vUQHK0f1=pdf*QoFXy9slW|+#F^MPR*&JQU(oE$7})gp zd&-Xd4L~UXK>gDWxH}p3s~{(|KOn^VmO&{>s2ka*epc_DtR*e@bJJYtG0^UOr5C-;bu^>>x{65SpK6hSw zOd#m5$b~uKH8QsR#k8*0IJk2GEbw-nA_8|u>BS09jw1Wwhw5CgcRlv|aF%ZK(idfAV1*+)_AoK zM~GA*?<#rnsA`=FW;Q-!>$eE5yl|ZKWaL`TOK#rQ;imY%B2N8i&ap0uwv0b}(5)SP zfRbHF0a8B1R}=!+F1WV|Ru~nKB?(B^gWyCg6ttjlU&tCg4XzL#+!fJ#BCI|u%*A}s z{U@?coZbM5yt$4oW4(=O?>0iCfoM-r9g}l=Y#jTfd#Vec?h4RG=J1Z&8vn^|oAs28IJ%AkW*LU=B51;0C*X)S>b)m>GEDh`V<|3Zfn7m&vhCpl z*vSsT1`rC!AhiYseKk?_b3$8#xjpz7BLC2%bJbI$1Fmss=BE#uLo05s*yGzG7jr&H z2%!a^3i0NIfbO+14tUO-MJ7W3YyTt(5)cM*!1+!P>M5`Y!hu+lAfjTZ*3rrm5b_d!1-g-zW|god zZ~NET+97ZCF&7cYMop3CM!7&2{+PJ(Acj1M<;(ntH2DF`M^}R+O7gq*{e~rW2xj6p z(hXs4qU|w6^xif!!;%1)3 za;Sk}eKDa8Db;DKZ*859X!+kU2^IrJ=_(HLJ0|jfEDc%^$cyA`iUZMX~ zL->Vx+>QSEH^~Fv|kr39w>sXUpE=N1EqqWKVW&)aXPO>?~cO zoY_go1szhaKI~QdH$O-FGLeOlP!&vky~)otgWq4g;YQRAW1G#6Y6+>KL%tZf7%w$@x>*=H zJkkRYTl7KIRA{cw8GTlcrD|tYo}o?YaqUQWYe;Tl-f%9l1&|NCIdIoYR>q^+}}fsw{p0Z zd}w#7oW46sYte3;0t=}zd7VtWuvmCea8H(PzJ-P^9kbOz=`QelxN-by%tLiVdH5Pt z5g{AZFTk+7KW%q4rnYpMFHV?R$#kJr-99cwn4m4BE2Jf-!X*|t@DJQRnOpLt7h!UG zv8>y$0_)~U=sXmpYyIL%)v)E(N-!j zaR<<<6n{5nXcf3D(wO1l7- zLPV+^4nb2Q_VZ7V-0sVGnxA`GzDI7-_l<=!g^e>vQ=IOHPqbK~O{$iGHxvRwc->rV zZl$oPi50eS6z1a`sss0PR;$6{_!tHFS*uiqmibmam@VN0aoo6hCFfx&O)k2Yq4K+f zd2cfq+wmAIaiqIU$vimTKEg^IYiw`!TGy!aoOS#b7wLQO@cy7FE10clc6`;%JwHh4 zMr~u5C|sBrdHu!d-Gp*&8%yENera3gPeG%ZrGN%J9Iz#Cyx%^KI*o%HH-}t0>N3 zbU5FyOKKC8u5J_T_rhvgs&O4=#1lftZ`34JN|!%3{~RoGE<$3T?1Oa6 z^^F|YfO(h>sZ%J5$dZ3iEjxjGuD8Xe6)ucMj&Ap=?XqQQQzQ{(v63^~3YN-wl}KIR zPLvflJqjHvGeIVs(#3?ej{KCPez!C3(#<`Y4Uy|6FpkWE5GK@cjDNC~fAO3hq36CJ zjm8oyqS&{+HZ*Flb&b3HgLz-OR;+|)qXHU(ISPc}-md$aYcJ;}dWAYq^7{BjfOSkX zh%PAH43ePe=6{K}ClRrOkki=6@cwHpILpx4qf$ zMqXg{O;z;@U$ewNc{9E7ax?4jOr$}MNWw|0K3}+Qm_mVZ`{#XEgkl%*0!&5C3X!Ml zy%rIc=AO7kaerO9fR1qYuT#SoSGn!Pube zk0E@5f{j(VB8#W=G*}O*pSDpI%mND;nK)FIHvrA$9IAxKP}#!L9g)5G6;itCnJh6+ zK4eNz^h~2?Saws+!oHk3PNwj}hn&t8+XJG+e)-?zQ(VQ$cT9V;QH6k0Rgk@ViV1Yn zd0^msbD!3Xu)$(ZPU3b~o1saUL}dW;;6yOelR^`3Y+&*O|Lz2hvEjPxnnk^M_4GzS zGH&R9c-O-`YZm0iew>=18Dj1zCgN#W5G>@dX^B!xzbTKY{I2(o(8^%nhnP8=`@jj{g_)7}u-rO#UDPMcDfUck@eRk-9 zR7#ps1QvF+TiQS)-u|7ygLsaT%y5UjjY2=hDVe_tGoR{`g&UYz}B3OyU(!Yx)g0UAYf$N}5L*CR<8Hu(L8{ZL%cyA-wOkC1f|X%aLqOgVDLrgc|WWiLLLu0u%2TbxsfBuxUeY>Clf8Apnir=9-w&j|| zGfn__>=bOzIAFt;Xi;fyEqA5Iv`+CD@!QR>xg6T);~>bxP<h1@`mL z*~f!;u9(wS=pGU68dj`*(K-AfKu@(sgs>QXM8=O)W+LujU%7dY9AMOW}S~A`6H|$GGB5zB%uA_mo5dO%5ErmlqQ`sIo7%ok- zzqUAdUA4$GO_Bq4--h^+pVij3Xckz+`6_RZ_x=)ZTztz6GOy461Lsb|PsB4w8~}+F zSlK~zT}X>NpLRUE4_4Lpjv{}=l(h{)nY5(c!$DsNB9h3Wo}V6*e{@7NW!%iFSbD{{ zR7>;T0lx~iJQz_e4`9gObHi8IPgu++$?!GY`Gf#l#vVv84xh-#Yo02V)>TNWF9qPFBo1GiHuy(@waEyppoQ%U**&UCsK!MrKmVd)bd7 zfEaLvs!nD0a+#j=x|j3ix&zDF~Ir+oe~M=Z^C z1^wdHjLx`0IwYg)4{I{XwK8?_=|;+*l^Nievu_I9Fq ztS_^EQOoTQJd)+M^I0cH!22rCt!%~dMm8Rq#>;CZ$O_2tFS1!}yc#k+lHkv9XBT^YX=Yql997E+e;{g|8HP;T4}zLT zT$@1(&u;@gFIW!`(IL`Ii8KMafD#eBNln|koep7x&K(3PKJX!DJh$Tk<#cUAQ>Ep( zS89?jrYYDg>+HxC=DxQHTSPZoCdW3=rkdD0>zG&4~xysQiVU6%zY9-Cx(0 z*3XC^9cRW1YNB6o%vq%35jyLthHU1?opcJh@PZBdqkmQHVI}c>3z_Bvc&GUbGk^>~{p6^fh_5}lCa1c9J zVLMfRJ6*m58Vk6OzDzArsy_)E3P^J}hUKW430Jt0lSV{BjDWn^cZNm|I3o$hgHkcT zbGR1jOGBih9c#EaM`VsV7T5vQ(T>j4W1E<|?JHd7sCpZcR zxt_HOY!+53*pd~%m{S(e(@c|lXqi4c4^Li~&(Hs`gq|#A`Ii$W8A40$vq2X+;5EKH zwju>$I#=OHp+MP&xu%~jch)p~d3O`p%tI?_@`SX9bE$5etjKt#Ha8X3!}KMk z&Lo%kt}}dB+Up|d4tStsr<0IS{cVI!3%J*irG`xt2mEA{R16zLCoZIL15^&NM0`)E zKJ+o-D4TGgq5Vv&wswuL{rhu0ri&liSg{+!s#AEdP#%nE3!@NVYdnVjQ+v}hIsB*& zXsE+66FVd%^`pON>7kL(S2oin@gt)bt&4D8EQ0$fTv!~DsXfQ+yF(5v&rvsWN9>g# zcQbq95yp{-F{P=U>Y%IJVIErEG6NqbL*ZY6VL6BNvwCy90Y6HQcPnctVcRy~?vnjh zOL-uS0C2am^fld_MqOAGiy7t1)C789AcF?c<$0+(tTdfbMjEiOFj_)c7s0Cw9V}uGW-wJ>&g<0h$#a2R`!1-;>CuXG{Y9K!!{$b!+LOk*?#8x zseh5Xhtqkhd+7ae(;lcP1(GBHU7*6`99daEee-NtZV{eGazpv=&=uf~jQ6tX=1b#; zcE>-#yb2GkuE}STjzlUs!c9q`&;KB@X<5i6xcc>l@6iK1z4X&_z>G$ELm)9Ir6cHB6&gQ>S^vp0q#!dS<qlS$uQve&AuCcY<6!f!{G5h=?OiReTW#oZwf;Y|ZU-bs{WwGy*F-`(|(j z`@6)KG+PmPZ1T)~a#M984i*X2<*b%tKQvdLT)+hFPY)uB1^Pnrw8m)IBsyy`pD!q` z!n7piD@G!|&gv9#HxC@gv$%NYm(5{Z_=Twtmh`cH{~tU%Z0e0Nqt|BC0s zi9fxrNMYpJ1Rs)K0nLmkV=f2v;xQ9=oMb{pd)E6yDs5Rizi}E)=o!XvZdC_1%VYi5 zYVHcI>Q}Zm-4dV~PqMOl;gJ+L`v_v<0W>l`eaUDnj>AY$y5uI4neE07a>%wiJ!ijX zM@x_8V^0<@XS#zj`6nW(Mst(6XZ(LJa_Cm98_nrq9Qd^qhjL?BB+one?$`T0lQB5D zA_pe1x~IJOSwK&3PIqP8Hq*V~bj`0D>a0}UidJipdCQ#QPd+n%p7MFQe73bV9vI4< zqFeY%sz&5IK(GY)y9rnmb~hspiUDAZb%h?5n3_jj#D-#Dw%9Z}tci(nFbZ!=8t_1P zHz$6bx$X3y$DU!%+UvWXZ{qemis3f~j~{WlqU{>kfz|p^J@ibgy4I!pb%VcQ6#rV> z$0I+Fwj=;3N9uA;+4wDfP5#|29skBM%=59X*Kr}Hk(tBQO)S^Yo&^5j&i5l}2mAKHq;A~cX_hzXxaneTIcxq)+#Q0U%yp6=siu_;7vskX zA9DU9Jd(46umHd>&0*}=$ZKWvT!-9_L3!h&I0m*|%iz!8>X8T)0sZ$EGb<31j$C^M|1EhrhJ&=#7?B^VVw)n=%m&& zs>-F@qHaI1%l2&ir~lHVWW_y$P}2e)(iw3$b;RIhOs0^=O&nuDIoRrlv-K;7CYQ7H zeB)dlhuHjH3!eZ{h{yy--_>O9lKtMYtWMr_?{8n4vo#AR5{hsk4VHZt&H?eAP_zr_ z3+#`dK_@~Y5Z`Ix_4gE023dANyKT8-!%c=#w9zLU7_$M#S3A%~%x*rYQaE99uEjI` z{Aio4wEAAd39&{jQ^stSM{^}MLm?Q0v7+zV?WzMFDB=)Sf0+2JWh+akb#&pd=HqQs zAah-IFu<{W#du34{FR?*!yzg`@@nRM?=tDUp$(^`&m5AYKjHh`ihjYM@i1|OqCaAG z@^(#Ww?1aG^uS45FV8?CMxyNIdXbT{;a1gFp7}>~qYc*n;(fb4^%9ObUeig|Lyd_S zb$c_OMT}#NCMn%7Ox`AcbTxZ_@Xd>$?{Nve5}r1q-6GFoZoWC!4$iusoRMMtk@DVL zAEml?QlQV`B-#cp1JU!sQ~$mYb{F8sC-hm!SN}P%4t#6++CB?!!rNiboKS}Ii+_$h zGYS7u5yxzH^2nUJCt$1n$>i@p(lUwRV*DZA^Kj?U7y-C^{EDcP;h4z}wEk89f?jDp z^b|PT{NnFtu5YwAtNybI#hx#HWr5|?$H#=qc5Wl|ug_=4%J;c;mpPoHN*Nrp?2-2n zvePQ)yziG3B0)xWNge~GGI4mQAH`bz`2FmYRo#1kMD!m$^ds-8d6nUJ&U4I0DzL)! zQFSGmgP7FKKG{r@0|Ze`Vm?FhFYPpSu17PZ3KL_ZB4@RO@ObMDKb{n!@nW?vf$b~Y z9e-24lP$SaIR}*;#lwT9yo`=}34h;QlbiK*3uzh45pt#BI6P|!Tywo1VMSqEfW0pN zJr6OQiq6SaR@KkI!|r}kiiv+OJBVc{5v-(!9iE%{cbCRFyQ#h1PXF0KeZo(@IKMA? z3asCbsD2!Y%{@4vBtJenZIQTi2sMJ z_xwxh{{#M!t$^a*g&Q~Sk>wuc2uG!5hI`~dQ`53!gEJf%mKJKcQp2(wS>a60OiRm3 zOS7S6Wn0US{Lc4x-MH>te*iZ)@Hmh2ex29z`FyZ#dtjeq=|uEPoUKA%tqIf(=Iz)gZr@& zL@|UdUlRhjjdA9nr(1PB*u^hkG?tR*wva*;44Ma773Dfa-kHF`&9+L=2hd=wj8#?X z-IAh!&4=|Qfg2%H3{8T%MrjwgoA1}<{mF?;E3^109YLWf^)4vBn}k~pTkzhTKcgBg z!M3@+n7@<5C=u1HMtu{G?Ra*l1_2T4cZ?xm6-9Ne$WpLE7wDP#k6^9CNnF~(8q35f zT;|Da)sDv-HA_ylsH3=5C#B~-NiB4f&v85(nls7Rk*hSiz{vATo87faBNHpfEN#W| z4x%Boqa@Y@@mFE2t;TJ+R43yx|04d=&*AblN$zR?FzIjmL9!PMlK#}{gsIney;@L= zYg1F-;jE)Nxh~y&mn4Rm-O#Ash6D}&I|GVk7b7UXL`32reSE{R#JRvdSN zTW||Px3-P+$%eJ%c3itJnY-?8vLQ`~coS*o!qmJzQkG1LIOSGpqjitSCN~a5>m0am z6xGc-_K=MU_pfN~CMLUF=L2q7I3Pr<+j{FJYgnIX|N_MRIq%Cmfg&w7MPL#cw%F8L(4>s!T_RXO#uWZIhsGE5IW_;R?5U~@f!=Ufq~a%0_9Jy-t|WN_?e+U5)KP)ej|GMMidQqNciDikiX>DD@z;^ zaZuXf@hUvyRmBO4`~Jr_E+mgfgdD=V{(FTjH6K~T$bm9mx4&>o2NB8#te5*_qMQjn z;t%I`Pmh+_@F7M}lA93)PNKkDKoW9ZnHtsA;flzB1y|&@S5^#U0#tQcrdO!yNp{of zJ0vm-P~Q|&8xh0J;cy-N4?7up8gs8#5QN(S8yDDo!0lm}kMq>EI|lyKK_=ysG~ zTl4_^lvwZKQa4hKF?G<1H$9p#If z!e>q+ec90i3K?|$g)@C}L&m-|yY&$J4p*zyzW@B8dcP(dZHqMVG{E`<0C2rIkMo|F zZrwqtPR=)0;@mDDM0yPXfmUfJDwpx7`=^BcAQ-f8*r`(Gbv1vX1V|ZxT7J#H62GV# zF!=Sb%$=LXo;jtSa(hh=x@on~%BQ>7U~24g`el@6 zzx2ZEyo}N_7$}`QsLXW^ZVC==UFu?-{S@k^_NCV0?!J6w(JS0K$82-pB?)Y^8m=Eo z?UPf`itfX4e7!s9Mv2aLUl!abgT_r#yRqZ98Ii6yDXp#7?wo^YFS^?1fZUo;g)jh7 z8R55UzRq}q%vZ@Qda>{@vL~)4+@G-(&KR_NYdk}ZYALbd(eY|x@7%QH&Wa#(tD+Ea?DQhSkJA!KIlaiy#8d24F%<4GCq=Vb;TW`c;u0(j~ zDE4b?8M`hyuL-KBmV=6_=%K zW<=NY>BHH=Hi(GdRbKv~RKpe>`woa%C^ds$FK$bfC6>qnylKgWNT0#T7EKVYI>F;Z z&@MLz@RDjdRVQ>#9F(|TL5Xf1&nHyDenQ1o(j<>(^<5XDs#D`+v z54N}b6hZw2ZP%P3U0jeWJ4&mM_wK$V1R>NW#gP_+7ZY9AYn5@8-5I zObu&TfjgDCeE7u0Q2h~ApFT_Axua&l{H>E>qAIX2E#V_($#AtUgqRsoHONcpM$T&H z%Wks`?5*V=R;7z8dbwM!TA_Wp??nts#NNJ~IR!6QZ+@v|d2o(FJ$=hbVNDpyA0Wxp zlhkz6!SU=9GTe=As!`5bZuNFV`WycVnMonaXrG+JfQ`>Xf*e)sGt9_HOl>{vpK=`! zp77K7jl!yPPDzDMqVskySI1ji;eC}3R9C{7IY4yN`+!KQ!UoMq!`&&yzk|#GJ^a6CW0ZL=JIGqCetinSJ7+#fVj3jjMm;dT z4A8vVE&jl5Lpn4TuQPHdY*qC-N(ujVkT77G(=R{b?BeTA2sJdmGNLf;Y_mFJ?iQw} z&-v>P?Vd>VvQ=wQ1|5Y_An8JMu-U?j|qNdixaC`|TM3qV58;ez7ee=NgK5 zsF=mieRiv&erZcuATZVF1^vmGS-jZRy=km<3)MH-@2KQz$?Nymo>nlXhj=8&+x4B@ zg!p0I2^T-Vy7|VDyu8PnVO(pnU-!#kNu8%;KfiUrK+ahK+K0l*1yK7ekpVUy&N^NL z7Nh}fXkXqczgzR##(qX<2;;@wD{jhk3x2=9oa$bOfzP`JW%w@MEv`mBp&1uVo8+sr zs=qoIm zxihpKK|lc9`KudMpS4=-L)4#kQnVH8QvP2LJ*e%vq4#%{D5~0YzxkS;Uhf0B<$mi; zZ@u7fWusR_wLbGfSF2vt?@GtCZ+UX23ci-7sGs?P(R$=N0k#ZsHFx`@>gKEm0*G(0(Q2QJ6V?AFs&^;dLEBYs z+W9Nx#u~@MX=&|?KG>c(VCvwZ8qF+sL&%tZS0xsgjV8Kn{_v!eZ+8QZ6uO1mQDsXP z{gHm7O&8;GnhpmoX{gyeN*Px}OG>FmiKK<2KKEHXMC#^nyy!2Yh#d~>rd(j0%Q->YN z)g*_uZQ9v$EM5No&u_Cz8vEq*Wd zNUHtp8yf~YELm9kK!S;M>$m~)ahKQw(7?{(xJ$_c-4k#B16w<>_sFtBehxA%T|~dW z9%BAZviYq3p+R$m>fdr^8=9tRNz+(6ud&(Z7-#7|eJe@tPuzgBx+Tq2>3-_qcB@qv z{m^`~MptW!^Fw>Jw3C1COuSQl`^XUhfqv?DRlNUVZ0*)1dAw6H;z4KgU1#-W>NY%B zk3`c62J4btbbdNtx_($0MBDarL5prtFlBSS-Fp9C|6B6 zdY``BJaaXnx%}OB$}^q8Q;*r5Sxy#nvCq~+>syNzvs%pN!tXuqQd{T@y=EH<%i?O8 zM$oMaWRYbyc7v(5?0+@~Vi{b2yL0#7x#F|Wz07b7)Kg=1S1KZVtGf@=yU%xKQw7}@ zj-;NyZ&$4~lJ{)G^PX1KlHH|08-ZWDFD-3UA$qhS_BBs7_}fo#4DIV|{%WiC)Oq$? zMj2e*YkyX+=gKp?`dIsh)w)y|%)_v~Bl_q05+ zZ++I&`r5wjLr>dR`)hxCu8Hggh<|6kPz8$rE=%<}k}kKKp1gEPg{^zk2?WyEfWlxP z5y%Jx3I#Cl!T$&5T{FPO{$I>nvQQ>EfB64k-q*E<_3^&Vp`+KYcyrW5zEqbVSN?y@ z+h{rUe-Ygy9;s=Um$}=Wi+%EB{)c({1-ex4x!LTj=T6(49iw|<^;9bls(ar`9K09< zM0E4^9evg&;%*sUhwd4_nf2r2{DaPvzFUr2xSu_4Ew2YSvW8)yX=5^-5+w?$5xn+y z4|o=)VKTwwf$ixvaodu9=X*AZY%|@wd#pnAoEx_7dx4* zH(ae+#Fpel@8$T)2mYoheutyWwYd6w;4f8A{QA26(gTsh$lsq?Yg+!zM?Rhy^)GaM z1K+TT`hNK5x?cX7iQE%gWji-Oq2;()F{W&gZ>~ zZkO{U65lVKk#sh5bN*)R&xr0xwS?sM>1;vMkU&fW(*3ZPe~XAemYz-SBCJ-n@b!TjB#AG=%)>71^e_U}Q-r@9@658bX!Ur)BX)aC2$FIz;ibC#=eSY4Uk?`Y&4 zyO%b0A>{hD))+z&W+qnS3UmXdd&MF<$n(kkLQK>eP5xPkJ*j#z)Z%k>#?y0y-A4*b z6_0^$Me|XC1tt+v$9KoCw*Z6I0 zIuS3~<+qPtGLG>0HT6tdyYue9o9_`sp_)k2wY+;Wn)dDj@|G_B_RHBgr2Py3+d&m2 zkHlG-ePX_HmR)^!eaJYCL7)@F*!IL$Jor-C!3t4_C4o9JOl$oXh%qi3IMW;FuT!Pi zauI5#AZfNM_WGNoQkfy0^U-M<&g%C{W6p=gm+U<>_B!crhok8mL?M*QpH%VmeCCDP zA8YW&Pk5`1U7f1!ofb)dPd9!rCGg0!ui1b4yZmg^lCVhtbIz75&=v*3#d#znMv8l<$r)lDFtFR1?dy zU&+U$J-_e&d(@=7nTTFR7pYdaybTJNDh;5-0ES{xmY<1g$w%EW^uR zuD-@#3UTGTGEG*qc}l*?L_fy+ZTG_4^Xt7|eDeci6mD^+SV1kRVng{RinMahw~mG* zF0!K|;@*&hpNQkP3;nw-VJ9Mzt9*S&_MN1w4_ICHBo2K%1LusIv<*>)N<%{xdK4++sO8F5Wbkw}QFTk7DfmBjC!1 zDq^itb@b^tIVo|=?R&%E5M3Z;rLXMs?!MZF?q4pX#ao z;5&ntg_n8^C4LSTC09iqVypQP9ILCqQ_9kFnfvtcsR6%epUxhi%Imz(9MdU~5gcst zGp`%+HM&7QSSWNS>`QNB%RHWBw4jWR-W-*?2y>+_b4->kl206yxr$D0xTDj4dH<`S zs^JXh{Td~u{rMx_5M}=&Jd8k$3nCqROCC`@AFt+UCx*&;oNq~WgD%rN|p==5g}FJG5ll|CI-s#~0WhKsjnJiDVNx;{u zCUJ|(8E~IBXXKo1(pM8}V~roN4UVB8ZDE)CLt?Ak77tVggtebJeD=zTlg|}O)QUa@ z=sm6YXTG4z_28Pr&TZ2cfVO{dMVL=sAtCIt;5YqlksY*D-c|@Lt#2PNC)S%-owCeN zHCqXkJDvAjL&mYNh^JmsVW6fVCJIY5ihTIeo*AkY(%8Y?`A6zX%gHx^Q=jEY4vGc9 zuA^-x_9-jim|ZU1qvY&J>(t4V3bmn_9~zmdokc$y3YCM@p6p*sXd`s2_pskHl0w&8 zWD@tf$7~;to&H+>`P_kdZHLdux?pWC#p3NJo^mYsLXu)9r1ibqd!2w{?r3KNY)HPH z`&@%|{IQ&ZCJ|fzTGj#2=CiO^gNMiN z8i6kL&uOLorA=?M2(fix&&a{7;Lh#W*r!O*+oiSkz5V^4g?$+>;<@ebtnYm(c|)dt z=__=^+}JgOYvScL23lifDtEVNsZ`#p6zBLgaCzAmZX%<0Beyf75c?c+9lFeZt>c@5 zeDz35ZMN~q6Pmm9FF7*kz;XSjnHvac2N3M{@!Y6yr|}3XRWs?Kbh>;WWWnbo-r}cx?WsquS%h>MeNWBr7eRv?8ss=5g z+sB;-e*OqJ!lOFzu@_2kH|4g`p;GjhJ2)|+McdNFM@c6&}z4sw)&*O|6v z+fi|hh%6<)ES7Z%#2L3Y!Am`Uopn1Mnu=$4`m;0RWLyQ=*;&e2vuw$7Dy2~|*Oud8 z4m(2PwE1)LdD8Bp1!hsOLLr_t$U|Q!3DRn3c7d&JzWL8vjun83xrCA{kDaJ!G*(Fg(JMey-N9G zvxO7ug$bpsab!_~ZPAT&``fWtfNr10%kVkUz#az)TinJe>V?LD+cEQa>9=u3vWvwf zoFX{fM8w8E5)?~I7w35uD~g>d!k@VgiC>>R1nWC+c39aEb%4TzXO~n^i^ORzr=M{pyRm&BgG3=*wGz98#4B#Vlmo2ZA5)&?SmXud z>xgzs0~Gf?0yY{~3=J>Y)~)F(uJ$S2;DA8FE=1<_np8AM!EvQLns8P=x`j}8*AAc@xzQ9DCWKo_`69DQ>EEdo_(i;JJ@ z#?Irg&jF;Iiw1I|Kr)a=kf-Ii>MSBbb*b>UHK{Q2 zd07qR5D*dowyO9D(IiqJM9+{a0BU%Ui+-?%z74d838+CK`rn4s6&zMsu?!au=^McS zW`GGSW)y(;*U&%_bqZkZDVXO1%pyVZ_9P-?LE;ezolk}x0jjx`+u!nvo{}+72{JiE z!xVEEi6C)rfky$siukA}0D2E#-Z)HbHyRUy0W<_pND{*Wpq)$fHY9bN+}$!>t7d* zlNekBLbG)MHxGdC06H%s)&nSWj3@+i9VY?crhP>5(=@B^(0nz!vnt`0ckuP|6wCk) zbB}^~zs6r8Hv^12kk5XHZDLKrxf}KE5cxVI~$(bwoHoz`y2V<^<^9 z5(w22>JUAXJV3ovSrBLp>4n5J~5k)?pzaH~{a; zIBWGY#5;uO^LE%OVZreCW2LtX>lv^Pp# zfafg0!5Ra}TtqSjZlN+@TLrh>l*-}4Elym7l)x=o;`6!?O*`&o5TV@y!7Kr@f5++C zZa9!weN4o(;Z#(WixatOf4{*Hd$3qLtVH7VzPHd^^3bRdeo_G<0`))H(e;Xm$Q5E1 zoiIl!;EZO2NCNy5D&KfF_SEWqm#=0m~&<0GvJ$P|6ZVEH3lrRiqCH-~#d)z>PkG!$zNP{8#nps963Xg7`E6v$%$` z8SXSCKhOnkOf8c0I0OrO?lBi;wpOMv-|wT@uw)CL^1+U;jyxJ4cfUPe;PCLtrqs}; zH17psfL!rp5^2Xr`L$q9iU<>R0~0`KW)$ef3(+j#`mIR;5&5$0&OHa<+6K})vr9L` zKp-v_g2PTzMk{-3Dyv4H3(BU~q~!m}G%jG!((QgBPKOsz1wBCaUB%T5isw&G3m&Wp zF^PPna1#x0NM#eil9>DbR8!B2$c%+N_vEyDg&GY_i!l4)QokOvY+}(KXs75I#lUIO^iOK zFrfmFz07biA_7K45jS3xo&(K^hl{&B1OU)8cnq?pxAzLp3| zNIQAY-Y*rgm-sIq16K-%0P59uj9(xR0tR~4rdSBTX-5kXx#WI8DWeyPIE+I83XfVq_Clx@kxP3B!zW}7 zuJVg_aSxt1 z@PIt*d6m~|J3pkE6c@C#YM7l3IIRb8(=X@5{no@&H>BnW;?eSC9nlqJk2+?Ocr9f? zVw`yWRZrD}4Qx9IBb;9pr!MZa!`>C3?h0Rs1T#qgnZD|x_;!$|5PsJISw<4)62+?~ z#ZwObk8!Uhf2tyXx>YQm;dH}v@=a2!@TBlX_ri)+i6LW4%GVG3QR(tY{yEjW_COF~ zkce6L83kTinM}MpQY`t7DEXWMPXCPQn=~X5uBaVlpX~n7qk(#~fPPGr@Dqv)d;eEo zKj5^tWgQmC9X`<3Q^ZHiCrp?5t&~d2R9{>aPOga-P$B`UcGt(tuU_PxQ1Yi>Tuk0h zQ!wj=nE5r#3q$M+?B!S3FUwrX2V`j2t2f}(`8n?FAn+OCniMzW$8M9ODc#sQ5d5D+ zJ|jkan(}A{he_nxTNHx_x8(NvR(%0UiLg?^B1T`{agbLGsm$r|9ONqBZel zCv*{^=9_or@dwkAi!YGh^!*xFV5wDyCg*&4uxP<`w?}Bwn&s?ah#?7b#2zE22Bt6Y zg*dyzpKfO6{W^T@oLt`P?CM{V-+$SKpSvg;ooHV}{}(UeJ&BwZl)c7DAPU=CkOqC+ zN00bbJD<0HYxy%O{3GGNCyo;s^5Dzs{&N*ms_lkA6nv$0Xworprg7hcv#_yJ4a@z#jZ{s~o8)PMF{&o+ zP#1|<-17YU70C;^(VG=3sIG`}CP##FTcyF@BKSq>jx4q3S|mcLaZ0GG*|B#fhlE`x zet)gJs$bL`|L+-QUxj(Fxa?Nxm5OI^lcI~#-kE04lkO>9T#(81`Bmzn~q>{I`;WL6(OFfaIFP)E#; zshn!#K`%6PmAuP;8b<#t5!Bqo64l05h3MK8sQss>92+Vosii2=FILUJyulvGtgyZ`>;h4+TZf>DbGqP`}JmroPZ<&n}$U={mzwMWUg|0YFZ2!kq`Y?Uyi2Kbj+ zuy7~%BMJoCRH+lzDplaiigv=OmrL`Bc|&IphL#MgmpX&LDyb(NUbv^U@-j;G^oRz>KF(~Y)Z;G& zQp`2AujObq7uJS1)hStshAQ3-+8=H0e7{UkLfnp!_p1rP$dun$tgpBtrViT&8P%}*ZmY;Hu}yX|WpA<<|3(y6-V{BkzpdEo%ft{fEjA6q3R zr|hg&HTjKT>h^K17$s6pO|*QF+ag2OTTbk9vANQg2J8Do0SFu;I`&mF4g=rob5NY z`0+QW{KnzJTZ;ww^1h=<|2!2y?S+YIg_?!U7ry=^!|E>Uo9b_ZRdHr{yMtY%4&nAZ z0h+WnKK=5%b%a4wO~KTPxF&26-msNX`Ne<2ZbDEMr@*{#ucEbIxXv_9Fe?b=*UD)_ z2XTLi2+zC(<!&Ify)wzrLR4+lbF$_ zD_Uooq^BAl;DH@@Ycn`d4PxiCb9~zhceNCK#g*V!(HNf? ziS-uoTp-mk^vHK0l_wj+j+5<@>HIpixwU)~TmL*qw2SoN)w3G62I2S6O?yx4fLl01rIYK{$V*gXhpu{?*VrH8tXPARHxSwqVGTT9mkrpF1ffD z*awzVB+`SAX35d{=LupaS3cNd26cV+FNm-`hx5T8~_Gzh{B!er50~ooJAmi~#mi1kKzhgW)&F1J) zo33xOd*kAzC|P=|Ki8xx?83!229at1xp zSNj$3t-F8NEH8?N4#-!mdurMG=MPqbD6Tp0 z8&9^^|ME#Ag|qIPLxthX5egk^?$q3NRET6i##KJtd&^8_+5M~Lm&wbwxuU|iS>uuN zyxCz>w-OyE&>Kuk$be#_HPfVbQ5M-AY96|1=!LFD>*x2Y{3Yb=3tCc5+48hEiOSP| zyRh9O&4tk4U6kN3pj5$4R{rROj(5`92Uia%k@pPz3a1R?h8CtE~~yo&bQwG zt|B>jQdvlW>B0Tk_N$9h`%cqkw^A8;9e>3|SuSU*CZX@29@Lt6hinTEuDnaUY))Q> zXd5lsyHYeBoFXtyFMq=vyIiMgb8O7ID!hE6HwIN**^kH0yxQxprPAXxVw5J`H04&4 ze~5fRgF`KjJyxe$Nr&Oa$gn$3E^>Jnm=>4Y3s9YV-9@%-snukLNT_~7r7`Y1QnT8XyQ`18 z?(~cvYyULzr55QhS5jKOnzQZhTD0O@0m2mxmc79nGNIMX1Ug6Fc-Peddl24bio`?l z0;;U;BC#-IN%h70kah(YqEfz7;@lMv6Ww-}NsB#-w7^i?&?`za5d_ ztXXq_vlo|{O{W>+X^M^8Faj~cI@6(qB@*85h#q6jmJYnUaW_fen#_fhoM1ixbVa^k z7+iATsFmCX;vnjdYsXFC@TFxhYuot0#G>OQ#EAg)c49{Hj9*x=(E3xy5 z>=zdp;1D*nsavDKBEySq>xy`(a&4L;u{CvdZxhGEjD_fEw^yR!x*80*5U&MSiYnMi z30|98Ju`5{gUG1;$KJgFt)j7ZqiV_PtQ==VNh3!G1qZk>fb=Glhh;3CwH|O_&+X2R zaI(4VEFl{}FmD)OMT)&hj-{bu2Rn6^ZbELA=TkLo!G1#ExbM8u3)qzslfW1M_j-d)F<8KIrs5R)ZP<&iWJfp2qcz}wKlu6!Voyr&_we&ATaz4P#h zV3=zooxn#LlWOGJWnA3`-PCp}eJ>baXHQV*rdjlz#Pe2-bPocouBtVD&dsl-^@Tx0 z=D)Ti4$#g7uNn*)s=B?|y9H7udyS7P* zhIBE?n6n4KQXuJl$cz?sXsJHUv=+Y%8-pgOO!_u<)7ZX=A2?xJ9G_B1E2+@Nri zy|)&b5qDk9h`no_))ChVkT zwAI{1$j*Y(iR?Xre%`8V+fYHnI9!;vXAm`cO~^`KgC_*TkARrFomx+((JIgnWZ$XW zSiPA`f_SftmO<}PfNKa!n}Z&*zXEF^hVEOZwM*g=)-qC$2SUp!fWjaY!Ih0bK-**j-x z=SHadAc!@A5z@$nTxABY!Mt%=8uQ@LW`>s<^l+Nb&PHe?p?AQwJh2hFi3V?5pyHHD zZ@nB$PVyVK@0GYYDItGAXkdJe*CF$bmBPm*P*~v{m}3ygha_-glq#SX0cynnAHJ7uIJfm6CujUl>q!To ziV`#@TQZDi>Fyt)5lDD22X-U_){+CUUNZ_rva@${6Nyl(JDktyf%#s3Mf|`5JYqfq z9;n1H{4uug2_y(xmD}jzPh_7;fB2~e=}{fDyOopHk35e@945aA5HO;=Jro9&U<^;Go+v?QN;ql4BaVLH5XpIO@p*v$?2YIaI)>gI8SKrResT()6ootkt zXC1_$w@Fu;;0A&@rH?-j6;*eHSsrlHXBrcs2i7J139ti1^?P>&0a#-n%JnSr#kg^n z2lnBrgKr_>q3x5`1;`gI>f)(yBoP0gM@l;PfmqJXu#m|Bi=@JZj-U^{oP^-wwJ7+( z5pC<6$m=(etZ}=q4(2D3@Sw@^Z~ZKC);ZO3R}V#qjj;6I_p7J$)|u*rBQ-CuVQ`}tli+{Qf6Vt4wNJrfiA#)-qi7F zgqlb&cJTl|0K}9;Q^kqFZ6if8IBM=1#VR?{I&5j~Y~*QJWdWX!7q;ybK!Fi&!mOL8 zZ`hllSI)_^drr=NJ0E`F7xO5p@@ZqC4i=W=RsN-DKw^mVcnt5O1dY!^a%?M?k&`YE zQ`|{KOD5y5`?<=aPd0yr6fVEEJM6d3n4PkmAA)Dbuj!LOmlH?}xr7n;tAmSj6DjM0 zp!O#TxV}Py`CgfQ9s98VF^BWx*xA|6J@ZOxRctbkVHC#zsL$hvp4ptVNWpzb#v=kL zkce4Nk7z@Wj1TUui+(RzyKTXE{G5H9k){~nM?k!>WG7({`Jv(N3k-_{=r4VHr{K#r zNctm92mwb2^5-J01+hpo+Cy2I0*R7~2NhpjI+KaMyHJ3<0E^%iu!odVmSa7mSDa&l z-&cDSPATn}W2LMy^$9}LWr!0OVm!b|J2lqm<}mnjHaVE(%rVYmjx8pEc@uUltm}Io%WnyJ^^{*Rej;~`?{F0O~^2ggI<_2KCbm4Rr13rOIR?Tef&%8SaR&C zO}Op`J$(=gWv~veQ*RI%g)5eUBVzfBtbItTmf+RIEbZ*S0#Z2L!j^7Bp<590_2a-6 z!1o7`c|acmb)w|PQ5NAVOYb=#3FG)irCZHPS;;{a$?@k*-lo;^*|jSv>#!#O+OB3m z^$D%1=j<_gRwF45r30&3fA>rba*nqxs^}lC-&N^Og+n@dUHT6d$xDj)9IuE;cpnRx zt0MfCX}j0n4{e2~o?cD!Y8;J;ttd|Rv>G`z&DsgLWwKbi$+U|mH2FsAUVN`aHB_z< zmb3;BA&Bi%vI?(3-X#>8Bl%W1h&cgbj?Z_QPSRLs%VtpkB{CZK0|gw?EIhwhc5-ZH z!9iWhsM6}Q7*~BpDxDlC^wGuy7RS-ek7Q+2T9v4a22Y2ZLs`0pj8qDV(e>T zX_}^BzsUx1QqoH-5=WlL8Tnp(n8Mf$Iq-_}qMviu{K=bYSP-A}VX_JQH~-plSnX5f z{(H!>MTwyEjI=mJ;_A<0!pnT@b*T?X(lt(}4m`zc<}4xAZx$?nE__(wgNnij0LDHb zFg{+9?6iM+TG+C)i(~xQ~;ViLR9w5jr_WGe%Z& z!y$IIbi>zwUN3ykjibuhipkG{X!j`Sb+$P12lLu@b0Rc|5HHG7_;CDU^0~0EZFf2x zp0z{?7_kHxe*IXi6H`+O>J|HOkKfN9nJnjJRvW%#mX?9K^7CKoU7x+@{(1QBFSgi% zlZvq!HFr4HRWScxhc-Uk&VIa*G`3@0DXlm{U$Vj7_uLTy^cWFQ-9K>^n1fEP6<{+9 zf@k)@QjdGF(l{e$g>2a)zvncQ8n%D1`PAXZ&(yf}`)I5o`8;bE2OLLchX|;-WSq7c zWA{~_ABTEm_VI2W*tSc;2LK;!2}eelAtUky|Dd5Xb%JE1$pTn^Eys#Ow*~NjK9VUy z04fkE+y9uCmbi9JI|;B@UcqYL>e;a1g4~sd57$Kwk60;QaKG7ert1*b^9=kf9cO=d zx9Qg!-I91EXfolj>V~1TSV1W+<`L`3=5M&k@wp9>Ic;%QalIeLF?YHQdB^nFw ziO`?3PFA^{{b~L4h0Zf`ck^8KnW&AO!TT2`R5T8`o-BXNEcnml#m#(x9v6>O}7p3Jod zvfDy$dVG7_boH*lKC^S>R>P-)FW2numg$+O{V`SQ$ZbQXzWkIF-kJLicHy;Z;JdE0 zkKTRWe+pmPCx<*cumje!G!X{<%p|!%`si4fWPR;N_Jcf&Ghs`?*Wr4vqXvC#G*0}K z_S$~d9ObRuHu%_^aLUrp>V(rbrflGd#(inCO~Ej3Fz5!Fz)PRvXrBC8!`3Xb?9bD0 z?|LI)a06@c&V0%z@F7tnxy;vUmht0}t?1U~Qa?h=$nxCbxQoi?LYdtgx>c!TA+stR zjs0+?6eXDl7K@3jO1lc!LCM&vod^{hW&IZjwKSt!?h1!&{Sj85#gD7j-;VF`wd57D z9$uMU@R)O%3A!O+b;8+ZG<`PwezpC4(w|2yCu`__S*PRc4YJFM00jFU|59|<$qthUdgrS zbXUxN{A2c3S!3MGtN~wTiR10C%OW>_w&i@Gu3Y_KMo3kvs89{Fe>#!=kX)y!Xl>Qz zoS8ry1c-ERcf8OTEg$;LQ!CKGb`#GYVm8W}9H9wy{$)nwR=<>OnDQ@tY zSkPkkJn1OEb79*cZZ27Uec?9hVO`s;6;d$KVSdE>D;t+t{?+3ZDRPhT#HMV3(C|*w zbKCbMt@|=4ot!~O{4}-o*vlH%`QwLT27bM${}^Ln^*oTCX)^71hlf?yxS7%MruQ%zB(l4y?MV9INt#d}s&Q?P~l_YVzFf`^U$f(UHM^ zrmq*hU#-7axR)1ezN`f2MTLw1w~X++v7|I?`KDsMqd~2E(!HgEYWFej=&`DQ_m|O{ zC3mwPs7t+gu(B0?CVewPUBYg}+Mpc~I1;0(hT6TyL8ds36p8gGGY6yI6v?+QAK$11 zMog2;T(<;qd@xlrf@v7~pMJz4+5Gx6`c9*~dKF+@Qgd7YGXgDcH+flbexmbk&m`>B z+72Cq*vuOj+QT(cC=j(-p^}KOyeRu%5^g^t?<96h&vKFHj%@=m_1z=_4$St;{iYP9 z;PNAY){SM0_Vw7p7S&0hRpxc9z5XFw6=zXnc)6rM!}3Gs!#w%pnadKv(*%Oev_|aK z`+@L8Ew#qRAxs~%0n7B-^(!t@~r;ONw+5Lo-wZcpneO7V#Jw zI6NjPD=<8TIwIRQh;?!siir$-V*C>@5kUHQJCx<~f-tSiM$m zcG@D44uG^&tg2a-K0K5+DMIEDo~{{Dg63^ORGQ>p`s%q1=K0h~1}^u@E2J?L z`6O)TSW@godI>Phxp25t$p)D6`E4$u4k8C8#>sHM7tEZ@=O2SDS{Bc1z+*E{45&Wk z3w8!YD2e7qLhY?@bc&f6`@ha&J=#iT0`sza#Kr-ee#nbl9>fFrv&}kv5sFv)fjWhE z*WYSKM?kfd?h%F^fVzF(Zw*qH;^4Z>d)TpM33Oqi8a zogO)V$ZN3WZjOHHiH(3$3g3(3oi?@)0&dB_T&ANBShgKBY*CRXc^nVjW`O?EHKH>G zVJ3(6-RU@VYq>a!r={>4@TdCOoQe9Wfizvef9eJxswVhaPD(#k91}3`y;Oy`f0Kdt zYKq94HV`=!E%2Et95Db zE$YHw2ox%qCTj0diIYs5SBX#Jg(_(O^<^8Z%fw=F!BYFjRJ)7mt#T)0Q%>1goHrgQ znuae?PW?spzTGS-p4>FeGI`{Z^GhlctEJf2IAmntOwV=FfTDsqV1kftHKD2e+Kat& zj)_aF=Vp)(d3IW360&Cpwyk@4IlK^)I^I~PzUakr05GOl?WOIOFZvx9)}(yM{Yv9= zUUrTDn9K|fRNBZ8+rvU`Bpz~1c%e`;rbB>7hr>+Q#bBW|l22u-%nvGw#Uz)`z2CL-WBjc#soPi19$j{k8zV{_jDl3ZcPbye-2V0MKh-aRaZupN zT3Kq}()J-!2i-IRbJHXWm9ai#Yg_M@z^j!+9bd<}Nuy(pEF6w8=FICCEeTg3+ivri z!=s5;%f5az<@tYiy!;JC;<>)pw%2q#B=@rFQ=sYjN+@ofX1WPB(DqPv>TCLM2+RXX zsPzRJx!SZ0tR$+~=g^<~LVRF!GblZ168!%Wc3(kFEe^c4(?dc6p?9VC5_%COp*JxI zB2|L)q67p5L`kP(sDdC>kfs76(o{kR5h6utDo7FQMs&MT(VYCh`EJhDnc+H2Ca~75 zmGygGHQxLQ2h!F6X_iv8m4}LKY5L>V$!JjYJX@xEK}LCkx6b?Lz{Lm$S_lF99u0Jx zkhS_bQC%@?c8jK>4fH(@6g}XQH7=ku#Q04$U)MMAXHDwjE zvh#1MI1Z< z0Kp8L0pI{Ao(=&BgpffII1FyU%9{*67y`-OJfltq<^%&iK_M~tPsLQDq@mAcm^fKh zm5z-LanK6IwKhngnZyjk@Pi=tXI8G(I;gb+AQ%rC(vuA_Mg_T44+&ia2H4>-W{1!T z1G=p?E|4lR0(y=&+uPyI1i|thz@7Ifr`{16|6szd*dRi;uIC8S;o79z5It}NSM=3;PGcF0GQxo)AqIdgM~SR$_K@V zKCurC%t{yG>8vwIl^W}lF4_*q6<4qa^SF0;5>&sSkxMZ+4P_5M(`-!SI zFmHeZ8;899grRA*f;36ihvzBRC-FiM3VM;ZcP4{zIMdn&;F`J-43PK1&Pdlbs#hbB z5DZw2G!9d(+=Ko}WsAyth#M&`j0;L0*whs4s9|UYQjPkSL%QFAN~-Uy6H0F`PDvc2 zbrDAIje|r13yFV+kgg#*jbLo;ki~(Ze=Su33;WA?*ZUrIS=Ux_HRtkqUIBJkmap;d zhbSN5Xb_ow2mm&eZ#-m%*P+`S`#a>Uud*N+E@8&j#?E%s)AVH3;?J}k91NXJ3X)qB z;=3to;tJOMPN^dUWybNVBS9(Kjeh-+;kppfd2u5$7cX>xH>qwe%Y6~puym-k;Y>~) z&}_hzhlrHo_!b9*Wr2GGnSEdEjLvLV98(G(%naLu!XiHAY$Gz7)Xv5PMR#qBKL+M> z@czjuhj!R9Wc+l|sr2_FH!-tn7-ZGXj)p=6huAhNSqa=Z6(!lmmdw%n*)_XQtr`2mm@D{v7j&<@`<`Ej)^sXc zX>`l*6I-y`+8kwP;tHahe4NK_iDAKSN^C568|TuN`q6uV+RXHnorAS030+cN;(9SK`CSsK7lR1njB6KL;qA ztYYvHRU2_zAg>gGHjCx++_Y`wg8x{`*_i=*&-l$wPD$9ei$29>oQmTw)Hx8g7jMy% z9AN8OiWnW>F&WlE=fG-wCp`pa#ai*ktf=r$))Kb*LE7i)o6k8-W|nIL4F1@BJ>bp4 zpNjtAB$1se<+iVLl%mhHEB@n3{H{6M>?g&`*Ifn6_1I$$<9W~2qDyg7$LSUs+INa* zD%iNEx*Zx-9Z!FaEUCg|cc_=~V0lrXS`Ljs8dA4qA9ikBm}i^ZDh%GpaezOLrs^9juh5DM?t2taHu z@g62Wz?<1BDC6)VB8Cp{j6R%epH{xzvpr~pvoSK_Mb~X{bs$l4h(`%UM1Am{c7X<< z7*gH=^u(c1OT5i`uO-f-6l5BkS8ySixZcx-9{# zTyCB;BrO?hK_8;MU{4QVec)X^U%zkk21soV#+(`w@}=5ym|8fzuHIR9k&3UMfoqfP z8d?BoKNly|N~yj0?@c*@=@D_2xeafAlY3ofo>nHdhOuAwLezF`MP(`IezK|{8>=j1 z5o05Pa_;~RidAd5)tSUq37_bz%y?n#NF2iXfg*8k+L#30aJDdU@SE&{o~X{cfl;8V z{-y9zAOVN=v^Gd($!vLE9expV5TEi7OI`F5f7OFsYNv$wXJyEYY$iw_zloUx7|4M8 zVr<0sFPZ`V6Bjl~RWtMXW2d#Cd$osZVhc8D9TfH)GzhiT$+-{`%N9xnq5cS}m1?2V z&s=h8&rG|dDMT)?2JoZ@#3BwO$`F;vnyJv5%*>ycSP@4?G0U)Jk`P2dYFMG%xCbN_4>XvYe9gzOkI8q)Z z=!!S^zIZ;Itt{zgHqI7wjoJnEHaxj^eFJf|*xJ|xjvxv2^Hqo}h zqO5~OyY2<{p)dD*wnu8a(tKFI4wD^C=rlbuO0~t7geYFO)5apz=CB#}GfAyG?AWIW zO+eS}iyD2Oq=yIZi2fE{1awGHR0tk$7rf0Wqme;&oAlw3+tI)vA7 zwJ{(LX^T=0B@CHr&tU;)-yF~NP_?-b!mIvWzWFBdp2LCLjYMtW;GC0=>^QMsd$nhduZT@idI6mht z5cLADW42_#0m)A7w2clPD#FkIxUwDoSN!oAsnS6MGaIZrb?_=)*OJG_&~yP*SsYMM z78qb&WwtPg3jRwSd;IP9h)fY%8G<~N2suQ3X%urJ*3t$G0LfGjs-diJCbiC5r41i8 zi@!mopP;Gu_b9dw>g|K{2SCaw9%Nvx5z(YU1evsgaXG&f-#xRU!G%;kyID2XCTIow zBD4IncG(j8Ve{Sk3gziBfJCiu?bU~|8&fqd*9Bf#l`LHS47?u}gwHdL+n(utiplV^|dyiKyZmr=qX(ZmRw*KIu7T zI{13+>pS>CS+1;kikZ)7dEsQfRz>(#1hX{st<-J7&#oWco**&%B21QGn2h*y*$R^(DS%x$i?*M*-_`5}s?-?+=UFML!=` zGX3@GKK~yXVIz~Z#aum+%ugSWDYsAU$!lz>=jR$*`YPFoz65M!>sdAnj%4(HbF^l@ zowWW|pT1S|A2(`zs%B$(P4C;Z(s{>O-S2bH#a|x0bK5{=eS7Yb ztF1n%gZAy1{4B15nsZl6DAaP1=`EN)<+L*Y*jZ`0aKR@sfN#b(?%DifYKE)+tlOz) zrxsn(j4cO55hKx|xU0h?rE`D8ONKF?n(=Q;q z)-yFqJeJRCO?z+n7LGWcxO$YC^n(0<;Sqj3JYwYkiAT6ijJMZ~{r`Bxt%*W)kCPRH z@y?>f*x<j5!4^6PGD$)U?pTJMq10 z7MUzi#9uv-+^-wYPt$9O4|v*jXXW9!8Z26v4j1eQPA|QQe0cB86EgVvf%J~?$} z&%C^ZH4(#ymy0|0r?Bm15D^JE>_3Gbx?d!lf6<~KUbIapIXIy$! z8pe5eR_yeq#QFuqxsVzh_`Db+HL<3|J=7AyzQNEtnzWt;Y96n(74h zZ9?;j1aXrF$6&GbwdPg}hxLn|y6wY4E@odn+TiU8CAUIGQf|gQn55r2Pe9dtysHLX zw@se19$yjKdmnn+!;Zxa>DGQ`;gwh#*;Vi6So^E4OF2c;15@Hw8vJ1WZ~f~WD+@8N zRxrL^Dy7w}eYlVLNR1UW33~dxx1-*-zQbF*`?J;Rpl8Eb<1Qp=AePdy-s)}#6~iyj z7R!y+xdFAtInGDo!oCBcO1VaN5k|h2#V#)eFG{O#Q%rUAV`}|;bK?CBXYI9nFD{#7 zZt5Ox_j&fS9TH82XmlI4jtWQ!cOCn+Q=A&QT|Tr*l`dX-7&B{O98!IbJ6734c%;pG z0TN^TMq`?H^a@S*6Rxj?33}H0gyWqE;wF2rwe!%h+Z>$xHAMD61T?^1~cg=}F1YJ}+dm8ErD`FQ%{b?Dp@G z?QJWsFDdvo5!)LD+^}#Pj7NYw#K*zG4I}vIh>>Obv62!HQwRX-=0Sla4{0o7*Q#o2`M&{#$Lm&kLd&QAA3 zv)mK_-G!jNS)7KAy)5O*=h<(<(2iNZ^82gEQ|HE;-`qLWMttrtS9q|$!RQ|&N7T}< zf=1ic3M_+~&maBeTOB<{P{H&_Hd?_*TTR{3_GD&I)Q#?8Wn^Yr%}6ruO~(=FrACV%x+bYk4@oq}Zk{IwY@Z1~9i*GRgq?R5=3 z57nz%ZkA%mTfd04de7HG3J(EKshsOM{QB$D=wXo;VvB`O%E$MV&D$vGN!y-w^asAI zvkh0{p;{17XmMlq>~(tPRN*GSnw@oyr|+J^>4Hr@;}Ci9$a}7AeEjFb6PmBANQ+Wd zry>x~?oW(G&AL2eZ8J+(6c0N{3a8qCuZ3)dpMyzFu#d-6@{UAIL9qXjDYb57=80@X-;5p#hsvdW?Qvb4?C zFQ^z?H_uI$dR8>m@_RjU^SdyCHJd2^)Cg(6Zo#-uTu@d@ZM9A^6~DDm&*ziWjFa8L zy>%CBhEqPIcZhQq39t}B{EayQ{>9x8*6pLYGyio(u!gzf&^pl4V1?tn)a2ixYqOV| zJTEw(q9?33oxE|#$Kl8@L%osjbazm+leth`iH@Gflu-0~{7~QBfA#ydPWHaOF-Lj4 zpir&z+Qm-O!+Bz_$Ak4Hp_qK* zIG*q)@o^qI)c*VrSNFdvy?*<%3EN{YA2fzNsQT=f%-9Y{KUizPFmvc?u4*H;-*i^) ze7Lq_vZ&L_*Zi8t7{3nL7!a416+$v95gIi67a;bjxKCMe0|c%v&e6n9^)ak z9XS{$Ej$$iUEY2%pj?AlE%Fw3F8Fu+bd79}=6{0mS3Sq3+{&I-cDP{B5L2HOb_*LCJnDPFd0(sqN$WC{tH=&fbMbKsz|vPg z7|}%bXx7)fRddhjPK~B~uotw`?Q1G1KmOLd?bm`~%nem<%XoN?>=lIEh(2j@(=62!(cT$4pVY%oRD4%wls5{pcf7}|Q{(LEP$N!zhKQE&{nJ=&M zcB3K3LoJ$*$^0Zn6{de)S}HQ?=)5pk@Sk0gsdn&vYiUHjuU>4{+WDLolRqrokRSX8 zuUy%s*NsCo`13D+O6dIb*2`ulgx_6~x)bwm^UB;N+n<}bR+RUz5UuK|hEZzn&(8h= z%9-;?v&AisJna;0P5@uexSV;M4&N?{2||?RWc9k97fW-vKn4Yl|7<;CX7OlMBeHNg zu#3acGAmh6^c+u4RDPL%a^X#Bd0tTEqeZWl5PmzeVEneYGtl5q*L5XF<`Kz6X2OX} z54_GSLq6PaQ4;+Wy1^Fuev~y+DaSV9b}-YgK9>`dQxUwivKrvM*(U;hQhFijpz$&5 zx|D3dnIri%@#Q2o>D5O?`i$nvc^i&q`9Rq-lH1mYxH8)y?T;oIbE{vHYd`HXb;}%; z9*l;Vos4`BznB`1liBn38n(sM9NoAe_p>PQuX5_VCHGAK$j;ltD!duN$&0_-Yy*08 z+9dSky5-)auu07;a-(Ncd#!|T3yv5)c@T~~8?~(_Dz%mNxz9VfaD6A8?_#YKi3R$e_Btb> z^?T@;s=?VuYIGy_%dP(pq-q{6fVek3Rh z<()On;ho}Ai&O|4H$31R;>E>}`xn#9vSk$|LU*XTq8IM%E05SDl|fJ!6FAVo>Iz$h>zpQ$ z0b}Tl`AutuvPB<}ArpvH_sun_%C}te%1xij?c~axvdRxVm7kU>zx=G+m8#k^uaf-= zed$!SpDgxYS=B+L=pofMpdE6 zxHv(GjTW~M2?P`zZmxLyvc^cLMlh%f3@n(?xOz!Jebo~)g{xHxs^zEDf@*4qoJ=F; z9k7~pvd^JIlv=ZtTBGIikK5Pz<}CGCN*qj`;8)bKUd-d&3KNT4(4aaEB+NUiKHWV1 z!p5OTM*8tmXm_OW00Bk-z(RKgHJ2N}K~+RRL7en$@5vil^_Z{oF2@oLXVz|oE(^WE zphzre^kh9m|MqF$TU|koYg{qYf!oJ(eB3UrBe`p+rvRae-P`;%Ji$Sb#1Z-71C#Ih zp8?X)3#;YjgAoPOO^pxOjh6f3=E5P(afaW(4ps%=Xw3hHzM!Bc{SUW!QN*(5COErB z))^JiT+b!IqCd1Uq;KD-ubqB>xNX@YR!H>9@U>YFSg!p4Opn@K#6}i^%R=?G@djRk zgkPxZlc;I=RtT_u)EToPk6GpXe`p2H(q{n1iE54^H%IwapBhPAm{j~vDkLMlh>#C< zYlB^`=DSRQXSE?`2hfW+^sGGkId6o`qbqg=@3-BZ!lJlsD1G17e{W#^o8-Ma^qcDT z6#{yiyN0~UvqiA{JR78Mjh{D=;0Ym@0q|lXBDM{B*!MPOuS#M^D47s`S5rv-C)TD7 z##}=V6OjQ}zIFn7YXJSG?SI$+PgJQ@@v@P>mfXt}5V8@)~zSR6nE5)q?hB$sp( znxYUb-2#t8%LSpIvG|nN?HE+VgEmwn2AZ|Tzl;@lg%RKl?|WPRCzh-bQM}prVQaC;>AX-7nmJ_kiBP z1q@*i1T|J4VPynXc{mG?Xj$WdCIVYLHiRXxBR~9}B``C92pB*-#qh^-pwlwie^&$# zqQzzqunPvzEFAwr8|o$jmWDyExAErTsFpQkVjG0G>)G)eHACQ6TS4TC8G*jGD!UFr z^3mMt_PMoN#yp>be@N-KAT0(n0YIlrohaivqjFpyscUtp#X&pT##YuIN%Nz408IVB zP;WK=lL3@mpTOrefgf#Xo;eedjktn)GIweO5d>3u4!wU8!eXI$iUMsHI*aLgy@pC0 zfR!04xe?$KJaq+!s;c&@u)_q9?x?5UeP{7-8HbtUjErJYIWef=$-&j99dID}AYqg@ z3Ex;nR16?W$cPfc!-x8ouXY8CKcQdYQ1dL*=bBP=BFKgVEo>9mO@|PeIz>=ep(X&`Iiv*p)bcG(kCQd3C8$e^)_!n8IhBlZ_ zb@L9d>^A^Q+!x%-!aU|WV}<~T33>iTBC?){Y}}o*(!sQlMnA=1DqGy^ut?B4@-Bei zO^2UwNBF@2y0;v?h(WJl`29`fcx;9h3tHSJum=#_-$h?;Lw^RKhyJUcZatie!=TP# zeq&yO^j}{5Eckms@E7*E29WnuFC>lAy@*A4uu%Cj0?z^P3FD(YU}qVN&aF;2ne3k_ zQ>rIn`pB3HBGNe*Ndh2x+V~$-KkUTvcMQxI{Sv%MK*Y4c?~X1t5bq|qpk`U)Dim{L zBYti*dW8r0aL{D|ICC<{1OWY`E%=ovI7@&p5(SGptyf~Vm?&36A`N}n8tyH zS$!?PYIq5j|LGc9%@R{OfVe4->E#JbYseOI*j-+zo{YeA)<6oa-Cl?lSc z<27778$5gzQqm^y6(jf!fC_9w@8I}NIM5hYJqh%b%YwWA7L1U`L=a)gYcQ*0n20qP zPgjW?fLm3`1j`~t3j(AEi{u;GU78v z!ic`s#ykb^+x0@L2t#=v`9bddeMAK4G(Q{5Z}-Z#PKUn~fEeN+dbogXE^%R@ZRcU` z1?_bnA%qV0L;l@SQa=wiA3)S;3+}b?2Vw-?WBB!nH(yHKj+s;p#lXOL9*F{T{rv$h z^m^_1M=nock%yhZ!n)22M+2aVYbz^cq#X{mwYwEmnc`)gN8UxrweTCht*HIbG~_Y2 z5{*nAPOM*R34Mx6?VE4hMT7JC#ac0lY1ao>Bn^wg`lBCZqrI-I{Ef14;lTR{kIVR> z@~89E31CZkBu`hUtmKc~MSsBXn~m@^*=lXdhtLorVW}@*|BnDJ+=T!BqQB? z(fSrcFok8@Z~j78%$L84cC$Nt>)%28Xkc`DFjoL!dPt9BfHM?yd=d_24`nsD%J_{#|on`Neko*E6jDrlK%{+}+l{f(}sQOvt(jL2gQ zNgf`*%lqWY{0Q)R!vAcm)oMO4cjS;B8DvBRw{hO;9OI8}LvNFjhYPmc{Uer;ujT&tc-h`Rlf@@zwT~HgGSKA~ z++WJUKTd2q=1-K|S++j8^+d0sG}JFLM%gsKH+5@oEBgAqK;?F}zm(?=q1G< zfSjh^5w{|Ks=TXlwKe6p!yV~P@4~1*Pwfmoo%Sfb3U$$(S9nppY_IuC?H#(@fXD+T zW<#G=`YyJ`(Y)ZbB8PYdifW4H>$gcgi>Wr@Sz}^-+)31<3a@Wr(>DtXgb*pWc8s{r zBG3)<$fy^}Phv7p!X%AjI=L0|n*SYtSgYvQ;CgT+6xk3yTYdbSN_uWZH|wvC$PL$! z$r>G-zb!vvLOau*h<=`5FbpR=^l|V~$~^OL$`36d%6pB-2JuO{R`UhnpFq)aivH`j zicY%X>v5j8KW~Y;nPoQI@U{OLex2{sY<97|WXS0-|u-Z&9XP+s#q$r=diUjAM3fX-p@3%S@7)0wisT3;PbWWe-2T!W# zYYCwqHK=b$#5C7z@tvMTyep40)2PkPoE8-*2ye(#m5#6lg7ZxO>W4nkY864qgk?xM zHAHm(48>Fo{toXiE@*;rWvWDPc07MZ7(a`?_G2d)V+WH85q80@LquFmMmDS5U4KGE z?AF#4GQ@0=>s2Q$@S!EXSMy1?DiX3tqHfIO>H7j!o)dS@HzeEW_I?@sn57%?GyFzm z8)7?KqgL`QBh9Ni27GqkZUxdbY+UnJK-&6LU}|1Et@3r@tg5g?7D0y*-3t%>E==G2aC?1SBfMS ztNt3>PFt18Z19;}Tej`TT!NZ(Dq=jU&mp3svsU~S1QUveWGet*3rwoDQFeW8)Xa6At{Vb8ZgP;W+w9&q+fysR zi~kK%6)iqMM*PLJUcEOcL4B#NPqa<;G9V~q`_jiGr;4iz z!E#FO4$|EG(ZtT@xv`d&-#2S=6{@RY>T8vV{Y|vvfwlDL_*;VzhzcT*TsPo5TVXn>k=<_*)2zN7UOqT-~I%*^L_N}eN zY(}O6xkk5YZcREtLs)TXL^ttkDAvZz{;as6df#R}^xV&DMV#8~;ck%XV<7>05wFY6 z?FX6M?}2)T1k0EWjT(yTGyWB_Q`P?IAU>}l?9>$^bu~_EGy`~~3OFQuLKbP-*3OGF zIpS(}Y;W7{Wx96{B7RW@Qu%mak4g?)di)!1yEGyS&aee4m0bhd792Ip36^{B80@&T zZ(q>$_3&rhd&|x^h)65(oO%Y+e3F880oX`CCEI_>(a*7#HV~h6WEzsZdS|~9q`BlF z4Ljj{3NT&#)&90gM2B6m_6Ab=U`+2O2hlNt3M<{u6=7m%lJf)S+F4^3%Hx@))f+Nd zjVh9x)qFMw!MeSxM2ngE`A3s8rD;%Y1LH-PzJ7c0)kb@RE@Gx6?*Zb*QYsg{kUVsf zsHBNyGqtk_{3>3FQcsEY+RF9Q6uV&qH*c_JHE`h^ZsYI_(f(&CJ~xd-6}J!acPjYW zn^sYHoBhAxzJB(poI&BN9onJSZ48C^0sH;;0GK8(d8Ix8cxj9S976Wj(A{$|82~7j zqbUkuBO3lVC>bpv+)F{?ZPg6@sTu)Rb8v2yY^2jm%E_HSLx(tgAS7?jFCQ~x^L~w~ zNL4^9>^UocsUJ0{eUARuaiRSU(OYf@4*gKXb`4;${#b4rg0I;o#Oy3fOcK%ql%t9k zNHBT&1)TKeK#x`iLu)QbAl!9G_BoDm=sSREtPT>dD}~7a-~!T(*BE6k-c*rWvZ3mp z=Ew-zpj8FHTUSKnUcekts)!-swizSkE;(#6xsE>1u{K+p-|ke!qZ{+4LStEsi`0%B z;^tee3(MBk4~c9Y02NJ>9MKL7$~qmSSlzZySGn7mePZoG{*qa<{>5K{@Iu?UcSY0T zHHA6#UpH0nXN+iyCNv$LuMr4Pw-$IIP8A>kKp55x2vto6YTNYzFbs8jeRM7 zHqx1^cDgYJ*-k_R%BmGCv$w~xNT6nQ+<12+Qn7%0o=1unq)5K)M&57laUAu)w4f`> zbv&kW!{4`!S-xmTADgij%_Y+nrJrY{eX3db+3*5WBwwJ&x5dXzO1>U?%q)PaU>8b= zM>7mF0&~z}cXxl7cGYCx7jre!r&`NZuIHZ1`Q(#%mFbjn+3os5tq@|y`b<>mzq(Tk zm|Vhe{3Hgthzl~mvNo({FP!ZQwbQ!0RY)s8`d^sf-rS9=0tux+-~0%*uBQXB>7D9-uG~hCMSqh>Rw^4a z$l?_iLV{)2_Z`e;gL0fOLsB=?Mt!12-X+&^1;uOmPN~@%WaN>rU@miP{{9OT zAngxoXpN&9CHG}g3+CT_G00AneXu^dNF!Af=!X~OVJ0}XrgVfr+yu>UImv#ib{$2m zw*FlD0es;*AblQ}jNtA+;o*5@O1Q$F9OERKg(Usn3QfA1=2XoH9f!eF9=%*)2I4AO zKmr-1AQMSggNS@&1~Z5y5XO>QlB#++%dnE9>KIC3cWC*2qBsB@&u7ld?FIl~;n=)O z!OWY!T|_>q+Fe*o1`KbZc8oWwzTc;MU=$kN6|`2Y;@_3ORxB!->3#%Xh&}v0^PwgP z_O0yp>$e&xDa(4HA!~!GNWdd*0?Ecy^k|gQBU6i}!uWK<8}PF@$_uUZG(gkOc$n)z z)1otzSk3q)0*%;*ZTi5YGzUZZhU(XwR3Nakjm&c#WK#jmGl{0cG7~WaMJ~b`4BPxk zeCC{bJpd$v#f&U13;zi%r*$ig1En)4LnLT|WO^DdJ&ly!X>c=w1q=5sj3ny>??XKY zAT}i9t&ddoBx+j5XoU7al#x_`wZ8cx*hL?LBS7rh=su-#v4hMwfXFMpLVimHw5UKv zH&v$^ifM%j#f;bnVKsRf#l`boXJ*=0t_ zGu=e8e0QN-UlJpbB@i)iR8_XBZ|De16mgcwj9Bc`>Fi5(hV`xJoL#go^qzPn4J%&l zo3S4C@fj>LstN)y0~#5;?W&0=!qihKU%qKJy3VYi@?u7MS}9a*4VJJ7i{xXbML%#Z zrQ7e*jxB;6`No1su(ATC`vBe1(CET*Q)yX<>zYWmO=WB;!*rh_jeDX&(rL~ZKPf5c z38C>Wtz%fQWoemn9EJuNt%j=>Yt#4UjKmYthVGg?W^ySw)8ZT~YaZAhSBOH^InDqJ1jBt62bz}tCK<<}^OyQz3U zl{X6-OcHY8N2-yjnFO2%Y2sy;+|=*RUVf+0k2(de%GR2ezWYvqdT9ALG&iAZ(*NO% z1v`JZ-fOX@qT>|8apL*$t(E@ucw@khbOJkyg{>D-HC{fG=^IN2kD>|vG& zdzvFxnFDnrjg$fbJy8Ad*ZMvu-9H!8d0+Edn)t z0Fcu*`etofW~2wl_+DBpI`a${yIp%XNvO|0qiogHN1flU5$t0rgrXkb-cZJpsNUsN zBH)p+bXJ}A(f2~nH!10f9A<2(Ow@0fw_`dtEn{kgm7enlo?M!qx3!p0;KfBAG^m66 z39_W}@-%FEtT#g=iE{l4<>)ReWDR0Qrpm5S6ud#XSVn$k*-9DA9b2jr(bE-F?#}0Y z$vY>RCqZE0QQfXnIlksM=N>7InqOfCkf3go5Kq}mwMC#tHt(o5-*L1dmk2f^(k>Of zaKi zzjFO^nG`yb_Xm4!k){rysgU?^rHqE}c2)_nPK-Mv03o4Ba*~S{0bv} zO{y$j%MEAMRYTF0#JIOXoSG9AoD@;&N&GY@8$GmB#3Lk`yysb5CF%Mk>Z@}go%;dz0|eQ=1@nvYibM9;QmXC_ z*iIc9m;`hAw_&;IX4Bfjho{O{lNIv!VNqmyFLCU?#wn9(7)kS{juXto@rYX+#F10v zLZRcyV8bO47b^*gsP=zY4GSM&T4YeJR#4>u5MQ&SXHo@n%#{kI5due*e!nHqjGbx5 z>F0NtF_L(qBf+uzp{^NKrL9AoMm;7eX5)R*)iHf_ml;bmtdJ_dR6ZWGGg2#xthG%~ zY-9-h&#PgaLg`d}e zZ;(8iM_f(w=S1>!&ZfSe&CH6*fSsg4-S{AeW->B&?G-2LpK>1Rshhj(LW9Z7MocxA z2W|CkEvR%MkH7L%vu_QLpsQdDTeDkL)M=3sy;&s@rx?t_Rh2dXa5F-KV$#Orv z6Jt+f#Fl8NiHpRLX^wx>4>ua9;V1^)=|h!p^t9O}Z2F}Ob6%Z%rylTelk+@+=u%Ir zVTJUGr{AIWSnymFNXh$4TErJA6VSW7FYiot3Y+)^`=-YYAfEE}5xe}SE6S>J{hDx* zO&!RV#R#>(QSNONT<~pCAT1o{_Hb=FoA-o(vVRN?s@4d08FzMNxzFfgpzNZzufQ?@ zdVn`PskHLUYT;blcgn<|jy_I0D}1=G-sv#_!^x;#x*xQh1<0TrM+x$v)k8 z0M5DcF2p=q3P|CZLFZ3+=fw99Ue6xu%T8_c1eVN0GAcW{WmSI=MY^%yj>TSZjrG-I z{0Q6WQ3th`MUt&jFi@UDei}B43bJMaL}_6c2;R; zP7mjK#jc%x7@KqKA4z2Nza|b7xC#vb#03C3_6OG${`U7V!4t(yt3_yI^UjCp-wi{s zv->nB4g>#X1g{xl>Wr-S%9OfII{)Tk<@4LNgLLVob8<$Uf@)E>s z^ccRH%=A9yO?lGAP)Yi_aN!&lel@@POu`c`4`qq+W~!+LUXFkh_rb#llyH`Yr-Rf1ci|anAh@u0#IF1x9m#Dk8_X;>ikvCYxvYB5_d$+y zdmPWvUg=^f+Qn=6#QXQeX^t^||9Do>B=1*(YN~7Tx+%|oT#SmG4RJiT#0(Q@JSQz5 z@TN29_rqrz56>+(M750Gk(PJtTz(*u@#T%)S?-HFGJU&&y_B8D;zsGD&!-=9Cxs5Y zvRBNaxRok}KR&k(#Pjfoh9lRvy1C~j3WEH8@Zanu1<&Q%d6#H!C;FRSN__Y8{*k2G z^^x-bVh=^lL*5;&W9n7*&wWn)w``A=Zj_+@wCv;OKGW624%a&_;Rj}W8y`x-^WNni zukvXeDE&1Iwv+N$cv0ggaW`8xac0si`F_Kcv`Oq@Yh)k{CHXz{bsz;4iY!t&5_V8X zlBYpr_>_S}sC1G%6`|=(l!{kBo8>)gEAq@}j&PyIej&j~)KMw-yT}=hJG?upuZw6| zA{E595Xs>fnv=l5?);pIJj`yM;C9MzTzB2|loIPCqW+oHY6Lh#@qVXA32yt70m`yi zzlq?>ZB1M&=8m6YS?HDoPw8?m3UkM+2d$(~MQjL{F7t&V@82fh`@T7Qt$mjbv{!j-dmn8w?-{Xf zznJ>HF8%Ng`mA$C+=W_^yZeJM$tPwsgy4fI$Bh$scRSBh%!9WZo+=|w#ki9|gK_OI z*vvfhUWmvR?`XU9!kYU?0fI8#;_S^BO&=)bG7rV=Z=ZnLeZOG)pO<8=Vel7&akGz} zO2;k9VGRO!ddK9FRpwPyU&=Q#o8$GMXZPK7X(2+xLW`-=QH`Vr_p{W~YHu{hwVZ7b zu$&K3$etznyF<`M+Q5;E+l{p2qE80yyGk??J4WT}6V5swPMKGL%O=j(j2$X_**+$h zSP=x1@T}OKL8wg;sL0hyEe=GY^UN9?bmy_|=Lh$)Ut5JH#Mz0bmF{I5&6A4OnTP*f z`Nv7|uTq;(d#a%KOoB95v6^bx`)bx3p!2Ny$^xra_s$ zC%!dI!*PU0gHxC$+dz$_c@XBbq_ybOsLbo?XR^^k{u=h{Cfyoikr$#Jj31LTBelU8 zVg?9#21mmuDamblj~R8aaxQXe`3y6uDuco~fjia`J>v}BFrn;IMb@I49k!|#&k-kL zti{T^?et2X^ZO02gIhKRAjbwM;AhV-UhEI1ZW~samco5Q7r~lj-ZVcXSV`96&|a^Q zz}B5xGFzMx3Hx=VNes}}PjXN*i8`S8FWugAy%P7Bo#{_kk}-Z;<~S*#h67lOyPV9P zSOqq6+i|=*Yu}K6ZrJw4O@TzX`>?W|h5S4e)<)M{HPioO!xQb;WUa__UF~-9ND}SH z10((e5Q9xiZIGAiEW+9E3x*MG=x00}5L|t_R)~%1HnAplZO=Nfh-&uK9gf}*S5NE& z%LD+1#(u~@lGr37(s(f9R820il`YmLIV_&F%dk+ViqzvqG-Z+5xwD|`AO(B7igi?2 zXM@aZj=d3NkAm`F^S?t2mV*ycN`>j*c9{(Re#Y3%y(0M(Td&KD>I_rNBAS=vI(vBHxt_~G4-T!|QQ}(}{w5AA$H8Kh^P2^3QC={u--^-PUk0!fC*}Lv@1Bw!M#%u5FPokYE`s z+ixMDbI*s}B(S3`lT?z-){y2X?p;IRH>6%Cjv6{< z3Hco;2^e&f-6o)86nb>t2FMlWPi9okN?aS8l*7N4XZ=eK;*TcK+0{Z~d8F9Dbjvjl zyIaD-<{jb=JA)E=Z3`MPY(&W#vkVhaV2XHu*lcp#>Y{#TNK&0T*F-u~qwYDM-EghJ zMHSc?XyQ!Trw7i+iF*951Lh%sBL<0_&_}<`Rk&OypB5B$qu{;pL^VyMf#hIO=`L`l zrr!DTqp+GruLm<;=iI%2k44yL`<~6Qq3^NMqkQzxS1I*}c7gQ?Jkf#RbR zk?uQ#Lh|jo!ntDVq)Bhn$H0(S^|Q!fvnD@E!DI|-NVsr-yHdny=a;%o`y(hO& z_lY>&bO^(z32@&`bKEZdA)sO?btEM9GEGJm{So-aQ^2M4?TIPOYU7Xom(Tvz-LL%I zfEz?@3s8SPUAN3VdNoME@V2;ICtz6kEQvwt@4?dJ6hh8^g`Z9sV(7LiRQ>m>S<$h( zTj3gBfT=H-JkUUs^B*&<{hH(Ck+NfZ&&aS8cm`=l6VKm=i&&q-le} z{iX=qkkkZul&%V7+;n8L#$K7!)6T!u>((XCCXL~^VV10$|A(;q{!6O={|An28HyV> zZZtI9BM0J4%`h!TR=7u6WLny|L{PvPZd~QcY?)iL1+JW>X=PTXre@>n!lstRhxc#a z-@bnUw;OQaob!5}=i~k$et4w&HOG05@m9aB3YR?XZbPZ#4C@arjI9W*>L-1U!NEWN zF0gE=rpR{PhF#p-Yo*o)71?K_%?}rBTKD*1E>=Y=y5~{Gz@CCm-)`|_`?Q+#`N9ZXGA5#6&Bk- z{G33IC!x+k-j;U-js*Y<<{^#q&adR3?^*QiVw0NL&(+73TAg)zfu@lz50oWeR><=S zSTCZBlB>i&v#(#T)`VXjWf(K{J_%NXW{n6S{ZC@#Vb1sN!UM7WJhiZs3e=q?ACd%{ z+JM%kMRN`>u)6l3#+4WAGK2C(hsh<(plzn%CYBM)+l{ISOM9$;&y|Q_Chh?RQ=iq| zxDf3&Ny2&s22_`uBFZH*?Q5aNH<qy)v-X3&%C3wBY?Y%PiIC#J*)x}WUWZf$1jm@l-AAFFd0F+TK{9aQr z>uEt5ko-~{P1yaj5HjnDAtw~89mpTba(5P1@2FljEE~4DLH6a5&_O^0aU1mwvI&t% zigmTJXBuJ|TKIm&)(nFDp46vgV;kmu3{QI!Lc77VP!qga^pLsBN7nLPdIzE#U5u8G z?9g7w45)Mq09o2Ichbn}KHf?}waU#Iz1uF{qmM|QHNd_{9|mQPB=JGl0zlg!(;^9F zY(rSfcpASF@|T&GoRR)r!U!{9o-j~ki1jXUv83uC5g|$>XG6HiJ-lmhuV)o8qAzLl)%mQJNjZA^f`^|&0|;Rd>K2 z{lqF@;I46GVN|2L*-YW>g`G9omFHY6bzP2%gTCj;dcFOGPyOZz_19C~-_@v|>Dv5(OE(5&>cVYkAtIT>7P0f@+hl`J8ELNq z&+3jlO+06iaNr!|9zDJjM?w`h9wzmkF^9iln)#2ZXzlZ6pgM_66gQ>ctq7=au}aAJ ztz3mrsbcjrtlLMeBSH5g2k&EnubrL65{Mk0Y*E7O{^MdWD^Lm*IAP26LKkGaV}c1w z$M+nt^@JJ_Kp{b+G>yT)8xtoqBAxR>gt9QDHFLdBsMEF~x#vp8%84 z&S)C}GMR*?lycC}YjLT##ii_q;1Tty|l}a)+ zQ2jVwe<K9C*%+Ae$D zsOSMRf_qJ@i}eZv>E=R6W{j6PpNNvcQf8f+M+j3l#&1H}59glvE;z)SC8^DDOF4f7 zu3NPVWQC99Q`Zl)(Dj6(S9T*$>^MhnL-Q?W`<=vvDCaUr>mNyt50&NDobvc^0E>?I zM1G?y3$K5E^5_B7(1kBh z;UirFi0I&!@59uyaaR2Fzdd99b7Vq7$xhlkCxW|P0150$hw}IbzVH?45{O>L3B+)X zGN(W}^Y1puBB)&N2ID7A?oGbJsUlB4KDdx@p&}KOT`QIooDByVJ2?GwLQ=DdIIqqJ zph$pi5CFg@;l&mT3EpUEOc*elVC<}A?4b4QeiL-r2&8NOho3;i3HR+*3Aiil?nB*e zvL#&%IkI7`sXe2-@ldAOSBf%#57)^A@fl== z3SSj=*xWQ>Rsx60Fl-(u>H>dyIs&|KX={UZqSH8w?~EN??T-_#W2Lfq^pfI*|9Gi`q*#{c?% z`0LV@-02ZGuDVU8iskx%0aZ2Uk?58K@lkr*=9oc{@DJYv5_Rb#>9ICzTnJyCk668_15R~i0>raci$Qb?SowmrNQuD$DH9$ z66t^!s44@cFBMR3g{=fKYv)|Y^$?!a|`K{z~B?vcmnAE z0ccDjpWVJj*(mhA#fF^XJAL}$d`{?;Nzcm^F%4~|3EYWj0}i#eT>`}il1T8>burnM z^gIJU>+kWj-;75u7f*Et03eM*;3kc1-{HL7;iLpkGJv1Z1go`5j2Eb9n1lH&b(h6Q zxNjNbV}cJF$j`d2`DLe-)-&)-FKc?z316hp?Z2HhFK;t7 zGxd64+=~)^xo18br34s!&$z1+aO)RiFO~cEX9hN|=I3Wc3x)+M%TNpk)iOKJ|BwC( zjA|Gp3uIa|tb%$Y!Js?!z2O&a{?S5eet)hQDX=^2th8=(HuW{LiVfZFC1U`9T7U)5 z#bBExA1R1P_)(;p`8N+_1QY$NR2>A`&_S-G%ImhrAMPSIryc((4_!&4Kt9psz!%M3 z!@pR3gxWA4hAiJL?mq^?b@sH+^PTL^$n^HxcQVBv#^_T<%t*iDRBSD1_{!dPN{xir z#ZtZ7LTWr0cG0<}=NCiTj6q5Hs6DQTB~L_yjA-U|or6xbhPgIbff@Nl5s^X=Fg3@RMha7#z9$|A5LIXIB3i9 z)@`Sc=9S~;$ah1+Pub1BP5x)q;iJa;e)iAK0N`ZVfOX!0wYUPOv0aXG4lRa6_>8#T z0sCGcu3DP_UxyTk?lP(+Ca>Imm+ttw$8PdrANfXx(%BfRUb0MH|Kpxe0!C?2<)wm} zvodvHR~^`zlb`eOE}7pqdl0uE?Rw?(?_l~amm5Izw|JS6jE#87_r|wJC5J;Z2QZoU zziVdpAHmV@ur)|7Ay`Mdb4L_?wvlsmIU8rfxjnml{^Dle7-8sg0-cw~ho`nP!#q7Q0lmUG`!osW8Iqpm%#21E_@BKhzc?XWU zm*agC?zXmpMP9~fAD>OSK$>eD0x5a2#vN<12YZe$4VS)rhTq$*p8fY_J504Fu`MT= zY+X=wJH!d0QC-vuuj)5@5H{Z*Z9H?k+*SoHXh4=2+JDIWZCwztr_%cPliBQwl#jJ3 zrUvR>CGV?tQkyQ1XFr;~VC+}0J@Y{~r{&him6Uz6$1YygJ5Fo~{#bb?<>T|03q#}4 z<5lrXcc+sWqpy08ttD$6P}3VL#hvLdwYI+LtNgpH?ExB>zMIvsDDzA&+)7M1+57~BrUVCos8w2Bg=kQ)KBZT=@R@3xXi0&xIDjM zWe2b8I+D9YAHs8E`Xvo`c$^=_<;d*8TaAv(IycLV8;jApbFs6Y8B!FQHr&Tk$5=ma zOxbw+gnUVMC#_F;S+lU-=c}`UdHobVcZ?)kb9^j&HHT0SU(QlW;?(C-@7u`~`SpKj zgxmfV_)WSgr-+luY3(1B6S{Xp5iaZ7`ZY)P?fX=_BL_R!(vQZ(Y_}Y z?~1h-Nl%|27o_aCwXS_=xgx$b7@Fg3w%>rK(oKZd5g7Erx~&Bs$1v=*{Ifui8hnYP z)g%JA%6NM@Usen+N{bect-fdZmXD>yT}V$wpPoLk1pJ{H_9DC?*QwhOrXDLB!eA-I z!=LGNnL?n`bkDe!EnjGu)JRzaRi4ztYKHCqFH z^K$SX%HP#ODbx%IZk?Zbvwbdt>p*b6EQ18h%_sJ~N=QNy8!IX+n%F^UaC|i&Lb<{~ z>#>Gs_~yI#OK*H%1rD0$l=JE;D#9-upLnmYPG#XE+M>$QWclQ&r6y@&-%aoRL*@uN zT>@_NRTDtHaPQv&zzFvH%bp!ZcDel8)w&q^sqV+dfUD4pDf1aIMb6?$*+N32=q&TZ ztE+6xiS9A#6JA_nSkoO=pYywl9euspIZ=~NK*ehr5^vGz*WblG`144OPyZcgP5-{R zB?>y7JBMRiqkyVw^kGGYxUOuQDt}(!Zu2UvJ{1c@JmIhi`qL2X_X|v^v2j%rye2Pb z1$hMPYF59L8|u14brm0MMVMw=CumpCwR_he+FAUe#b|eqJFQUI zCYT7d(e-{O@#;>zcGMe~V(pr0D@X=}L;AQZg1m&odUXLODic{k!m1M^B~Uz1s735F zM^lU|zMXTo?k&taf?D={m)nntEi6dz2}jdXHI*lMo^DdP=;K_`fMT>vK~zbG%@O=d zT|gT<>YPsa#diUoPi9m!t$uS;nHUT!$!aOWiHyq z)#TtPce^lDeC;wKh39IFSCEPyA&c?VA)^nrNMDqW`grOa?A~DCjD^nuv`wHvw^n|P z587v)^3ZNp!Y-xpt?DoqjI{~lTvt9(s}9+%vIJnK`z$LxCPJ_ugcl+y#_I1W4_zPD zivRfu=Ff8koSr8)4f0Q$?qWL1)*eY=6gNc4W#v$Gx}Jqi{fWpK)wk(sIm|UBLTuO%(>5}CGN-w$mLhwodcJsxjRvvpU?yQ1<3v+tiP$udMQt?!LG9+mlo{q4Q~YtsqiD1eJnA5Hbs zf>q;>xJbX@U5E2Ch1Dly;uu%wZ|SPE6pG-6Y?mB7M!I_dfB1TKF>m2zll8spv$O!) z>bKWgcn=-kE15cNw_S^$pK>UQ=81-bGUgGwBQdAUDP^A&jUL>7`0n!8n)LSQ3lqwZ-CngB?SHZ6 zDE-UqjJ}14Jg?}Y`RfrQ+9H?PzV7kh#dL8&d!zBcYhE#ZXS7}?@BLG?`cK1k zb_vv@e`wnx)-I%0&Ohz$?z*J@DZvFlZQB0f(vTVkptS{tKmZ~D0RRXUQ#ynHUrOh1 zZhK+F@c&EcTnoJ_n^UagU4W{1QF!@(l+K4&qa9ZsS5sJEN%2F*X&sO1)a}vEt20+9 z4PK=mB6njN#3x6!FUKY2@%{rj>fYTqUNrB_jdTmregC3|_I9ksyNCKz+b!P+l>{Cu z>7#>?8a})g+3RV_P{U<#!qP+Wy@HgzxQ-EvA zo@?1o;l~fCnC2wDtUvj2!8pb8{Y;Y*S#a>1w)B19>h1iZkfp>|cN=m)5$^Q~cFc7g z$y@I0eU_V>n=0D#`c+?A@zmo>k01SArq#c({JZ(^bVS9&-uD#fXHzkg^$ zNgnk@w>C!x9keKITm5Yyyz}OIgp1tYplNxC{^_8IbhN}!mhB{7=2S3^^E^XWZ*xG_ z2XR%;c@EN}=jtcFu{U9tiB)uV@Is@OYbkpA878~V;!=_HKkwfjd0-lNrAGRE4=-ZZ zA(<#HC{4GS^q)fMK#1X_(xB|QzrB}oCsN=MXA1SfapYwQqqol6%7*?4dCRWa^oq5I z7ro20x?J}IO-1F`oGIYKsqm_WJgqyhKO|8- zBlw8wRmH1vNcGc$q&Tu`1bOmA@6&K|v|IFHd&2zeIXB{FRr^F`AocpeY1cQ=iGDvn zmxr6p{ug*e;>7~#`k`{M+n+G2679O$+B|TX{GBOh^5w(g#SPgXxWaC<0rw_+(gNI# zeS}CNhoVc5lEpyh$9B-|l{)mUq7SWoU){C?WEwALpBTPScz`N@AklJa^qb6gW|7{l z^{5_r{^s63mm8?~Q^7Wyuln7R|NZW>Uf>zcd6R{GTIx^wV?GrVrGEY5n5;N~&)Ym;8U++bO70Aoc2W`!UOqQFs4c-6FT&wmdJ9Vn| z&Hh{D)0cez%_+H7>Vk1_ENLi3oVU~y-eD@b&JTGH%XnPAt(!Qe*>LWglh>g_TBg5i z#f$17@=EKcXw{XFK5K2-g1ew>+cwTjfOP@Frc zpDCI<@J5uR(~MvAWV!Fy{j>gSv+6RJ==r`f9P?!$z4vO|F;Hz}XmVD__ec8Jys+4k zl|ci=rX#IkVHk&~8pG5PeEg>iSaY+?$O;*=SVEZdAlTAavB}J&F)Ss#r?V04<8$(^ zr~02%k7*Pn?!Nbw%reYqnug~_TwC^PE|DXDhUps14ng+$-=D6yFO6O&q%0wL zezVe~-H*=5HfF=zn$t)>JpcT0DJznQO)~jak-R70_48W;`|n$hHT4}ey^W7$7hhce z}n}QZtjPD z*Bho7Hu3prLSC)o*qzaUn>%wqG7dkzc7WyjH1|q^=h~CLXMa(?EXfaR5q;DlH+2Q# z%*i7m4=SF-dNtm9wMB728jkg=9LNAw2(^_DIueZ1N@ zCOY$@V|S-^MCz(<-#7V7Z_kC!0gFMAKW49o=O-%t4D|IK`rd7;JNmw|{65Yq+2rBs zem1whGgCZ{yNiYiNR)o>k?2c7VZ_n9tix_Qs8sSU4r=5SD3W9S9fXHK1==IX* zYhRUH%c9F2Z5Zq#_4PVve7c!oE;TC~zDXtCnK%5DUxYOEktuu{__$^tEfUjxw2-pv zQt@z%)7R`rnH%rQ1(AePa|y*e)H3RA$3hD(Ih5UylzTSgu6Og}4{x6M%lJCM`EPC$ zL+d+*ll<7fy!P5J?1!uI{Px58)U|{&yWC!#wz|S{J4Jp;=pg3ZnV{?K%giZO>h2J! zo$^w@Uu+nv=dm?VG-~`vF3vr>My}#`to1_Iv%edbyUDY%murI}?;kqpfAhi>?Gol1BJ-JE!r;Kj2u8f?@|UN6<*;Jv-^<2QGR4At$;+}|XGcijw!S(X_2lRXaGnM->Z0Z| z8FO~q(~KOBT<1@+=@nWjM=sy*6x`sftEZVmIJ*if`{SW~&w-qzLSlAvj;)^pFWT0h zdA7wnVNOv!z0lYg!s zr00=8$1{3Yp6{rY{|Ya2kK^?QtFT~GVDGo<=z)T@-hyWvhmPb}_QnZHphJI?*y&-!h6lwlHqJ7{}3kjE)ts5Em!| zY78oczXR*M!0f3gHOnrWi?u08vU48*N$Q}10#tam%#skfbE_C30X2P50<0^)&nY05 z?fzLr^0qBcNt1aglpbh>UiE{bmP+Dm^A1rh(GegE5=hqCp`ufVUBS~7pdV0Rfs`UD zpaS9tjpCM@ZIu_j&&@THcWZ@E0nmh2=utlO`uk&4Dq?~!c3`SGl9dW=;+Qz<2o0>c zRdkey;ch|BZ50Gd@*ePXZpuNZt+1L_cj48 zF@*CKC88e- zQ6e0Av=uc@L5>qqj{w#0CAlwyWOKKq7Z%0T2O58-`oSWyhJt7(BD;jh0m?-_5yhuV z9tXgVPC?YSDzC*Vvxta0{2fdR@+ncuU>^O7i5(onO*oStjHc z`V{~r7F1S+wc%rEpp4X8iqs1_;y6+AIt7~dy&@zD{S0>{$`5)F1CGKV2Zj5XT;v@8 z@=GH62?qU`g7&$Fo+2V=FsMP15T#@!Ru|GGr>jK(7+kCTF$pbicL^keDw~3x6~aUS zxT4ZkM*&*rSFK2hHn2l?(ZzO5V@Th%H;d>PJE^zaCK^Su9RNEXQuSaCGMNTWT11Qs zQDuB+DG7b!m-G}DDQHF1;E*kJMD_n{XmQP9^DqfDPDkVyTK<%{0%=2y3Zcf@Vr!)p-6DkM;E?C}4OgE? z1KXs-{Hmy}4HLbvK|Xp0AbFOKUc*SeSwvl;NT$;X-KJm~20cS-8C|@2xmD&Mu?4-< z0xCoYitI4MV&rA&CeRd>_X3lDrem=A8mR8_0tRhVg&gD}MHrNrj1ki?Yg1Am7p2}% z5Z7Cg4Xv;euRQ*krZ*AwijJf@(e!;RM5&BUqp!=nf*)JDa#EuFFW2> zwg6?&m0qZ`l^sg)*QDE8rm`eOBxDXSMm6(Opt9 zN(-sdOSSM-5?Vy-do&VfwTOIKi*DJ4Zd1L(t5sXkX}KlX5#vCpV4AWe1!POP zLlgFYrc2LG!9Ehv7R17FL)~LS=`^AAIUFWSbWYJl_+SZu3>Ko=eoL=X5WAk zUV?3)MQi#QfV3E9`GG^1ElSM@fxCVcHs98s^}#5k6`DqiuS6l*?2v)2s5PP#=qMsD zLwBPCd0YC0YZDj)WYJDE&`V_B>XPm;umB_eDf>fj3$c zB^GfWyPco)xF;w$D|?)TIXYD+Sq?eA_~aGf>8cn@Dgo`F0|)PdSwiWri&N9J@DD_k zDfNPXXin7m%Kt{S=n~PEY zgvmK1GfJ$_5&b*2)drm7_q`B`6=HN~PRnd7s(~+gTZq&ojQ3HH9)F~psgfYA&Q9P? z`MMXNjY6F*LD$&jGCnpW1860LQ0Q;IimfFQirFe9pny&xYNGaFuBT0(#@2?-CC{BH zrwEbj)WHS}_>`)(>WRs&ZRxI7n9n_EN-Io?&?D*GE7jHx6QJ)*!8d+MJKUe?B%;O0 zR~KrbI1J!<41j0__&i!c2v?A`04NQ-pi=#q*!+lIH_As%QP7V8NFD_t7QiA=7yBr) zVt1&CE~&mUt!VvU=&4$mX`v3DHsCLm+`vh{^G2qN7RA3M zkiwp}+clM?o<)eB#WpXL{UYK$Q7Sqf;Y{+{-cb6@mR!BZdqR}#x(!XDz=q=ADhV3@ zL-dOMvm{$&&eYqDdBH{>@@pdEx)Aj;aRn4MezFZ960Rvsp`VlGqG{f{D;80kA0P(p2q(&6koHDza3!KGZZK`8jT@Yx%RR5KBL z1aOzJ51d0szg|SoahuQn4=nm{mR^UGc)V)&ky(qpUyFRVAb21Gym1LZUIw7%0iS?{ zEq3XO60Hyc5jC(VzEp^B3Q$uxwD=M5<+bAmO;qQh24lN=8x1_3T;Tv4! zPO%FY{0^}f6Fuq3rJ%Kt5IIe$1&UNtZ8iT+v>zY(h;qI0nB)-6@%TCV zYEm#VfAP!GUuiz^>ziAkzmI z5YA)&Jt{=Npk0((!N0`!VHIu^@jwCa&wU6$%lo2z@_U=$oWPHe>Ydav`)wt^G2Sd0&)cd_$!ACKtKX9s-@btKWnnir8?+@-SCGeH(#y|x=P9K2(O;7GC4qq8!h{z z>z;sZf;Y6kr(pi>pO4xyQDZv~0-WCt|Et+^ zysO>DkgPm(;bQ07kV{X?6Wz2HAL6I>==>p0!rz-$H}$l=3aETxmgbSa=YFZ1A8-}v zjp5==9+VgvRHxrJjLJ4i%304buBQR9$D^M>t733zZ}SNU!dN;H`1v?(h~Ah`vsphU zzA`;oka;b=(<@gwW>8k9DvoEGCFf_ir2CNLB?D0qCnm&W2=YWa{qC1*w;CmM&1y%} z<+=DwOu{BaeE{K4Fdgnr$TK~CEd!XP^fy~8)428hT9vO)_L_P0U2T0{`ah=sY6e^k zj;=`T+%l+oM*Yn$v#jSWcN1s>|B5c*L$^FsoqDo!>yH;z0Pm%9e%I$2hmHAM%YHHHLGgt!p5c!mmjZ{sa}5P{D^#Y#qBc1h8OBzy+8uGh%_=xs zL-xN*X0ztfSDfo54Jr+73}dQchisRp(rNxQghr^i=k$2*Xj5hITvW%`MCN-bj5V_RsC|`_))$3oAxL5RpNZ|jO(XX&Yk8RNg5q0 z-S4xNS-ku2R7Ac>b*;~slo5@e0a3&i0UiKJ`x#%A+e@(hCwYy5l3VnHDN7Gz=u1WU@`CdhAk>~B)G3F{D0 z!XQ5TN==H?fWbFfbas@Yx4v@Yh4c?}kd)P#nq`ho8C@GOuPwVj`1R>`HI31ezuD+I zWBX<4@J&}eUc!U-tb;Cs{he^%ZquJVi9F@Vd_uhB#--EF2O*{VjJCRvL*uC~_Z$f_ zdWr##g2*C{T{c8Epe#+le00yQT{k0n8Ge@6Hl$+`Rue?nVd7n-(q@{TcGO2NVv@MS zS8P#S#|{|~!Z?nocoE!|lObs*9%UodMiF&nCkrymw^GRR_4pyDaOd36*?PskO*f*v zCyG7#-r#Op$Sh_+PuoggV}?$Kr(%F4T7$~n_bk0gt$b>NxGgcj&#-Z$B9Q`8m8f#Z zwk_rDzp;d%Ol5BYPG{k_T@)u$S>_ivP}%!+_K7wpF_<3ca%3H{g+FZ7w_$k9XBqBi z(=UCP&X_P3$cuRMRC0`Txle>Lzt+vr3NK^Z>Z>Q3D!+fRwNUTdqmnD1UaKrj^;vF9 zU}yjrP5rvum}HP?rt(AUyQaB1n=2IC3bK6J6eo`NF?4>8Md%}Dh1d*W>jd?tJej;G zqeogpqPVep^mkq)pE^`a1as?0E8B~+tl1Dd=oD|77sDFHZWae&8%!rVp3YqS;j?(4 zc61>1kM7}dDl5LX-qdb2T(KDo(f5UM9M&_?k0rDaWD;2}XE=Qnp6~ii8P&B)Ol;Ua zY<&@Gsij!R`M`Z>p3us`pu$z3Zldk3g_Xu|+}Q$QmWhfLB34%?T-6S5;M1lYU_p*` zJ-Mo(+Yhy&)yvn+E#jc!X?#k9pR6QVd5*&RDGpC0V4;nUUHJ*v`ts~^0z@h|OM5C@ z{VmDErq6UV0pntM(R7#?zl7KWtd|nIJSv@lECa$4d@okd?OT@DuvOX4|Jr6nD!dSw z1Ar`(gMrLkG*yhtb0LcGFpa8{o;8d5JU=``quEW4o-czz&xc>s!0!pS$$(vkFg0u> za)bHga}DcYeJ>g0A;7G17^=ZS_zmTKQBKh@v%$4p;%dC-+wd*a9><>gz2`$_n|_pV zq?CfXFO67f52voZh_^uo^2qYld~gk2+@xtlOuVxgWJ24NE*Ohbe!J;`@s8h@A|Ip< ziDR2HFpS-)AXQq{QA@8AZn2N9DvEf6=DlGBpeqq-X8S&yeepugr0QWusmHADn-

6Txn<%8tfIUcg-uZ*6aux77ouNb$eT} zCZF5a?e2&&dF9}mhNCXx?RBVs{F)RA5ElaK*vRc|+a`WFVd~^gS1#?C|EmviJ%{e9 z3Xa9CR_v%caQnqC1CxfmmVE=-YdH8Gf-$tv-Nc`;f&my4#><8A%&o?QsC@I!Am+_U zJ*P9IfrOliIODDKwOBbZXoGi|*$#b^<6qa+Kq^f*wtpqKcG3~@hdh6|$Uhk=muwP> z6%dadPl^=^z5v!GS7>_Ur2%{X8hRkojAymKU%0+-2mUhSzkzqN7;x`I4b^?0_-9Bm z_@=NenSxBEqDqT5=T;r9BS93UQuzenNOJrGGqwt{pyTIuRdgAw=iY}VFy4kA(>GWU zDrTNTyO5SbK7tc%$G{zgyPhC#ocWd;r)bUqI&RG<$R*HpM%9TCvfC-^4PU=~Nt^BQ z(DtloE-vy`$D*?XV3IXUZdb}mN$4&g)Wd?H9EvqizdHDgF5Dtab~IqZjfd574w;ek zsJR`m_*dN?G28w>hVLBFB4JnrHnP~4m($*KAGSPNe*7Bq+uX$c)9E|i_Af7w{*Dp3 zAuxn8-Ho*&vq8;DTGcG8Vr6~mKIuSUk>?g|$GzGaA2V36?&kOvnS$}g3X*rN?Y>R_ zCqS%V$omHnlUt+i_kGp6lKJ6ZDO~YpDF3(Y&$rnNYAl?VL3M9kxMc!H3)dyRQygsU zU5fcp+~~RGm`&!AZ*2_Aoj2qwx6BWHj`XKC(s?7vcYGr$zB)m_a)ZeB!Z z8manw{z^R`MO8^Sbz`ZPrz!b6`(7(UF#@%I&&Ml1Ci|BH2lVJ3veVE%o<@PIm29OV zm>s=%m3r`|Uq)4<+Uq@pKj9M|2N2RV3-uUBBEYlBE;-d16g1&&J6Srlxwa~FsoyT^ zan0%zy^M$bCMR?c^&s5x;Fg1&{ev`aL5jlg5%n!T>0lwO>_Kq1t%>Phz7s+(!v3v^ z!Be#}J{^M2x>5d%FE28duadx3O_~)|TR-ULcg*p7J}#e0)XI`hhd3$?_( z+$%Im)lJZL%1rkCnsZ8huQ~1Jk9UvNgMA(x3gHm$zwj$?WT9Mio==~1-P^9TZi=|P zhLV1>P{BTTyvF3APt9k>3rhPRR0Ma0UstriOh{#8)WUA7?c}M>R>uk;%^_*=N$Zbj zt5a|WEFb@_S0{Oa&qTxH{>NA+6UK>`ij zL|Ib6Y0uR-bJW#SPNaGFzIzuI(A5@)u@{W<iVvs^=JWG|9v&$_;TwN1)alw z<7RrF#2-Yvet#D=B~FnTjo=qHeGb}0#PQC7c>b4An_--p*z(4f7%kM`!W14KJ_7EO z07rDABIbXbyyj_-YkJq=L#Nc8@txaroD|{x<;KvGTCc=iN{T7A6oPe<^GH6Od-vGq z%er)Buo^z$Wu8YD?&2jUXh(NVFK04g)GfnWYDWtwPd{nU$8|%yyO+!Uob<7|zVA+o zDoB^0JgD{DmD?H72o&Hgais^JWEjSwdKrz1vwX_>SDrEXCty+F?X;p$5?2Q3`yBpNgq*1- zb_4q5>G@OY`gE$pkAXtOGJt0bJVcWgM~^~^Qp-1&7lr-A|M+95BWLuRe{ywat6wxz zkpV_W7Rqu*4E6qucsY%)AIRx4q6y?p9N7Xm|mi<5+U^aYnK{++rM13yC2!5v#S0br*r{7b06#`+Xmu zTcWOY7CraPA8XXf-s%B&6rW~qZ-&Q;ihepm#>!=9ZGYuIj8^@Pk6mjNgeXZ1G9p1Y z&c$dv5fC<Qgvt1@eWXN+&$ne%t+Q?zNYHdEe9X zbb{~w=vp}ask^SpepJll1THIo^0>hPb0merz0_i1=&r>)N<1}B6 zuXLQxIPU1&d}EQ^?r1TD%K-(9_mtB#Uw!s)i``YNmQppTw8DoTLoHI7dl!>*6X=}Q zo1|Ik{8+~4O)qWN7%Pfmw}099JNs>@d!N-9NaLx>_g>EPffal5HFW0#`1TK7 zap{b9O_T6GwMgHp29L{@*s$9|Vts2M;N_EgEX(@fr@Dfav+W8BEjP+0SvJ};G24DW z?PO3bh0osnO>6d-opzAJG<15nW^oI=Vb+TW$L*-tG)zdLIzb>0To5NH; z+^ts0bcM$yr&~MxRgw>^$ZB-lF5^de3kF|0+F#>w(I{Sv!d!&Intx6&FJ630eFAOu zOFgF*nN2-&vg91oo1YG@fTttlh`b$R+z3D;SPC|Ha7|h5Xs{(lz|s`MTxpyFn#Q4E zE%9anosPa1gWkiU^1Xr8-Uu2KIkWe+(lq)~J&7(tW`^;z=zOKZBWcyVcv~J#TCM&I z?k8C3$SQ=*fD`_Q`e7XT0dK?ql!^<+N=}V58D^tb#dS-@xW43L{sL~G6hW6F&e*wR z5%|=5R_U^aplIb_hHD`M?n#BM3}ZEnoHKxRB3cS7orc)+k1H4ECT@o zG=ITrG;N0KBU8Mf;1MlF#C4s|GDT%m`RUcX=q^Nr5D`r5@nyhmAw`;E3};N66X?K6 z0`zEt0QBJkso=C7a%j!QB6~p3yO%zI%%Gw&Y?1!5wWa6{v@oRU9pvX)UTlDBFsa9f z1>YzvGGIXPl2)wrcwmQ3N{yK+UEnX{hj|ME?|Kf71JLopASpMY3&{w%nkL{nk6FfQHsUIaQiKw#|X zeX6TWQ^wiB6f>y&$jn=51H1^J>OzJ?97}sAr{9|fcN9Wb&iw0*oszECkK8Nhy1Hw% zQi65`hf+~MZRAL=av9e4tv5NgXOA!QUjkTED>9ve*>n(P_zIah&3P+8-2d%tVFb67 z6&_3hobIYNl9UpbSq0tzC$qZWW3Vv;EzT$Q%mO?CheJg0iN)M7NgC6J*W&I_M^qn& zM^bsoGGsQo!_BQZSB9i94sDTPqd6Q~A(SX(!Gy$`hpjy6WjU9o*+>CiO@i_HrklSm z6wFj`={JJ{&|6iD<7Ir0KszqEw1Cu`Qdhmgb_f+QM9t&7E%9?n8&k#*{t}ouILt)4 zE64!8qALa?(e^^92D%wdEnE*!JqI`i!ak0-HN3K?=GWkD87ez~f4t62Z4CbSIx;wYB#cEX4CyajKA(Cm;)@YUw( ztw@Jmc2B2=e=A$D&_ zA2V`2k$JFyrr+s^Rwfq3O1ZHjUaF{rDeF-EeJzE``)$dFSC?^V08;p9^FF~n8J|KA z^!7&kuN|1^>YHL|Jv}47#F4ZU3Mm1qSE$G&>gAM|JTOt*DdPGMzzxPo=$R)4Gf#FR zo~r(-MauYVWO%P?P60L4?bjLO@QYJl4dySh@QU0B*^P)U@B=LBqdt%E3%+Hh5F#LE zuB{6S(Q59xYNb}V2H?mG#;|*wRGd>A?c&fB(~aZG5T6&wgCayE!A)Tar9T%MA^X?Q ztJwm0TG)Qa1L47F=1Z-0*r8L*_P?>i1Tx!Ja+v946Jj|~P^4KmN1S&Ah_bRo0#E%p zH<5vywpDoh4e=ouyz30>ed%(F*3K~Ex8KmO8^TO&7OVt{oMfmaUo_iFf8jO)rahpu zg|&iEwzmOZc z(fkhM{HF^&XX79V1k~Yg$m(&c-C?MzC8R>@aIzST=2%1FXnh8H;N2UpK>ZF|usRF< z&8a)*AY?m(cf{WG&e&N{xJF&&B~il@TX@c4EL@lG+@H6n=+tY;5}q_H9q8D+#aoX) zKyTq?kBGYr9v%2?lq^6V-iO=>a-(3+NP=EA>c;sU&`m?rt;H$61FK2An_WotVg5-f z|ElKos^cdLt+@mW@b_JiUZ~>!LP1(U2)Cv4gXu;bnzbH0?4a;ZzC_9QkWsfk@eoxY z;LQ7&gxo&P4j36d-Wzj@euhJZIfS7TM92}}XBcn5afTbgoXQ$-*eBqJzdV&J5+%}j z98z&w0G}{C)g*n(llFlaeOzHsN;D_*FfSK0yjxJd7N@l?iRg5mPtJ|_0p9j|)6Fa! zPc+Q0j2lJdCD@unPXym*a54i>G3xxBYE(X*kABWW_*M-y`VF>%!_d>)Jr$X;`hPa(`nY^L*nPN_z5zk=>^noT77B@a>YFFZl$JL9nbpm`z8uXeU~6@hXAoE zXg}RW>r@}f~m;FvGwNjEn8*{g1J++`;i|#kaS|i;T^L_(q=Id z*3kr>#{MUn18(IxvFatrM3(m1(USIa3H6shcFwU>MBIdc3DA*d2;OdZ^N_>3diJ>P zM|e>3&5xJ%Z^ly~+rxOEwV(2Xm(Aic#=Kj!!fv*7eVkQNKbw5{<_G^@ER`|tI>qp; zj!)^f=K7^g@#97bBEOqL!tKi+-#}Q(LT-`>0gOYya2P+`Tb1f|_YKed)%8Io{*xW4 z_lM(5{_ycLY_}|)B^59v@lz| zPJ-ch!)qkUyIFMhwPW0f(!hpmQ+<;TSI!j#@YBe!buHX@ZwSCBl#uwjWR&*~Nz3_b zigCS?#kBb?EUP4Wm|N?H~#>_0n}Mj)agc~`lAvsRCa7Zx?fK>L$V0As#yR( zfehnHp;0Yt4ggR|{4|oK`irCp51tPVVorG|DreAkvqLTTJEc&b?2BOlTAj+^~HTfp&(Q$^5KA~q*1(^Lji0ik6m;5vrP+>YDO3saW>01dLGlAyjW zlYD6nL%`Oje3O%@S*A1WUIYL|1FGKKth1WbafliXq71OG0^U#9H%jj2egw*t29~+( z0y@-`$%aq>2mwIZvQ~&;_A?MwDnu2$6%htL@WQp1R=IqkF$hHk-cYV>wl)EP0W6SS z#*qtET29Ur3d6Sfcr#Fk7r)Eb@-0T#f&OUY04T}35X$&gKmuJY7Fq(}$8|6Rg~_%k zgIhncv8etV9R2Yh1vEAY1RJ5jlC==-jb_*YFk2Q@3g9Iy!VEWS<~!Yg+vg{{cdX0i zQnS_y3ZX0jVawW=&T6guk03zoZb`}Y-?n=OVdTx`*nH!B_(2BP3e|ud8Nfn{m<^O% zU;u9RF^lcumO-ap@?q~uWCrR%SD~TkYCwtZSap#}x+^RE!0f#9JlY$*LvK%D1(ZzP zgPU<_kmds8@Un_uo44{~so3e>?NUa+DD>@6E&}Wm(}G36w~LM2z)z zzP*dI;wMv?Jetgi1~mpCXma5_mI-BsyW942idLM-wVWAAaw#!SU9$T4 z7!-ulJ}+6%jdlG0Nqt%2$^Vo3zD)12#OLB(7=G=$?`qwjD$JX9oif>$Q0)A7`E0LG zMA+tA8H0d#9R;SzB(W7tyGTV?dl`xI|CRdEw}!8|Dx2g}qW<@`R}RPl2>1h_;eZ?g z|G%PNb?}hvv?Q|*lyL6YM z5S(y}v;6%}<9i5rIRW6vGVhBmqm7{N>qO>+{ztn*NuCybj`jYh`C1kS#XIelEiP!? zf6yGxiT(5WTW1-Pg+%diQJXr?zrMyqd5(D8Uny?Uu*tco=~vg4`Qh^UUC(yEbIM=3 zb8zh%)ekNOzy4nNy&gFK>bl6iM0X3N-{f>blVacHbKvHhuuEqnaxI#!=b8Q3_{QY9 zaZmp5`9g?d)y0LWfeLo2^1z2(D|>g$jS|nRP`)#? z@hz7)dCAS_ItETXGo7xJ#%I=rJvN}YiU@H9?E`<7%SVwue8#NT|MOfAXYLl5a8#q8=%5_ zZ*QBfO)=f9{qjrxE>%v|C#W*1 z;b5b1)5q2fH-oAo{bN-J514hyR+UnE2&xUo{mYjIt4>2@iMHW~Ln0hIT|?L8DcrvJ zz@>>uqyBfRdGE^n6@S0$1}HxU&pEFbA z;r2^Cc;~+i=&7q}kE|a<=0msFD`b+p?~>c^oJqNGCtuO@)&q0HkCuCbtVwpo`<|^T zi!OdHby=RC^22@EI%gT=8lM6n^&bn}agHO@A~bc6WTW0OPSCowccH3adrZ5Lax?pc z_T(Y6EGt^*Y|5HOC-dhige~%!LwLIn%^GtLvQ6NRAv-x1TO1a~vZ9hLMArLGG z&G*}3zpDyW!JC_Y7Yz|PzTG~nYc1Z~mtMoXEm_y6x9-<;Kka+z*c%cL*JjE!SMNf+ zEC1H>V|nC4ZQF&vSDS8&FO0iL{`4FR`#n8%^QDZ^fYdK%#3=61c++re?eaJO&GIht zj_Ilu4Ii*bFst@qPF8AhSDEfzzsJXg?okS<+f1IgPYa-pm!yl`b+4%0Uqp7`U!Q8y zj2tT>8BZvj(J4{yVAY$&-L4akP8KZpZ2THDRl0i5wAQ=o9S-vDN9QP8k&%>%K&QCr zCY$TMyEWoo1MDh=q?DfgU&Q;1>hTWyr97|2aS!5>NZ^ygRy{%P{gYg+7~G}oGFYsS z`_)-;i`2+}OdGOMLAUN1o6@~-RiS5D+4e^i((FF-IHcLOliYkCkdJp$nitA)#708H zWz@Orw&ttOPGGag+%>G*75q!P)tZRCCTic8Vl6?`{HSQ($^QcXayr1Z<=;{3L z)E46^Wp74IrpEV)M%@hJPNC-Pz|LL+VpXJv9kc?M)wN0I3&YpbPG~Mci=ri8#n#Df8ZmM-?gxPEQx(K6B z21aL*IkvgDn?nP-7rvq#=jx9fs}hzp?Rx2yugpe-&>$}B$-SB5#UbCpqg%3 zkBK&pdhgIS)&hcZeWEp6;;x6*N4o+IZS++feWG%)Z_77T#`UA?>YkL+rj9Vne3(Gd;P9GfIBu; zc9uR%McGv^Ud$F3g+Ueqz2gir%x)arKTj?zm#4r4lV?y)!ETXAi)3rA+$kNNbV=xsMRW+vUezRzVrrIb*P>!rGOYwNnT#-~< zCanz5i?q4+DU5IbcodgIaK}YbigI5Pc6>d!?RqlZUAtQmz47{nroID*vgWl88jBX(FP@Zn?U8IMOO@O?g>Ltj-m7DQRVpy`oJcd`88B zx1U|;%xSRem-Snv?ZVaU;pz(2UsXK{EKhIQw6$%PXM6c}Y3v<0!d`$=)1$y>^XbmpR#`Pn_gd6y~G1n=#8t@=8S5f zqge}rMeg(Z@+?7**2@;&cY5k6_u?H?^Cp7Och@M}V zfrooXu_*!WnhyqotLhfkC3?pWzm-dnRevv)ChCL9vv{MKRXgA2R2Xh;!h}i8gi>_a zIo6oQsKw>mDtv{GXE%pa>|R~+32&WSb$T*Y2~n6-#4mCc`Ep-rw6~J z0((_&eV$kg-s_q+`I0@AG7dP7c&uhDR5&P3YfTar>^F7q&Su`w9Hk*G1j?ll=QP&9 zr;S$P(VPx^&xe6)2u$$pV&||zg!#-oae4&h=`p0nNH};%R9MzcvCEDQul}rFpi#Z- zK5K3(foe)CkRIc|eKc5dnSvV&7V=k**uq*`PvAE@ztbBT(Vp?jEH5CE!F7}UE**ho z1-3Aa+apR>f4cmh3c42HI7q?9dSSw0c9$70Cs-&q66nSPN&(PFDe~=OR5d$)c*4x! zA&nY``x0O%nIM&PZ+u>4xx~QV5d-?;5U^&Q-3CFd-v|T8Dn$fE@b(%B0#>mfwh`0` zps$Rsrzzc{U=A$eUrO;~nYf^^0x(~lpb+FMG1q8H9V4C>)V$J-F=toi4iqV!5qZ{; z&@KT`Bmn}pggPvUF^D*F!A?j)$H3%-!HQ>q$DS2m`%grG3oH26>!@ejoqi4=dC zs?;8k+kVP3-9zasA}hk%{lv&#KY$JkfV@4uUuy&~qwQc)(Sk#Ym((yT3r(!mx$}&` zH{DtnEmW^OVu!1#E&*VF3|MtRJ|2aMglfInwI zSoFY+^%eX8;aw7;S-fe!Y1606X%bbtzm|$82nzcG;A9%0M1YhLAs3Za!|h_FOJwUBaGrq%T`>dMAj7-0lv8DR zEe0Z!hPn~Esa@p$`!?nQHG^M?lS)^7C*i+R@oOf$qU%*%4+kR>@#W%uSmA!VJu9^V zAd(i>DW;8(g4@El@QkY0LM-iBl7#d>(JMhgNKjZ6A7p%3p%$=c7Ab&%@>&omq#S`} zltU}ak5)rqLRhvinJ3-e9I!dZDDlwksiAsJ==Vt{ge=cGF)CCF#W8?tZ$eu* zK_dWSz(8b(Q6Poazf!4Fl>TzW^pn)?Rm{;H7KWBzSKKxxG!zNe7USOrKqtE(Lq03D zsQ{Uvp#Nx(SqR`MwqBIt>uBh`Via?vfk|kre~Q{CLfVm_$_zkT z0y(>y1LoI6!jV~9f?F2^kU&owp;|X6oB=RH4DLLMuqYL&B?NBGYf>{N)T}4`q6N~6 zlu**cE6%Fv3IR{Ru~UlI53i6*v9S7r0D8sqfQn%Nb4{}MvpOn+w0-BL)6oI&bpavo zSDu9HH~$}$y?0nr|NqB*7%~I|H<|zvp7@q9d8<{PX~fV+5q znv{lWlVGRmau!!J@amjy%s5pdJ*2+^l#hsD;2P#WA>V5I^A$|8u8-I+=XLFo|T!z5%= z5Of)+6@x1q=SZ-*qb=ChmP@kdabl=HGAirrwzmX@ zrs%Q`Q^He1@{pvavKwwLhOTEojY&`)dj8br?3R_wSG)<2J_)W?Ky(1WfsT1X*K`?> zd%4w8uANXd?jGOY2z7C}ci}1ya|O&2?51z+5}&_u1J@Ewc*oP6AmJWM=~xR;%}hYp z%mYrV*&|bz@fdlKEWQ#00eG->lJ2C?7P%yM^gcKlaEy3Iwrh2go^PCp!l!zp3}clP zK&qN=a+d@`rnuLHdYDdq=S{^?5Z@*p1|eQ&0iY>_xE)tj5krt-SgXkF38^go2Jyd9 z1=~h%uc55jLtfKUCD72&1MB2L}mKlYe>yz&T1{rK6U;(*5M2dtPoV0Fz2ig5wKXO{@w_`2M)D8x@g_NYjn z`s2c%sidag_#xUwsQ?{H2bwE8Qy^7xps1N)<|l2voo~3MTiGtsPZ3$H_;to<;;5gm zO&fG{&%kGb7NheK8P`mcH=M}SvjZ;;xXB~9RoT3^YO+#roJB313Q@IfK@gC)3@>hT z(YNfl74G$$EPv3?->$K15zn)^i`Ri%n1a%m@OS7~{jqkv*6#R+We@4~t^d=&%U~Fg zuU*1zN$JjF`zqZ7YIU}kN~kxOMoU^WUZZlhot1&&_&yCghp0A0TgS?ilMzc+25{M zk#9&4M|oFJ*%^-tk+{rw1zkmg(@|%fPN~{7AwE`A)q6b%bvs~ngJ?1B`5{U178~CY zdUnn%e)9DGFT95+ojx=bPO=O?VoJO=R0|`F}TG@Z)Jgz)e(@bdS99^>Q z2E?$1an-eSzHph4)-?@3~Hi(c6xv+Ldywu?VpC&pI8Dp9$1vb4bOK7j$ zd*8_B$qPTFr{bZmFRyq54va~`>KPwy(VipE-iXy-ka1(QigpS52*9byS3TPVvX!Wx zGsQzQCI?E5E+*qD25o~~jAxlc!4Y`&Xm`RfgO|e0DZ@AH%YZ-lW*@NKWw?0t=Fc=A zjm}IGGVf>$`Vc95SX2FL7ku@_t5{q?Ds)OCRP%CqYV-E$NI$|ChNgCF*$ZKfh>)yw zwGt_SFOOo3U&-h9oC>*|S&GFyBy=`YvF-q%EG|4>?D`Y7DR4$3ML`@eZIrx2!Fm70 z#h%zmCjP*0ZHXq%&558Ogn${KlfMHC{;+gg-}p|xIb~xoBEX(xB9+w6KfQcYfh?0H zWl$Q#`F7)n&(&|T-LF|Ohx2O!C)DKAKVxGdc$cg4VH4QQokwy#US7Hd%@V1$K2%RS zR@Rah|B{XyCA_~w!hk_9P=TfCJKypd*v6Z`kYbiUqv{KJomFgVX>e?Tpm!;5;?{HU zPHyl?GIoz1w%_fYg82GwA-a>4HX(ef7g{D=_bz|a%{%<-3ID71`1<+P}z{E*iO$^uykUtwJ%l#&Y6~tGA4B+8OJ3RCZw{Wq+xJMQQ z%l3VV3Bzi>l2VX_7Gf3ReBKIcRM2Tjm4H|R%?QySmZgb+|C?JPvqk}v~23277;@~^K4sIBmYBgsFuoO^ME zywN0et4{xqCyUlk>!14hD8P=b!`6Ebw5vR&MckOY1R8?(U#kRq0J2b~P;mHrkm+Md z-{E}vvjB4Yju~{Q2ZTH;FU6e z8gCU0i)!&;hX7QCux7aQ~@MKwI>Sse8Ue zi-?Dnj(NKmr|u=Z9XM^@`B?LI`p>WLLS7VU-_2j+{e0K{A%`g!tm(|w*qiKu)|~=Q zfrzh$!wIF{*@2ho{UhPXDEyi4Mo~ zw#gd)eRA%$cfb~Sw1D(8<~cwXt+Uzk>Kz{2d$A^MWo4Uo@7g<0awY@9hho>78IG8Z?dC9Kkg<=v z>xxjX&}KY3yU+<0%2M>$?khAMC%4DIV98uJf`FovXA_*T*O(YO6*gCqdA^R_30B%& zsfN6OG*e1`c|SgvKV1<9!P{{Gj}4t8TRl`ajYcSdly5{4MTGiRu=yAFJYFgI_Nj;Y zHe4Z$ypy#>(FfbN@yfr#k6`CoQTsOUqU9xwlx&O%iP6NXFCzh4qed$|EO}DQ&~;kW zZzrpLoN1zX+{orRZee`Cx8b#=7-LT5p=#_nKcT0gC)9)eXva8tGiee_Nn$;r-ZGt@Jc=3$X$3vNRh}_TurByYpId z6}K|;*rm@`50C%(P{Z>W<7k_x?K9B|5hQich@3E&(#(Se2Fm}F94p4jd~7JnM7g;1 zP)uHf!Tag?>|(*M{Ck&!rEvd=%(iCl`@jXENf-m7&lz7sKJM*~qr(OGjx52}AJfv<_`QfN<*nE-tQ%1X=GF@r5wHkql=%;EFOi{p z@BUU5wZ*4@UTxBE9bK=dk^aI{ZeU}d10ieQv=HgQugf$B_0K#8RF22QXV4tg7yf(V zL}!@1n%36I7__V`zC^YQXFc?KyQvERXj@t1F16OK&8f%+>C{vgf)D$QUSi zC`9W5K_s}>WS_cNNCWaBW*jFINe<{ z>e8;k^)c_5W?!&p<%L2e35n}vZ0?DQIlIw`*!^1co@4D&<+XK;--{irSa>Id_zF?6 z{Dzb-zMft${JheI*(!-Gx=06t39?L#y1--G|9GY<`j@Tsi7@1FJxTt-t{Du5r~Qh& zi>cfcYF{cUJ+YM5_Whrp?qcP(9fcKzCXeFCM%~88t!5zs1eDfSV7&u%Q_Y0|k;k-P4 zYD`c6qCu_`yAl6>yg_rGEPaDVX=Hv*CsvY-@*5r zvO1<2kGa(~*xd`le9>5gi?j*pFxC3z=#NOPZ}SLiL8x5XFxI8^>4vi9R{Yx1nY+J0 z%KL$fT#|1;5=k+KZ|1=cS{$)Ky=d6DrZdvHrJr%<57PEfeRmrFx0ZAgxmCDL6OVEw zj*&eben7;B%lq$bv>CE}{7$azdH>+Wf0&=@5tsjc($lVdG*mR9Lrco9hiO)cK5mi{ zn79n4L;6&JDgWUOw9jvCg^GPUKJ6;ZM|oC!CrxvkOCb(F>eXISI1Xc@IDMUFU(Fbf z!`EVb=9lcwoA2XWf5k>Us4h@tz&fs&|ESqD#u!o{KtqOviGcz_B^<|%oNOL~Jp-*e8gc&!=SWmxu1Qldh!JmqExL;Ln` zU@)V(E@rk3|wBELr?OGK97cLNsL8yQH_ zraOMJUb6%1K^ATzuydR59%)A*(%;|i&QMyvuqyEMem$C;%Ae5|4tZFgU&KbB+=vG# z)OEJUn`Qq2c-HV!XSqX|TJlCcrcBr_gM`1IiB#D(QPqBeFvm;hpQs@mWVZxh%R4fI zr1I$4#@FQ?b1tWAQ?wvg?|$yf z>AN$l&TQk#y55{4d!1%=Hl_(UseEMRM;!V;%X$w0 zd=Nu>683}(-?@x@-CY;rd#93yh`x?aq&id$Usl7O!bSs9J%-c4`J7d99&1vaMsEQT zucRi*mRbN~y?v}FeMg$mrj^Y^@k zj8zlxG1>t}V^Tnx*;k{aIk&wjclJK2y9tfEZgzxpZ)S$+3zE7`AhOJACFk&MyFfSS zz87rX3g?mSt-~Z@Sae?qsq(-qyeAuOgn}TuWRsKYChV=EPHiy}I8I7fo)1wuy6j52 zOUBK+;Ws_5h-I~xS@E~o2>^Qs9W8A$mWcxi>*%~#V-DCdRus)S3>u7uw{z}ueV36S z8R(Xlt-%GnD$Z@|R+2mb>Y*^Z2dw=0Tlv(ygNIu(CkyUR+u^n$Gh&9%iBG8$Wp)i9 z^pw~;eBlTBaw3~| zF4|oPGYVqLGRkm#0-A!`777|T0DM=LBfxq&<6SMd&DSqEzA`W{v#rqqP!+TO3u5~} z$V;6>1Ta{Q_uGx<0tHwcCN{I#Wq{8 zl_lH5&D8z@cimWTeh{L%34^QJ0sdxC_qq=hR4*eA2XT%He9|bK|7ed7qMz4O8ST4$aU`E`&agf|vq^Nqj99t-^5gl&2W4%QzD@bW z{%GE{nx<<%2XbWzOs_7Ph;nuUk-)vQF>RUc*EOJFi`h%e*-C?3lc6eJ45OQ*FC%EZ zM&9X9=oe2-K?8^tu_<%X`^98#XBXNR>#lqcjgpOAV3fxBOI!vj=hLzGZ=RD@VcK#;bx7Xc3Rmrx1d{spG~|3?0Gkd zIoHQ@0z&>F;!y0+WhSJFmoYAizLJZ60mu`Y#skaqg?d#KuPPET`CcwA8nC8flA}3^ z5^g?l=?LvsLKh-xSw@cnVCW2J&@R0%M0s*{<>ajcR+PHZ_G-XMDh_#u<*A!9?nI$D zg@pBKg3d1?|4SZ(l*4sMAn40DeR`rsd{K4y{`lqG+P}A=;@Fj4MscL_<2NVeB!CG4 zOee@hFc8U;dDjjhj~H{}quC)|0cDRErz07B)b6J)ID^-@ll{QQWoTaUSSH`Un#iy8 z>Z2=`)ZPP3B&@ZvoNE?-hm1QxteNIJ;LBx!ski2T$mW{hnT9q#&k@WzC@}EQn!U8P zTy9s}L1O>W{m+`^v-}C{@9jC@O6>}2Bv*!nNLb#>5U3dFd4xJ6^Ze_5F1#yupOt3x zBQjqCJaM>c)>@J&)UJx2;D4^n7dZU-gWP!Pxl~pH*a~xm>WBjZ8J#2-)i_YH{KkjG z@}p#_1aa*ZuV){@h<4Xe@K9fE6g*wzGy{ z$CcUq1?EF}L(a;(?}9i$&RIbr0+t!FP+Ap(A^Qj&S26*S0O|rXm7(lLhg&e=I|+!S z<(ttx-sWRf4M~Ut;(_%c?BUpR(G)FOG!x9S0UiZ|yfWpvH@hA&^J$POF{|W7P9)uB zrG&HZ<&C^6rL;+QB%htWf|qs`un&nI+?;1G-rA&14>i-xI`aq}8`o9E6Xa8ok9u>D ziQl0JkiEm~fKQV=Q(pPrjmadUfz^x+Rj}j6Oih=SuLk%<+41vsXSey;7XnJ$oX{rJ zHG5uK5c1n+wgj_ze*`<00PlXtFusbWm(Ny9-c-+rS9jIsIRfhQGEsc4Qa>_NfUIs2 zre}rh$JY6yAOLlLmFPn7AUcVtAM+J02QajS6kQX}weOr`u%joL&N(*8NuR%TSJyh}*5279_RJ_MYJXJrT<*4n7g#cI zyg()j6az1?77iCudb`0RnbBgwb-(g=t?;|1(mTTbh)a(c6HlsMlf;d5uoU|^` z)Q(7;Y<3Ntt0b|bf&0AYxyjMHtBgOzq;$)b?uq-FeMopo&kv~`hs+;lkFPgan%NS@ zVBcB#R4us7_d1kp?d~ZKIx>7Ug@JtDhg!VUPX5#tNn}R}Ki_6AoNHoiCpchAM^m?P zx*0Fy`5Fi z;^sYli0J6;HicjFC*wb{Z7XxDsuo5N_D_c2|QZ|c)z*Hf2rmzzz-}^llqLk8)|U(Qc{W?;C03IGi>&JLy{Hc$aIV{65`2+T|NUpAut zFd_oDf;pE|RX!aHe{@*BkU$Rqje;kfNq$$8QPZ%{^=$$3}i z*wvL#(1|;obwHH7k^Dr73P8y@psXEa*D)F;meU@CSdMY#Qt($`T^HPLBDsnx10Ckt z5VwFYNK$F|n8gk)hw4po-6l@;-0?t?v%WRRm=5PUbHh}l*>OS0RN{w&!mUx0Eaf0# ziU8yD8*LeJVpb(+1s>)qgZg3+%BDg>L7gtmzz4`yAVcJdfFkV(wEtJImU*giw$A*o{N+@A zG6O&X00n@iL45c*4x$ldIz$yjlqG=Gwr|p7XD5yq$((rmJCh3~p%`!!15#d3;4v#v z%zR@A3;?XT7P*~A6TOhZg5^pOP+kTAe!A!xq4Js{o&dq4n*NxloIblJnI8!Tpbh}P z^Co_i1WY2xF&hI2%Ef%D;B*V16pctByYUlWBuyHIrlso-a}Ae~2ehHeC^3`-9%z7{ zjDPYYC#5U(iqQmp^1=Z@+KCTGZ%a9*6bP`B0q4mvmiEE~GO66--3Ok%vs*kX<=h%t zHTC@;+$_syoLu1yHUTuoYOLp9wZOkIM5tkO#!%*;VGf{LLU{6HFTl+ye*gFJ<~vE{ zPvW^yL$53yudLhJC!_}CRXiU!d}99-IK!WQV)8@aRVfk#!VQQ2z104f2-=Cc5Y`oR z%>f43cma@erZ=D5pvl>0i8K|QIQit?twgBuvc4Rz5^T*jZ-P`N{_Fp?_Vbk?-8kEv znw5zBJ*a(R7|DejfC6+8m3K3)IWBd*>R0Xm^ZWk4(C@;J^*!)#{y03Ec;jh?50i{GtVq^BmY1+oW9%p|3b*-wiq!xsJHM>6E zec1T2vf`SAXj&$q8Nzut~b7X5zw z_upS})m!Enm5pl$yuZ(XIJfKW$r#G}KZmt1e3RbY`;Yltn;|26n#qJ^f!aM%D8UaY zV>(I7Q9cPT&-wr1_th(MTv^uRxyah;7rU#c>z8<&c1IK~S$H>;`pnIrE!!2Wrh9tN zp>Bh-`;YxGD0dG%WqUBEtGJ@RBC4g^unL^98dfJgur;blok};V1sx4W=T5BrG2%02 z?TqVk)Q=h0=bGMZ+WXC7#rS;jR=b$on42I#q4NhWBLmXLW(EKNyab;7f9r&C5L&ra zd~j#{>pR8kkM7jG1p>wQt30pOI%X{YSPbcIdn-Ii-mmiGw~w|{=F4b+D*%Mf=Lp%d znp^)z7Q>M=n$^M!P(n;TiP`g5!!GsH6jRCe+JBB2t9@UOn*`|Gt(4B$LWN+wp~GwD zLCv;KbHM!0F^kx_?NiqIZ|&EA|f^aE+*Gt1^FNG~1Cu4F{OWyR9nQ0H@J9M|*O?97QYwf(9CXzj#@mlss zzM2&{`43%~+d$rRIOpXJdyOZbdosdO&r01VpBxOF!&GJt2dM@8Quq?X(@Cr1N^;ghhJW0khFnm9r6HaX2jCV>9R_`$_#H#aqa&L#dTr~i#>l`jJ9j|!@^}_PDas0DXU#fZsc$bHHfxA&d_r}bE=fJ2C}%r8Yf_bG z@S>k~2IGC^iSt|;Km5kuLF;%|Yht~($tw?a(5bAEy}fI?#Og2C=+Wx2K}8r zx;i|`b0+_>^)A=ntSSGn${p8+`kxWGx8r%ncMHl!4RcExCpzJz(Xs0ZwdP?N>&~px z+wv6TlLLy>SMB0|yC84hJA<-amXhu%?_-7L;GOxTKH~9#kuO(-pu(A4h}W~V5SxP| zwB)O2U>hRH*SF}Q$7F^%L zCWL8&K(>9YpijrusAhAuA{Y|b-S%i9+uX0C$Z_DjQSzt1TUT98zeL=Al9m5{#^}si z%6GPIXb1zU&iO`zuTRrzUe3`E7$i_ znbP{L@V>NjnXg{oha5%p6`e3U=<-j<(H#+TfAtipbO`U6gN9L+slJ?z12X2b9OoA0GQfN;-Eg_($M!n)_sd8}mFp#$)C<`Kp#+;g z09Bq7rqoPO*f2=(*jsL)(nf69@SNhNt`MWmU-bD{NEcKRTjVY9@5XWu0KzwY$MV=>8F|>6VJr!J5f8bSw z+1Pp41K4o2oqKT%Zlm1Ml=u2;yo-+0E^3ZPM5iRImpkU4Gf#gh-3|mX4Z|SVs1!F% zNtdVcUTEj({6rV^+sF-F;GHkjRlbnH3cM(r+q5-Rp>!B-=%?_A_h)YJO0v6^KX5)TKoPrNCke5!yFPxOLzUQgC{D3>yvt#x#tzC-vi-ugE)+7AJ$ z%(3JNEvY6ISIf=W$n(P`U3Swtv|-9DR9CGE)F%J0+V718){0Sw+i}7z{3D6;$tF-P zMF<167${fju8@6>p_JTKY_zYQ=_iF}4hdoI?@nC}|IO!+enn19u?OLW#2ja-3l4Gt z*5whu9U1Rx|NdsS=EqlTQWt}Lq2*mK-XmLWgv6V->%g;&-|gP)ou{U7-?q~7A}v8z zCHUr-cy<8?{VMFh$u$<{>-8LRtqYD>-LJVsL2q5^4KGt#*8I{`ZZ}p}6F$tu984pp z=sAR1^51FWPiAXKM95z;)}`Mp8>=p~;(7tmx+UU)9gO)7#G7n2U0QHn!Bd7)N|RJ| zfZs|Ljmo7}KiB`=#rg87?$wc|8I3uVuWjX?g8jsL9BsLeHN-%m?Ynz%g1C7Kk_2$>y{`|exI9Wy`iN`^xi|q%lnbiVC!fb0nk$kRTX;SY}OVF!n%{!KgjXqJq;~PEWf2* z@nGD_Ym3ok+KiV#W>7sm^iGRc!S>L-`ICtO_wY73X4 z9h==})b_6-uT}QuN2bLS?@Y>USZhU7hh1*Q3t=QuZ?13ov`TQ*xaHbXQ39=Dt3vRZ z?Nb*#D<;FW@`I>I8wRsa^$t{-jPivNfGiCX#KDLwqfdfhG-&85;yv@FFZnSjeT~D0 zzV}Soa>;3W>wFUj`?xx`!;X)CKAC4*4ZKf{V61BQbloEc$jk0rU}D14$XalD^v;Yd zs{+g(OVBl)ERxqU?&ZAM?|RK?4Q3!|VnR#_kO93r&t#H>QfE^i9(IeCPT6naI<04z zP_yvMPBMC3pz@~9|NC>1eklyZwH9$%3Oz$7RP#Waf1fy*#0I)D>E zpzk0!U)YYHzF+k8dn6lfE@7Vu+~xuN{rcTE^t0R}@$`UgY-_MZB5fTtEv=lRAVM}s z@Lgo=!{4fJCHO!W!mI@MhL*6(Nd_6L+Swh?et0*F{qB(5I!KsSvTU^k;lxlwGSYCO z6GRc9MUpv0LS~6k)x1a{0sFuRcW~Ht0odp8++`G*g*MPRF^ivjDrYTFe0`MDi;_RX zftC`IZ@pJ~K_;wMAVFL6K^W0@2;0lRbPzBvX3@GPC3OVZbJQJ+mPwVf$7_cbmC5O4 z$Wk@X9ZNu{c%i;XEoCidFthJ9#(A;3M&&L>(!NRX5|VqT1;Jg<$0Qa1Pk=!P01(2) zm?(k%Wk-Unl&U=91gn zf(o<_FQo?^6y-^MIsE$s5DhoxquPJr`$&WdswQ96J=;(Y+KL+|;ohD(b3q7tnfJ1I zd^UOSDbNH;KqrE7Ur8FMsa6)(9x;YMi>tj|n4tIXO(VKpz?u`u$w0E^z89Gs+h&qf z3l9xip>F}LvnT%4N@);EWrOX?Sy?fxnkU-@ge3PRN<~bTSBjbm|DgomNdWh&&?5(t zDKw=2A!OilGjoK@)S&}@9Bj-VG>GW$ za7T{)L_9_y0(h|XKrD_>USdR0-+H0Zlwf5F-6lZR3b5TOR-Xb50$HXqse$v}7rR&R zCcy@Y;1Gn+)D+yJK!dU+c&#w~r1#g34$og@N}RPE#ocNW5IsW3ACERJ3m zA$viN*}&|E^xDbX5oSE%$bCF-)3vCOe#qVA{qE}#gx{`QD>}feBxn%;Pe#+eTy6R5 z=Fr8ah>z+Z+W44?4U3YM3T3nip!payvu={-1JgrwZlEJrd{&tZY!mJo6-7=QBIzein3Xs4$@&DSz1h%?Ex>1 z1l+Y~o6x;-Yq_x#B)(LP@gGLVlR5P$br3ywAYpEaPwq3MYA(tjEo<`#cejLWM&BSo zd&4ndPG|lE|D@tQ_jbTSAzD;W3@qD7$Go#S|IDuwHj0BnSR+(yjIC^`0Irf%m&$BV zAj3-ehC_mkOQAb8{i5<#-98~UED5`zbsRMbr0O@i{8#1v3-T~| zxrdbEr(!Iq0IrbEgW&`yMp9Ah2SJDs-?A~ifTxcRca|>apJmo%aeH5hS!bQgN3~k+ z``E{^EegI()+F7VyKYE%=K^#xvpopZE^P1r%xkcfn{~B*0nYpl4jAmP2%B7=4-2y( z_IE{`G3DI2+o4DJ_cHc7Z(q`b?kp1sk|t9vvR8M&87`%p_9dz&5kQf4A_>}l{EnFb zS;Y%k_Q3A{;|z;Uxf&5=9C8=#qL@5W^R}Yf)C_NSdEeu_1~>y+=$kDSVr$Q4n=I+S z<=tpqomes|UuL*!}jLLPeMM*3{3zE7Q-y1bS7m~vl;N@7=E&+g$n9et11 z;UUuBa_%4dz}bK;-`nL-ED*TcboyLWhA`N(xkG}l6CgMG)`5MBwK@ec)0tC6D)j^odWmOZ7JcRXLHKbyS|e#kbOK^O?1fCk^H40^DLM4MEevQ zBBqXyP*GQBp<(3GkdEZ7G(Fu~Rq9)jxxr7{jIz9?cKiba1+(qz+CxbTBw@n%iRdldE3V_eki!`#n$j$S>ufv7=E;Jk+RSfuX$Yuk5~}?-F~R8H+f_!VHM9 zQo1gBI~RGWczYUn?Z8))Wl&^|xjoPn;St9#8@hFE%9C+sSLB!MM>{MYKCbutLAtB` z@9{vr?&A;IYrWmkpP{FHW!q@k4?QQ}UY37PkaN40=wgh$LnvhVLX`#8=ZYb+01ST* z?HEsvR~Rfm-0u&0d@a!a+cA|*ZTQc=%6{i{-|=)GcE!A)arr(qE`)C^XLPk@i*IvuX5Wm`&`zf4E%+&+$@WBRVL17 zGcGNpLjge0UZwwqj0W|Zj~W*|W+eB}cSz~LI`ZY(I=~e`ffAp-ZrMK zr@YQn(=k!T=Q{&e)u;YKk|H9c1`Ktx{>ZdS@ah?{V~dZLvo1r+Qp0;U{p zs7bn7E8pem>peK+cjr4^_VAfyzwmi$3(X|b<@oJh0aouBCN{U}eiK;1`_#wwfQN8{ zkeq_Bco`5%ADc{#)s<1a{2WQ1IgplNyv0&VCm-m4)Z2qg-E4-H+h*djuWa%4sw&R= z4femI*vm)HRj&gh3FxW`)vIRF&3QP8`js9krjd`{C=~(Oo{#?ggE2@&LuWk}8>|y9 zrRt77bG)PL>~tyiu)AbH?&c-m2xxGk&rF$vbB2P1P6 zsY8D7_q7`6H+H1X)aJN0j#85Ln{UgStFk0rRl2Pne&UUYGDN@v(ayI-_tmu^W+G&} z;Muh%`IU^p=(UvgtDRCZ+JOf&pl6aU1GWt0fiI`g|sf-OD}dLuA3$WVnbPR2JP|s6@pM}^s{5}mu9bgWN?L?Bpe!~L&VSCB z=Glzg%Rcm%2DHMfpRi&8BZ2NF)!4;genva*c#vD}b9%w0-0JRPEs$)Kf`Lb$ySL^n zP&0cw;s6w%cH`rBL_wwF36$+vd+t-`9j%3M0j*?qCr|4# zZ$tPmELh$)(H8%C?#qF0_80N}OGkaRo!P7EE3tzOeM}TiSHfDi=j*E)oq57k_=f^@ z>%;{>_Cd_kCJJ)X{P~BLZZK_gz5CcmrH@zk-(jHb5zoNEXJBi5?DCF%{i)w%pZA|F zT5vx3Pkk!fLfC&7w@#|?cCcnO9Dy`mq55xWDypF*P7S=!lUFcuK+ApB>Ym(E?sUp9 zUf0yN`F&=8t<6ibEAKuOe7v32!=Y>UpIlr1b9{FgjGc+#za7GF{%}{uoaT`{K%oBO z!f;k^cr(|$-$3#j3)nuJUFI z?udbYIeSvEo)nJ$I*!Vg)0Na2xSRhNC<|Px%W2DG#C&Sbw5eiOW;$6GSF=Y}O)qCW zf5_FzT(J0XE``{rycv_Wo>?4p)CQ2g*vX2w)DZ;0||%cci6|1N1; zG&jp$N*p%1SZ%e#(yM3l+nFfs^zkh=ue;2|REW;@`{ODh(RH9n8K}{xx?8on`9+*q z5Cg<{uLK2bUSHX!hm|YHmZ*C4=`D$U7C)<*;+RD(j?$?`?Mw-CNHf*bJQs!^=iNKg znDMdkY{;j7&q{X~q9cnC(#FIW>wgj83U#g~?~Owe_R5xrRtFn8#CbawuTP!)({gWo zaAinpT_kPw)GFyjR%x#OYC2((MusP!L%xkk}6vfUWjH# zw#Vm2s#>e037%u^n#9OjBTdtJT=(sfW*;f!wrSxQ>qGna$f4VZF6rIf@x7X|%t*&m z#9~{X;aM@v?byc@wJ#N+2(>V_{GjS0r@Ig6^8Ceku<`3Lo3_k^i#B>upi`_pzI{{1 zJ+bPZFKM%ftE!PseDG07$bcDxncd~vne96dYj_Fej}=!mQD6>F1T@QbBfALfj1&oo zf%}IJ18Rage1190(82H2HXRvNOh2}K4N_2$(m*%8S?*%B+dA{_lid#w3jru2OAY0M z3MkK#XOUq@fCSN^9Pmhx>A`ByV5jJVHg`q~;e!L8No7@0tFtA>k5x_xg{Y@YIWY1lwyqm>{Dqp=pODZOa;BHpN9<{ zCeO>64bQ=FH&4Tp0Ypeyc;*k_ywj2kK9#GtZc;e7tHY%rCa6v)PrafII+*SFx8KfG zz=EYpd%x7Dfx$dyCzgc>ygQofhbn8l5i!$b6+D+s0Gb=hpN6K}Pp%Rwm zNUz+nk^XBwgYNkt=!}N1|?_NAI{Z>kpo7&9cOq zl;+A#5c1db_5~h)73A3m0Z?_SPpL!BlHQ`@qGwePQ#kq)esXldjOH}!VqRb+;g{f` z_9|h)=~J)V;W9Uk*)#-BP6W|5J#DeUMW?+zJC6-_)BDkY$W;$B&0FhVFXeLvmB!qj zonpbN`(-xWY?V6>nuQ;K+1=T7W8~<#o|)IX z@%NbhlW3o^ErCE$IuFJsJ*+Q`R%E78F1^7?YW_0awz=3?F0%JXoo66`kn zk$1VMKymNz>Zr4+7_$EMsO!{g|4GVfPmG|l_7%p5^V@u{$Qnjj z>EGsm9CY@0_&(~Y>^MmWz?jD-7_G&cw@a8O4D_&0kkIRkU$Xi~)unx;(7T zx8;W}PpfqBa)Lx~)ig{_X%#}uw3%;Y50{Kg-O60%6%mk!gDzy!lLc{}Dp3(2GTATb$A&O$7e^)YtbY*`}sKl=*GOygmf9eE;DfShEKyN z>_hI|kd7j;EE9C43x)YX3kn`E$vnUKr!1`igarrNI|_A^79pZ$r;+Hzazb9htHusti$;%f~xE-PMGC=!Tt7_JEI?G86 zRT30!RON1B2er|E<2-5 zCmHN;CnA86UfofUl4ViISqedbXYoBY&y1LseQT7JN$;w9T2?4(h+bDP>0c@}hiz$` z%HBWhO0fsk$1*NWayw8mG=aCc|f>I788bdnhn0&%59_pTN z;MtHBrW55>W|x4?ZA1RxUT79(iVUgwWV@~$8ufZ|kbEiwv5zYQ0<1nFUI^7Y3eXGd zk_iyAya-B`!w|(L1}KA_zmGbz%0Xst>-xheV3@^TRt}zp)-vG<@XF#Y#8rjX>=7=G z!mx$2qbCt9aojXMCv6fDOb7q1x*$Q$LjVyBsCe-_)Wi%}S`}8}T|9ZekUY#ob^N75 z&XD2uDZ}|*9lWODc-`%IB0!#0iVhk{41MtG80VlEF0J?r-;kT*FNV8C!*oES2G~MR zd{iPT&|(qrWQNyAgN0?zlkX@ldVAk2>gB+W1HRj@1|bW?H&T}op(q*8a<~^A?$C6f z;LDi9>U`74#i5w%Cmr0QxmZYUG(q`l+mlELV7`o8e03^bp@L1QSW!gA0BkZDqEuc0 z7e0ji$kZGJFz0B_YXqud6u4oNdUeAdM;?Rx#E?_JAm)LPsaCKzE>5TGv z!-wzuin#SCF~mMvr4p69HI^&=%Cgzp&R{Gu{RoCS_MC&s9Q%0ArBzN`8X`mtMT!f^ z1$k3KKs^msVthgVk=~V(d#EO+A4tKLBPf{KlFFM$L6Wx|5nRq%@5|6s9agR}7gn=0>qv z2}<#xs5YG9D)|hw>A?d8`H>E6@-cQ)G%DJYOLFA-6Zbdh)@h zl6hc7$VJ&R6v$Z=6uMgg#0{P<<0uy{pL4M;hQ3L#7}{T@zD z&MBkvZpBMYR}_T;n!Yl4tgPAc92-HUhtT2vBfJQ4VEuW=s^5b3(?zD6fW~)fG&($h z1+QyCF#A{M_4nh5kdTq0U@|XC6sVhmOrko)PZtrYi*`;Ubbu(s$Vly7-j!org}=8@ z!TACvKQfsg*Z*8kE41)DGBJWrgs7M-y}By%MNX`IB12pD&@kci+8Vx zpTk7%_d)%B99% z%P|RPy3r*znhJ?zUS>`sZw(9b+D@%_fOPsL_`dV`NjZAY;T>J171&fjcL@dhv~RWv za{2{%wBB>OgiLyPJPSD#A%ESr1AEDNhx{^!D#($d@?22oNph#mXR%w6NnInvN9E-f zgVrZFi9$itXXGB4U<}>`nTBLuGG$EX!e;jjx9rksSlOPlr9YW5xp>kyHL%6+uQZhufVMq0^2KKM$r_GlzJ9%*MZ;j#TDG!+>` zJbce4G)E?X+~!Ewb$O5?uy{T}OgO(xzDjt9zdJ~9`nuKmGe~OkzkCiYe)`CTyJP;} z-(pEX!I>zga5A&jEwKuDT8!L+P@AR4)4y!bwgViQq)pe6E_wIPWw;CLOwPm3w;tYU z`JD|eC}Tz-eML|i8MT**k||6lFqL`MmY98SVxFUE@?Pp20MliGUSb1eXhJ_9JdI*3 zA$Kd@yl}b|rh;Nh&C-^;q`XCMG^A%(Y@xoM5;BZ~#14!3;4lXnd47Y< zKJASqX=p?(V9*a;NhvIUj?f0!uv)Xu48g9E@v6(>o&9Br(?z?2Z0;p9YK>%gHXBt7 zAcYWfN})XyZQaH5LIbc2IBSH@$$9fVUzK$f?#;a5=c#sTY6wSS6I?j9UC9TRrhz4a zLBypjmLN@TmGf6KiGpz4ip*HzYvd+fHj<%<&`?UD7qPJXkEx&hGwhC z($yJ2pc)4u<|I*2MB|JxPeBZ0R@<1XvKbHjV)MNn52!Of_x&n-1Wo$e+a>#%r zFMXj}4eDngwO+&}D{E7w4}pH^_=Wnv)jF z>0I)E2S<;gwSc}$p*{s55XndyCuw?qy-r$TA%DU%a}v47ycR%<0aXSY8pN^g0^epp z)RutX2l<(`iIFI;*;Rrhuzw{lL|yr&BVenD0bI_U290Y-h7g!6ga}BYXD8^SeL2sk zh`yUJ7R$(4(T!}Zj9tKBYk>R?ttk2v1nB3a2=`>Z$YN0i$zrItQs9udcOngHE}xzH zA%FrLr419gcJ6D6tYjx@>H5UmGj{4X-?1j^})Q&%KJa8ij1-3_HobHNkh@5sV*svw=Fc40AuMKNf-uxZ$mA0Y%a zYGgJY6-k9NS+etjU%MQB)@-&>Yi>!S3YrO5Gf1dA#`}vLewI-h()-bzKKtIE$bpLe zrvIX^)T~M>{g)MV?vc*M@VZ~JMCv^~oN!fsWc*BlPlD~76UxYUm>K$(iWuvhL%% zMsDQ)>g{ZHubgjr>3({58 z@z(cGFP)jw$K{;$Dfp@Q)BS!KoQ)PP^E@7W{W~27wA%Pit>5aDa^!u9!>P3B>yL6y zzWsRppC8OSDu4dW_k}ikWqS3zY+*jXy!chFGNat)Gw{ML@o`HS>_BdsONQZ#s~-&x zpP3&%b#d#J7gp^d9b*UzIS%NO7O#{VbPqZVt?xeWOgx}*FkxDfY2aZp)LpaV> zW$zo{x|_Nw?dx@$9b`0(;KHXHWQyw=O}`T9n4j{iq(H*hvFNuHouIA@2FKD zCMeJXbBi-i5`?>2@-XVs6IrZ4jVCHZn zG_h{m_9GKE6|(xQ$7_F1U75DEoN`m#_l7X(I1%emNvRZ_x&G<^HPg23fL>|&y;nI^ znngy@lnVaOPWT(2-))wsV_%;5)ae6gmyvM1c>4zfH+$9(+BvKYzxdE4eA~nJ&l&ft zn?5sKI#*jGo{PNxNQzssLtlKB0m$`^n^S;(B@kqOyjIJnKfu!C!mhJgVu9-^RQvX&j+tmaaJZ$s1)Pg4+(vNa1lgV?D&U zrLhjHv@d0!ik_TvJ7;-qn*i;E8c%-mDRpj^qI`cxr(YWWIO`8_$g^X-f^nm1XU>Ux zD>{&6$n3|QH~M@kFRbgXN+GFxEn)Jqoyn$l>y@-v&C0(fwHL%wVOH&ZG0<$U-|6ez z9Ti0$ilTq^Q{Qh|lA^puOaz`TT#fn@_hyv)y?eHkW`%*~rfP;k7h=5QR=-+826}MY z_Q^l)jk>cIIOR*onV#5A`N7}y={ z`klTHqj$Bh$R}(Mb@>Ta2m@9RVBIERD+cxmgZ_;4t)6MB_|dMS{_;oYlLyo0H~vhh zjx6=MO*g5lRVu0n>o$4ybNHUgqoqNRj?; zX4?d2wj0_9qU*fk4Pp9L9Mv2RZ)keLZLQb6?M_yZ2Z>{5^R{GW_PXAp57#W*vmUfvteXA9CjHeqg zrXY+=qmbPqZ4p45nZybO*Js$ysI=kAklB>We>!f z%~9Rv*MUwLfL6zAs8Pm^-+A*LJJJXL@Dr{&_b5EZAr;x@V1}QG0xR(E-sy&Sk4XSX z080}%wWG=#+?-iUk6D%4w3WL^)d7z$%$89u!!~@UU5Le)8Wsc%8>Iqlw9TRTS6KiI z2awWQSb^K%ak}^!zUv62!tb+%z_nr0Lq3Mj-al&49oFYy-^8~QN8%EKF4jNu7s)7xH_BtV_WFA%x9^n2Y-=`p3Kp4K3s|dF<<+$Aw`Zy9-oA-+rN6_I-(k``LwxY zZ)E;q_(tEc9AiUCGKfBzXko?IjNr#HIfU6FBn#0bXVpw$pUND*#^C)9<3Gsrq26H9 z%2i4VuP6iuCf6A*VVx=7xJe9%@wT%z zrN>|e#Q9Nt@OPT|Uk2e9+Z?X<_P6t*-jL`5AxcUg@kh#M$?p+B+ zDPDKoudJPn=>)$9q|kk&u#=(MBnCT7n5DENYmsS7Psjny-VL<_V`o~HI9Fvli|qNnlIY((#&?UgPczBKMEn} zJx}{eB@P|(h39BpJVf}WWFepu$oKxeOB7855fH9W$<0U_B2zN#O!Q5N<8s{cAe>B! zy(yH%|w$fyK)gqv!8&!tEWNZ_y3! zH1psZ(T8P!|TzttV5u4`piHi*#-Da?=oq+fyP%IbCL8CiW0B^|n1jLasZSNK-HnkNhq z*Y;j+#my2_XQF6 zNP_KCN-!PZ3NflmrRaE-p|0NFpd@cprMjz>6j#*z<{zw|%hfFC1)sSWJpEL5%nb`M_N{ zX!fccWuWsVsO){G^2q4aohTm#)I_h_q=I7ffn`0+W z{ujlXvYpi>jcPFvZ8Aig1sJhWH)Z5eGQMI4ze_{!{#4wQrm2!11FuwHQg}TEt8OB{ z@g>oK)fUILx(VL`B!Yc*N$Knww7=yBG~D)#o-1hWK-VhnmR?^o0;?43J6zW-^Bt4 z^L0s87e;eMd0p7M49sa-fd?IG31Ym&43Y9O0H*l2R3)@AhzcD(;f5WOSd7y*9(&&M z!7&&%tDe@G2emu7Zf7<=nJ_0s1U+y6^#cNz!s-~Rm`?1Fg1``5Ktc}NlwuxFt89~$ z+$lLik~S(8|ImicLddY~c}Xg-a5LcsxLy7SR5S*(8UNT5m)+TzS9~(>2jRO6XCZ4> zv1?H(AOL{$t8*HU(0wDr)rFmyr0)Lo6MNxj*-$@BMGiTCpQI**mWgTIS=C3HJOwEA z+;)oIUgBwvx~n6x$I>H1DaA1o!R%Ypq{pgF{PqafWEEM2AK>g&_oQ94fk<3Ja+ zAe{`w%g;VMrL8M($Ph2Pu2k@c#TNV48F<95d~_ydM@v`l{p&Xe#L9~?bL6@^yNK!{ zu=4}1g{gLl%bw71qY4~oHILKqNi#TTIxf}vFh;lB=?-}1uk30ETfn#t>R8F5AAHaH zihTy2rYoM>>%Dj&zFFF(_(fQt67;6%-|~p(uQKy#c#Q9b*c#lJ>=@!TsE}n24`BP` zn9B@RB?IN5dQQEeLWKe4Qg@8ag*Rrn8*DsC9y)jXV&{WMb&IfV*qP{M=VFxfmD`@* zMKm=k*-(*;QMicZsQbS;eIev3?gQ%DKlQ5b*T9f6$lZNC%rU^9s8TQCjeU&z;BB3- z*5DJ+AVAm;C|e17t#{vkBNUyyi{G@8G_0#2_r^5PTaWu>Q%))F$L+T zn>Vk7s#O(V$+2p~e=o!LZp)CgaonddM+43Fm0Djs)%r>-73*WWM5>Jvlr4~Pc8~

t5JL zWz*F*(>gfrz(X4Ll!0o3{Bmg}1Z1C+8Bu=sR|muGuJ~qUMBqP&9|^v>clD{yvvOdU z@q2UdJ35Xzd+694gLJ<_=G?74dgYGkw8hz`xX|$sZoRN@}-T{qJD3_>m zRP1)n!C_T+2SFb3@l)&k`5UMaK}%J^<$`kBzaV zEDkPi{ux|~Xav1`>8AW6S5IYhpFX1*>wc5wp?aJFN0OhGLrU#Ms4~fmi%N4_s*giy zraOF(u12iR^m08TsPkVUVWHQe64zI0g&P8JHmTsa#!aQPw%ShmcsciM{nb~%VQdPf zS%xaLeERA-Nks(9lfCi#V2YmG1gCH4Na?Ca{B2 zZ13yF<#Kd83lk8DtBUOWD7*1i(%pC+n;ML1k|9lHkdcQZaOv7=`XQ`y9D11AanWTa z{gJ1GfB2^>%k2!!#tGkK7a}%{TRy@TKRK}c0$@p08S`nSFHB|yiQbX%W^Y?-bx$?0 z5NgtT%<-2f87xcrrpCsfhNxre(@Lt%L&>!D0qi&^Xfg*q zK4_oq4%7FOF8msW-k5TG+tDh6U}TVkL-i;+jBxzDk6+x|xS;8wNy4GhPnn%o=_60- zM@FgG?n!Q?Em4niAF>>x3Lup{?1f#ccHFH-d&pH(u-?DdAQ{(Q*-WD3(3E?u9Jr00 zna#v8i!VMpdKw?e8$*OE2z^8cWIDzMC;90DYhYmdSf&4bw3u-tJ|iD!wZXJo!*ImO zgO%Wh0@PWn&^{*S%mMG?T%&b2x%)6HRe#>8sY)r{gYRNtgcKq;N|a--`XTMb28GHk zDR$qKgRZYk^%M5p0nACF>Na}q#rDU$W)ba1r$>vlOu2+t zBC8WymMa;m%~a$E{PSP)p!vIVBmX({H=$(^>tXm$g9wI^Kr$bZ&fkY@k)wB8gxcSJ zZ>Mo^zt3A&FK$E3O4x{&xg%|fg}tbWQHoUeK1ErI77WCIE(`J56FabioBW`4NIYTd zu9`)MO0Rt@8-u7y;CzMef|Fu=9JBU-C!1>{x;f;&+ckg8q?JT)wFm^$`{nZBHH7Cl zIjn@3!^n$s-;W!XcPoCXfT1}?veXGF1vBA;)I@e*D7@mc=0U~lTR&W&UxG@tv}Oq7 zqAdsIDqJ!w`scHsx?ukfO_r#5D4lXjHS8YJzg!oo>PEsaV)-Q#$Z{fTrFNY6({Snd z>WkPBr#S-Yi6-yMkJOF9Rco=pP~tF22j`ZuR6`&0;o}TFd8Dv$zY;C8wJzjwfu8Tt z*r6FMZ0$eWyW;a-I;sS~@Y*)FcoYsy$EVUI_vc1ytrbyMvcEws%SiSKkB+Z7y7{x- z<*nGQ9$Vd6*eGD3=x) zc$e9~dAe-i2-weZjV`7*);lKu4;k#5<#uLs`^>AFYmK)H7ES>~wL7$;_kaE$}y{PcUrrO9=a#)1cRJvFI=O&y_L zx_1E>?ADTB)fxj6xRU5Go-=`SQ%w7c)+Yzi9(XB78HL6Q^1*hx(XV0OuRKVo-@^wV zKj~-C<4>JAOMf+EOp0ng)sSg>@9+cM1;@!My2qHgMo>wo??IPIsjq0wemaA?Z8Z&o zrD2PCcfuBC6sPX@#G6kxeTJ54N3nj;DFZjk`91Sbw{5cCyDdNTIsZ#~ z;`XY{|G3<{vV+=@-|gRlpbp%xJvhTfDqpu84Jls@zatvJ?QY8Hi0REj>dl>5<7ALA zm{jGMHTwgl^c2h#zmGrvY8==a*!c@p^O;$EQj=lD;Z?5j7;9p@XQdtl_fk#5W5aJX zkSI;k?wtC$ReuwLvj)pgbw0UPl5PS%-1fb_@@$UGF<#$(vZf%w^!|~WxPUK~deDBx z+iEk)_Q+0- z)93C=k)~wss;3C`dZJ!@$@dBd_MP!t)5l(tN+YMkabRv9O^TVU_;onl$AAPL@iKT+ z7gMc+x(IWFCcZ&60N7L?f~yZZp$q^Z0qk%ev>(i_j?;fC3P|YHc$f$eQ$;EzPw%_Q z0AtxnOXnfFk7X-ygN1q0lcm67^%K^osq?`LSnj>T&NVKb*?lFKV6daw~}E0NMok~OR9Nc)-wBCoZ%-X%4=+kR^DJC zUPZx1m=pW7BkrjA{y~*~imAvO`CvR3)aMKezbOr;^qw%yksC)`@Qw^bvZT=T%%&^6 z{&8c!>)TwFV`TzfYc?;Fuq*!Q+Qy6(5PK%l^|?vKd3(HZ#lt?O=gVgsGtMypa1>Q% zgIf7sS)37Td?xOj-KheZui=;?z`4GooT*>{h9EQi?h*h@k{OtveU~&dN(+`^O$KX& z+yX9|x_;}Fq^=o-NEF!JS=q*aWhl=XwXodRah|`~s8!$wti+&u7v~k9@`45kbB}_I zX2=4UTVr)$j$&x?;T0ErUa&2P5$aVz!e!dr(gASNeTvuX^L&wzZXR#_)x#jB;`)&Z zHGpupw%2vs?&ZE469$)l?Q(xvc`#EHU?e{ucuk=;`sQ1q@vQ4CbJm2ARa7AE*e{XE;O@mpIBzuV|5Ex>CU@6Wbc-WiAv@i@{n`n}sj&1(iT zY>iN}6(4LXRv9mKp(Z|s5gtP|qd!swE7r;YY|oLW>&v83ZwxwxNqxQz>(K;I+uW-IjcHPrxNz{m>DT@0^M7O z@mV>|I84q!+r%z=?9*&Q9=*q_Wn|*U-!0FdF7;_^n8w5U^qqBsq&g{TWpUWNYwPu&k2{Z9GkT>se$CisNYh-h;+PdoUHKVi@<_7*SASM08-zqO873qHWBj{I$Q zC&bhb?15+2!MZ(K_9yTz6@YR43R{8m8L)l#i_`4`koUS6pr`xj zamQ(?7Wo?inQQtednbB;iC$pes&QuDoRPYIL5T+Qv^-Hw8h+j$%Z0KL;s1(|7vX`DGrkeuxL)`g^O; zwb|Rc{gj>%u|w=}gVgwW1fh(f@e_ko_lN}d?h5kT+9Y?8$!z{kGLj*@8zIFo#&}>D zj+ftuJ$F^B*KB|l$=n2r^J^CfADTHErV$DB zl4yo#1GOlOtj7ROFwuf6iXcm2wN3x#AxY6qO3`F37IQk@IUli>->E=QBYxcd0i@y>AT> zZY$y_f76$jcQ*%a4J=~zd9JBLh@kn^|G+_V4lFGxote}8?R4IZ93B;cy!gs>K4L|( z3%`J(A4Tu(BulXNoMY)z>UufYK6T4XZd zvL^@y)}{Vbp2uvFLsoZLB{C_3znyV<4Nc!?iEGeLr~w>fPM}r5W!PdgueJtWd(blo zy?z7w`1JWRgB~af#DAnHPK*rD$Avozc9Qy357llTXU4=xz0<)YF7mFb{T z$+~?W7tlm*k&9=yM?jAwudsoi#&le&L*=@l7$b*VCR93pz}M2@_C%;sBM3mTOrB?< z2@3(;Kd)c1vxt5>rolCNJKr?cnLzHaNr_9Yn;8fAH60+7|IaF`pHT} zY@!f0u--DO_R$QyZBNkcR0eVf4FZN{h_*u$xpd()TeTlDMj3h~1su`EyQcX&$E{|{ zz+d9+Brr6UL!4s+b=(|keg&x(0|IoBR&Xgo&W#56DGOIy=B!R$97^lr?;I&I2>MTu zmDxNHkRJA~c?gC;1tj3oH2d2&;ih@sn`?nevwSpYGMdphFxyV=VRgA7D0`;)i9&>L zEd;T|rW*QYEeTk){0JG(vldz_AKj>Om ztO-u4(8`MoD8ZT$!t_zS>QSN4G+O9%ep8fx=<**N+xDW3=o35Hd?xz& z5R4xU(yJ_<9-SR#xQY7to&ZfPqDXqx1S~L7EKI#m4QuN!pD2%o_NQ|iVl`VZj9NdbG zks_Med`1yJ!39Y%Kqv#Ji;U3#Uh*Qb=xGU&SK-79IN29Q=Cf)AKXM;WQ#fnnV5p7X zN^L2~84>y;cep%X5B?X}KQgA)I&TmzAfs5*5k*p!V+-fO0&%aef6hL-^9pD155XxZi zV*moK1Q|;ON8$mrq-m54m_$74I4q1TRLu#CG7C0~B%=~(u9o}xDZ+=KbeYL6Nt8+=O&|5^o1C<|(1otBXMYf;0y zwDKZQj%!W<&Bz4c!XE?@^iv%|CUE#_Ft&GYLq2vB#1*1k-||;xZ#j4D)nXo!%7ACN zyz&Z(^KLCnq-tcipuiMAi$?hFOBl?VjH~5a0Bnm3@#}8I)OHt6l_HacL)nstC+Wr- z0al4QUQ8BOX9W38T>wegIb3e-O>2qx`|h5Ppxj6G0cPUncsElHwWXt?FjFzwJCL+y z*a)n7gzqqWHHU&q0peV+aVjzf9nA1p)x9Fm-uw8S%*!wRhhFZUQG zvwe4q`Q%vSwl;p!%>>5-uqaxzj95C8T9{Ep-J)rIXqV9&r z`c8Q?1z=B(QUZ9ox@!?O?|MT@{{Z4-UU$jvycWLXqbXo?%HT zUm}V(L+ljLl}ji)DR&i=O&}ph_X{#cu$V8-S?c6u5QV4y%g|0}33wcq51@q{8?c3C z&HPWd%69SL#L)qW0})tcfnN^qi3ggg(=QT9UXX^#2H0kaR67F$2hK1Ax!lh}tc*Ob{XimQavsuuEeb zFp;gWuUe}G$#m$P5w}3hB{RMtz%wWim}UTwB}j6FC8zgFh6o0afT+p7;3&ykaIEeY z_?h3}GYcQ;ynBB87l3LBPynC};+6v#3yYE!h)6Lsfi3VQvL9(f2nu!rFiSM{RV(7` z+lFSLw^~ybbDN?1V8Tjf!)u$JUARauh#iA#12(NJfqfSnL*y9$3q(;-%4*BGML3E@ zgsq@_byf;UbO0)66DWX9EeGs6NNpgf3aTGPSwN=R^d}+}2$ec{g=E(FW(xi{_zmJZ zd$B0sk8{NeISqgrFL^rCk_O$%K!vl}>S7#$2!uokHf_%ugne;e23t|P08^qY+o0wo z4x9m?z@;!mwkCsX$>f^Qxb|$p4hr}_nS-BZ!$x?Uc7Lt>4d$G5%^#N3psPHf#tSMCyeIW<~a(Mn}>XA=tKV@5mpZpW^@Y>m{X>+LV;z*fl8VX% z1Su5%g^Qbo&g=8`f+g?Q0`a%93a%k(6RwMm?_!G{L(PTUq=*U>WHwvH1+7N? z(8&qUv}FvUrZO-Gq_|{h6NJ}=EFN*0BSDaCE;f_{_=kJ^TO@C<{g>d zhxt3i+!8@9!uU6y2!R98y~JPQE6>xJzqb_ZZ-4T$fRf8e0;-rqq5y=F|iA=5)CCwAVeClDgyQD%I1B2`T3e1$(!cHD|0P1^Fl8@KOg${ z@Qwo$DF;lRY}pO`$qYgb-TwRW@qwuun~!|lcOg(I)3N^;`gbnyac_;%`;Q=9tUPRn zniCXEY5w_%5~eHv7U}DxiSHDS;nfYM6(;|0N7t_qjyPyT`C@*j$lSZ*zuI-M*518D zGbrQr{RW4X&nJJg-dyf~G2`>hH?Ve% z?K||pj_&`!0pC}=?#g&Se16xW?b{ps7Qupbai#n}N7pt5^lyWEN^~63J}ucz_8+ne zzmW37eroVPM|WFg!+Y6@z$)AG>95y5Y3e>!_&w;`R0i^4x<35+#jCHH4o41u{(e(*ZyDvADwc`{wzP*N%$9Bo$g9_jkDcQxiw?T|xv3GlQ-0I` z5DWUlAs7uzYmJps^|IJ{%8@yOozlfj&VG)bGF&bxatHm-C89z3 zRR%CAUvuORsJA*m^K~tq+$wdSJHN<{h^JRyI@!{Is&A?A8cHF)JKk_S0Ra42u_fhF zV)sc0H&2an$C%9%W)a>Q%IT*1&!jbxtM^#{AbK_a@O`)zm1S+i09YnxR)7P*gZ6{O znUghVLmVDDyEBV~UHqbEq612eX?IDS3E@NDkRmgO}{JJG=Gj8*c)LMW`_pF zGbgj2bd}UPm#HPiAFWBZbnwa^?WaEKuGjxBc^zIymBeJ0t!Vdy7MteBkFT-rl$$Pi zasT=*yzz5*^67?bMET0Pj$Q*}4RnpiDLB6;C-9jbnV%)79b{PO>Kgk?6|BDt%_sB@ z#;dQjNyn_f+I3@nu^(EGUMuS(Tb-ZjEY1&q5n0HeNj!Q=hA{%1v$^pzGPWP=khG-9iVD8^`*OW8TDjMNSXMNbTclZ;|@vwg# z+5gHws;NQoZoEsL!Q)Efu3t)Pyy$bYd?Ecv{JiYy1mEB6Fa$mkvrBt zy^X2=VI3;okLUi^WYX45H_YQp7$JuR0lr^vJl?{p&H4>94q7H!bNuev?T2C5JSt;Z z+Y4LN__*MTq==~8osQYoHNa7Ge737z`^YP%mA!sUX%v3L@hb2pB(Q+;oP(4hPm9)W zn4>K_l8)Qc599w0U&~2G*W{%@abMi_tX!Z6Trx(`Jmm#&53oxWKaAts`gztag_3%mKyH4ohP zD=OB-W~{EC^tRd8UY1yU{1PA&!r%+_Tz>4I%r&!zAbnwTCB*{!jxaE{qxle~&rZR|{^$3iAj% zS> z65g8dwk%2nrj&r8l3}*SE6rYq8;}QY{pQb%seSnUiGz2q^~PmQ!%RqE4BLiNXFBcL zYGqfvzSF)@Qf<-E311&$nPBr-8ohej?yA6Oz44x(oa)QZH%dtiRrZ-aqY2oXL7^roF~5c(-Z?(n*`>%;OPBCs>y;jj_faZ#7{cDCXY{youHNOd zeCHkxK1%{KoTP1c<>?R_wRp*qb&uU1j8~NSBU3M?8)u+T8s6soOFJ`tgz-BLvfj{^ zVQvWztsd8wM(`ak4B;{wb~4g_3WL6S6LL51HJot~$REU%*zsb>uix3~1>AVE>IMg& z1DrQ~?bc`bav}Qme&njTs@l|Z-K>G5>!y}s2;g2!Kuc81zBtT=82~xSB!BDd*@gm} zMdOe9Lt95;M=`rx49cz@bUmV0Oa=MbRFY74Q1Pxnq>Fo%U%2L%Srfv&gO%XbA$=mz@s z+8rEfKM^*eKN8V9$l;Vm^_Xg%Bq7!zVo*-|H{q9U?y0Ch@oC5Yqhl!8O4l>;C18?Hu-aQSVjtrj`?{MTaF z`_khRmDU1go{1^tW>310vNAIcRGr&dm z5WY6VkPTTbjf{DRuBWQ5dWYehaJIM9uAH*}625k=TFRu3`kFlmC>tW(Q)ml9-+nv5q!!bxdHygg2)lwj{jc^yF3kCxD8R`E$u@s%lzUv*%+LIqrno}hqP zfbWk)+0ZbszHwqGka-Mrm0acNlXX#taz~}4_cA=F`lWeCrp0O^W7I)ykO2^; zZ0i@`!ElxitEO5@*;uzr+n$*aCuJ)mo@eZRkL{Bdw@Y$XIvqT}u)Tx4u2sIaM1fc- z0}Qr66hXu!9f+5LAUcJvCzmSCg9f>2AD-Z=zvDki?U~-1@EE5Xu{w{%Wdr?XxH}LS z8U7>=b5{zkPEYmj*HDVeBc^acBpk*C+eO9<^=-Bs-CV~wbd<5~xFqYS0=Z5BP6O`K zVne{wHfQAz!oDyFD63j35Dcx{b&Iioi?B*Cv7>>7v8Gb2rj+L*Il6xUov~T9g1J5T z`$PjdV8KQ`EyVPQ!?6MSSK2ELRkWW1nf$>2kltO*XqIkGdi91hEwC~}GZat*Ipk45 zx&f8wybPkwfEbB^im1m+@{nwH2rt%@`!An?R#uLE2kX<7-{HyMPxqf=%rEACruTu3>hwmsCiKRubvS1IK!<|dGH0?0NQ zbJMk4sG6=)t`^=xtT!XptT_R-iD_YqpaIn2)s3GdI^jg`65aznP9B$>NhYF7If z;`>LV>>WgBV(&4ecUg_{8LIJt_~TyiBB#hpS%oL`Nj1xkg z{$;3nr1OF(rv{|WU=FQhAOHzOI-`@I14&k>7zfq=Gi%+^>>XUZ-Z=fVxi?kGxZLF* z-FU6VfQD>$Ts6R6`HX&LOb_p$!&BSx9xAY~CgV%6W&c(ZCc=yYE@}5(-=d@vYW$-QRo;ladf?MuU;_=? zF2QK}MZI7cW)Dz|a<93+#GL!6QpVUP(CgS*2}v11*RlESPS{f!E8{ZiCl!8QWR?{? zV(&W58vmr=$mqXg#*JqH6E=$Z1QTUyIKnXW;Oq=2#qD!vH%_Z;0k-KY_L%O{>PbRC z!&IL&TNq{D0_)~Db@z*fYO@NT&1NA>>>JSZNVth62x7yo;u&Sf<7*&*9Cnzf`v1`N z=h09-e&9cTXE6&iX6$1h`zX~=wk(Y$Bx$5Y+QzoMl(df$(l#V( zig=;4jHQyKAr+$e-uLHse&_o=-*dkI8|U2R%<{aC=i{;PXFDS4Iz8u`|h%5&3%S-O{T z3UO%uTCY0l!gkz0FZ>9tS#wvTOHahMQQRkKcXOEtfe=0I`r5}?LUF_yKV*Wg8xUX5 z5q>M!_~jfJHTCo?AZV1G$uBGLj?$efg+XgCsf_#b-wdQg)x2}^<6z@sG@kTO?k+<% z8LaBSl2ir2IvV=B;c2H;LUoa~6wn+L2iI+U-5IGP<3q@aD?_wI*agN+jg~43VJHEr zo*~yFd9YllcehY}jfwoA1@zIyye7ahM5kOTR3JC=20=;8#_Myi4UJm(<7tCIm6ZW@ zr{c#5#V)VBjbm(c)?_;C@_Jz~G4dKH7wqei`j}+%A|Beic_CTOj6FhxU0hY$zD!t0Msw)z|4Wd&ddm!6X%PQ+%~G84?ORWm0JR7t z;ZCK2-cQ1ndk%RyBW>4!BYa4QjWbLs8@qm8C!#L0OSHHRfdEffP4&U+;IUx-{ZMy6 z#<9em^2eFz^qQnG_#Bn3J~2j^q$MC=INc|55q}BlWS9{dT}Q+Xs!lo-d>r3P5;6aW zl7@?6DQ5T6`-dofs4c4|r&X;1H5O}pvzC3(;Z=f0xBL&0f~Z6}H@Hgo_9K}V!Ko>D zig3rJ^1G)ohHs=)XgLY@OxXPPF9J=g=)0w|O9z!HwvrOJr$-(4w#JoQeb3INeCYKZ zJM^^e+b~4|cg~#{wM4kWe{d;cqOwo!8FO5`xqd_v&riv!7NU)bFxGL6$W)n3k>|j@ z&*_6&8941b69!;{wqu>Vt9R}jTW)bt7ougSP&qW>Mgz1~;7i3`0jmF?RsWOl;>_eO ziLky52-}{y5|9idBUvJhlS-&dOHk=yNea;ynk4uNOHPuj5>>xt-9&JStd$Z)SY z+=)`@XnY872_I`pIko3hhF99e7xn%nh z4Sg!=^jA+$W1Sm$biEe4nQxyPp z_kk4)f_Bk+XEOJe3vNrrOBn@!qH4l(BbKEC@q`&s@Q*NH9yGB13!>!?FqeNxlp)3G zxR(4s&|4=QNh5{6J7=I~TQ27N($$*Ya_ba~X=EjtoteE(S6-0e&NtX0bw0Oj^6k>C zL#Qlmmxh~fwuHZ~-LtXje^W`hIc>A4UDLa-?=gr6#1lo=c2(QQjU&5=WPaS_g3qMB zGfHmnRsY()7TLGk%50*~7@Z!vb@&O0N32;mQXhf3xB9JpLAN=5_FsR3=KlG~^XmVO zhXb6wW-kwJiF-ZiLD#iU#n=`qWVjsYR@|6U+mGT`rI$32R=xeCg|jO6cBZtx zb@-pD%CP@Z{AbiU6TgD4p>+outU4@I*4)&0+NfSB5;Z(8#(5)?*-ABQ!d*Oe-Sp5lq zbE`Q0BqB#WOtAEY5=H#$=B%qM-a8Xl9 z#clLgz6P+#b&2bd>j85^#Zkv46IFIh%kw({JjjUgq)OJVPIK*CX8m^gwiPadV819r z$Xi`W)HCmx6p`&t%tfn*o>$0G56x3BE>TNW2qhq9awVQUfi7zcaa+2g=>(^hFp6US z=JmTgItC%$@qCCX2-9jZ+f5}b|9Fjv6o!tC*#t_0zmw1+r3*dbm}vCXZ^aPH!A*(^%SdTW4lYoY9D+S zg8L_FEX1kB$+%f;hEUq6>o zu2zO>L}Y4i&BRz?NbGd^&apF&q-&>(d~o9u@>1TmL|1mLmcO&PEj_cM=FNVS`J{Kp zH(xwH_27%D5^j7mLRWw8ljia1(yKbDGcE4AY12L?6;anSv^DQva+&~h;5C|Te1)(& z-$MiUoP2?}ELV9->4-T3{z1}Sacue;_u@cLd)TG4g|0B2<3ge!Q>})MEK9t2HB2Y9 zw!=g>?e|#6#pKSfq2*EY4^bp#joP9^9%_DLx_ok1+o71>`4?AQ!sM>CXY;Lf$KvXTDgcMMGVIHbKmNVPgfTsJf*5RP|NCl+u2xO}sNp!)ln?yqoYF4BKy zG1^4|F-5zec=aKEQLsrW8QAi!y6AwiM3?8!n71c_>cQVMXN4V(GqC(b0n{g=a61Mw zB)~b|VDKi(>G9PWhnXKg~;6&%iEsERMBSZw6#RgcrJ`=6bzQL$1 z19-$xejMIz+3*V&E-AV+FydzOa%}5Ket%Y_*Tk>g#rdffFLnBhI!0y{2njp`#pb_+ z9!|15&Q*l)rDAr(BoO_@t-Sen`Fi^$*@w-ZsYeF-dS$`;(uD>(zee2E`%~Ozq6c)Y zu*0D(_Pp8_NC;cfPI!IAD8X44q1~w`Cy@}Gkp21Wz|J}Pno@IZhD_OrOx1!VF5v7Q z(kFj6%LYC9&G1&bh7l!2~sjn8E!5+VJ1iGK_>!ThHn#y z2egnropheG@1H_m7A^EfKsOCe7xRo^25uJ4zPXwGxiMlDs1(L^dX@4x)pcj;9G$y) zs4_31lV18}s@)=!0osP{zPR%_s4~OAJpUJ@thww?#?P1cc-H8@iUzUD{c1;c4>$k! zUCta@M^B~UuVUVGI85p7J|_O9rTdq&a$WCC*d_xFH3t!D4c+@}vKX*f%b(w^^gSC@Hx=y4U|^heB_O*M15 zA;f3*YM3ps?g!%^-Nd@yRF62kKBdCaP=lsaW=;88~M3U$19dTI*e!_Eh^!{5SK3}{Vr^ip? zIPnAdZNM8#ZGp>%JO$j#rUdKya8qh%cS%y;M8|Ry+J4YUJ~nDXqmSXXv1Dw`x6Uf% znkhE=@bOSP-ASu!Q;7-oH0~iSw(FzUXUv$DH3~Z>G;@-3Wxm$Q$44zi-+cRg-ECjl zohelW3U9+{ms|XQI+GxNTfgvGJ!thVkTmn@SKQy3(?Kggb=~)LY^g%$$Jd@YD4NQ; z?K`HjBREhgF(o4>>()&ArYYS=fq#O97N{`yAkCLhhz>GI@47tR(n>>hyimxK#tR{j zET&`A`7ya^Xx#Y-)%ybzkf~Uq-b?%7`pC2>16IAVJjw7xdA6fUwcVK4@AdARhsN;!HY{Q;>A5+S z9b*uy)%Eu-uJanh?(l+ti6p{hfk|M=jSNp});{{S%E#`Ho<8sTtG8-_i3XjmYOgv` zwy%8-Cszb%)=`$?LVSXKLmX5p7$lu161cpL7&tIa+xjo4anwkfIgeU;{5dO@NH7y% zE~cZb+A{Kz?QdmDYTGHsacaI(&sFOdbM%P$a5RMmFItmtX8k@@Ja9};*2W{VM&_C& z;nEs)KR`cYF83%Op*@qr9hjHOCz=^3=XpHdDM8u`;cpGVBn2h!1C3lzP9dBJ6I7=Q zH9aa}eCC#GodDzl+l@gjD>5FvUVin2QaL}$h>VtoY9jyU)x6 zq|VEPjc{U{wm>i?+ombOBhOba6T<|_+h|hL7p>>%x6L*Ylptd(j|1_ttc2Woi#rP^ zP{AW?DIGvD0M&<0)~;>TY*3Mrc}c{v*D6opx3#BSS{}=!3IXRq*B$n*V>eVZcx=}w z3=VSBhC}jGR4CL4@3czhuS=Lhg-ywPHDI^Cb@fIz|0?IHrnNp06-={@$>1cdxG;$J zZk-UP+Hqn9jqx*=o(CN3w}VIYn-cl!;=^;YOK95h7=J3}h#zlymz6vTFlc&mK$1z9 zAOpqc(~0Ve2-E?pjC+$zFa;JKfyq6{3lrC+d*r2Kws~N=Oz^VyQLNfGAS?VSyJ=0K zhO&PjW+%x?z8128X8IA4TX{%-!M3UtR3sA>3UK_yndwv&Ju=v7+R+N_Y(O4YS&?#bG{K9sHsqZoD)*Q*#Hrff(|e-8wP-EA;P|7 z4Xp&vxQX`%QAsuzZrKC66!iLMoahlwSS_a^!!W@QO?=2{yvFe)f&Yc`dLc;3!&CZV z#=uvQ^$|oRFmY4r!dqIP5t$Pu;e_r&v)SCrvNFinslcv}6v`;^NneQG*J<0LgincD znry$9w~*jk40ITjWIj4ofKDbg#dMgOQgOUMIP#Xi#VI=zX#nuFBU%JPufWH7jga~WOcb-7Y z8E|96>mxf~#WDFGjGVBPI6)qcLN5W)OoO)kKBV$y05d2KCZV z8Y)zPP}>gZdGK^)UUNvYU+poSkdR<4bcYs3dTbsPi1)!IquhXUmHQimuQ_C1yO!5UkW-c zg&P`q<2VNGe&9}oh|{4}yyl7wfPrlrf4%=4=D;d9WomHUqpVYLJL2i+ZMnKO-yv{Z zcJH1Z878a-!+nssx0w7oU=&0MG7e9jhj7tY8}8NP1HUZtY>H4}yp8t{?o>Z9l(@Am zIc?vi3{E6aV!psRN-Rwa>0n@010~?L@Bt~P;%Dmxs)PG7qkG$#Xm?-t81=f7IUG5*?BegTyw}GERf2L_1k}b6}>s-8O{b! zo|2*Zse1V3%*)oDio7#X!eJ+J7<_mH#y^g>?|f3GsVi04hBb-+sXXs0S@no1lRX)n z;h9pUOxxSv-zL6Cxc8~_mOnCILbLQhgblP$g;*PaPVV%+AH6{#Zo2^F?8H2t6#G|2 zv*lj6q80%e5L68ZL;7D>LzEcfNid%_@%`sdz-j-tRnvWK;FM#V+H2@=Nj}LWKsv{8Xn_VG${9*!%Yx z3i6>884UnHG{I|94o+x4A)A6&Q3i!3qbVwxT7@V>SeQ+2vJE=c1}sceKdwSW^x4HyWso%3stQDjGPW%<#@H|?9vp6kAwz}wl*4cm zs0n03+`J8w6Am$JeJrz1jvozBpukpT0N*LG_Kg=e2a(Voh(BJ96}N!02HbT z?3n@pe%9M}!H5G-b#81_?}pQ?Fc6QZNQMlVAc79SYGLb`pA5rU=@?eX6v|KlQ=owu zBH%SNc{sF@w2C(Lz!=fsDi{!nf!gw*RxN~reu5xCayaVkqa#){nCev4_@^MIPFe5) zUK|OXMQ7GBN}6`4Hx|Ts@Dl8L*CI50B}lDAC6P%|0-gAs|~ z^(T%Q&}mKi$2B7>u<5%St-4R`jdG5Ea4I{bITZfrB2XJIQlf^%uV=r$yqgU~G|7Lz zrQgKyfG|W@?J`=5^nk5tnmN#E#kQ$=X64Dh9ZfDjK(WC%otlA^rbHpkkb;P1My~xD z_0oHmp3trHO>F}SPL&Uaq^pJiYYk6EFKs%0Dys4K%=g*)Q&wMm+~8|!zm&M~+BmVj zK{&-2*6vzVPWz8nLqAsY8n3u^vzd`>-q#XiboYs)eOAoTy%=PAWNmUcrdWb4HtBYr z?b^)azpHze$CTe9$+yCEN9LfV=(d_@r7cWV-M5nWO!+(Qp!(FanwwY5;z%a>-kNbp zDO2}H%au(r`UIsj8)x<0=QB%0>AY^^;(61n^J^OC*LKXC4bQLpGQa-M{08(-s@hL; zlb;sWKP@-9|J=0ir)Ahrt7AW{xj$`+e~#Ulv;COAx$&n;Rm7YH$gU_-2yhY+GGF-mI=b_y$>aj|&7MhMU{(*e~L(&yO< zyOg=f-W&T~={z~Py!h+emsh$ir_ifohz2CM1EHe9Kmz}NiKoV#?(=j!(8v3A>q2v~ zu1lWTaf?sg=lu?~x4p&Zqsy(bbF{ZN+}xju%5@W(eo}uJKRI;kD0-LSwj#=&yDzT) z5;&&${detwEok!U9#3iQVKZv3ZyRFAI!mQ4$J94IYBtz0yY_KxTKuPV(rYW+bsdr47JrtXs|{5*4}0y! z-eLXWq=C2Xm=-T@^UO(PzK8MZe;?x3nojQ8zOpj0(;@oZ)sI~Azc$1=5fql+*uT4| z*Qz<~Cn4qBm1o{|KL)oF!c2WIN-pc?*gH8zu3>&WSJmTuG;3k}bT(zzJ^hRi$|(Zd zFSQ$s?Pgcpc7=WWdfy;ly7DRC)M^j)azQxDMzqDgEl`fyQ9;354tovZGd|Aj_0Ija zX|dqYAHiipy!7OQJtZ0+cD1_RzVfv;NuhQuG~2{YiD5b7)m~*iR^Yq;+{RG1J&uQS z8i-r|RScbx13ZSOs)g&ND3NT%<@oK8jguX?so%>5UsHOwR?`-Ju_*6cVn$+d*zDKm z#Op7Xg5+_xE~!SFvZ^6AT0;igPr@oBrDr6_znJm%QI@lV?a_oXY0O{IE~-wc1a~ z*7cvaC|=n*4^!Da=w=%8TQRp0%kBBriVM1@fBJZi^~Hnqj7^GRmqOn0^QC9ma6mEZ z=7JNVFK*L$Z{MH2qbV-l&0iLV#Ie4g*cFwS`;)(| zZ|Vpa-b**FqhqCB(zz_XT#7zMZJ$j68yCQAUDqNaRUF;Ox4V}#+((-@`k?f~(wUS! z%byc6S8X2BPcAP0^tw+P>%G(E+;(?|{iO)ro|0dJAf8@DN#OPkB4h&2;=y`@N0JxR zf%{Fx))i-Be18umFn_(9c$2ES>|5r@BHy|*9r5-t+~Aw&?@mW)#aV*m;)qh{mW!PQ zT_*L!6$^=oaAZqsQ8ngwMbfltUI^~G!h((O8oB*jb$^vOyESw;=-;}A8c6A|o6)O0 zRsTizZ=ZYE>=@xdTY%#ILYaw7r`({DzRWhtSPN&L{Vm&|gWhY(ZED*DwN2YkEGU*a z-DTyc*&D!7eo6?b=AxcDxms(wq$A$~S+o>P_Zp?M_2bn}FV3wewL)EAHZ1ppOc1G+ z>SJxuf&0=gsB3t_xdC!z{QRQ!8 zuudA$)zCRW)_M$TQ%?n|>22G#ExF)y$&3Hwt`(TZD)(6H1xyHP8!y_lyRe70Us7m= z-?!&X;iVC>Q1`7!_ItSQJPfz~361A*vZ|n7v~>gL&FMokaJA01Ec5KIaz;*f<32^~OlY?Iu=QT(`@a2~$(sqO2N!g{jrbgq4Sal3 zaBfeQUf5oR1dy7`a_uN-x9$t*Kl{kgYngnBHVfgGkDTOF=}1G`6n5v};Qb2Tt*8Uv zvgy)X{X5H#WPWhwZiP{CVV@Z8%qb_W`LxhFWJ?a}*Ie!$kL0@{`<3Ky3OUw#K^h;; zxm&eQ_xuW`ru`ChY!N%<2Z2ub$Polt+2@r{vK3C{gN3fDX6-;YM>2G`W%?0 z2G$m;>@S*LGOQ6#%nx)#+9GmW_8iV6qAAeV{HDXS9zpSri#FVxYa0{5`B~K{#hbOW zE9My7&7&~F`crk}-EysT@%@~K-`<;-WgL1Rh0q+}xo`Pr(cP~i3*qukZZ|7PxcblN z3QE>G<}cijlxnSuMY0aAD}<{h(Ej?Odq($Mt|Qojn>zDL^R0xiAlp`d^$J2qF#_Y! zHdM28_Q>tKbNE7^2E-yVNQbsw{n8s z+~O(Vwy$Fcyr*;RUi-+4=s)PI;ujQsG92eBo*0M$JKbN_110Y!rBX7`D5DSC*e}@I z;P*PqZs}=aW02c4)!n8!BRqUlb&Ax_t*jRRN@5!|d;v_+D4 z%yYZoZ7em*EV*UW`wq|d(&nL3X+U0zuYpFdU%NS{<$1;?@05oUBzaPT+C+W-Gl;~_ zc?PuzGFv`|hMSWyV;Jw1*Q%{N!`KaG>UHN3x_|skS?X(xQtMq%D5{gpW-w!1^XcN2 zE+BIwq|yp^KK8_>WRrynFE{24rERSUz1YPpa^KM0X+c~ph6|6NXSnwOur}y@oYWN36O^+5t_z6Dw{m2s{K%^{vsj_Es0a%XZbIJ zN+U#d0btaJzCzp8D#Z1P4X^zsVD;sr7V(7z_yGy41Hd(kSWqz5)`)1kRjw7p;n0vR zG^t5Ks3$|I_OGN4i3w@dl?aT@Y%Jl|Q z2pj;#*ZvU5#W{zXi0XU@phA=j?3i~mR*N{~5|a<)*a6_UxKYlm1S+Ny;w|^ZWpN)5 zcv&^=yi44-c?uIwMy~IJ?IXdUB7Lj`wXBAHpyahLf!a&Nw;AhvV;Y#usULRMXmWMz z)w8SeI|_g>6{y}&n{{g{M_vp)3CT)jI?wbn`X9yD`8h;r#>*H4wO34)U z3tw?TU*z_F#qy!C7G$s_qvHhCQV3HOqT?hoQUGBj$kGPRwucG2ub!0hp^FJw?)8Mmj+B*V~?c!!6!kx3P|W;D;~AJ$ELz|XuH** zVeUH(^|IY#hnru>a9}uFhu>r4+5AvB3PEQBhOM-MsE*XZ_mp@pT4EaB_dv5 z2*BUgzzbl>Xq1hSR}UF)cETj-`bF+g=?lQ^F;VXJFO)tLkcDmlngX7duLxZ0T~<=1 zUelzao-jG75$amMH@<03&3b)n-f06$&tGvX4pJrSfwy;-0h?&pvdg5) z3EjEa#--TFuYbbN%%=`vZnsm;KcI{dR#pUwYd48E9U^6%Z-*5K@pZ&B*S+D_jrnGy zr5ilXnfGA%VgwpI$+S~_9tM-;BQ6Q5`sgO8Ky^Iap}i#v<)bm7Zm^N3I%IK?)NKy(n;`S_ID~VW3 z;rU}7H?!+t3Lq?qDBGZ)5LROQi77AG?e}KVt)|kElT`!P3ys=WIrfY2vkzzJFGP?L z`pOTsO|3=DpY@4R|OP)0DZ>&n3*PbM){Ag`t-Xn(9fauH-|x zPcJOtdTHk>)ei)Lg1oZ!?6GoNGNzPFMOGK~GHkct7)n3Mil21m>lF7GsXQBN0nG?P zoYt2)c|XPHyS#vX;!{HCp)rT^K@iz_06$1;fT+(V;=OVz)>Z(-p6&{(JPGkSMUs>H zyQvR$nc{vLj`+c$bE<%${(fM5ILeVvft%?vLUF0 zx{5Hcm?v-iy8nK?;sT&zl$;P>Ag^;FjoHE(@4J9nkvTIcH-EGEV`b@eEA!FLQw4ncWwxf9M{4-Da05 z{_dlO4p%Pw{Ss_Uy=xLhg1pbBBOso=O29%aBKa!(u6>HL{KeLU{6{!wl!pZs#H<|`ortw?LWLC060U2&yWj(TM`2`{YqXdr zzYKG4{#V$KKOu`Vx8pcVid2}#?&!gmo6>h9gYPyv#~fN;K5j}}(X_Ux(|CRB8{H&? z{b-nM)h~E7=3E66!;AXlTE+RTx;p~$E4|HSR{Zc>U;C= zz0HT#0l8lUuC>uun%dFbMWgjmzlHcGEX_%6NR^wg#l+q)5+)DI)b+{zST@}8Rje?J zOVuc=f#i$)3%(WOIhB*TkovdN;`VjJeMM`f5@#IS)P`;K*~iZYsr0TsN&=7}dFVld z>ID}ZWALFO9iAxS7WOPVf&9i(A4ytH_*<8z+Ngwqo| zyv~;RSNpHfXHFdJ z-k~a^`L*cw5n8*Q;ey@3V|r;-Z{NbJGZKB6d-tCN(S?RT)sk{$dusJd@@I_xo&RK0skV=;&p@l|$OpQS% zU4wso*j)^)m7uC=7a^<0=$}#uvVJs;aqI)M`=;vjU~YZrcf6fogIq!8){Q!EEjOz3 z+>O48zrH=>=`c>1=8rz461j`pVbb9zcTxZ&kxT(qwsD^D@HH;=?N#$!w7#(X(Z$(7 zXb0sjIvM&g9fVF)o|p$k(^-?}A)Ax0)5YlLf1m5_`bw z$NYJnd56_!Huq+9$3EvtKPmc75hj@f_kR;qh;SXz->+pr9J7E$zAUAo(`Xnz{YVjA z)>pWaS}cvfBS@z90%KnXD86^2#-{)4*+&iNIB%J%x&unhk2I|Q{C%e4LE^V}&#S`- zmmE*6F3$b^bLa9pnxoaG#bL6uXPIU6hqhARFWwg&(mubC5VjibEHgHL`?IEZi)|Xl zG_Zb~Cy0|bJh)nV?y8JZC~51sp>VgEKl<1&_z>~UGoEr?$mme-fu{J+gAdr&cRoBm zxx9SE^}#FMC#KTPyZg%g<^tOt2p-ug-AY%}S%p7pC}!?)4r*65J9vDv zshQK=h8RA#n@E6`Y9YqpwRT?wm4 zPBPb39*Wu)q3lgoxSa0@l)CZ|7Jdbu7pTli)2+t+ZAwGo4?f+@3jQ0W9(M7;y2ke> z{-U*$KfofK%9r18rMhYF%+cDGy0`M!h{L>3YK-+V?Zwcxsgd#y{kS#-?^9%8hpOIv zEE`iZ;zIPW7;9_ajdS*J5BL|fwoF%=(Nmt@x%9>Q(ZYC7O`-SQunWobw8VNrc(-`J zz(NeN)0KhCPZ=bQP*T9jx-3<1m&zAKTD6`<`^yeTDiK_E7b!ix8^01pI;dCpS@+%e zGH3n65o}CT`SKk4%JK7i{a)y@In~;)_^G?RW!FjNn z;`D}%pDyh>XalknmD&L|K1CSh=!f>qx|vS&JWb+;vqQ_y-rbhn7~eNXxtOlJg6=B( zS7oYuMXBbtbd0A&hJJCOAomhnOEBdBEvi{|oS-OVlN|me)~JWRJM31%NNxyG^LC~G z*nQpix(KoUHyK%I^P^{j(ZQ(a|COFS_2Smlnb%H|OUGT8xlZLPOJ6RY_N4q`__%239fC`3KQDx$s(j3^TFo|#ApQfLedNK zFb!uq9Y}^aP!q_Uz{nu}mf-T6f^-)79acggeE6WT#w!mjw5TeBXqpMxeQz%!7vwrp z;L^PpMX$Q1LvKu9agBQ|Xt%^nZb%Xu7!^J2@W=~soMzHs4m3Br@iFsi)I|*V}*dE`>gP&*T@=@BJCxaHcQV)`I<8Qjy{G!uw?p66G#RfSS z0TKEz1L?e|ukEHk02qY@xxjXQR@`HV<65D-+U#8l(3Ny~6W7sJC2(YH31cqxfM8^V|2I9%=x)(jcrV*W6 zO2%-9#@tdh#yYnUQBNj`3Fc@K!u)P!9%2ZgGevc`-8B6qiL$*EQY#q;bqcO(qn-bf zBka59&Lke5(8weK^OM_N;9bSBJ-+y{ZWjOSBAV9FKWtfltVnE=xLKXtwm|@sKh|lW z{ei#zX`54Cyq1Sf`5@Y$#q?!R>E-w{Z5pHwv;jgSQLbp|_bvCtA(9I7UovJn7 zP&dd8}_51bmV##cj+!QV1%v<2;uK-73u1;}sz>P~z zeZqUuJ}7xe{-M2 zSN$7(2OEGm!707XolbcP0t2llG$*84)86W25ju??eY0Jve>y!l!X3WnVBh9kJv5_5 zH3EyOsmJ98oixz-PIb4J#A&^li+fP6Eh+x5E-$eJ(eeiDvA*8V!3V3I!&^1bzMb)R@|uz6n|C!RvBl-sw?&Z)!JQU zXp^;JK1P(_qlX#blU<`jEvDwDtK}YfEqg_&&yu#D1Q_mj<1;|l}j850&@E5yw zwXa>7*pZ<9d`n>5-SphX!yWWo`}X0O@?bLH%-iZ8tZ;hhUF&W8Lbr`V1+AnJg!A^J z9fYXC=v&tkZcb(+1)%M0e=meg+|f)EfPcn?0Jyb`*%cZh!uTvM0iH zX95UPaM*-t(dcj7u5)s-ISIpO?_O+G9}s30`WDE>$yBTR<2p9Ws`sYctk$f4l-wnW z$?-`ER4N@oY9E#y;~DserXko`z#QSrC+X#|=Jl$>W9!(v7OT{u-F36w8*_G@9slse zuYJ>#y4MLJg7zCG%HqUW{A~S2rP7i%Lreft;oX}Q!{S9aoqE)%Q^n-rVnA&b5i)dCYHj9C)QFyXVJ?k)C#I)fiB9KmIGm1k~eCD(Kk zgjf`B02S7R(x|u;P=b`YkVVWoD9~OKE^rAH$ZW7}^?+Q+iy4Z3_lTeb+X0}01^+{soFcf1WG(|lx`>f0P0&A7XYjLj zjbv5}*lYbV`L zpi~iHchjrsi|E7yxMWO~XCf4*$s{SkWNZ5^&35QtBgyu!us;Zg>P6E=cR=5Z(NU#2tB zi6f{`QkEkl0|_O61uxUdJs$>TkD3D-LcUp>_w!CrmdR?V&tlYaVj#ULo!d;|M)Nrg zUX~XTsY(W>FTeb@^0G|?=!g)y(_ zjKfJX<^+A0I>D9$@PkZL1dT&F`M>yfM2a93vaRy6b`X)ulyiH_`*8osPDTJ40<1gV z=Yk(WL6CV!fPz}mJJfx`1<%5Gnkw&+E+d&LOyFB?|3zNsO55`hFKq9N{=ye-^NB!W5aj&Ikp)SW2=gar7TbWRfq7Or5Wn?1V1X&v=i+WNw z=s(I2;&bdhKpdZL_52=6^Gtt}YB_NJ$2*`6(_$+lOYj2>Y@UaMj{ZU`ejFz@f&&R1 zbt+N5w4&+D*opqF<&wH1OWf9~-JW<^gany{DT{^}vJuXqPi^NORUH*@c;P7ZPE8bV z&vRN&&^lYR2;9Nrj4t69=iF0>4zVMg$P(0ydcVP&s*ze_~1syI^WGxRC?H73Ip>Xk=XS_bnue&o%Z<0FOtWy8b}C@2$L!ifjbsUzqV zGWvY;UdYdRGy!#hmf?IKlT)54d~onDSAdG|a?8bP{9Vt|HD+ z>H)qjC!hq9zJmxVixzR9XwQcADX8Nj?z!g6CxoL%zxzRNe(T|-{$(s#3Cx?$O{jg^ zdVjd&4JebsR=9%k9;}H6H%2|)8(PA-n7S_953W{=y8Q|NYV}}gMs34!6m$(Bo=|$6 z!hN^-CIA~4KEcr!fnmh^t*kwxGQ;vVpo3UDqEjtSbcflrcls9I_oyI*dULHf;{oPC zT=?NHdxrjq*kKG*L?`FyA}WdBo}4B?pWv`UP-)o+HyS#Yd}QA82=kn>1)t;T2lE#0 zUBsiu(#R2HpFdIM;pEIP8}x^%kJ8n>1OTwGL8*}d4G{;*z^Cx<<)x8X&SqgLybyj? z4D;TM#cK=$T6~O{njO zj)eAQYAx!nXP{-FZ(;4&=h^nt6))kPB}m{P&{<~Cgi>`x$Cd=6YETeT3i+U=K8Pgo zq}uPv50_uU7ttzHFc=9C;Q=@az))l!>R|cBED=HU)KrFJnH%S`X#?pr^>;20ygCI_6F-C;ft0u;cI#)2G` zSOx&20dfGKD9O~Me~nc|tRa70W5ZUag1JxNNfK1rY;e9~TW}I`4T)7X1Xm=6Qjjn$ zj|gHPYmEo17K(%0AXIFC3(4FVNyH)4wCOue5>))Av(jlSvIIm30V7WkQa`HLuxs-o z*9oSfcsiO0nEG)K&QAAMT#BI}%4n=~0AfEuI30vj0Tc$ljyDa#oyHi}M!~oArlSXE zryj>N0v=dTUg22)&0PFe7Yc{COfmqA+Y16I0GTmUmB-S%;VJz~zaV8ENaA>xvyOaX@u9#y1#t=bE(8)BI;S*k?9WMul%hiKPt zH>|ACaXu`=MJ{w06dnvC1aK*!JOCq8rq7aC=^*O}zzw0ugbP3S%+9_E^sERM9mdR@ z^_ZnVi{m_X|BC>b&RVpJFs#i=XSOE*==Za+PsgXvhKr71W+uE@##APz@18uwmXBnZ zmBfnvamNnN$u>&lVjDNhqUvJcWt}V&%#=I`oNdT3W3bAZG`sjY95?Rg*LM|*s084_ znsE4hD2p}j|7MTZA^vFi@G7KpZ%P(0W;)GZK;vK$h zW>UBjf{1n0h$bC);fD;82xeF^o!-gXO}A6snXOj5Ag_dWe8mZ%u+3;J-F>V%Z|JN| zuYo+Co$zov_to#Hc;?)`9Z9$E$t8560#lM8GIVlpB4sMe{m9(4WiFG1{;d5w*v>8~TnVSk+VE?WKLp0r++9=a)x6a41BI+nFF+dXTMx1}wu z=64*p$Wr4*ep&2I3`n@T$W32d?m0HQeyQ5-_y67dI+kw^FW>sIeEZMx9rRzJ z+TS{pzjv+w-gEz3zwht;u)ht*{x;@6s^tDPJwEv0V|jDq-$xq`#!=BR6y)QbBu_49 zE3lGzt)=y9Sx5@9E$pPH5xR1TdocWD(%grD;=ed;PS@~C@0XRAe^y?hSNqgf`%P9~ zTdxkduMX~8{V!~F=-BEocXgzA_05JSDSo&Nt|LSZBll?(?|>l)Ia zu>1Sw`{lQ&--{j9`j=top09MOWOMO>DSAf zinghU!w*k=@Tg%y@G+~iW1V2wT^RDaWUJ8GAawdp=0e4~ie-`N$4YlF?EYUR^5n#9 zR)pUzIj9Qoj|rXW6v)JaLX3lkA+Ng=4u|Soa%OrsPjsHtZG8S8>ei2i9*^4p;&Vy( zp`7mag^>ctbw}H<8U2vw9buYHzI=;QXdDSLZ?XNV=y|4Rp z4UEK5QqP;|44yJPd-3Cw*TXS;-sBXR+*EKYZ4L;{97|LTJL?r5_U`FDB2BS7QG|bZ z8U5;?%JR&wpyc}71&VKOCz(r_|974K=hkA@Gev8IH-ehfKw(Y0^STRvjGq`qwe-9- zS-kM|nAh4UqR>+9O-W(Mrr@yW?rYym3bS*OU2K|WQ?uA!QeHHb9g}w$&hJ%QKnY2_1_cT_Q`3NsF}*6bL*uOZo=aYeh1!)TWt<0Cm(-m@ufNT71dk9 zDI|3fdBb%_CQJ;iH!@Y={z*IH3EF^Pm3uYM^t{+L^G}vb^_5GZna`})$>$6mVUZng zExuO=J*VpbY4ou9K{`I7TFXk_-Q15h$RjNar&~Yj343GRB6Rs>KF>l|!^0}%a zKc~N@e-$4blVxt8quC3J2m0S0=r}1eI6Hu4B5Uv0WZn{j4ocl;A0inNz~0b8`XH~o zwxg?NZo|cY3sz-Ig~~U-8C2Mqh6@9x?J}dv1U`vsW!#`%_S^By-%%$5|0j?`X;7B@ zhg*`S&#SM`=kx_17t^b-y}mT&$H}fvdfe1@znMuKkIJ$78)cF(4HJ#LJl810$pUW! zGViF)mUr|U`Ym&PF1&KyoC0!OGX}(6?miHUN)tXz_`>Y&71W8db=eU_^0?ohccg5- zNa5hqeY$4())hYr@9$e8sk_w6ykCS}KrKkWp&%^R(r#ObI-J>21ef|rMkc$GBs*9j zJhnq^$5OFm)_zr`+R`h-j`cE8D8%J?SYh81%&1k*-G;Xh_lMn}_-h5xSTLUEmtX8^ zdJs@>kGd5^t(W@*hU^uLn9t|ZbvL#~@Dh4Cd-k6eZyG(h)3b>G%=5y4_^&lJowJog z=mAXwwXR3zvm&_n#Ic>YzO15e^)jb*aEg^%&rjWNQI^ph5br|{>olb@Pnb0iZVRP0kEf%gWJ5#ry$T6Q)AHR9g?VbKETpzzXKz_v~OY1R-QTfC6pMO%B zV0*;L^m1BpJhV0jd3c2$@AK>-eJ#*n#n&98C($lrVW#MN!V)= zzJ?jB!1}-{vCv=bnD*>xV+8)A1kd$6Rj!^deQ*M4wrY1bZhA)k6D2DpDj5^%ZZG3= z6|OH=2PbtYjgtSj0>7dN+r~uW+x+U}miD{6WId{Ista7iBvdr*s=T;jxRHj=iC=#l zcn|Kc6eU( z{QTD^Sb~bx6*J&dL6cs_<)8e~5sPSmc1E5G!MKtQ4`mqoX1;{7raAm_ zV`C^$=M53@mQ-2Q^l2fpAee?wW^W2PaJPaKz^yPYfI<#ICAXa64Sri_hyO5VqdN^6 z`dK5gJLTr^BmBjlqWn6O1;QZbuGVo8&M^hO@;*)#TX%HGF8bK_YEFjIB1ur^uF_0A z8A*xLpM#*sC-zT+d0!fKovj&OuI_MokFKF0K!gsz1U8g)GY}%Y>fi#>M8!7^#X`o<- zj2IuLHc^FlifP}k3;8~LG@ov^2?^3lBV!tH&v{TIDTpj3ImIU)+Ygb81f20g9eB@% zfnx&w+HY9_aw-@O7d^xkw(u3IVWW~)jy(N-#N0^jUZikOWU8m95tE4YXTmhWW+@+F zNN^#$iGff!s+zas{QIE4qL|lAzmFu`xk+*pYt={x8k_F7lk^h~9mtyg{(x-ImCVJTkb19BVxCaFkjL><8&Q1`qDb zgY6;#n8@TeqY&xHVvZCVBj!sCcXdZAKgfEs~0i zi^?FLt|IEwdGI4dm?Rm%uyb3taH5gL@u-wnE6`9*F&!V*L8h0rr@V{=qsq9?k%v3& z)NMR74{jaY@e*qX0B;s^Wmy-5=O6$ZHYcW#G;!$d$oax@j64hjApUtW>shD_8X}ew z=%9}1Xvv_1044RG>QM;~A@Cpy)D%!%8821M$toWBkZVH>OkyETPlTK=Csx{Gb${Rj zpc1MZII9HQvvIet@woR~sBC5>nhzFLsR&P~f6;@K*SvV2F@?8my_X=Za5k&EEwKbZ z+It5&|A71R1ig4LU1}PJ2?$XkLC6%OTQyQ91-S~^EFn}NB!!EtiqyYqgqdU0q?9F+ z$Lo^oF1<3tpG$Y$(PR08iL0T+$hTddPr$blAUZ6R=A>{xS7VB)02RT4rR-IuSS>=N z?p7%%Gu+FCSuQKul%f_ExmYOm0~YWWQUZKpM+8u{f?AMwUdhbJ4GvDxbj4F$w=dh0v1T z6!BAYS6b6H>(UP{RtEse6RrsArD(OGetMo*stXY`z*`-{OyMzyXG+`gpyCUDGq^Z@ z`}&Kl7Jg(S&L6^-&e_dzdP??u--d1Il-gJkm0h;~m1ee-OJ1LndPId@&%V}H0fA8w zADKe&1L*xZ^>2B&gSRo$+>?BDbT5xt%|@DW0Ex&JTgM>@ShV3pGbBMA;Q6zFtQB!uNjdN;UbO#($Y zsM5ZeP~5vVXz!tF1Rfek4cV7)LZMR{YuBvRTROx_uuBw#)6PyFl9i4GjCeZ)a@^tR zn#6tW;dgqVbuv&$Z{p;gaJ4JZ2XKM0xW>rdelx&^m3V$+Kf4HX{3B7{0>fdWK_>p# zwpS7bifDtJok`2DD;I8qwi+`>$rT@zu+G24%NOIQ%c4?^B}D$KI!jll4ZMfyH9&|1 zXUAF#2*^d(-7J)nl3$2;#7yYsp%@1Qgn7ADs|1b@2<8iJ3Ha+vCyJ{dDBFKvWAtF{ zQr%m4pJl>9u-ne3+*iE_0XM>nxG1Eu=dwR@+dQoQaMlRzdJ+Ml3^2;>-2QtJBFqI3 zCf6234$jQyd`&YB&uynYs)LF2i&^5nkbRbt$Y;${uw?je2VtgonCT=2s`OvUBT#`S zY*CTw1X5p-*R+1$#Zo{mpVz%R`-?It)k+5*EU0XY1+7FM)KQaw>fs{ghL#TdWGD24 zj9vk|cc?98)eOIFJ}?w~H@FX#M1;QcE$yY9iL;^xZAu2OwTnK6 zj8tij*t-YBzre21u7RT4PsViOOY|fyKx2#8`Qqlc-L-zwC`WuwkAJHqQIOe&Y9tE3 zT-Fy79eZQf)Fc#YEwJw=#YcHxe~kM`d|BA-Cahy}aVS%0XA=5#miXtK`pzG?m%NkD zxO7NgVrCxXg^%pG1_Wf>%BHpSS~QkKjH80&&TH*FwcQ{rXtuJ?} z4vSuLU;e3dQB|>4PW>b64m9gxc)`SS{n&K?1su$E=}@ zqS_!&g{9$F0XvSf#=X}XBJYrFuI1(i$tfDQ%2H8Ci+E3-G`vJ#6M53` z8`nod*J;Qd`VnuQ8&KARHvUywLlmG~mFK*N_)wAO1YFMd=<6SRZfG#UplhN}m|YPo zbb;cQ@RJ6AaP!1-GjdWI)0fY>0_t4k$?q>dhzvw)Mxdh;d^^w4Xwab^`J?XeZ-I3S zo%+N-77FPG7c#qKIz%^>#D1}`aM-!o2{q`r-jEyStW1hD2k-)|v60fRPstse2^;4< z8KvCrWePQNVZt;>e~2uH{~l0h!D&yl^6xq<)f*kKA{|jy8k%(9v3T@FAZ})D$m-S2 zNj&&Zr7@zNBFTdU;f0OdFgVf9hB5lPS!NgMSUd%a#rH`4A;?iXqKL?Lgv;Iv+d+=L zvV(y^N5LBz(bpf3z8J^8ELM|`dH0N`|Ab?t8ph)0Biz=|FUfKktIo%fu^_n(F2~s6 zAy((dMQWbXDRnQ(_ABmrE+ne?rPJ}`Z~^>Y)F!4bj3C z-jI9=>Y$%RUU&S1swN`he4gUg3GN4>K~&@x)MDbqTj}*jFO(yq^rYn4DP?CwZAH^u z^l?oc7Dr>yEBtgL!qohW5wI%`4Q0;`;=`uN-HzqwzK1+89bYC~g0w!Vt^q9WR`1^> zru~QuYN($LjB9^jV~OjI&2?t0 zM;5<%@{*emk5*WH-{R1bewv}JGEEA5O9|U!Ywk7I6gH1LmZkw67e18_t_~#}tYL9p zLUf6U0&;#g&(_p;>e>j3ijNWHCMT!dQsxQX5?^%|aNoUu_5SaEFh3$%jBR`+7h!}? z$D$Ema6MEPKBe#0wU5YGw-ty8nD=hl)b7M))lhIL=i2AjMYEn{q)e6v#KyX?VNU6i znkj#9^=+@WCr!( zX*?oj2|3z~swKk&NGY@atr#*amR()SaB%zfWqnOUKbm)p&Td+j%NI?H3j~*!P9zhA z@`x~5!X{=HBKSV4goTXf!O6oL1>o^y2nLIMx_#`CBn6^Od~5o^D|S6&+3NMOh^B_A zD=M|(#Am6bYkU4uv0=A=(kZYm#Z8#VoDLT}l6zI-QMYcNv2#Ln8KR89_kT^zXZ47u z91}qr#iPUdNjJ-(ZX$MZZtF|;>a7=VpA@~``mM>ZMMvnvdBqQ&+N1zQ{r%zxyN*BD zxs)TOYL~QjH$?1Yp^6Mv--WF?_s*$69$aUYF0Ri!Z}da6YG`ay!>c`bW&i|8+dzO6 zjIHmHxfMG7_smBSAT^8q`1ZlI{{xWzJU#W^L!m(pf&Fd4AuoF0IC}4#;K%2-D97%{ z6UC*gB^rD31m=pw5QRhn)-)J>(Wike5g}kU(a^Df=fR+}+fem2LdS`xHI5fw7`*Nd ze>+fWaOLUIy9wXd=U(@0?D#L`@6|uo+H60EzGywTdz3_W(K_76Py9Y`g0sJQPxuBG zqPmg^effaz%5Dq9)wx_WZI4BHskiy(MXlzom3--Wv@+da;_T6KKlS%x{@1K?LVyS# zy`QAuXZ^8{kB0mbMC-L3>j`dj(-d<=rZwQiL@PXWi?J)hcqe@ktulJ3y}RCU)mX@t z$-gthvUU2euXjEhU2r!1vO4FlqR4Y;bG%7153kSrJ4U^R*5?AwK*O{eK`|5TeEV;8 zI-2ZN-w4FvhAxl_s5&e|QK+!u5a`(S&dI`)2vMvH-k{!PQghh`%aW}jmJg}Nz3 z2tt%Vq(J~vY`2V6F*n^D0@O4NPb5Y>WRp}YeE z)+P^&(igA<8lX^cTTA}zgz%m@)xo}q{T>dOK>Wci?I|Ujw5sBMrv^*pKjUfTFKA}9cQ1bzhev2=(R^kz`eWm-DsEX6d zi1D2ul}C)k@0U_nTHe9Sq?$|J?L}j^j$b^p7+lCXxZBRZGe(OzMqfP4_{D%i@Me1VK z&W$Ks(ptL0ie{GS{u6K@mTdH5Z4_=C2}rl4WtJcx&mWr*F3?<7w7=+muX`guNTwr; zPrM|^pVJM6cI`5W2ILdd@*a3FW}=W>h+D!pMb$Ajytq@&dFA@ix&cAw=C6e(sG2g)hyBbr<3)<$s#Z?-rlNS9 z^Zpc&tL$|>6s4aZmc3BDX{rYKQ~L1Ya%}vOYG+I1fWkQDg6w34odDpozuxmI3`0(n zUYS{`oRm7sn zm_AkkDS1&v=4W=p@)nq7Z{K%iRQ$@33oOgP*XC!MVe<3D_hthk`HBQq&;3g`JiSyh zQ-R}0t0^l^$Dw(tawWl6gj{blUHlJ{kygm2kuo-6|9DOMp+4sv(+P*9MWa()j#=gt z{@AEkmHZjtp{g5e>fLeg7TI97&|;gMOKd1fXM2Q{&Onp@+RF&<#Ur3>!Hw+!sUEX0 zMY8;*^I=ST`bY97r`;Ka36ZVcpB%HyM*ZjSSg9O-j(5VM+tP%(2-h}Y3Fa$TKupU1GJgNuB;@(5=!OC?v1QTpo zFFoSBzm6@DHtoRCCg=46hsas{6 zf2>)+yon0eVWdr*t_IB^6|Ls#`RG4ubjdp{3F^vvImR3SCQ(t-pXNS|)nW^t3ewWB z+bFbrs66sEZr#4T#-=Z8KoIy+dZ6vWZD)mo2ysFA*YUq~PALgzB-6zz zDHbX}A_YYnoS+j5zhCQdVdjCdc6?32p?sZRN=_D{pX@8yDQksAhjIWC$5*uCU5M3utX+vhEM<+)JeUy&U4+8>pv_CM=i zi_?(T*s$XM^!8)lBx>#m=Xc?|F0o!<(PIH=QFinWohs-wq z{u)`lWd=U;>Zm#~>u{vnp;3R?O=w$df*6`kSB6|kdbTBfvuv82&6UsD0lx zQoyo;E=Pud4mV+ZbI)!};{^LMU2g}~z>y=s%)VMlW-u!>y~o-4WF;KQIuP0KlZI$J zpLJSO&~ZA$GxGXjRvif0?dvrobLk42VD|xw*WR<>8W9 z(1tPlo!jt*wucQeVeklKJ4ji!l_26x87i(QOE*C;Q(MwXnk1*Tzk?>%?+~&}&TNQw zr8C`XI(ulWJ~bYd^VR-lu(^G&pxrk{ECu0kci?PrR@^i^kd)~{6mSIoMbV|W0Mvyh zyP-X;*&EPBGnryH38yKy!6YZTJ*JWW9lmkg?Ln(A+ltU)=Z;9(&T@$Dis5JkW(&$h zmH{q+n}}4P<<3A=Im5%lJs)YLW)&AxyRYZ58@Gq=x#XLYtxvAN&v2w1930M4vb3); z0ScqrrSo>`mgL)@-Gc06Ftp2v~^9bnM?XI9#8 zMEq7(93>0P(uNWl`zz95Od2?_o4hz$;9K^*`2vmy%=gyZn6{30$BTHztG!{d74n8ZPWIWM4zE$_1zT zSt0#j5U|zlwUQYMBB)2QVn?sAzX=}dy)EP745#dYSBMGw(o$Iv7m$+TW}9;9a)9PP zMd@_5WXIzhk$3oV(*g%~iTjZhM|v-w;Nm7@Go)RfJdZ6(UCllN6iIYBpcC|>*H_f=2ygn=ZPczz< z8Ah~lN`Q~h7@<*&?-w#XfDB(E-QU6e@9$hB3z9<=KndnFEeNDfXIx+lhRq-^xN*wn zGWIkxjA@m!{givnG@+y8g&Z}7Y(W$}2v}6IFqk9*$&q;H9>!pGgTm#gG7L zF48G}A32BiS%7hZoe9EpC$r^BZ;xLXLs8@5(0Y;Qs-9herEGgx4*=z*~yg00LTp= zCc{BaGn$#z%*xvT2N5w%3}wR02g@i(aYD%R8zh?d6Pf@s?TbT8berlqCPMTVBb;O$ z+R}C5gW#&ti{nc#?wNv01Ixf{cywe|A{`MO-*}p$@_q*=pXyzE=~pg+3g3<5f%qj5s}{l}yu(rf43@ zueB@iDkC(F5tf~~pO)2fLFcL3L}4bw1E4ALP!Y;mVZk;0RL!cTF^23J_(=jh3Yj$% zYxnBtzSalO;L)^Ory1eRsxiIrFw!pkCCTp&yH4`lqmRFRb-K-!S1N#f2C}j-zCPu< zO6MJSb?tPBVovk4y<}VgrR-w>lNOp?a+Z{}Z0qsgp2`!ZrAJp7(I61(d+cW^r=0=> z?xO{)FwcTK8H#(s3|@_gs}KcDK*#;DeS#!OfHt*<#|SfhIl6TqB>&$di4{z&>`cxUcEAUJSTK#EtoD>6&Kn=8{j=enm8Lj>fVBmr&)%o=ej zo1t}%LE%B9;?slxK*a@-b7Efo2h#lYJ${9R6O31yivQuT;*108wP+|dL=*rZri-Zn4V4X1!V3hl1&?ULz|Oh4X*y_aLeLPH;1>LEcu1o|#6Xr3duE*cN0$;lV_Pvk= z8nPnoaQ6xDr}>SmiH<@=@H7z$-L;7hYA?0fX;4kMy)KC8oeR_^M&lzIq9RQxn;s?! zBa$S+P`dyzO^5*aNTzFoBFX7&6&ejPO>^H`j>Ina{{n!>v?NfINv3O>LZRG;a6I5p z0NF`^@-w`l>SVe`1rP#H-&ysJ_JS->muBMvEvQ)8nVkl5mC(pwpe@ayVg*D*Q=6e$ z72whU06yvPmEgh`?1)}Qxpiy36ikH80rq(ePwY zLg@mnP=Jb7&_HRW;L1O`H3z$@#12qcOba7r%`~ot1Uycy$S~bT)Ug?=RJsypwOk#7 z9|bV+v{WFi<1ZrJ398)&30a1mq8YlTgb`J+gzSvt%h}OD7D%wN-ey<8AviF%y#nBA z^djqz25pSfq|6g-r@T{6osS7S{)m2kcopo7-NdE|tpEktA#a{S`KPld-9>X>c-w$~ zoI5%6e8LBHDpZsPzF2NCz+n( zO|RHX-|;f^?q7u7N@h4M%5_h)nqQj=0^#dEs^1LdtB-!vG+n8{(zTd^U~K&7@2o{k zRum9SGPyc)My(Z^b$TmPe-x@(5uKrve$uo-rS>Z*p0pT=DZKpE41suLoE6;+E-ye; zHPeH$V;;G@jbev8MSQa?+;I309m9hMu^F+f7;{C04ED_T!^b{$hl?KmK2!b1JN0}2 z?qe_3vs=Q|3wYm-_}F~t`0jA>_=lg-{OYd|_8fVKwD5_uIWix5^GC>kPGKWI zZkRqljkAkDY(~Bp$`?6nvo@AG`YGCH^UTT3xU-vQvo_<)HxsUGCiZM5jcg{r+)R1D zd2Vwv6|qH=+Dg;dqMK}`N2nfi-l9XkXL>LhXSYsdo4A$H8P3f3XcQub%dqW@k1qOJ zpdodlO@OJ95Zd$f5G6WOV}hcSU?##S%i69e->$r}UDX2;pxf0iw=ccluG!qKMf_w* z{jAgYdD-M=z4On8TCq}}pG{|fUO}LmHh=uzHqQTV@LL@mB)tM2|G$t-`z#pR#W0f0 zN=pUwv0LvKy{;c-GnB%9pbvF{Z%+S5-K`gUBIX~K+FvOEbJ!d6Q7sRnpdv4-%sh&3^y={<1N+x%`ga@=w#bcHx7KxOI~Yi2aWi%4x~~Y$O?@;nk5S zsKUsrG-%hjvhSLAe&ghdKffUC@%HX(>tA2i zKb#iHF#+y_O|(@_3xEQG3!6E zDhQ?81S1*!Mk7!#>75(z={8+WC@^h*^5UsQ?0C#Y>t8%|O2h=Fw9uyOx0ghk&5IBX zJE@j-jM+M;Q6xV{iW;OZcO};17GE-#rH*Za7S&Uv(RRZJ3gY`IAr%o=YD+lyDwANQY^vbntOb9Ep6fk9@k_$Csr&30GW zYq7ETy*$rw^?9L2lqU3)R>w3wf;5OUaDUW~T+lBy)Gb*m)4nC4Xc4#?_^kGF_iJ3_ zpJuO(@rO%PH?4ld&U|y;^xzGO$!gOs8wa=;oXCvtFw{N|g}IZCms@o|*8cBzodJh+ zq0UG)VV-CQIVg=C#&so1ZpVJgtaMqjRf8Yvvr@o9$?EH27 z_R>92rn+2qUf%ujAYRP-_0c#nu{{AV9C1Z1uimU%Z^l~y@6Nrv!SUZabo`+Xn`rRF z+i^fo)-BJ{*W#y zbXVa$LG4aZwSerKEvHlS^U8N576X1wzdH)nuZ6lkXCN!-TK6aWPErD7-x*v+Q1%0-{Zn%9VzF7{cXx`I@T;4~4+Ogdv#1C(6j-8(@8&{gXXBQZnmRNOr5a8 zSKoq&SQYJ~UmOT;d3;l{=731iKm1THhc06%c5ymGUn6U@kgI&@aXceuR8M=Oe^BT4 z+-_EMXF;lOv*z4ysM(BEQ7R3R(+$8wR3D0B9u8NnO)r{r{0kyMt>epPhT%hHv@L6{ zJaraE6tG3wxS z`7A5s0emj8+0Gf_TG}EmU78zq_>~?mF;-HMzlDovh`FVMg_nkWdcCGhMyRgOD~=Qg zf4HnB7Q>$|D}Or;2ThOY|GLox{)(WEavgl&@0W6h)w=HXj;vv9sR$kIsFdk={p~?s z(wqwdvlK5IJ7s^^5L&q}HXRqwBHnU-?SjRAkeEL9(n$KZsM(NGLFA&b?DK3V1EwCD zdTMX4$T!EGKWU6wg&sE2xXoXr4`B<6*Y{!^+t!T!J3&sD;n?|DS%%>X6XW+2{|c{t z^A|eL@;M@$4RcG2LI)k0c6gJ$vHQONvn1~Tup$H3r-Oq)66xHYhD_b?I+O*=A5A3< zQZd)z>euQpPfoX~WV?gK+J-dAK3p+hQH0M3SYpAUk}qfCRtD2^Oodh)#Te7RaHIPoxP{8X z^L8O#)@%Oo1D9Xz)tt`Q5x!A+B0fT`bMN^}5szP=_~!GnUDHuB@3y-~tcG|=iDUck zi)MaXrjomVkEj+4AsxP!U@;2HQ2RlBfAS5bv2vD1$f(Yb@U$`xU9%d=zcVetq6(v~jw%zrkv-GrGQ*S0b+avav z+TkzQM$0x_M|m_1NDdHX?{}rx#Bh8SBs*lglPARv92HoC=OTe*vaZsIq*|Nx`1P=q zu;aW+$rfIQx;g~qM0ze#fY-Fm@x7_ID@uH9RzT?$TTp{T77)>dUcR^s=^T8Sx#f29 z4|O{4ZELze(dON`uF{6H;*d`ver!i?o%4s0gFz9D?>6)KlOYcEHU*;D>*-m-NRI;8Q5QMy@$J}5?g>Orsc#a<;PI#>ER?km zg-(V05Csc+AkwxX2a6wEx=k|x3dgjtCQ8U(?CP+2MP46>prS{sh>kq}#>DcYpbcLeYJOvjC~GOOFA zb&(PTPS(L-ffgS5@?7|-A<<6flV9Va5+%|0WoIk-EM&@sBd6IOzZ+6Q*@C;dFnt;~rmt4w{yQ{1v$0Kh{; zqT&QafFTz=f(azK;IYJ9B^Gj{Q*(ri)`)TqG6G?Th+k^xWOd>CHdGN0Zb^ojabcE} z0wX5OkeUhdp8pEUoC1(66eSgY@+}ml6h4~H{8<4DB_fj8$OGk0RVQs{IFevNU9CdV zXOJ}KEv|UW^dnKAYXRWn3k8ZGW4?G$@hQ<3x7>zqr)V8`?i6H{^d$}x{{w9@l5KB_ z0(oWecmP2L3=@FQ!4Ok^2t>NA1WZd?Z-bF+h^$$z2p;N940$Rhe0R{QX~Ryh?xC2VE=Z~$JZW|&YQ{9Mos(a{ z6%Yn;v8)oyu@dr3`MI2ubJJO}ZGa)*esd*lYhLpS5%ZF2zSM>th3)*w#EExEiO?;aQ#BDji5mpSh-zvfwGlLH}ose((0{x>briqOz!6OuCfL}#<(sudX znevalkd$c%7_;``!N;4Bqi4@Z1R4BDKd?%&-{4^*0~IYHhq{$D8zk)B6JZFp3abU5 zb{m4>v!Nw`RX+yO9(1`&R1g zbc`PjQa=q~@rB#lm!WguLjg^7Fqdg6lOoi|wRlYdGvPaeJaPO;DF?R(T(QZ85To1x z9FHiN7+(j%v7%%E3{v%d)z|SMsaIxm+Wh|967GmR1^PqD_xMz!nsw}iQAcEfHYVoMW#`R2%+*LT})hLCRU80 zdNEr)=p^-wk#1Bj*z+crNpP}sf0pp^WoBl0)3GMAnG#WAt`S?Xl7`+)$409-a}8DQ zv`dNWgM($cv-@x*%;tUOfB^-iX<+jPc6K!(e@9Dz=~>}FS6cjlguoA3p)zIE7JSM~ z(G78o;B93-Me5C>Skr_$tzG+0@t(x?YXecZ4d6N=su0vMUVx$3y?1z*VpPl#WFO z$o4`K{f$*Z=%yLwl?h@N3cuP>B$zBzbd;E{nu9q#lWsQb2YQC%M^IH%xICw1YmCrv zwFIPZIylkuFENWW^KO4S%crzn|Io3x8|k5?VxosOc{UzlS3yS16Q6Cef<84QLlTGy zuPk043wZi4iOz(<$=&eRDv}%soC0eh8tc4pddHLeNE5r1p*}lBqI!!5i`ofnh~-UQ zlmFGjXG7pbfdRXl<4n<=`D4fne5-Z!8RG_0bC&=f$ST_9{# zFR6S=Z7MSCxJt&F1~r;A>h?9fCLDm@uOjE@)*z&X z|HeJ|mCKe)0CwY#fEmK}rVf)h(Y{RiU4|}s6sV!>e~8N^SPnFWa;Cl4xCh)Yr(-Wc z*`BUFPIYWy%VAk#97Gj|O)ioof?%1Uj%rxv`zk5WY=Os&aQr|xcsB(i&ul7{eLxHo zz%Qq9A(E>5NIn-xHT-DPGh*WP-*6UkW3t18Ux+v}2#&`bHXVatL5(0)cu>-ZaNVn? z2fdmU`}>MK`!<9k_rQDyG=S{B@4)EDaT!yXb)-_e{7dt=N2JmtV?lCcv#7DpYfkBX_#AAia&4nRs$$cpqd$tzqq$++H?n#K8uuVs?E5Jnr}Ss1uL8O}cwL)t=!f)Y zl*@OFFIMweaDzt=RZrcPkcNhmL&}U@741Y1dzzEll?}SggTLT<2XO8`u@7d!Jo>XU zrC38XF-^<`!#lZEZ5G;_nsFK#8tb{d;du~?Qd3+Rhj*Mi_OI%dRa5q5>-Fg^wR3q~VES`%z zt*y07Y${-*ZfB8!xZphtJxlB$?hD1|Jy`ncq(*18$N zYp-%JkO-?sKC}p18Fr z4@kK8=KIjpkL7ZBh(2wm3P6Fq@0{#0J@nCP#-{j%CxFajCwE>qQ<~Fk(o>Fv zzl!L`uFZzaL%V`iw=79PF_+;@>FwG7aAt zByaz?8K#3M+ky)$L&D#_MO_4(iSDOU9NeGkSKm{cLW+6a5R3mbigm?t$Y_0gV}WwB z5X-B4ZWDrao8n;g+vlHfoe3bFM?I2wg5QLzE6y$MCcm%ce(0tg)vK>i+o&Tgdrr+8 zBZOHRBow_nhbNffEn1!^5Frnf%*xY+JJ_)Z3^JaKh$SMu*dr;v zYvzw&c7`sP2a5p#qd(+1AxcY=(J#04qHWsOreb0@RD@TI)+u`HOHUz+WWbZCRW~0s_Ub{|2z9Te^=9G?2dZ!IfjE; z*`cH{hyo8{_ZjjEy#W_lw@6r5r=VDS(R=xak6p9q!=lnOZu@SPM&2k{*oJ3t()>Et z$_&(q%B!&2clKf0<5r1JiCTA?TT4Z&r$97d`Ax}X3q#xhYF|^ewVH(5#d4(!~A#ZYIXA{uT(@A^^~vKPR(;?fn=T% zjObtGGI2ntk$DIKfTszl4iRR<7W9o2bY{YIsL+Je_3%|l_)kczBH+6Z8cH!W^2fer z28`0taaWT3WrSL$09o>vgZvh64oJN^)PnE-s#>#e+Eb%<6zXdqo!R$QA@kA%jhv`) zl+ot4R0C*};az0RBFmN6g5IaJg&CA z=+t_s`}CXpMHW{I-dH4jUz?j8`Rr$N<1cqSw;@|ZgS6`ih*^5KK155)`9^i`J$5&q zH+%2AMudV@;@5Aj3sCN2mO`kz)$1SO$E>b_0OsJG!eeHqCaRAHb>~$$dyte*u>rB= zLleP{yGZ^{_%AwE+(?1%e5$!OI%VIS-p^Rqlj=jD;YkJhP+0%ofQ z4;<1bp11a>#@gI+5r9_{Rz=$8TBFkf#r9gyxJuS0LYyl6!vmHpgNyG3T|9kv zyQw;6A_P%$RpHU9>eBCiXAvFmW-4S=X0gbSE{+eBiM%_Bs7;(b=q!IGJ00v*Pao7! zxWCeO#rk^hKu7K3&oM+zWLu^Bp!>^R?WSBU>#YVj{;#Z)?knkJ-vy3?~9`SU%@xoix6U*&=AhU`8s z%PW@>6b9elPx;Xw@%-HH1c?{tyq|0AN`CPHelhH7ixb%ZOQt+QPj~HaHNnJ#O>AV2 zLy54#ET^1mJ+#Lmr1>^u$CXh%=Sz~;+>C}(fBP5ID8hl$>BnC>q9#R^QR-FU#j{OS zM{i2+mpj948QGWmSCH^x(buT(K+0Nro?_zT55q&DP1_CvhPy-0`^G&JZKWftr|WS} ztKS?nYEI3lY5Jc!4Cja>{mPe{d(r=~Z}iK>=d}R>Vr%nfUjMuzV1F*8sVY&o4@n8h zaLV#ah5bEyJN>ggp*CswVl)3zgv@<-rK02tOS?pTN;;sz*q6*O4W&2SqI^-6ZVt&2 zidt&y-frTA|91v`yLD?@3MbM_QC&O!dY)Q%tRSJO@&wa%*rT_$Zuz3-hX0+A^hU;7 zd(vv%$s5^Rr7LqGi_>hnzq6QStBJN|zmTQ(`HT{#^WU*R8+!-09q;as?VOK*F( zc1KUuoa_+M`0jRZxL(SiDIIjkpZ$P~5Arhp2#aptN}vuxwYY~$9n z!nCrD*|5@bWmFc=`Tm|io`0X~@=v`k#UIJ=g*^X~$YggcIkLz7e1Qi&c|$Z=Oa zOVgbu`8W>F7w)6?n7{1g7Bnv;#!$;qWVi zrrUkZ`cqolT>niFtvHkFw?uu`H>F;y-x(4fPI#}IsmC6E|H);EH?U4{rYNmEvIz5a z^O}aqf;dv2h7*~Bbcc0pZZ$SdxX;pArkK^eKW~nb$A4V>>C?6YX zta>_XsF66Y6jq+L<&G%F>garZ?EWmhzM+k&V2HPIeOAu4o~fQwU5Zirdo^@Qph7Zv zWK=p|E2D{7cjs<;q`F77id9ZGM|-}ByO>m3fKqL8bkTf0C1@Ibry8ZCxD!xnSl^Ok zx#C%Hrrk*I%k+t#(_KYr%nL=&cnJHN(MN%Ay4Bk!ymYi^5HVi$fWB)k+nEk%O+aw^ zWxLGj9{DeRoF^G7m*-~0HYZ01J=7MN0L6#H7lh36IdEo!G9`0TR#Md99=w$plDa4R5x$Cg2VEQv=! zVvhtrGE_Cy2?fsyNlWc}<1MG()9lk02NO^7!lpZ8LX_87Z&%xPKsQu`i+~hldK#(M ziG0mBvhpL#6*YO)kxrGtMFec4#x3djq{#5R0EW9tnK;{2M29wLRaCtRp~3%gknTE< zRsMYSB{e-6G(ymd?nVw6+vOKONbS27|5*g2l6S|_VOrMMLAL|2 zzt=|+Zi)9Krn%bA3sbqJh z6h2#Fyj;+8*vVwEjEU?NazC{rx<_lCo)*kg^Q}{KWulmj-stJd4C0Lz;^La_@S;R< z1MY})!i>qw&s=My1%)E4HcsxLf@@qv_S6Trv<~$WB;f*+h4~UaO1zFp5oKMTmAmX( zJ+oHz+OrM*kDXbTC$*WVCa&kvt|4i*uFek+_EY;0FK5aVKpwPA=x`HO741irWT}?>hOY`SU z$W9TOPR`Pr?2OsdPIz{xky+3(a(8<>J%$ToRlI_4Qd(;GrxOH(e&yhIwdPW4;wDE|XX z3RPNt3h}fyqg&Fo706Ub?Z-fsc#>1|FrWq!|n)62Iq_fP5PupKvTHCbV$1Ni^hJq^@8oaXC( zoZ}=8-qr~PU5u!&9-{2PJK71Z--g%gC>P>UFz@{A=s(Dp3VGpDZiCqMh;KtO6`k&g zK0HU7v_n7Ho7MBn@omuEgQ3VYpetGc*8{Un+q-mjh!6>s%IWo#RshRq&V7aXbmnqf zb6o2SGo@vjf_AW1%u`w4LCHnMWo7Q*LTcnM?=4-m!bu24Y#)TcGj3_`)P=w58h7%j z5Z$#usv^UJ1Rdet$L_L{&kgI{IAw&A%uY@j(AAXh{%x;IiXj;Oj7Xi(xGBgtYgv^@ z;RJU=kj?9DU4$E4+V$Ik4-I(F-*V^kFxN*#WmWB&&73ky$$KYmx%kY6SIquZ>}V8X z52YYAuEaFOEwz&qJ(m;Akkh9zspY-ljlJnDOiUFUU7ekoQMvesTjqpTazZD@-J|~I z?x*D*<#og20V5$?w-MgQLNrM#;zALaf}G8CIRm`M9^)SRepdw^@L|VUc|T+474CY2 zwu(6p7{Dw|LzXiYe=jl-5*BS5t{rwYf1)s+&xyq&Ru<&Ez?^t{+pm#66=Yr6n(g)< zZ{qz|xM7ZHI*}6-jQ;77yH~y+_8c6E&DmGQiJZ;}>*U4pIjg%!TAljtgQu6E*D^&pWf^*}9MQ(Vk#Bs_n4mrco<*a=!^t@=H&AhelK41| zc4N*Kx}3)#1WmRy`r|85?G)(rV@Rx=jn^X;t4}(1?{>_MlyW z46LKV-Gs2RHh5f>{hKO8obam6OA(a{^juhPtWw)?+YwFc!B8tRiE>Z*C!aayHrYGd z)|$qxaL|kb4Mn3r6PP&S!>{};GZIbQY~z9Lc$1#2OyQa+#hh|d^^1v3uLT^p_}tm| zPDDkBzatno&G{zI&xk`Fs4_}!K0(e!%o}F|QXu=cB_&XSEn&i>NVp>!D@9tYDO8Hq zSn~_%ot0fS{V0>rrdZw{-~2G&x$jv)w;~OYsq^5C0z_IB^6q)A#&3i{ABTI$FQ$_d zh=N=XI)$0DKQVY0OR+#xAkRH=o85D#4LJ!z7cMWHwEV+8o_(_*3li#5gZ)iB6Esc2?KykpMXVrP=G z{rnusyNq8}S=;W@9Nrj&107ocI;xWc#*H6`oIFc-9G|fUv`B_CIB5`fL89Q;k|juM zkwUV{1S+04MZ6u}zFBRuCo?C5T)dhWnP8YTzmAg;3i>X=Gr22J9;?59%ht|kkt)7DED9v(e3Aq z+%vCx;-)J`LhE9Lu<_v+`3B=~3B*at{Uj`Vh7XI6AIBduE}u|~r@h4SnGOJAKcAag zWpli%;;>RkWfY<>ye<|mXXE$eUNoPv>rR(zZcO#bUJU0Yy1b0f*|md{ZtLQrig$)>N`HFmiOs=dCN@GAN|pN|eJtro6x$sM8VK$Y$m zHo*!ACHsin1EGXO5hCC+XBfc8(sW|Ua9lIg$gV{nTb->26^vr_b+ zn7Z*)*|v3qsOnw>zYNKNl*!@{{k;VZ(>XW>^VcqojZV3sCs0+&T1(yt1lg1ea+DBb zr)_gajkiKU6DS3777TNzat{&L+^*RLm}^a`A!^F@C|tpkj=lM9!?u}*l@r!&k#Ym4 zFK=dKQ$u|Pmq!5sEH0E|M3+mR<}@`GES`K_b%xXX3t7N_5I#AXkA9X3_R{bWnVu9m ze-Z6PmUAa(7ni`l3AmY5uT#SSAYtzXO`934glWWn9x|6&cf6x$WZ97txP)hq6zqo}F0)4q8{HIwE9t6!cIO`jCLT?#)Q1C(X2R{P?$5bnf)z<3YvH1evPxJ@>2dtp`u^=0{-Y2jT*IEr~10c20J z;=x$*`pGzQUZfz$fy{zX%CPvecq71&cdt4IzhQ-I6Pgd0#nywco8+|Ch5U5=0FJ1r4Z^-v0%!D>=$3lL0)HZ7X2g z(vmEREaV)ZG@KnLJO`RUXPzc~B_a0+;yzY5D^Ejh=Abq_R`G5?iON(RWTVMU^kDMJ zS*V2+WO;$_Gq4QiQwC`U7RwK4%vnu*b&Zs~de~7-3)uu!#TP`L`V+yGM}g2NHFAaUOb_$=*hY|E=` z8F3Ck5txn?r0SLwQt|1-YukT^F;yJ13`C0tbkJ)Gfzkmak9lo9)M9XvM1WcWP!tn@ zN!X5u(;Qc0Qmc$kgr3`5@W45l?Xm^xvH_+nB>M8^Y`K2Q<>0q}rEhJ4hP<@U}V2WoEMG&MaqNLl#9xN6x#m_Brj ziOygWtI}P3pjL4(1Nx=Z4L`rqeu8%v!NjJ?NB}X&gk~&To=BIuTm{isW_$0!BwV^x zGn;P}okn=Ux>xknKc|dsXcptXi zG@|%_Hcx~(7xtqS+}*x^{O&oRAa#1C`0DJW%?a-Zq5Gdm9$ z6|;>Q$BgMv8xr_>?RG)-SCScpbNreqkSkq6Fy=U`RbiiF+0RZK+U+}T<6=6&-r})VwfmdTmMSpuh!vyt)ag6e*Q$KM>cEr z_9p(e|B_h)+k|!TPx~^_s!*2ncX`ds^P2~YO=kZbjDOS3)rKeSB+tLUzei7YXT@ph z)&pOkt4X^K#D95sHEqv&-9ta;hOT{5Pd@IL_~p~Hw&d^sT#t@xz8m}GdT;%|mES+h z+C{PrOo+TAkpbRe*EzpW>C}*|ASow`+UUtZ!2({Q?AdU1-qYpP{c9JW zU8N(nq}R`UXifO=;=%CsWQz?&$zETKZd@)D_@46XYdA3cY!h9St>oc7VQP1B^lZSz zN~`A1`spImT|01Z*JlOW{hT`YUC&NYX2{Xqe6u}1%hG*lAt&*LL;C!;V@sWf_6*)w znHc(e;l!S$D`A4d#g8rMfLZGDjfdhTZE(ylt@>u$$lM_ zwEtS1*2MBWR;iOC#2xin2fu%Q`RDqN54X4>cs=jBg3|lDZ=qr(j4o9Nztpu(V>)Y| zCr%aa_qw)N6gc4&!aw*|I)&Tt>-|&_uD&VuUG6yyz*Om2L5$dpMi~`3FN7{XI;ID9 z8C`!YWhiJdJ>LzH4nJoPTT_=yqgMN2%?PQ(j*f*}UQ;!ya|mmHj0e9w@O+e;@?q+c zEvYj8>^6lJqi*9>&y`1P$LK*#&Wo>l)RU5Dx8YnD#CC;R$4I3^{3FjJrt7(HQlnNM zhrSKT`6Y>bq!(M6kl-HAR?0WOwd7u4my#q?@pt~# z>rw2wJjX3Qwa}}AbNK=^aEK)gWl3_o*l<(pU~3e~dh_pV65B`AAk6*~8$YgcU2**o z9iy|ouQ+;Xoblzx^i%!`%R4~Uh}}5dXw~J7KepqpEQ=TSuA31|6_F!vD@B>sHLDJH zA#uF9)(+AOi?Z(qQw7%w(FaUi<_6QQ7QRY3c)HVIHmi7be8b+LIyb%4h5 z`I2DRf%aY8_FVb?p{Ux<-YyL8so$lSsEUWqGsF-6f!{7Q7CF65OxwKXO}4DtOFMa~ zYtXos@os36XQX%E%+qkCw&adnmY@XXH$V=uNG<7y_)oTVCrJq_Q5n#9&z(+3)Q@+I;E zkAv-GJ%l zvLdIOUlCxKbYU#H(R75uAwo^<-AHVuB8Hrt0VJ2|_l_;Ms>=L=kAk-^cB|OHCm@b< z^2knvU2XM!u4j${48+2|=ZCxZzheh9_nHjw%dah%UF|4o)S(y;ILPiAQ2wWJByz|= zn&Qr0Hw>)+^jV6z7EpIE4_(ecb)KT2m6YNahPFOxP;k&~+HBHsAV3n}Ub@nw|KU&F zhUHP!!y+Rcds2zw&kQ~skYHpJ3Yu@>h4H~z+?Uc^hudHjxpAuY6SARg<+OsyY(&A? z3=cv-;3XPz!|q2l={8RwDT$*>V4ZVveZ9uhJ6z4V(q|4ME#7CVXhcS^LF`gEF4MkA z?^zu+;%K`sx0<*Oc`)BxTEnGsQjnYZmxiPYy0tbx{C@A?PkY zK5^d3$j0>s$MbYGNP|xC$4GR$A_GN`*H?cM*=%L1gtQaXgI>)ZLO=bn|AooAudgDE z9pxz=;$^FC&=O~e_&9BfLsZ2aJ*`4R&NO&6q538X1D!Nxiz@7$oY5OH zf?V~q-O>x@G)3o9hMq9I@?PCKyHu7c1LMoCzpD(AOqeVl;Mqx=2i84Bdh~oNNu?dI z47vQGz!=p0b_%>KT)J{M8$Sx=c+|CQ9L`1(Ys?^J{;^&+sW>J7hDx8`f#i^DAMNTUUtPZ6t$KQ**Vu3p zCBFloHT=@kJc^~T^Hq24tS@NVoJ3hKyJ70ic<9U7IQnNttiFTqw>br}Z&i(Y^Na!4 zfAu))0}p~=m?YOcvZTx_$}*LjV<}gvbJ+P4A9clh&6=A9k#db1vn;Y1F&t$XQ<9Gh z_RPtN%DZBEDPDU;&dlBh?J>iWVUuYd+Te4qmtO$t|{yYpVE9o@;QEVWY3nA zv+K{Svb~8QtLwFY(l7agd{So~a3QdV_mE1oVJhtk%5YcV<2?_}QxXDqDP1XGX16FG z>;w}jRAizo9WfbhpxV`*AZR=36fVD`-H-5)dd9wpg-N;OwV&xac!JV;I!#0wHMIkX zia&6BjtY0=ms}`UJ4#vgv%yPgtEawXg_C+BEKf!|2QvztRPe9DXAoc-1vHRcBtn5f z2h1Bf#|denvbrO^_vmQB-kcs?g9|?H_C13?g zdb5SlR|yH{rk+@AN|Etkq(9#&XzQ_k*5383mo^$&7-1XP`Tx>j+JaN8{tD>0{!iKAw?5lDTRZDp1m` z(a%I!hla~D_H^Sw)Ka604s(8VBX8lYAcw|R`1yNvfu7*mp(bX|EQjp#`-e>hlbCY8QK$Hixsp@ znzsf|>FgoPY%Oj*2`!Hp=J46y(>4I!i~oLp{d6l2%Yd(GS6{taZ|YQWS3yFyht5ke z_O`L9A5v|PNANGh4bYfl=Sq?lgvh633Oz)8`B7&S?BjV@{{vbh8-W5R7=_1Y zH2{eC`1}dB(U0Pg z2;4D;`);!aIvV;&?)cp_&p`$+%uAsW91-2W0I}I&PYV2LwK*j(7#fVi48C%0T>D5T$-l@yVRx1951; zH3!X{&1bG}Zo!9_;E_&D$Or*4LCRO>LxMF++N8Lx)fGE_@s)|top|scNNB{f^4DOV z6IDL~xFs6ywIN<7#mGqM&`-eB*&QeERtO7+tgSwAzY11Q-2c>Daa@9#Ktvx2+FbgC ze&R!X4F% zh{V~GT7bmWW0(_xy6O>j6QipBUFHt9YKF2BoN!3(K|JC}fcM&YTvrDsC@}s>JL^4n zdo2J`Q!oTjh?&C;{o4S9KBgFU2#WWh|yX!pA63kh5S8#f>c@oDptYFT{ctU zIUnnOt+Mp`D%A`627zbZ|H8dLzh^g0L-Rttyjw-^FC19%+62UxwW-MH^ul@EI0e%% zps2H^z~BVB1k8iSL$qm-5Z^{q<&vS#5Y%?LYFgq)zN%K+sx$*-eTZ#pJRDUMc@KY4;&O$M|@^_;^MYn=0ksv&X` z=x^T1caqhKOE~}fb8YkHwJiO%N%fS`Gg&p@x&g}c{BFvYF;P=Mhbwea@y!Q?>q3iK zO1c-Q%oIW@;!O|7L$GuRj0Wopkn4%#5UoDOnOZ((|Z?eI57!J4HtuSPRYFM5A();yMQ z@#7A>l5d4J5q?Un@B(%7m_;to)UssqOTN6&uaJty$a^%X^+%iih@`-Px)~6=4Cn5acanPL? zlLwMtHPi1v6d#%=-fQD+^~`ot@*=kBhEm}`*v;N87QXoR=FU=nhw|QvAx+4>u%jnq zH1RYJjm;qqt`L655E8eDHfv%*PH-!Em>Y?d1LOR3YEJ?t4E*N1TxP` z$6QQrls+qUHN>Ys2kG64ze5mE+L|mvof2xHQ+b_0pk5p*feBR*@jor_!T9DBL4w?Z zUVyFnbF#rFiu>~}VT!7u+ zmvH-TXnX~TWNr|~@WsefpmJ5ZOB8aO6TWQQQPZK%z#1X)!qdJu8CAvJFU&YzwYE|B zbcEU;25wQZs>-GJ9@{2m=GOYJ5H?Nzln`A+PWrIcYr7|Eb*P+qqHT~lBnZFlwrP*8 zx;eqj%s3aTumhJQ7rZqEcb9EbS77s<>@X`H`g*IQ{k%qX$Z0kOnYxU~5c&@>Ox3kBYNb1zTQa`9`|7H+omF-{)|1V(j%uhcC>Ly+^?2W5ldd zDyUCn&v~x)LLMQaYWc8{JnOb;z?z9$d=5^#gCe#*l zr>zRuAoQvgC_7tODK>aK8pRZ^T&oP%)@P~ty&eaaFtVSR^ti%6E67cYC#dIm37%!`7Q>rR-Q$RNs?e1@u?_|B5%zd1$oNDZ#-FV15eqjmuEWa*-~ zasuSGk-{|7s@z}cz^!9ty?0*fiy-oR07iuD6V@tLdfL>7NDv7eI;ub@r$%cydId+&2I#BFg>N z1>{99T}AK$8ACDlGuCmdW`hUrB|{~|Td^AqG!>$=B~Uf-r5A}1LneH-$*oxB1-a{x zy$)|8P?*?T8OGl98;?y3Q(41O91vu~IAtWF!dGJNa*mx=ThWht+;ed9g@QOmR~Qxu z=0wBm9viuRIroo(dqc+L4h8HuaIXW9!e}c2pvRc7Jlaf{gU`N?@U#2U-4gq*Am!}lb?0Au?@2ZKjmH#plO);3x5#uo znEiNU-5DSLXI&{xc31e zl&imTQ?TY+LEwJ>55$K`@6<5sJG!_1IZ*$Vk^dvjmm9HDllFEEQDIPs`6$MI5xomG zF^f0A{ZO(t_Y9`@C`~zQR2twWX`3IfTo2v#b-OLnj;=!+YsD*$5}zr2RCMmrDKo^*(u_Q1MV>zl{*sm7 z@0h!N2{%KgOgLj6&=s8cBZ0r~nd(A7uWh=it9JWjnEq(#V;#*C)Z*L2Z;rIN$$n_Z zp0&Ted+a=*s8dTB5WX5L(Rskfe2&vhhFD+v%qhKi>sTpnp5Blj?wP=RpbazuC6jL{ zY&b^Gvq~(;QPd&xXdb9QQ~&yn)p^kh+g9%padbWUN5Ckku`AIppIYs7Ism#>|Er1K z&HO8!{d#Uo)%oDF-pAxW_)gLqyb29R_@W&1Jp^njM=wltB`d{Q&eYl?b`RR?U?a8M1SSw4vRt>}lH)qzZO_A3LTRVDYmCSqdkBVE* zzU>aV(-&rzw0r&4J;`4-g%LGdptth-r0yyDTdZy# z5NQATKy$$PsQ6b;=BGgUt04StM|GXkfmumkqmSto`3q+1{B*NH8C8ZqsGNWG&BsDjhs_qkv7GbANNx(6Qn4%8*z-JVh#f6Atjtw>Zwxgevz z=EKlCGd%c9PxtyY4w_#4t{LAvl&qb+)%{bO_}gf#D06xKleX7CB~Lu%(u9p)10xv7 z+05vgQ(u$(oKzW_zWt+i=XkY`zHqt4M^CkBFIV@=h|;;*q`S{Q*6h7&5G&J;H&tR8 zpsesgE=rkJ$qWhJ&%V|f6aZNp;QFQod^G;eri`g}21k-Y4FXB#`$L%6 zTf~0*N~OHs;B1w45!~v+W8;+eIPFo#e#zsfw_X=^tJF~VruGIoC`Tr&JuKqkzpiVT z6%qCrjUOTQxjL}qZEJ9-|Ja-B)qxLYH$dEXDcxEq&hX39dBdAZ6!$@Zs(Otcp7+|y zuH2<;hKlt|FLLF4!NvVk`MvnaEiTh&|F{UZB1W(AZwU-X7aS>B(L*?knRo#xUtq|2 zS=zRTF?x+=gC5_lYghg!-V*YQIJkLb6qnJQrQ0bhf6%xd0PL6E>5oqIJ5<)AT}Tls zwWvO;=_d-|r_J1Tx%U%c+|Zm7`%tY`SmZ8_$Q{ z_BrM-65j0nq~~F|b%=-MpyAh+BKDPGs2&;6NQ5ZHCr-sbC&6`>8C6t9gKEzL+=k|x zza=q3na_|jLX9@L-exJdH?vTRVrJj-g#cX>c|RAG6!vb4_5!L+KtsuK!;Xg$_YAf=!8wwk4_6*ASD z>v1QSJcGH{l<2fI!P~sbou~(?Ii9O-cszdsJvxVb646-wUAo1Ex*xNJ@~$I8l%+dO z&e6;kLFH&nSZ_ZB#~{M`uYJfg`13m3vIDl25BrdvyO#Un;xVzra^vCVT_<{BTX*%n zrSLuIYVL!ucYl!Ns_@+hI;T97oJPZL*(mN@3WuAZSaLc<2v+(tKv}YTPkG*zK5SKw z94is|A{yyJGz~i4`E~y@8P`MiU2L_Cr+i_$elqiR9&zixmMe_?0HL>A<59D>)B3as z)$2VvvSyB*<0u3!nFuh;UJNk$I%Ub-2U8-kG-vQVy(D41_l0j!&gZTstYii2MGkC2 zq!wE|d#``y{GvNU6{1nlpz%oHZ8x-{ZYML+9wB(4jTw!OCvLWEEVOsSIs@yzxhYiz zZZ6F|`}~a617BF~LZ-Fi=V1Nb0L?f+-hTeWzN-7ZNpADbJ5@1JWDCey>jQ4I*Lyj1 zfn4MS%z*9WQ6QIpvs*MN@TyQ|hmQ4X%wCiC-33u)G-!;|eKa=Ly-^9dsBIMPi8?B` z&v8@j!vp;#uo;rE?8i>)q3UZ%_W#05S@yH>e*@b6ZkHzQDtYmO4HCo`z`V7Ub5;*n z1J3s+F>y=pFnSWbd!q-8GK1<2KwMOF>&;o$`-W`;mvGrOSr`waFZ!pPu3vzD#90Pu z`yfp`?Jd;{_h$FlO-~m)bwCQ~1S-aa!9<7n)ADehOid|N&tiC=!;@hR&`fCW;&7pY z@_X0H)D0=&9{3?hJFkKVG1Z zD(e3Cs#h!{8`YHgVaL|vPrW@%d}{w1@3!dvOnsdO{vM>NNu<2TDQ0RHngP@THaRwugTqzu0zV3JWp? zAX>Ygdbm@41y8QCQ$#^v`0N1N+@u@0QYPmtXtbQ*#DsDZfb4IBJ+8sL`L7<|e|h*0 zS92Ipr)ii6Q*KC`N57Gi>3ECPT+F7|WJ)hRhTtt&Ztew44I*bB2zmN)|IyEYg0!@0 z&fOtS7zxr_2E0ncv+xjWO0R!}qPcO+8!|7RxZWeuRPgeGh8zW_4d@Y2!JgaRcA9mj8jxuc0NBT#mtOyJLgpi{Rr&-i;gV>)cS?9nM4j-RKS|9*Ec+Q zLV&a|Z}^yn-}oC!yODRG8QGG--8)ptdS4lv!P%Dq%Q@qV9IY{7UbSk`VP_QYBJjdd zxonBkrfgetH{+{;8##`^8U`m5Xag;it@s-ZDTnz=J)VcS)QfPV4I0ecpTP4laaS^F z*|}2W+cZVCBj?vD)Zf7kVr9&@%}wyn*AXgX=Q#T_xUHc`kn>CYwMldoQNon_XEV}M zP*{C~?J7ljOOg96a#(^K7OFinj*}_5B>OXL-CWk%*6icn3wYxZQ4@r;IAl8wnIOtb z45d8D;yj7s?2c=Dmi-{qo`-Q{YDtmXzV;2+gU~AYQ_P|uZUsAT>A8@~yy>ZcIk8B_ z(dAM@K_4H75r_OB_PzviZdB3Nl}d+R=WjFqjT21798kTkfV~&To*r7(;hp@0>O{c6@KJT;30#ff-l8Hw;pXYiGA<9b-Z%68{Z%0H)uscRtwUr== z`C?WT__4$~%ErS>1+sLJ zklsN`?!WS|z%rPcos9;+xWf^iZRLt@gO!7IR7p;ODs7Ln%~`>sjq%MK@ll1(w>iGA zI2wN|tuVQUsPP>10G_9tO(V!Yle{aSguJHBQsj~*FKjL+Q_3^=TW5BtW=&uJ;SqqF z3y)=RO3CMC#PYqgJFyHz6RTH89@wO@`m`n5KJf5}x`EI1bi9cT_GBcEdl(%zR;9#&9kdajcFWk2>97~yi zTq`c2h1ULkF&C<%LCdNrHSoQBLJB*By0zg?nRgudW+q{~ixhwZ02yC?fQht{^Ut|h zz#ggRqh59G!`Gxh_Gqo^voh_!wyEimzP%C6p&(3!$$}68K*%nqATwyHvIN@ZOZ%T% zMRVv(7Mw;KTa!2QnF$Mp*b6p$;mi&N9#1j#Y+RA(>nw@0I0Zj07T9ZxE zc*rjo5i?U`F;eY=h6r;OIMCw8AGsX7cos3<0wdk-V+ zxk*B1ROKh%596~iEG!XlSpq3@$@4iIWD_LKuQ+os`($}{ zrU<{?QCs7mT)31IJm!I-GvO4;&1@y1zMMo^V0F znTbNNw5p(MCY1Yo&D!pqTjJ%!OLjiYw_p9#160Iny+T>q%E1Uhob9hXLTDF52yS0buCB$b;9J;8i4gjiy4ZJ9A>@ z;M?(8Mno1m15g=MXnaT6f-U%24rPb34(R4M-j*+lM5_M5nLM!F^+I1+#L}$-Xx@Mv z0D`$$1UyKkLT#F%HuO){8Biq#Dyrj-VerQZ9()~v7l_)*IINXU3Cxfp4^<&O9@?Ur zOd|ov?`081ul+ax{y#jGDMM1&n@BJl>a>TLjiv+2?`|H(;tnvg*<>PH^o*%DP2EdV zbA*AI>FPPCwv>y)gA2eURQ*SF+A!lScx=l-D2WUj&w+kTR4wAOZr7)_Y)-=5E7mlv zA_-7qvJD7O6TyG-QV<_?P-b3T4=FecHKDOVn$S3d1)XSV?C#0goFJlb$h2oH;h?W2 zl0Da{Fx-l8g^*~_i+WIyM8s4712y3k03wB)_J>|9f*On2njrHkKBc)>bUg`gCq)M9 zp<)QAQO#A~0zZRR+6#yo&{InUSP&`z-^#QC8B`$Aq#0^TWfft`SQHaRhRQ~;iuzhS zGKmLGMVwQ&J4iRa^Y4l{2v9~rFK%U<3KJ}7p#PSM2n7&S7BP<9ug5lShFWz(jE@`T z%s`$xBJG!F8&JAl0PKYhYA3UoO?jMIRdZNsgL)3`OxCB4FUBBX*$maGVuD<}Le-2e zfA%|;K_WoFs|+sXYD#8)APOqP?hmYaK9(r|kZ&KXt&!8oBE+0QGgO<&0N;nOOhCIC zig4IVBC_NpOda9ebJ~lz4A>en3TuWkhT~U0lK+1Eo+LOC{Md47eKff@O4B@+#>WhBR0gF&b^iD@zbM5NDu|Ca>vrcQB) z1D#(jWwU7$aBD$UBM@hUObN4HG(yf;fHRm<=7N-ooM62G!OttuNIEwOK)T`-Q(W`X zI!%G0WCal*&t%$dNi!9)z*{l);zb0b^$L3;25QkM7X=_Q zk~4Vvc|-5#w_VIQz4Rb{Fk|PR{Tvd27eR<(c2O+5wQ}+MKP13~S`hD4#2$*v%s8=y zw_dnezUfy?RWDoo^S!$UVlD!i!Ne0;+Cm740yQS?ZC$(9xS72vgTpCK2eqxw@tj|J zyn!E8`?z@5@xy&uOxy%JS_rohq?u;?uo#5yA*pr5{yv-eXO91~E>qRJDZbs7JA~vW zP&l@ZS(_#h3<@&tCx?UMinp!w>A&**!c41#?jUfRwjEAmB*jcf2Hd`rpE*;~({pOa2|la7t3A4L)jcr6*+4*nc0mnLqZ(zP$&aC?E^q zB~K3KtO}*+bZ4UnG!qADukP`b%>pmQ%^UU?XgQ?L{Ezunvx<@qxOLsrs=FCrY<4Bw zF~?R#>nJL~_+g#%!G)Qjw4T0Xl~`q~8nM}b%&+aW&U$xLk@va#i3vX}o?asCs`^6x zaq%h0{4USLJT&UP>N(W9?`wKQ)~N)wyO;O=v>vRMJ$*O(_2>71#v?Li>lO7&lV!bm z8g@xDQk(aKrDj1O^K1KYq{bob+srS!X>o&3ne{%9`5nKot<8UD>zc%~S0l%+?EAC! z+pC)g7r)K^ahQ{Ib5&L+tvD{czkk9m`5VamPCq^ubT#R(^YYA#>uKM=-TCq0`@4a% z;@Q@tu_+%r)!dVxn{=j%)o%jU)A+?%*|531fgRqWEU`_h* z*^uFm2Vst>AIHJ31iRbi@bbdE!g=A_d&mDQb%o6f|KoIf*t%qjoLN}QKgb_5Ozrj5 zuU|eaPRu84C|&+C)EMjkP|xSo#=gAhi`z!3>{w6Qoh(1u#ymXkf2-s2%j>Bh#h25N zxHr3x=$tp5c~<;(FjlGe!tMt*uep=2$BlkjGxB`H{kM<1YOgEl-z@>%ytQVl^;`~Q zj}vNC9V;${b*B4%_xj6-2zNYad&IO*DZY_j=U}_Uf-bRxg&l>+To9t5y)=~9XpnHBWnja`Kx<~Dx25HR=ED_>iUcx zxh##_6{pNL2R(H77(B+&$@c3W%5FXIIXXwIX<8OBuw>kj`IZ-1lM{H^OvM*rmT|0q*BEwPV0znwweLw#gf82! z0d3Z(X!@mj`E~5@elEOi%x+BjtkCg;z05-50)N+2yaCZP@ThM4=$KF8am1=bH{^;3 zEd1QocE!wzsKsK3ga)Hk>x!1Xn1)&7K5N@w!K5t2lbWgmuiQ|sF1=4b8-W_D ze~Av+?&#Z6W}N(U+UQfrw#|KyT)zv+Goqe!FrDp|>RAgrad288rP9D;*7=Jd@?rVw zD7($}k6gz5?2C?$dg~l>EJd4z9d2kftIu8-A~lw;x?s8dIs!zG9gQ&2;-~p%YNhXg zH|zq@Xpk+=aG!g8Y=_$>%T7^to1KUA%$Mk@U6v0W-X?lr21bZ!iZ+8Y3;l#-@hH-$ zEUF>bv^J5w@QQTAHqX;;>eKM}x<|6FZ9%jaQccLp!dG0~XGY)ByZL&FuSFYN<;)iM zkgUSYij)V}94eE7F!sYlJ3q3BhAgm3s8ZtYVUxOfMkN$wU*odzQ@Jn0jyHUxFaLm! zkca)t4ml;Jdhd;s{{^D$halb3#mna>b*x42#})0}{-zyjJCS}Dv-VlA-2=N3{M4q^ z0o$m<)^*L3|FlyjEl468ZkrTy3W_&J+CIw&Mcp`2I2Yidr4t64Mp^mi=8F!NWn^i-avO%o>W#smOs|i>r2oK5KkFtcY-P|A z6U)ZQHy#Mne|}EvXp6Vx!3s6Zd+vxO_ZM@qt5*HAuG+_2gVC*VOtV)1(%`pkxe4zO z6UcyWx!E(8;`Ku^_eQs6-erl?I);9+36-3h1=UxcQCnLUuE$up==766zwm){C7t`O zdeJjmTR?}KclVv5&1hjhgO8x2ID8hxRnsBLbGMYcTx0wzi$UX#kN6zF>5O_u0ih^e z-oSlD7a?Y|&5yw&1}P@xM>f~F@2J9OKclG4p2#Q*NC`irw^#m_otiMm0(4zz_#pB} z4~lss1_utL>ail^mEkYR_9Im+_PgCZKJR82_+ez?oxj4V9Sf>!qa*Ial&5EZ_G!62 zmN#>lA*r{V-TR!*G!4>4hidA})Pi7v$(V)jho8p|mhg0~jB_2D)zF^Gner!Aix|Cq z*fh$w2lEz$3ZQ7mW~#UC@^ekLSd*%!>4!5u$+)!m0hrdG$+Xjyk#%yi?O1aNGW51_ zrOA|BpCH>{I9ROShC%q3oJEB^%27R`E|c{zOKlmCaJ*F5BAky>S|%cIe0{3rXahHW zm(+5&SwqFA6FhbYcFy_BIAm!QSvE>%S~xrDQnu!s2$d5R=3O<4gJ*{=uO`TL zlZJHcz%z?k&(jUlCN3+=w%&yb{ zCEuEnlHX(3T3n045rJZc7OU@uFr46!;PNM&)WMz$3t_JRh$B^m+g0^Z%_XCTD)Uqq z8>bn2V zq{PbQh}xlHV>PS03V=-y#UlOfq1`;Gno$uAU}1vsv!kfyVd$nn2Wj05LGL0la5OFy zM+Jc9V@`7~fmaXXCM9#EnWs7a{XgPeRQgiGca;7moUDLdN!JdBfh(wC3C)>$QPb=l zw>k>PUXFEp4(V7-+%`r!iS25K%JmDLk#t|7Bfz!Qp7t!&bt1xuoPo5%LxS$CeQZA6 zr+8wvT)!hy))aNt6r92JuzN~nt(oQi_u^gIb4Mkl^>?+YPbg7R-_rU%3GZ~0W2=UT1 zw}prvjnXz-y>m~niqB3Zp0Q3+m&n44-~e#yMvvmRsN<_nFAMQOYur=2o@PDV43m>; zTTy&NgCDYlo*lzK{UvN4G4(vWvMRz?btH>F)4A!_76Uu^%4$NHU zpS#Zb^ied`(#5kVZc7LX_Y@;4G}u&=?6i-l`ZDTn!@hv~VC4ENc-`sO*W}OXR!?P- zdxuFk22$G8gjuH9=+1968bPdv56+4em8P5$Q#)bu7yrQn7QocnYod6MXzd<^iDk(D z7VMZ&bMuJ6^>Wh|rxhS%1Xs)J5gzSO9KU%Sqq^j7e$?U5Ad1aJ(l`)W`7v9hOq?Y^ z0N?@*Wa~(@iLv!_9%h0rF938B1Ek%OWtWLK2MS|h0U9qu?&liVXzV)BcvQq4eKFG^ z`3tI;z0Zi78rO8{RR1v{$D)u+iImcOZ|px|j1%$|XZ+0`W*#{ZmVLQ{?o3gJzT9e4 z;`Kv>9&+3P6(ROl_yw6IfFbArl&S$w$PHQ2sp!eANy$Yd{Fm5b$fpzm_<~DT4UpJN zOnk!i^rm5dQgNv%F{a1THYi~BlG8Q@5mF$bB*pu%$b*_vaamqdU5R}>@tYL7-4JpY z9Ri~Ra2`OQLtdv8ya|R}$tVDMVhjZmAb=x>kTt-8moBW_=caQcT!M-0_2c-PEWIVp znadqO98vrp-SjbE^22isQOe<OoqKvIxcHJwhSKmiiS=t88q1*aGgMLgv9&ciwp zV%>s>z7kA%81@(6RbL{-%tHEzvrd4NljwrV{l7R7G60T_U!vi`>T?%WycbaS5N6rG zpl*3d#6Nt4t`D@KL1NkM!K8LTf)7Zvm&));eYfEKay8`X5EZIu(@aRag(BgPaf*jg zR{&1YSmLOY&WRQE#|`-HTk!Ju5|Beh2w>d_CB+b_o*~bV?FLsgw?AAltD~oauDmh@ z;wOJjBojg)!?ueebrwT90DrJV9uug3B^g71%byr0Xm8Wm*|A3?3=;oV8o`BD^2FB& zyUtCK&ehRWBukS-V!>c9kOM)nA(@qBuuKRBEQX1Ns3DY)j(*G0p69xHspGtzar^#g z!#maQ1XvNn6lzg2@7Zd=b@iW=Qw5| z^g;QPQk^eZ0d|B;p16?yUugH6h<7rTc=ndi`iii#(dektw!6`1H*euHS8-tVEDyjh z0qDnE8R;h4J<(FTVx1dovB9DLCT6P;E2M6lDG}=&sA6x)SRorL1om(s0l!AcqSHp3 zCK1G;dV?ywQ5*!^hSa7ay78bYo9HIPeoS$Am;zpR7GI&rOEMK6HekdB33~@g;pL6v zu|f{kM?~6bkx&xUoaLhMOV=%H;Nm{v9Nst%V#q-bEu)(?9Tqe#I)YMP>&5Lz#x1)o8?*pq4ZSOkA95^EtPX!UkBkiC9#W=5ZtSj5P5=x!T5`GKxtd0Yi?Pd{ zikv?6J*_dT`0FsWGt_O@v3(F2N%Y0J>nTKpnnidqXj!sTqbZG1X*WbP>cSFC*va8l zL&{exqz2{SG_{Rpqb1_)~V1}`Gh_#VGs*bGM@j}V~}u{Q)Z zB#^we=J<47Bt`WXNnUiVDJF9|^j@8ih5F-!Jk8O!ccB@qrZf14IWP-H-66>prlg+Y z1#iy|p@V<_G3p&f`W>GL$VVDHpM$!{_mOQba_sXvBcWG)0N3pqp<|7o%Vw>4qIHCf3{AL0xN9ZB2X{*j8)Wo3)dx8F zlf88fGQ<*Cdm>f@b>|5e_3ZG!*k|;8@F3x-&qduQX`4E2FKkA={R8h^I_B68!F?F; znF6#0@O(C^j;|yave!P$efLG}X)bnKn~_mJYgJGOgW#YO*pg1{cW&8%Rp}4H6To4T z%>W7APeeDuLY7NWR%_mZ5|}g}^5db|D?M234OA^#Ovu*PWtMD|V+bWuZC<$hb@l5c zoU+%b*x564Z0rmj>r)P%9f0Jnb+?!oP zJ9>`M;d=Dp^ZKpF_lPjbg$*GOSD4DS#^r9qrtRuCkDRf~+k^W-#53a!{+skgc_zN= zakD#!ivnUqs1_co%Y}%r0f=Bg$bEEg9n#_rG;7x>az$TIuoCw$9@_M?@qrzrpkgZ0 z)=X5H55e8F@&z}c1W!0n>!wNZrggcSQP!0%*y(nxj2muM*kA9Kj1we`!osi<2~v~% zCY$B1b$yX&0M*Sl{m8X`OT>&&#p0+?!&RIZa6(T2C2>U$;>AZP*z;o_t~JV&}LJ7UiQ)p!pG7f)f{ z^YyQ3H5h(?ajDqNy-LH|^hA?zlthdp7f@rvBDtu(1Png|=Q*uNMJaH898f5aw0q;+ zf{z6o(x6)q3H^o;ykXM$=UnpBqxzVe3(DTj*r{UmpGd|Z;E0g-VqX_#xH&=z%>M=A zJ5JiIkW#4Ihza2!Sd4u|_5Z`c1y3mY3yW(t2%R^>aoR)^9AdK<3agal&CtwWRYZs{o)5NjW z+fo8D?q;|S=ZU(JM2cv+$|``{TzR~$Y!|H$WxxkU^&1>QpkZWWqU=`l0X0kir+V2{ zZS(K_7PRNxq&Ee1lO-JTg!_%+op;x9>U?A$1v9~y`ogy_hhF*FPPjRFd{e#CSRy6j zob*Nl?t44N_T8*BH ze9~Sty)X2DJT#w|EH{R^E8L24Qj_|~B|zh2a#P?xdZuMCebyLJMdh4^eukGmjtJUEZpBRP^EiUpt z7mdW0+Vn{tc!z$Ifc;5lZ9X5l6Rx20N6{(M>_nY<=u`JF4RJFba8sc{{AbteHhA+@ zTM&v>3fOym13fU5&Fl+&{AZ z06gaMM!`$jRPm)4IR8P`if)=H*CvPgvyPc*|2T#XSS8)2KG4i$)eJk0LVx2vQZQqD z^eJMop2M7X1VoG|%HSg3~N6p9x!ePF>wZ@$_#% z8u`t%i}I1r;zvHBzmRc1sMtj|E@H@TG`41V7R&T8m`hlZ&BO}m*!P^HbzCTh2dOvw zbF2!26~NL2!%ietSH6b9dq4Mw09ZUi>Bz-$C(k`T^b`D!(vRemNo0 zOTmtpxqp zI?pPrQ(L3F%C79YcM_s_3@vXO!)x@v^Lk9t8uT9Sm3TZ;={+U<_h)VTuxe*|hgbH$ zk=!pkukO3YJc5Up8|;ZXcz#Ihd+;^tqsGdTn5W9U;5z+-15HnBdJao;*yqb&s!XFt zbJWsgFuN6T(xgLK>pMDkmB`6lrnrn2dv9;}&p>FqbdAa?xAsOaeZFyM@^RhXX~R!< zFa8s*IDKt;7HaKx(e7xC+3uBuvx*8Q--x;@r=_XaS5&{4S9#Voyt+22`TT_Z?FIR*_z{ zExszQGwero=IdC5O6pvPPVK3cRaWh(^$wjfPiZR!|v)OPBV=7hk*;e1b5T1-EH`)+?3$;u!-T z*Y3i8(kb@UbS4f8A4yMP3_Hbd&VEx&e7J48`EA^LfyL?dzG$4=rhh|@0pe?GCZw@P zR45mHQa-A*qUw&8OlVoGwqmko{Pg*|H|mBf6*Fet?seA3KP}zvye$eRsm`Zsh$EGk zULkjqrtWXEm>4VxsOb_dFU&G7=&QY&A*i)}R>$i<@pG)H;eCBQtJpFLuLcdiCK@}W zPFwgYALG+^-N%o)`X@9_uQCDN_Z~|6S&g|$ZvUh^@$g@}vJ?#0 zGvk8yGL`5hMG&0{<&rm%*itTM~WQG@(#QDX8&g2 zZ0!qm_}1$5UR0CPk(VtA7f#GLSGzPXPdEd(%dbxIureIAvVA|9ALae#0TGD`Ym`>m z-ji=*sMMkxXShW@r@xyaW^yUqX~#a$k63;B&UyOKe0cY-%0 zCMzD+v}5^`E=k>vAKjvQd&p6Sp7G~kEDV;=r!&8^;BaGv@~0e8m1V&_&y;?lR21r! zVWhv9pAUn;rVOSF0Ol5bHH7{Q09Q|NSlnpK7<@|>2@x>u=g zVh+>{WPTT2j7o&bHy5owKJGR#Lx2TvGu4zJrk6=9ncmwENI|Ts+I5)or;0%TxSN-| zX0NKMp75|bJ?JqBo}tzg3@)@13XcTQEEX#eb~TV(2Y`WR=oc&Z5Jgn(a*V|i=-c$c z8=nNADD|a=j!tr~Xb%~4T8y$mTPR*Pm{DC%!`FP#w6!JR^EQM%1&)F~Y}jOba&d)} zdB2lwO6iLl0g+`EUyO40$v{}A^dY3k0P4fo1^EsgmGl;Z_I`K~IOa&EIwXB2RGJV(uz%kO5MM*K|}@x9-f zA(q3zsVT==`<@6mj(@PPuiY6O3o%kz_KF#xmFsQ-7Hk}~)75=d8wp`0(I!)sht6tS zN8T(v9yzc2cn~KLYu*k0yp0~9p+Q5sw3pXG^7Eo->s^{=K?8<4 ziP&UzL&tql4V%Y_1=0F2G}g-Sn_c*eZzgXpecKpy-%1o6!~Rx{`i&gO8NYt*sHUQ{ zo>zQymp;Zxv;lCqrqe_(i4h!AmN`2TPpmFH93LUyNpiN|Cu;sD%*s)octNRkxrk9% zuMy+*MP1_?Rd{QdQL>H*te-4u>XFm5Imnf&5++(veFlONTM%h?oG_8|;Zns!XTy>+ zwL*o;TfbMG*Rjhu+$QXL@`lIeZJ7d%V?u2jrQpH8Dk*?w|^?~4j| zGrOicY@U=^xEQ44Ov|3fI3G z@w8zRv11n(wa3-Px`#VtdJ;MVVj~xCthj1tfpF-TDwAhBx{K|K-kvD*GUjJ5Fhl9}LM%UI1eiiV6x z`}Lt)og+`fsa#>Rg4z{v1+y1x8i(gbYnDC|QrFGfd9P=|ky@zG;9K$|g6u+MCOVRj zlYiogB{}0?q?727;23`DRPQ;ZpX@0%@6E_F*O%u>oktVqkjE~=Lef$ORX3?-a90vw z7a1YyF`9}=5D zhVo=>lHXs;6K@AAR>Ss82dYSgb#wMCl4_MNn#yGU&as}&$-RC4cX&6N0)RwlbP6+8 zmz6q$z=yH!t-ueD!`H>lVk+RfNswnJq#;L)6_$*kOF3u(#CAM0oi376jVem8u~^Ib z>1 z#NBKSc|zo_jSpfp+`_B1>-0LysF``P9V8u@N3BLlXORX{xaejh%?zdk4fsbf%+0Dw zr`Q>C6u?!ibdo3=3IB0ho=qDrYQEjC_h6U?iw38@TR9|y)+!Z|%XQ45RaUt&X%!;d zAJWf%dEnPdSKxs9timaOd-h^BJHh15Eb?8NJHMaZ6i>IJ!3QgtkCG85f>{TH`_fZN z`l!sPV0dH#TrM66)qga>rNhY(vlWC>Fxf;eTX9jks9o>sN_``(-loCbMj)g7mI=19 zC-AH|00%<0G#WhCN@6e)zBf2SG~w}x(xp);h86i7{#;>?)Yt|R&3W>_oGV7YZLILEMxbz~g=Fb#Qdv25D)Y&snR#k(xj^fqmIh8V)x zx6;J~85#d1eP?p&Beg{n;YI96(KX74I<2stV73eo!$X~B;D<-C$z0}rHj~DYqEULI zD!8=Z3<&Mq8fiQ7d=Zr)tzZKAgI30z8YvuqTsY(7@w>Lrid8CUvvC(nqhvwI8MGB< zG8>Gva;gdFgMqy{sqi=sgy-V%ab8R)%E`zG&nog1_4aNyb74k(5IaUge6JXWAYprv z5P+N!CLpAGBI4WOaTV~z;9(A(3Ht-#9jLZB^Rj6IK({j(iCIOY;Rx6BNRhFFf*jqC zx)Rd9&>n^!I7v`91Jpzla#+qEo!z1;nYNEIKUpT}<0FpIK9{}NTkTXYEJPx5=Fa$g(;=WrO0?WNUU@750otVU7!SrlcpLzCT7iHsJj~mc zJychyn_;xV`Zh)>rZg7w(1VJV^ zU<9Z|7zpdg$ULi0lm50Mn6}53e?m@K%jSc!*j`Cg>vbxq0cF zYvNO&sAy>@1qV{Na=44Yw%Y#Yp-=76=6grBVK^%ojAn8C4@Z=Q3H06I; zC_dAKGXdPl5M?*43bw&-Ux%0F!-9d@%K$rAW2{5nZ#>JBDsuHb)2P24q&*!u4Edc< zBoe^sLPTj9igNVy9*7YTv6aKn9c2&&VDGzEsCLv^B&>jbXOOpryfaeEFZzjY zp!JqKRx7L>od77(pnIdCT0I%*AoYXaFTs!4+Z&|~cAWw`dVEKyU$Nki$Q};%wI(Y- zy*C0*y7`DMk^}MR{i;oaZlyC&R-Z(XfW+{(z3xyvKUx_cQzAc2U7Vkmp3tC8mL~TrZe<#NN*YU^mGY0>wi|A-2Jb{g zWgoMJlg1>uvue6?=@cl~n&JfX+Gsk83}qG0G(^*}Jm6$F|I(*COMCa@qC4KT%=O=% zYx@a6d2#hBbJw&X$ecQGkr_p2)VW7BxI-I<>Efew95S~h^T5PPNe~TplSFHKdf?`J zp!d^U5sx9ojT4^%kfiU?-{Q2WAkQk@5YhiYrPR?ldoP~ZT;>FbkY)o>!jfCkkLKGXn*N&}FaE{E#0=hS#m zO#uKHkA>1fYS5NS_{5{02npUF9N$dtD22&j~oqa%KZ zCF*M3WhP7k83yCOHa1z>D+u;ZP~wFaUWKMIX_`oo>V+Q#5Y_}1++*Pi`S-OPOba6c z&ZCP15d9p+Ml_>v6H#=UCT2(@ut*4&M(A%%*<7Is>xRxRB$AjRhx|`v4eb4` zN&AAonE-x5LdW5c#gk1ul1<+{(YYUoB>j*CRaYcqYcn+W^#ZObA&?FN)Cgl7!qG8_ ztW#LmPjYGseZd6ax^yUQQJMNn+e)Cnl64cG>~-ykut-m2 zQt%&Adh?lsM@@DuUtK9_B`cpD*VM=a)OPMLr-OGZtVAMf=fPJb*}oCT|0E%%JMNy< zAYVzRYaSLd4};9`!@p;gS*NCtTkKTb3m}9=oO>i4R>bxjd6qKXhf}=S!}+1I$)I)4j12=&dTp2*xpIo6KQ)dV?KA!XG&CbdU~Rr6*gJvgQIb86_$ z#Aw&$bE+rIG4zt&q6UwDjYYkWW^?`%YLSISL~wdt>VuWk=ItKfr5kOwGxqO^A0M{> zx@$=>88yCXK7Zj44yBD_CwrRKZr@zHGqQH~&Dy=`wcfvL_Yvz{+4Vl1^?u9s0gv@T zu)&R4uS@?ve64GQwf>-K{o&2^Mg5GUVr*`{TX6|C%ZAGv+>+=*6l?Nw_Vk+??Te@5)ovUTL;k;r6eL~&2>1hlQ_6&*|DOW;82rWmr@*>o1^8U7 zcYE}vBZ_w^?EB6`=WSCKzP(bkPTFsm^6T}z_oD6;O}|>7%KGbV<-XP2B&fJWyj*AP zqbmCnu*S4F3}UOcH?QuqP5C|Zc3|XMon!ij;O+ax|67-y5T!5z_4nL7wqZM*KjWS_ zJAO(;e*1-eDL=tXxYNM8wWo>Jm>vp zDZ=i=-{svyw~K0TBEtjQz`B$Jft`vU3ZM5L?~HlTD*q(k?|jJdU;K%EO;1C54t>7y z$NvSZSlh25{6W3v`Lc<M&JY>;VKlJX{h-MAB+)H2SnC_z^ z%(viSpx)BaeH7jd^FzQ~_f)0b?3Hr-&ftZHqMeTGru5Tx%gqXaZpvh>fjw%m$n-@> za)EzEabThKtZQnaHSSR06SFb$qK|1}vy+Evab$n4PJ?G@o=;1>?)jsv2@`e0-j$a= zW^PAKRRRr%C7%bGsK3M&Sk7fWDRhvDqq%@*dsqgYAHv6sM<4I@weXJa^0oA|-iEcF zJd%kq=b3dq-Y%O89acO%-{+}aoiG2etu|k%eqf74V(|GKKs~wItSoByWk{{BmV)#8 z%D{HVwfW>C`+TLj`7RN8fQyUU=n^O0wt!)-33YP|E|#C3^0lmp1`EjsEX*gjcbqXI zcd+r{sAg4n)x=V8Y_7=z{SXz@Vh8DhpIoXgME z^T_DMAlYHX%l6}y^{6%BISJS6T4JHj8oXT&N>}CjD!SqoE z=p`(TA&7KjzokZ@>+dd|THaRiv2pd-Er-wdX-Mqw7hl@%@Q=&C{T@S1U|rw?f~A;rjGcJ`;^|cVfQj z7j|L}yRw8#xpn z?qNE&0qpTS>Ew6^<3>?FC%qMyc*2!!j=Ry?#N1csNN!{!GBhe#v4= z7SZCirAtZ>;bfqQIl>x6zT1b6kb}u}TR%|0p@vOKQNQ;vHgEcmGehB4sntt@M9UYA zb8}-Jw!JHEe+3a2ggpowO&Q9bO|qQSt=UMXvqk3<(!n|fX<{->Y`cC5{?v-HWIE!m zNL**tSgxp!i80C@9Auv&H>#=g7H$Xh;~(lxyDGWa==)t$`bCbgpZCY5CTuq|SIF`I zV>}+6d#xq-eX%$VJUsqEO8(S`*W$ZbJO2G?+&8Kus-y0dV?U~fZ8jjbmX5pLeJ38e z`a4ToY78MFJQf>$<)Zcxv92>z*SLT$>K=BR{zXk(m};*1Xf40tTzn3{gMIHEM8xS# z%sf=~K5_V9ec}l7hM&To6L3?unm?~fU8<%+L`^{7YVO*3)-~Sclk+>v`)atDMvNZx zs{p57sJ4TVFqmB59rKxG>FIEne;ow30Jh6LD| zNb5Q)ZdO}*+Qn$!lN&a!Q6n`T8Bki18{LkZyb!eiYuG=oC{tq%M=0%=?V#ryk-m2@ z9}0wC{U4s26cW%8*v_^}UbBKL{R<|CD5A%KhzFB1ofWI#CiFgWDxCq3=L5NU-Hnpc z5RKp@TvpDY_LrVBqe=}5lRa?b#tuyC{8W?p)NjOUSkdtnzN)6u;@~{~%-$3^`2j#H zMM1&QAy4eh@)~8Ac^}e=S0_^9ccZiX{CtMy9N^Ytrbg_`#lj@y9*w%2RTLM1`xB+h zqaOC>ykFuzO{sLU|8zmyHAo-SWtL%Z3>IE3vwTC$17en0jCXU9;83f zic3a%^mNLafU*Z)%(c`-RmuNpaJ#ttxZgX==W4h#9xN_ICI=zkhE)K_AG3uDT*ziI zY%gD3<`sR|(AB)ORTmHE2#gjX1++kNj*CGT}qw%xA*UP4}e7Op5n9`Uvxf&u-{|ePr%04OsP&-$fS*K zxG9chswDQDECQ&kQ2wS|vtsqq=XIM~=_{m8lG_P;1vr{`DjZ0068;hyYh9X6l6!Za znK77Hm`eM)^{w|;f1S_bU#E5a)$y*rJq>NK@eQB)x-A})wptFF-{738;v>Pd$WU^(2<|DD+*`&ETyx_0fCLM=9##otv zFez?#HKq2LY*8<>m~q~J^ip^WMeKDXGED%(#2h)_WgW=3r4zN4;ly{ZWZo08+kak44)UntM|Z4O1?gIl!hjBb2Shch8@CMBr5*nbNQbkX zg$Zs|TBn43%zmW*vWDXHb(BIBT%S)P5Fs)Yh#VXLsz*VZUGR1VS9TN7r^1uimU01N zd#A+TWou44sr)TvUF>tZu~N7Krln4~*6pZ!+~_MBEI755$P&^laaivEdUJkkR%!q5F3 zj0a;wF*YQLteN-1Muf3LDH$Uaatyhge3lf7Nru5WZ08nsa0vvYSPcbmUsu1eKDnfR ztIt#{YEpiYB<*xmLv7ocQD?lE0EZ<)zy?&W5-(N>L9k&L62wRG7J>nr-6r&>q%E%{ z#BIMI^EpUw0b8C}_9dd!(?T?k9-GHT)sn>r$Wq4`MDa;^805@c*crEr_QY~X#H_Ro zwG@QyE`fPxf=zgd)-!>mss(zCqOP=4Ob8&=c@RZz`BVcN#8@$G*kKYpg)P=k#>@x^ z7rXVB1=ZZuYFMK6cVl;vj&tWwGR`21Nr4`uR`fuQ?{!AAC&hp56q6f338_f)1VDuj zDc|iZA!I|+rXgW?F>n__+Y{H`OTHq2becb3~;btGE*t`fl0Me|Db@8&vrfR4i>fL}7 zT+N-hryl2D=J6JAXh#&Y#r&D*BhlxTCjWzmQ#}eU-zwMo0uiBJc*L_&BFMTboQW*8 z?@GZRo@?Cx4=3^8YA}q+LokS%`Vn%{qPc}+qvE!YVbn5TA@ed&ULB5oeXWIhv9X?(8l zc~;BII#Ed2FS(|QIqB!45C~C37}R=%ZV4$ftsQ&aLHJYvGBA2fG+Javts(yPXEsqBfJj6Y!RRezqn|t{%sklGT z&Jb|0eb^wSQ5LiNv|b9K?hEEC9jh|tRwSR)jZ9jo2)ZS#I74W|yFY*^0YCsx^#)*> z0!JR9xb`+QB~hTlgn|pnm0)SOp6#tSBRRIkt9Jr>ea}_bb6%cW_-SptMsXL?snYfl zM3oOXvK`(gI@*t*_HRY}ya*@#!5t*xecoG_qYkzOh!vboaW2+8R-g6ZVOFA8Sa9VT z%>~@YdNO$NEHN(d3)08A6G)|9>7m+!AtyusPI9#7SX^sPz3S3 zLlmz+di+8gI7SYRz75eTg`l{wLI9PNC39U^r*}`pvBHUzq=wtETR+e349*mHV-5Ff zt#|Iyonh~$^6>4iPQaQ6%ykOaI63&5+F{5nvg^f0_ZvV^#v++uk-$|e-3T#j0bht z5I*>QUNwHkeCig+2XCzwpoC;MU{X?SsH`kZ2c~Fk?(M!KOkZDV0G6n-n08n7zn&X2 z!Nvxrk_3FhJQ3}IkJT0eFgv1XDp&1!g34k7?hoDFG8{JxU>u#$7UPC3+>6Iskb&)k ztkn5RMd%{N?<`g>5_e~h^iC**YvoY$02$uN}kZV}lY81uj&t2)uq5;~sQkbptbx?mS+cP;MsZzN9}4 z2DYJixmU+z62h|{3vlMUFy$sHGh8gOSfyUAev^X}P#Jz>*m)BEJ}Zpt4W#ff)4as( zF1TN0-W*T;JOTIbi1aTM0r3=A1BxA>q2k5HjJ{L=7We#;~k3O>jM zymsyoqC>W+ozqr2^g}mkjTGXmhEMayLe*Z%4MVVWX!<;6o+R;|Y*=25dCTqmj>iQW z*Z->2zZj-J`qfD_RzpC|uXm1Fevw?uhN1Wn_qTU~O8^i;Hu`~LF5+Y>(%uF=(#u8Z&aHx{9Bb|%p?!{n=C!@JL=bp zN|3+8GOBis{$E0Q%GHtc3O@DVPVALyAP{RrkF5gUbO>;7)mW2zU$~E1fmqs(-2OeW zI41-ABwOjD05?uNfNh7?0%*k^46hx{Q~t<#iIF{l!zMSne^n_v@ya~y&>tc9zmW2C zwxQ%7lo1DLz4vZc1O${{&G3N*L4n;*#G$GmZpI@_(I$n^htq> zalXc8A+Qu~U*|#PrSlo1`24X{OqUXtQva-P^2y{J?hlFok#RWOG&+0>M4gNJo8n^A zXLw-ehtaw^4U}q~foj&!h0^uvB_eKteqC!EqvL{kLPQ7C2j@OEV8QQcZr?XeW%Yn` zJAaS!D92l;bPSvuZ+Hc*QpTYW3=jX-Fej}20i=@St<^7QDfE{F^VK;D?kgW#N2qK% z_I1P(7osxolS@<~;J#9|_BbQOTHa}Qmpit9t7cZc$gpA?AO199{P8!gAOdUnzTe?o zTcuJy4EZrQ?#p*Olx3fZMu22yW7&I(tn^jf$rW75$X6XTr8znlc@{fO`tgM`^^1yq zpWso~4wYbk(rRR5`LHL1_suA$r6-aG-3Bk|B_75qR{PpC_elR1poOHvunF-_?J^|} z5{z@jg_E;)1a-FH}( z)cdGTwZn!ljuw2r<@<OLKMS0u4t|Ih@_v5t=Uuna z|22V|r=-7TzWBA zAiAZu=1}83Jt88Dn(|~3_u5JQ!ve1TL-dI9ccW^jQrbxu!OWL5u`T$25jtgIJnp@#pc zSB7w9qdMl%%lpBX+>g0d27L7@GuYQTh*x{;820Q~;_ol9r7ixQ@v90qE>~L}o_yJ& zSN=oZIP_k^$4<91J1?JY@G20?HkGQt%9#WMYXS4Yow{1VR_%>N_1miLPN{Eu^!n=l zUIt<9=6{F!g{>eodocX=(VzSWZO4s1k1#gYw<*Rx4BY+j+=D~G+#wkf?U~Q@uToX7 z4fk-Fz5`5O!OghG^odSsy>l&XwZhJ%cir0pH9d=aQi9td@xhOVw$z&QVMX?q7^*sM0D6k7YIH%lzwHg;!Ao_(+M3@Gbwf zhfd!rW6EaT%C_4jvL$_${Il?G{UVJx^V11+P;{1Jp{M1OR!-)Yf277+>2_PRq%#h^ z9g=+^_0C)22Ov4GDj2uU7hXu)>D)wg{**B3yUicGwD)Xgz!gCxl__IA8H_#a>p*BO zr_yJ$%L1$_2a6G+YFTXi`IJm?HL7kM18&ny_C@QQdkICPP@fn3)VxOx-NxSjSxf7l zx~ll=afk7R)cFS<7f%ONGFTGy^DkjQlJ02bfzd5K$}xURkvMlN<87R?78#A7NNZf! za|J3X;|)xI6v*8FW)S#bX_~;zwtSs*R#H;9u+8mGj{nRMYxC_l)x?L^I(G+>zRcWJ z5iWeC!(@WFd`p}zt(-CHKSE0VQa61*nmFs?qcgih6K6i$Gl@{}Ss_A1C9KF$oYgo0 zYdXJkl`86rj1c0SloA7)BoTX#Roq?9V^-b2QJgb%1Ye-j5wEz`tc=^-Vl}5`Yei-T zY$krIO$uisE~KoNjnwS3%W%cpa{1~rGA0xA55uU_ugiIDIwc8l4nIAWoXbd@?$BD%0e># z^SiMBb$oXO84%4~PTF9+;`$Es;`vt@{8>$npnc9&6Z$`-T=#s@Mc9lR-^p*xGX9Al zkt~>kxB)ZrLNJSG1Q#cl!W2i_vvB}5V}3Wq<$d53({NXY9%)wfssDpKrhms@r>yvi zmBNj09TLML&rRfJ=;~sf*krRg33+`h8&(Hqoi-aYSS@v?@ ztsm5j8j6K0ONz}I3E8z)!7Dh~O_-{3%NM;zo!Yoji0mVxqP3U=F8q**vXn5EX>fuM z>^$aKIoubC;!*InmAW!Q&#^q+Z}qP?T-+7bJT``>&Z?e%p;eJjm#^;-52rLJPOsG2 zepo0v-aMuFg6OWVv^41~y`k1t1bGW9#l1!;|SE6j%U%LZCQ zCuh9GUW4W=RIl3#ZhSSdAij~Q@WhH~6yAaISm)Gj*-^=q;X=*lC+bt?att=d#G^Md zasyMEi&PwLTRuTiN*I?CQ?acn(Z!W`J~~qqN<*;V2_-SQv03@eE~YN!3sD za^q{M45hmhs#SL-y}mj3N1Qav&h{E{+>;}bF3|1TGRuX=k)_YpG|LvAA2w??E{Gux z$aV`{wNC&5_O48@9LdQaML=zwblxuNPw;*HU`P&L&58o6FXU22?nZY4nN>ߞW2QPtD%tLa$ErM48w{BGv!T4KZP?G<%=l| zC0*(u4R;W86A$LvLg}jcP`SRDY%`{sU8LCn`Dp^vtWc1v!i2kohjQfUrJbeKa$$DtgGUUR7Ew9oVPzP>+vfB0OVKLFRYaqaSW-tM>C-;7Ol zCZ7t03`l7S((0mON$l@iT9eX)8wIU7OFIoTaOpti@WBe%P7OGQ^CTg4|nK< z3oAB`Y@vqoZ(;4M|2`5yON?jh1`#=@=H!R4Z&yzovNhPcn>3?xaqa5202|vUliH_uqzx zJnxe|Q4SfmpIdQEDAlW;mIyXTq9c&12mm9hQp!ox?@L4%tA4aW<` zE8WBHR%z2;-7;;y9G~Y2pLD>04ZbFm-0gVClsJ;&52WsMOwX; z6y1+*`+SElIo**9IdYEIafO9fmfM0Lu`-X%ea@$1np}0h(>)t~4&?NwLH{^mfk}Wzvht&3f}@;_B&j&18aZ?Vsio2pwv5^? zySw=cGl z?W?GgY)xlXVUk@531%^B?PkzE6i3`JW+$&I`T=jB_^5%t3?brtcS-MQ%k7M` z|L{X$1-3&g#qbnvnv=TBl|-H9)tM#epG~E9&N{SQ<6nYlH-HEsMEq2V#6{kR929Ch z`#0{8aY6VGoP9v390jHZ!6Fw;;;!S|D{L(cQbzL3g`fLM&MfKg1523_4v%b!WOG1F z5R2eIC;*ZS(GaG6xB>^e-f~5IK#>Mf69N!>fIH@GV1Zo)I5|(>DQtDWH;t|?=&Z8t z%IF+)c?Y1GbcE`E*r29;8ioX@^g=0K5E2M+kswGC1XD7^yX?0~6-%7%kAw1y#QH^2 zf>4Ak`+Nl?(6Frl+6$uT1p&|?W(R?Yxz->sNQGE}0!k97rG%)GxhUZASICP#>NQv( zH_lYJ7}by~Q@$td%w^uG)DjFQ)hT`fX(_G_jb~*HGo^4-B^)JV4yKh0BXKm1Ve3S@ z*P#P6dnG&e1)Px;feh8EUdO`1fTDW0LK@QPKH?k1)EvPxuizy;g@RuQWpMx+Acs@H zRQB$5AaF?L>5Xtj{L+&aSnLWa^9tvGLQ>ek{PTRe>5Uq z0>=1z$;0Q4l_~(xi*tcSOdi>o15kjQhFoj=J-2;$sSJ>N%nFFtugiH|OywY#GZciJ zLQ=usgL%0n@Mc*<0vq+rB91Q_4wF?o7Is1d*gyf|Qb9wUa_em80e3KflSwCWKa z{CU&Igqgu?JV*I~fr41FLGK@<$2D(LM@G-*@F*0noLB+;hZdFqhV^fZjQ1hyp7+Ps zy|5)XqtgRr>CYDh_qiDbpG|SS{e|M-54P`8>q$f!@9v)r!`8hN4p4h`$J8;RD-|)e zk`aT>2x+_`hMHnW_7{?QsT|&iIRH<+Hh!4LqkN!veb5g-Kp1QGm9Am-BC$=nZFdhm z$>QaD@y`E22_KTM9L{(+biww((ysmZihg)A2)U+*Fg^0EaF`o6|7i0JCD41{IM-(x zUwwF#%m}vkzMapPEji$>kwvGz2{@#enSO%Xd5mlqllt zet0c8kq;`8VPeg==~^M#0~2_-W?ii*Rqd46 z@T}=sMfj=5HUUQ1(6got-h#Fi^lEB?sH~SdkpaGH(mxhLXe+1xb$c!yg&dzagMLEL zL|T7fQ!rHM9E|mWSdgXQ`+PSXYJ`Sr(z(h2M3u=Sw!blCLXBk{^Be%{#VMpn zcI0j3`09rVLp>UP!xu(7U2~PuW@JvUb!D~4X4q(Sb zCbqVnPsEsNN71tC@XH(w>GLs*Xib2(wwGri#bqg=%{*5yH2++R2lsFBXi-1K=e~gnMC4|ERI&($zhE!u;xr&9b z@!{N>Xnjs*%!_B7n-SnA1jLFXNT7p2G3w3VS+%Eg4Wjg*MZcl1wW%Bqk9{sQ(e$FY zjYWx_QOl6t_*xw3v-Cyy?8ePc?wB6Oe^+W_m$t_?3NL(bZvHv>?_zuGgnbJ;^xn$L zlAnKLDaeexud$yUWe>jn%L|ktr^28uv6vPaR$eO!wlsSvJNfY1Z@i3v8qZamS6V-> z>^ZNpDz0PKyxQ^kRT=Z-GxO?~<~3U8H6P7uy_(man%DU;uZvosJlLT3;r4yQ1p}wJ z%^nM@BNvR0FRaN}Fg~+ja%sV|Wx?#xg88cji>ZaRKNi-mK`F@>EY~brtzR^;_FS~t zy=eR4mO|uFLfqo|Gb-`IqZ?WlZ&WRAdbPNDYS9sO1uWBXK%f5#9Dx9dLi5!C0K5U7 z{@>`qt~7^(V~y$ks~W?fmT##3Umt$F@4R2j5$#QhpNG$ytvaIFe7OI6w?-h{#erZwY(}Wr&oA!lZ=Tz`;poiE+ecCBbnc({N&Y_Z3QTizFLwEXKof~^^M-7x&xO!YWYfg>*PK$Oh-F59>sopmE%b8oNCZG0}Z2mIh zf3fZIF5jyGt)(A!v#sE`-lq>9q^4232MgA9l7>dDCEklf+ZX<~hQZasqN3f9Ll^E? z2jE&k`CrxiENfwlNo}E5Xy*HeR^=8gO@WG$@jeszeg+^o=P>^yjOh6DT7<~y5BlH* z$7MA52wcAU^1;JcYNr|%xwgyOW5CV&X_1!gGQ|$B^b%*)wLExgNAuD`rh4=}E~r*y zg%+$~3G}DdREwt1o3lN>D;M@_1^D=VEc1K4Y1hE5>O9!DTf0)SUi&@Q+~#3=*)?`V zKYv|U@Wt|?-HCm^#n0Vgc$-zoiGGVlnjq4g$FKCz)ZH#WooUq67IpPp`EaH(yJ#*{ z(Havml;ijBZRG=-9rQo%IrLZ7_1y92+gm=cf`CJFG^fCq*uwM92KeIg#64si4GZOn zb?<`5g)URZ@ugOe?=qVd zK`sx_N9zfUU2YoWN;N}`+iJ)6oh`9aernrwTKR?l`r6{>PJJ4~c}~kx*ZzOBGM*kl zmA$oM75eXAA@&W4t`4MkGTB$mYqQ5QuOGj=f-z)r@#$La!{|M`{)kR^#ff8ys_y4T*7G|pLiZ8jizj%x&LI@T$?e8N2OO}C+zo{h(F z|9(+mnf`l@z_MbD%@j&ukRQkm(lOS+xo)HQbmdGS?Vm3zy+1|<2=ilMx=Lofj^FhR z)f(${-ULE^MYM|kT%)LUkd?n!#gh@fVTXsvXADFKmQa;q5Vw#8TEt`K5yuH~jD!b2R66&!Id>eM4MT(sIG_8-MjQHZCW%1;< zWBU1K+o_!d4eKH7Xbxr4c-f;Mm z`?Ee{^OZOte2+i6qb@r_q_-;SDGNC^f3K~yj;O?_5^a&-$$%XYW0G=5Zgq!6aFRN}b-v=D9#xON8aTe$mc zNM3wBaJCw+2|-eU4c=BqI;eEdO$fK?!c(d3!UON_VKC0U&S*vQdHx!QHkdiB6D8wd z8~_fsAh%OxErguwnenyxu`*@C&!%KhrD(WX=Xt1}i%Jpw#M>^C_OpL`kaS;tX_W-2 z2Rb8IKRFPT-sdYnCoBX_2uwFWF`>KWEGr7cb^Q0wW;Qh*;V9IlP zSxBXOqfcUulJZ*mivV|66_H8p$cIx+%pO$WnT=_bo|sdq07Cuwv>#KV_~LteQjg1N zW9t5t>u{3Gxme70yWxoe=-wfhUZG~&PE~A+RUA&Ay)=#158*QJm{)1ttkH(B*a<2@ zV?Y6`P$NG9M?!fJ|F@>`u+H&7KUvGz<0kzJf zoXX3u!wodM=8bQhamL{*%_6+AyOlo4c%I5{KArA6j%t-4?|Y2vmK!53h*1C9+Jw1$4{m|>vL z^>*%l8{cEwtCxGYDXo2(6F4>L)o^_z>`L;1(-{2$Y=}*l`uoP(XLHBD&MXn<4O;dZ zsdQND(0(QWGFtouAoOPItDVq5(k>0;q&lqDNq(zw2o5#;B{BH6MS}+0$U!|yEVNfW z?IB;^rk9f+p#8)0mzxnzaW|DA9r$u{qEBG$_T4mpW^?? zd@emj-T)w_aNyP+<3)AuJPt$wL#z}V5g1NADp>XpV``V`s&(1EN83-wJ*DG6&72g}0ID9ETaS(Gw!7G<*julDPY-)pa&Yz$LX{r-#UR9wgzAe(rQEVO z+lYJ8q6OyF=Wg@xzLwMxT~P3-E&>8b*!%Ukh-0gFE#M>p_->Zz>4AWA6`*7i*_jBy z7(hG|xD!so&;YiOgsj*7{UYO^<&0FJcN`k9p(mz@(faX8@OVWDB|2H&KoBet?_RV$ z%C}8046{*zC{~a(S!!esq^uVLdY;%cY==}G8h50ZrcFVqG*cChG&17=7+jR>}|n2htyyeUD92ljW&# zNE3mYnk>MPf?C~!E+r{I7u2-A+06O62;zw=Vq<5hg}I7hogL|h8UUe@P~bdp@f2J! zTdoIoe<64&fDyq;Sy-)ak+)%af2_B(RbjG0H{EU-M9e(>MOh@ThhSyUSlY?uadHF2 zN-k2V9Mh@sRo%EiT!*#@QuN&Ge4HR7e)1xzv(oY0)A)M8d_!Ux1uL%5QFFo7LapB~ z1*9+#Mp7_@Tj-=NnwbElXnu#l*H?;rLo%La8QAj-Q0d9vWI+y9#wsw&-7`gh<}>B3 z5TgoYK11O?gTjE~?n={YMa(R)_e+7|>ACV{V!}!R8AQ-TuxJLVkwu-6`TLIAHf36p ztw~KQL}Ryg`g;iN-DW?SJFKRV>f<)WH9ju-5+u`EP8byhZ8-@xq~HOK zAh~aCa~yDhl6N=4a>AJ`c2!;Z0mN@linqH{K2!I_?JDu4e?^ID$K^9$lY}p+o+DXZg595YJ9^Ap2 z%f3aMK3}=Nfz)7{iS|0JCAl8?x(Eijfto+X{0srTesBrwf!IpD%E#j~rnCYrm+gGC z=w}X=QIoE{ayjE7O7y&qD_m482{W(DH;2zh#32*l4ds`2-_ViON1B3IY>`|F(Ph;l zd~c{T8q_HbC;-?{j~$}AMPJra_+G~6p!y4}5742>*1UJs z@UJvLZp*y?*kwgrFK2N)e?a822JpN_*MLs;K@>>9w!00JrX=IbO)G&=Dh+mkil40~ ze3sw`5;qy0V&+oNi7bc16a;;1#pp^VgRX4P#p({P+4@398s=i|c05iH{e#{#7v7}2 zrU4*9H%pKOzy>hfYY4*`uE*@Ghj{LUXqrK7Wr#2ds+rF7Q6+w(5SLlRc^Te1XeTDZ z?HsF_E%URXS#*wO&fWsENglW)|0_j`Z(Ysddx?Ys@crDMv4wQbI!+x#2LWWiXq(b8 zRfk668h@gUhE0&7o5Z+LDPe(1+&HdUxy|s(#wMb?1s}EvR~wJL4BRwBpqbJp9a-CK z!GE;oH>UsiH{uhi`s~=|f8z|!O$6OY_WZ$0fpU}OH1W+I2#f?iz%y`Y^pwfOe5meH z1(7yrFmsuh)U@rufcdFL)kR8svupc(8urg+%#TpGs-%5(@syerSW83Mcs`)(lRjJG zaf3R(ijEsk+kU#`iTc(B)g#(3L~Hj$$~pMzp1U#{VN8lw9N#=!VX%47{6K??QgzU& zpyX3k#5p?tS$)>Lef)bjv~hh(XViKBJrEDD2zOOqGQ9D_!kVseojZl*@rKDOtP-L* z$@OHy!!OVVDQ=V+G)2RQuvyx?JMIxvh9;Y@Me!>>`E7VXC z5XSlL%%0jXP?-v0P&cn1>v45u)JM6Pplmy{QOP)EI!;+3IiL`2$azy3J!h! zq@)->UQhT=t5i~c>Yr&@{wat&Vf@ga_>qpU($_9k$2yS!HG1y&Jx4qpcD7k`nYs;} z-#?QP6Y_7pt6nuDmv}5NhzjAEN)yB%Qo`Ne#PK_X85W`Y9AL{(5X)A>)~r9v#l5Q_ zz-)>3ZN?IpbIbM7>xy4oH6k8KAbt_yD?4%Ood^tdaLl`G!oeisKHx}Q_aDnC9*lLy z*?1os6zg9=5%waLTud8&`=#&7w$dF;3K7I?@)E} zQs|Os^z8Zj!G|^G81%V%{40_hxI73G0T-hnQapECbf;m6 zb8?XqI)gC7Axu_K|D_W~D=6I(lnw=)NS9tcyz%9RL=Iiqnndq#7|TbNI>!i@bu%6?J>}^RK?9>`t6moH|OFWZ~107$Z95!`3o*$LrHBW%@D%M;4nmUKaU zdvy|4`SF#^6?X$z4PaVH>YJPuLvLfxF5t!}#2E>pJX}}u>)lCT0!NPkLYZslO`Mx* z-c#`XVvIQzc%j~BwU%VF)SeP=`qw!YQ+6Dg4q(-KFt z>ru7w7o}rqa=P~C2K;9ZZ-gwKqY2 zQ5<1>9v4%;(!Q$3>m4*(@2Cf+FR$Y!-$sM;g@MMZU zp7V@1u#TvkJxfcMYdb0UP7$-!YTKLd$5T>y?`imc02fNsF^YFfa&<4SKsz#ko|T2f zuix+7Fns+O!I#DU@YJ^_s=!^HKF2vZUC`o2%SMgEw7%kmO<2!W*}4G0g^&- z)M{GFG2(fZ&sD+Uy)Chyz$nkE*!}lYe=cL*{_I9`q0Ox!O^$2L(;deV{d*0R5(RdBa7qz z*^~VKz7rDx3qJC$E$XancGT7DzpL-Tfzw5O1x8+3(a=tVsi&(lG7?DFoK|Sisiz`#5sm=2qT1SUNrp~jc8&J9_rzbow zq`uAkbh{4V$LSG}y&Y-{<3U0>`?cPsvIzSbSCN-ZNT#xv4eaJE6E?epk2j=q0EEUg zqv>yG_i4&sEqfZ=meBuEcL(FpfEr5EV3K^JJYN7hG1bkqZt)GCwVvGmJMu!x5=2ly z|2t~9%^5Q;=4jD)5%P2K!*QOEK;RCg6X{|Jzqk2gg=>yUJfjk>sP9FApsb|Np#(3B zq9*5tw+k0w+0$tvy&#R%MQX7P3gi%@+0R$&dwvSah^|@<-Koo&hjdfhEkEkIlNAr{ za>f>Qs2r&1nC$X6mW|S3zqgFk3_W=EqJZSsOM{wNP;NUV`mNsjn#>(e;K6~ESQe``VN@{r9kJ!OULY{MP$+;B9e!ao7EV{TM zT>vaAKiyY!vuxQ3qp=Z4w_|1*dhZA=sOi}M7ZX9Yy&JvgLwIO1rFBeT_O)EO;MXPH z)RG{5l%fVxUEYIJ3k*@twv8BmlY95rR9S3ukf2ygNyZ32o*H^5`i!LrN~CF><@X}O zDx=S&#+;+CKhUsp=^Tr{d0ThV*E@a>|9KC+$3yG0em%fxko1%oqO%bLW9?tnKCVOWc7Y-$7(Dy1= z^_TS6b>^!jb-U^;E_-fzGL{pyG!s)(upM>0j)aQ=_%;Qq-k2L-Dk$u*3zic_eGGRO@*Q zWbKHv*IB8X|G~wFsc&mtVqU)!1TW_i^`34&97F!zSLt<^Ed@eG+|8fBDzQFc8iVW} zD?yyncItSHI!V`Ljewh)0DAN5!S$%3(Fof&_5`-%L$aSoRgFQ;!##mR@G9c*Yp!S9 z-JRURGD_R3v;?}^hQ z#Zgu3NO|wBKQBL;+24`m&BzXBzI7p;bdXge#{eL@FsqlPuPiR<*)6uhM`{@qovU#3 zj7#!MS~-n~9qFQZlbx*R%+Jb~HLc}i-ilA@?(iAZ=8|L*jx?^u7rPqnbjC$BWopPp zJyykvxSWll$}S_%cRn($L&t~}*d(|i^jqeFWL&q!Ym5(Xe4dKF?waa$O1@`=cZvSJ zI_HF{5Cu@u_gx%UE@SpkMe}))^)u>E13f&rdLABZ|C=T014s=~+Imsp0b~Q-nU{zs zJkCt@TD+op2KFY^i*{?LEPb75EPE&*OylV?%C^(8nRU=rqgyDja04Ldd&RBtQ5xon zxSdwic|hPUG<#<#Y7|o~_8%*CYBv+%dS9xH_2zDPHc)pY#anxFy2p0^mf_rgIPHt) za}jnVu0D`hB1gMF$l^Ung<~5npJv2g-17E*1x0OGN~+FXCLF6s(|SLGw7cPpj~4MY zc7t=Wzs{!c9g!X8%rrGjXnC?}cSHN;*G^Kd+efN-VadB~ghcrOE-E-o`@8Is<77UF zq_${|wjyn7AvqB-t|U}R!|_AeXYgbi{J^p&qf6y{fzC%Wc`xXYo6kFn?$++S(~Hm^OH-zWUrb_ehLEzw3A*JB{$n^s>p$5RHW2X@Q0t19H|^ zpxx8E7;_@*#`d^R?w$r3!5(w**8xBs`_|?+xbs^(hbDj9u@*XN9bqAXc-BqmOv>EX zQ}+{db{jsdKj=~V@iopyq;<^b0TyK_hHZ5F=JepG{rB!GQzh0fl6WP^&6CcA__{C) z;Jt@ky(Rwre!}g3VUG?Vf$Z1UUN`Fk(fH0l7t1d_>n@)?9ybbcXXLhwc|B6>x}6iP z(ynQ62x-050`Gq9KGgI0U0=7O>6?LZT@gE33DtOHymlMBw8Yk?ZXhSJANEikY8iFQ zVmFft1#|-Ue=PXQSp@>Je0F`*q&cYxEjN6ge1?Mtk8PCV39jnn<70QnannaWsn^J8 zZ3pGwNx@t~itt@jBGF;TVEy9#CAX-%mN}`SYV9TTD!V3crNL)=C{L#mSS@PGJ?S9I zQlrMXJ!`ZkH&o+3IX$8m8OH?4IAp_B<5tt_kqqR+MFiQ4bGq8;o*2euXU#~jq?WYx zcba4B;L!jK7=guk=_jEx4w33B_8^hh1SuP@qZ|Osb7Ckj!?FO_K9WuvF;5FZB^hU^ zo~U86kk>i|5nWdp6B@dj-s`#I2AO~R<+`So^kpyIfbIhWa zTZfVbK?MSajEev&tv`12#g5MTs1e?2`+J?KEC_?7&!(X|{oIkiQSU?oa80qwOP46- zaDLS_Uv_T+`{yKg01bgmbD5;ZW4!{k#VjV%GDr$l1~^DGC?ED<2CJ&uC`9oUaZHX0 zsqlDR2O$C24+n6)Jw#(fY+%OG3goVC(LOqSEeis%e{>$Gj6CQW5Qi>H_S~gjcxme` zIrvucneA1S=5wb(%^U!wy8$Gylf;3N0W}%iy`ed*&PAC9CX%^m0D#qT1P3*fqJ$(b z^y)H$3v{qquQwz^YQi6*$UwRZ0AJ1kK+P2!(3A4FPV>}DI4Ce@OM|G40FXcc2W+c9 z=|zqbvI|#LwDP#D3#r1Kbm1*5%J-H#8-CT{y#NyE0RzQ%k{y=y5D2hE zfd&9%h$#tXO8+mo{P!&vvkYLRtJzu-9^M}tu5+wP9Eq*4SgOm`r}zS^q3Mqp351VFLM zP$CYQ$ulJR+RW{clQ^8zz@3o8JGsnFTqZ{qNTc}jvHn7&+ru|v#L}KMxC#z*gllX( zs8`3Mkhxz=?_enqBifLm$bU5msny+l$se-+#^D0}h-H)k3EfRXFAknP4-xpiJGY;9 zjV>8F*2jU?LtOu$Y_!32^e|=`z)u67FQ8kB{6VB@O$mSjD$BC{OkZ<+RD}d%;iY9| zJ~N*hCt{v_@j*psND{hjeiA&#L3wel&%ZE~KHqvDz>~JUatPp;_@ztvJXv}}=ozRO zVoK(*-2IL1pA5(Vq!+|c91s)EOBM4lLg1+F%Y?&&?1xoZ!`x0VCGC z4nr=K%_#@A3A{LOe9%fZ=#aXGcjm7!AnZ26rAVNrfx(I|d_jpNMaVs8!KoB+R$$gz zy!Sjx#~}a?+bnG1U%%M;Sl0qT16*Y>gd*L`xV{TSDm4KJD6Bg-ixI*1aqS!C()P#G z1okvo!L1LGAA#o?BH3@e{91(rU?nelRC3NAK9Ek$*iVJEgmLQMatOTux|M;n z=YXj*B??#9-J2Z2DQE8lsP)R*g`gsD56xOZN5S7&l{n2IP#FjYXHA3tPT!3HX}pRu z-n;31IXi^i0Kj0O?6%N!(f*b<<9{ita*Wucbt{U?l3GSEI!b7_Lo~56&i&t<^=v`w zZ{#2DL=_W%ag%n-b-+vweQY_yM=8VVZx~+)x88pi*E;d)P+A1@w&VVfsl6XP9MNy8 zHJjbWE5#hs$AB3jO>elB)%(%?{lV>y=n+Nq9`^2nUx66#0E`LUUTPgM8SatzX-}CS zRocU4PaJT}iVSzL*2svXPAY%@6cMpEKrqQHpNwvvJk&E8^K$a=ld;GtmfBRD z(Nw(M)KQPAgn+4I5mSkYQ^y5U?Bc1U+NtE`sS`$1w;x7ceFFxbBT~Lc?%U(iiJ#`# zO{aNG^8=>SBc=t3Af_=bES~nytewtko<3!l6VNlAGdZ36eL4?0BYHm_sTM`n%Q&r5 zSl}^Jgj`P?6Sy#D$dC-rV17w%{>EET=0O6_-kI|KYvR$*gP9RI5qtfYX5_7S;{V@Y z_x}LRTzSmo(YD)WA>zhhH~EkAThR?-p8jSRa~0?%K@--3ot{IM7gStaOQ9 zd+=Rb`k^z=_tR1!Ff}ll5z;NP{Vy@xod2Qktm~s2pydwq)eXJ+&sX>B>zxx2X(hO> z9J&%7*j;Q9+;S4Xw;8;1FtuxrT??4oH#B2}mzwz$r-5+~k@?c3@ zI7pm@tU5dT;>|#{XY}y$LX92%^{wzO-pc2iQNNP)Cn#}pFzOs&9yC3$yXT~taU`QF zH>41G`r@6VpRY9+|Je9FhX3bDV&3M%0E=^^eRZ9b2hXg}T=%f!IL@lixhvmO&c3+H zbI>jAmGu(}61TQ>ME_LMT^qGWVWljqtx1zLr?Zl#2CNi!&>#r!ozL7R{MV0p-_G4N z|GP^!rcrz8fYUE&SKfO3?=(u9e?Zhr0E($9p)Xi;Wm~K54-CwB8TIkW*$iz19QD2= zzRHBvV+C?&O%0xg7Rg{DxF)-EO&PVXQ77UQW@5G9s~F`M8?JN=y>|F6z4bg5Hg6r} z^p|mk=(y}{RZ~bi91L-S}lVc^jJR(PT zhjPG$>s?UB-*3TxE&UfW_M@*dCBk52f51VwbAAoNBH zO?;@P`DM#3n?4@)$`hI&e#^&;wFeybd>T@Hf*h59f4*M7see%#9TEk#_=L7*ojef1 zKO8+cy(Y9*C*pUtfEL^B{OHfMtMazlT<_CUHwrVc@#SNM1^F=TFUzR; z&-26^RKD)HHcwkqfTQ5}FAv`__*B$@eGW{JRU1Y7Yv=Qr_Y~ZyK?T=YstVhgor+o0 zT{^QIrz$9IyR5goipWbHGJ__d63 z+8C6_E;+5k3oKvNvFuU6_UR|1Jkt%f{B#HavD~br~^y7MZcW$r;b| znj{=&dpo%C6xouH-<>3ZWeEh|AN)>d|0SVUGIUKt{llhGy_`b{)mqaMHHS%G;>m6g z%B@QEi_KMeUe3|#cS33$Q8YOx^}SkK>r9iTQIy~F#|mzzcEraS;Z zRI2|_Y%lYCyPcamt}*20??-wQYn*KFL5OUM+soYa0%qp5wJ)=_8jZ~py|~!&-Pbal zrWO1C2{hGRu0uKeQ@=IkYYc!|_Cz~4Q}3W*HctbKEV@4SeARZ{MA!VVCYX#_8sMV9 zJUqgi16BVhM!5ubD%Da2y6@?v3T3#?c*TIWkuv@=Y)AL+N0~b=x~zG50_jD~EJ^}7 zvWdYcC$h094u4R0#eQ}ToZ(!(UjqCoOmpKbWT#q$?|QRIZ(WE>c1X-6MguL-NdGm8 z+FHS@&pC`h(YYjfVFld0q9f=$D}5cma{FQXNvks}LlaB0{D9 zRU{sNQXLFcuW|l5PmG^_(n#(ebjrL%J{|ILmzql*^Ne$Lpremk=_35)V1@wnS2xyc zi(|t3Km3MP!1U4eXm2SG`hbE`!^5=s(?Ycz{W6)ez@~frLT5~2 zac9QnX+^=O)vEWN|Kg4F^|Qmo3ip>yhpv_k?B9E5wd$v%-M@M`(BEpe8+Y=q7sAIM zDxIth$>Db!{q6D(f}elJbPGJVM3;?L%oOu zPQJXx##yUBFL}62Sq)_$TW^z2DE|>RKv(f2Ox!=PaY-4>o#;+Wkd4dslL~!Ytzinv z*)9H6yZE7#W65Hw{{*?YL=fZeNGe7h)6^HO+y%sGflF0uL)*5cSC@7Qdh}JRX(hQR zleAv}S~Hkvj-r1H%AGZ?TgHClw8uO!w)LR;c)e$VY%Q%4r4)j>$#Cgv3G0pejvbV?ppEjY?g9Hgh%ffZdiu@ zC?kHR5$&q?O}+}L<`dnk{;AmMY+Hf3FC#Ke+sGSnuPycNGZfasT_3H6H$L3@^96(< zK_=4BkHZz_ENxUyA04Nt%EbHDt8%NBh`%UAH8vOII=0I&;FCi2d8Ha#++i!NErwX) z6oxNFf2uw3Cvvs81D5at1q)P&4e?kQOZgz#hi6)E>LvYQ5S^K;6{Uaz9m=jqIjU&( z!CJp4U!jJkg9$@`Oc=QyPyi)#R3YD92#o{aBH^EdB&0+bA{VUwqnhbbtf|k~c>*N- zq`R9rrj?fK71#tB)g2G#Dhv>{YIms8A(;7nQ4Nr5LXi1_VCXP`_&@U=&}CHjja5o= zW!J;?=n$QHh$;gV$U%Bbviq12B}q0qKkM=`QDUDn9GEjihTv(=4iwaN1D#5do1BE( zuLO=r3_pnpd$`0E($9Qc3v6t zuQfsk%@r!DH>Fg5cGvSJ|mnqTVxxfHNd&p)(G z0`WQUSH_LHu8FRYUC$VAScATW$pX*`VuT(Ef}P2tNBOH$ip+yx-p5^`ao9(saA$o7 znT&9K%wn-ZRbG*Mu{GRL^$d0#0GEt5B89s&gX#)&0tuBu+9;BuQz%|G;Bi6%>1~B% zV)m;_0AspOEJLB2j=$#YxAu78K0C^jT0wMOY=P0*iaV#P&Z>bqQUVD8(FPx~?R|T% zw`^A{HxyeggV)tCo!wogA{%FpKKG-ACoh- zE5w~arK_cwtPrhcD}{4X^hSRt8Xv`21i#6-smD<|RG?W6H%<+I2Q{&)CjQ%W!LgNS zs8Hn?7&WR|`d|%&AO%2!6=)T+`gs8zQebNW(PIgXL<-LtDy{>EFH1260GjXb#PdI( z%E`muId_c@5i724ppe6QE!fH?CJNk7Q@JOtw^kY+J+-0Q`gJjeaURwIIiOIjL#l@Q zp0_+Jgo&ZeQoK>2OEJv$gB_@fLyin1uO3H`D=u#9yU1t)RKS_;viJh@$;Os$&4nXexOIc-9{bz<~epjk4-MvTaoCT|Su&TOiPhioWtLdoT1Rpce#mDyfKNIrh zR79hAQ~VGfWn=i|qgD0C!0}M`&4DD@bWN-m`aPXUFb?&zaR-qs7XC-22 zib(r5UWVn@mw5n*qAj~UE-X|KrWk}zBC9c0$WNJSV}r>GP*tGcxZBVg(rNgOM)>k` z^OH*z*+5}}2!@wJdZ!C5PdWRq5S?U1gct59fd51`{46GH+D5FO-_rI&_uG~xU=75W zp&*gsr|pT86s1uP-X~%ES1D&*m!V0NNlE zKH;px0?as>ua9dTn>P>@>tcsng4e9wr%?6CC~@ZuaOn*ijxR0?HN4qS_QZ}jPiuHb!)rj4#SHyyF_d50QTNN;eg?vn z5zjIdvrw2;zRQ%Pf~kEG^z_x(QSJkR-^^Ze%@ z=HT3O-}8E3uj`_oJvthR;zAoqN$-EwUxbLfpy4)aadWl36?5LoRrpbp;)-E;KYhH~ ze{EbI1^z8&j-D)%D5p>|DgzioJ6nB?K$(@;7qB+f1()nw|A|7fJ1n#*h zDvzi3u|X~l|DE%!I32%9z+d=`8=SyNrsEbV?7aa(iPPBE1nfpS+My64M=9Z;`y@&s zf|RUmBB7Q2sE?E&GKaaVOn56K3UXJnXYiy6(JdgA&y(?;rIYd%QcY15=Jm@RR}dfM zU=|4YB?2DTfNxv?1JR?)?5-s)R#^eZ(3g12#jX%>uK~p#Eg78MU3s_h_OX@U>6J!5@F=4mNfwf}U-C?zS+SY;C>IOj zTwmHn-G%Vq3UMAeLNi2(Sr8=yp6iZbCOFs+MC{WHID&j(Uv7!t9}BT|zyUyh|B1R1 zpe}!aV6~3b=xo9Jwx9LJ?^hsve}el$DDORr?4$cHDX6QhV?KPsekCY7U&R05fS0XM zfxB#xEXiIF6D@?%Uc-P^FhK%jwBiY6YAVI>0ti;`=W+2cQvn`TQo14n+94>CWEKx%~(4rI47wQZ>9{wpb+00~|-#*e|5BY5ZXL7yF83IT?c~RU*Ms zB>TwX6AvH)^yh-DA1o$v1=x^4ELSHKUT#SREB&Z`uDQ`szuyqK#PFj)fzXFW_ayr8-@cci1wm!CjXRFwK8F~v{=>eOYc?S z04?XCFs2G{9=>vEV<2#k0roioQ&yyf*tnn*Yg`1_h7I!TvLP3e7KJY@9(b_Gs|EDv zi08V5Piyl^x`cIvs&c9N$&yZi)LrMMgYG=LkK*uk6EWjl>_-A7pN;_axFv)l<6bU|#Y+dYPk@SF4$MmrJ59mau4B77$Xu4W z(nFKpTl;EkkzbUYxZC`ZRxoX96QUi`Q(5hDW`z@0g5y9>(zuRYV+!@3L;qs#o_w=l zLC~`-etCC5Yy?cC!$99f-c8(ry3tu0CchnF6N=0wptg>o3gggL0F9-W!DjUn^+b-SCO;<;UXxxx>o%unDsd;Y>5&jS<%! zU>0}CB5`x6@@)CjqS`$Nt|2QKicBa9fitBQGHlZ^Vy59Ng24hD!*lv;`~PU_`ckvJ z1|IS$zCvaXeLmdc)%tg8pv+6cC7f65ZhQAz&7I`MSGRww-JE%tv~%s}ytwyQFoMhr zGX>^L^dcrN3dl(4$@QN4%swW3N(%u%amw$@sMg;P^~u<-i~5a!r4H!GCiEzd6seZh z|9!N5`s#(7$piUyCx3cK-99>1p8oqn{y~?s>c3mH{}hN_AGm%nCB7duY1sLN$8IYV zzxmoL@N$G%5-;-@cNq@^btrXjt|p89C}7kk3*_gbL*wso>F{XOjrw_<-QGR?ccH|LJwDq* zr9N%bi}Fv?@8(t>`D-muoqX?C`o*}vQyz`yZu#rU`BBzGt;P3U@!)ezG7Fdbvz4Q! z+07PIlMX#I8w9`v?YQ zlL{|;lQ*Z-RL<; zA4|vmbk%Y^&0gD(q^1(7><53xt~LfAG`^*T5ZTH=fUf^CVGoD3)_bL-9ml~^ixs#E zIJHoFJU;H@T;sJ(x5I`m=8&<63mM_nCq_z|XAAtV%3^o~0@knO`+58Jg5lDWt$B`}6Bf^m7QFEb+^+B=Txmu0c?y zpTpp4TfakVDckRpY^m4$WR3CXEj7OWl^IP~M^&`Q9)QmwaFH zkat?&T{F=nh6KBaL5q_(ZD9_@C#rX za;b8>IdSP&fW?zgfqVSN&vS}Xw-5wJRfT)aHM;gs44MyYgWw{C>C$%AXCTU5ugkp+Jic*A zW|<29-?ttq1?(hxLp_`6QUq=Z~y`z8Dg#K{A&4vx#31!`PVc!DQPyx z_r0RXNT$8RCKLkS^vsPhXW=OW{lg8RE*g>VPMQBG_`Z`Ovy>q4`b&pZto`1!WV>-N z2bX(@^;Q0u-LOHo!p#$W5r&T=h7EkFkUibSkcy-+xC!`-_-8PSN6U?(8$7BD{VJ(s z=X{4UVEVX&9W`wG#D|(yjB%pEI<|(5+6Aw~<)U=Bye$vYTh`dyo`V8>96JB@$m6hk zEimaqrpz{5v$Vp-xTu5hUAak;hgT+6d<)EDQ+JQ9!NmE zvj?YCBaQppVz6bkDR!DZP0pWO$hv$X!XuO5MlU$T>q(Izei=4?qnQ^$o|hcW9L57I zMz4fGm%z3>k=Q{hUH+l+YAa*Tt}TCUC`Ilk>GhfLYP#O&nB*Ec!~6@wB03P(eBt1< z;l&tCR14(dqwSSA)C7b78d0UmKFfpiS*W35=sd^9Sz`B3eDc;{i%^2C@u*CABF(VNyv}dU)8s zV=Xrf86x>^jnBEXccDMavZ>J>yaRV(RnFK$Iy{ z@?DXG$;cS)OtkOyw-sH@FMBbEGi#v@CdNV`GG%7}1&x2G7&aaV3W|$X8m(yTN>Vu& z9y&@_Jc=`UX}4VvUpSmlklqLb^s&JSP|2ySVe9)_QUTZaO#HJZ>E_^P*??siy%} z4q$;--}bA!UM=z?vwmxmf{*+%Z(F_Ks}}=U0Kj2}orKA7NeH7i*;8}y?Ve|*aDzis z0B=`&H@4<1A0-;`BWzB-hCn;YXMmr%-1a@ejQ;Z63n+MLNUu48eqoouh>L-J@9G@n zNfe0jW1j4W{?s4*3ip~b`+dMx&W2B{u0yXW9bo>Kh;%E;JJvg|gLe-wtnd_xvKSPL zLR$0J%Ki8l#}AVxGo;>RonGxr@%cTt;P$r;c+H!KK@+S4KFs1~|BkPHkmT3p0(Uk5 zTcwBV6WJd&=o((&j;%PrZf-WZlK!^Yw)HI>CAbYn` zolT))%K)D#APhoL7G1W#(I4w=E=16!dhQP_r_%^>WfDlY0XmLT&quN31La^~ViRD% z5&&sa2#D&y=yb$C9tBWWMrmx?LIhA{$XxGI`~yxVVT+0I6dh=(iOpoiw$b@1Af>?& z0fVbl8$K3Podm#$3I|p^gD45e{14`2zO0k9w~Z3@%uanvJ231C;niO$yp zIK77^Z9+9Ond%^`0i={=(V6D+BhLI&Ev7;FxC-Wx zEc;hya!Y}9tzQV2LERj_JXZG8)-Fh=(I^-b6$QyE8XZgu3Yn%18o74uWT05Uv)%bt z3)z@Vx+q257K~D_rS?MW%Ba_muh}dOs)O{=6B(!q8!FV21J9&Gogh!#n5tB!Af1k9 z(R*pGyyq*~GGqx`8sE#D!qYBQT0!PfwSCE?p}q~JHz(aerbdWPKN2{EA~TgqqhL5x zll21A0&p4}W|L5U+cn9=)V?tkWICkRyv=l|~4bw)2;=DXV1E8<#9>f9;-k0Qeii zWSONcP>~-%K?NP`hKk#xR5QmB96FZdA@d`mnVOsBG$XmM1n8A62&RKhd(tn8% z3GQ^&KYL4^+z?wpUduR1L$Y0!!8?;Y@Zi@Z8Y2p#h~(I+_0rNI!@i zHw^=ziVQ(xSCw{eQFTBtL1m8s7}MOVW640W=x7Na8~#0IWO;j?J_-$UGzJw|n}!x8 zB1iV}6CujPF(LO+81M*3V4#rD@0%}@Bbcg%V_3o~>9E&jG{c&m3^y)ceV|}K4}Sm^ z>oJ+?%;k$<)vmm!^8pZLjz?*N`#)74m5u!=S0ei8ZXDSWm_ zey{)v+9netj3DpmV1N}}0T4Ma)htJqGnvZEFF+zN^xUMJ6Fu|yB!8t_fNUQC?{(_!Ps$QT zu`+hfhokIkivq#5*wTdTt*=TLf{%zPLzc{hF8X+#b8j_vQ>OnTE@2V$JC@|T@q$HB zh{r*Fdj`-;RDeK%#M?2oEBv4EF{LFKP^1_=I`DBBzR@XTr0j)^HVS;(f`URnQ-}-z z%}{wpj5r{`qGQ-VL~a0YVln$z$$Np({(K87zhFCAHz0BJJ&RtN_sTvQKgoR25!SH|8G2s##ZDV%Z^BZ#iP3E*3_MGbZ+oaG66uQ zXT|xZ>yLD!_u%rk1WKKXaX&fu8GhZu-9mqnXiBN*jKH;t(R;r#lW9OH6(*IAVrTBh zQA#gqx3{hb!8(IB13xOIbCA@m-=T9Aq|^*;s|aj~`gxRvdf&$lWH}j;yOW_c99-f1 zsv-plUZYRLxm6|{lO37)b9v8_dzg`wj6G-P-;gI-L$IX25DtIF9{2)TY{6P}!Nz34 z)?vYJ|AKw^g2Sl=$MglK@&)In1()sx*Wm@XHw*4d3wwVqc)%AaVvC-ti(c@sYsO(1 zn?;}SFsaM4`}Yr(QmMX8i~ik<0mF-dZx#0*Quni+| zUqI2=f4IxNXZ~CNyz%yC)a$hEcPI!IpdSFxgW0mKr-+xR_oIIZn8ZwV-jOo?`@c(d zv+L=qr>CtV*;NXierDOus90FMh>*_jU0zA0x*9V77nX!5{8(25{|v-%54! zc%7(uw7bb?K9LjBf_xVbzumIO8ZiWwMy*&4ijU=TXd!-wW&&Lv zR$DvXd-<>ZIIvKQl;wH|vM|WeVy1DYw8PkraF`Lh_eZW_1+?+Kem^iz(CKJU%u$S5 znMJDcDvBp{?r@mTbZ^|_-Fv2M^vmE1=`m$ z{ceOu`;1-B<5aMgID(G z#fV~O)sl$dOvxAyPhrF=aY8yuvq|K5c7^5qblcS&&r%~#H?`M(?JKiNKa!gMgcMi` zfBhty8~{`Q23*`+cQYmmC{>I|x=ZFYKCg9iYtEV*zok)=>h+&;;SLO?l<#&cL+ThC zk_l2{b5GRjN%Ai0qXh;ovwNne6&NE%wo_q?EhUGJc-ZG1vBuS;zcd*Y_?5W)*ICO( z{#hw1mo#N%e#_|Q;p}yNXgIhvsy9ERs#u4#2DeI>#8je)HPX0t78|?uc+E(^Q^21V z{;dAcOCej;*Jdy&m-{(py>IhR57qCzQulOUlPV$O&)`2GNn(9o`{x4(e{==k@iQGQ z$udgz1;s+Kyxw?~zo_}ZJ6koQ@MR=&DNPBgr z;Gxm!Ac2hGgC{YPFKgjBfty#&mg@7pc9#qM$iyeIU|4_YP+usSp4=5AA!jpORXC;` zu`^gTll|e8dL-J<*MMG0PgUU3?6u7aIZ%yH5~EbO5p@k4Qwwe@kzZ>5v@T1hH%eOS z^DJ?1QYG263C9sZrPIixnm(Shdz!AOo#hP5{iw~bD4f0fLnBTBf&}nlKNRi|Qq<&6 zdcC9GDVb8y%qrhW9aZf|TKfv-;FD~npGNLAnk>DvIutB@>Z!M`XAGV>@=3z1$hvNg zAPI>7x?VeKgA3tIaz2gy|wQ z5?X&QHL@4}zVw8iym7DBYC5D5YV-$3OzPPm0NHXfAdp59v> zUW7Ymdb!s||G{UUjH>CuT(dW8rDtB*8a4jN*n^C{*7k@dt5Q1&!BFYRn-{v_Ma<$< z1;J3|Z#q!VuZ_WXFu@6$I?h7})lDEM8_sR4F*h6VHv}SOLjmxt3Y)}%_2>6rB!wM0 zJxxTIYf}zA`&#KgsYtq?SufM_;eGpi;eFSFj}x26{y~db;pg@i9ya!oSh^rRk~$w> zHn3!Piiruvs2`rmO&c{**n6feh+oWh-A0oNRnYE7G54j&gk~R%V;#jkS@5F$5($|)wLU3cWoO{ZuoR5)k2x_vIeQIL zeUu}TdHEQX0bqy#8yf}D8?nZva$yRz*&#e%o8s`Zx`Tm7CC9f$4!zPZIBnV$l^h;q zy%2y;;sjX*|NSDe$LHaPm29cEp+_4n({heCDbo3NjAU7KC?sL})k@rPEQ^|MQXBhb z!^O=#b1nB+lC8{#7P#5WSV7vVM%!t=bt|W_0-gdV1+n@mCoxrO4vXY?`E;DqA?Z_;VkyE^hB6m`~=IT2Ld+^!w8*P}Pvi;aguodY7T6EQ=BDG9b z(iekE+#0OY#GtKKJqx0C?x&lIBZ)~dxlbY%yyOxc8u?Q{U#_${T|(iD{Y>HGOOXC{ zxU3vKNo%@mGoe%XA24QQ3b(93A*#2(O8{cB{?!?>5bEobkh2GdlO?U*PyWA(c zkTV0iWXIW)Pe@&eD~Cp)^m}o3kl)~n)8Y3&#J_##;on4O?CIrOyF)6m+xsc+qbaz4 zS@HA|?$)~r5KOZgDae@6)lsMj76(HQ?9Wnb~GXsG9j!B`A7GY&?AcX7}?n>sroVO{O$XB_lt#{;L*4rmu9 z?)-;WXU8-v>t$IJ<@v$mFu89ueBBy@&(qOojkNmc%K#1k^0)`w#y^d|LlKVe>j6q0xJ7VX4-{pcTe@B;H_F;R0N zZU&B!$y^4KDd14y*zNst2sxp|zeJS-cKrtz z6~ldi8KaeqH{(TrwVNro5T+|~9!%z>wE!wCBu-y|zY8U!h;9u&dr=IvHx;f&1Ekv_ zzqT?yR1`ct0O~d%Xfn+3HX^+cb(xlJvFZ7Oj6IQxTO);fS!*BYNQLSjPO>{yR7*(C z)Ss$=AgIu49ue~s{E6Jie3E64?SZ+}13@4f#ev}OLVmX-Ar&A8YT=wPi8>BIbN}p z(uGL~zBQ+Jq!dvE0kvnBhl%_u0b})4ZHv>sj19SCsj(&u!652^6m*lj(zFF6Ub#}f+P>PEJ?X6 zR|rW}hX??GVxhnkAi3kcyMrQ74Is@M?O%u>yy*~vALM;c4oJ@R`4NN&*=Af_Pf7F$ z@x+&QxeYR&;DTQ@uCsl^u<$ZI-QxITOpU*;T#gHotOXE-o)B=X1a3dKm-7nqgeabe zXCW$Fs1^tIk_&2!a1%5Y%qKLDh^_}|KMr}d%R83DFCLjE%FO{ZYhmUD{(GSNia!GM zw6tSp+HqVEU|OX7EW-Q$Xr#97^Rkw2w7=9+gohX9fr>o^3Um*Pe?OQ1d@b_Yri(WV zroaZk-lhT@Y6Zm8DX4BZcCr@tk%*U-uwCF{u)Lr6epXrs3sp#H$a&ZTNtL(a4{3@XzN;2* zwC^VsH%qIxPP(?&!3>~gk4g=$+yw>Z}QCYHFIISmMX~Ab8_C%s$^cg#UZ*S3N z1%m%Rf(!{bKm^;1NB<+^Ka*w7@nW#2$8ej39Q-`VqAAr9-i7bPZ_u#Sio`Cub1oZk zAoZWFPOQ3BV!A<=3g~iBA_}Rq+>V-A%DANbnrFK=tn2rwjD7XDWXuW6&WI6O>^C-U znxgWu@F(#D$2R=UZU1ps{-m0 zURkUBf>ROj)$*&LD6Z4r@|2@Xh2zQ>l8zeTyXNJy6xtL8=Wt)RP+u@V5%-;rKcr#Y ztS@z@<(dVweT&TiY1-FZ%v0+#SZP!)6`{)RalTtx{SM;TiUiU3y9>vax^SxmZQJn5 z#ND^}gKpfE3bo)B<0H-xPI1xCxZ>0L80A~a`BT^>GJe(5e{t|W{t?4JEY;Q_u6hDH zPU^j^cs+gthHkH}y4Sjx1;Nsp8tRx)0@n2Y?a$=4Nv%C!s!}(KZo%~Xx+WQKoe4rj z!~+`U1&elxsrrl_vO>VE7uu*lQ`)+3_LG)uv|d{-j=!0J>(@HjO%-@P+bR~oa=!=C zw15oP?E>K z3@x5f_r`2&I*mr#X_}f8Vw-0eu{}|DK9`CqMmGcoTF} zEmH1$FT@gJRr;vlTRjx_x#sssLv=Ppkj2kdkbS+D4p}_D!13e2L^Yq>AP?hzsFw>@ z`TK9b#@*#_z{Y{% zsN63a*;FX3@bcYj&tOrYH4-``DIha$I@6(;o`idY#@EH;LHPi~S@9W@1 z{@;p5RoC>ISP94OV85`RatTsDK>~>-K1sp8;z-k;x0rRv@MmD(vW5HT2t@)!ru`*w zuT_kjqt213BEPa2QkU-%JTc(vd&XvWxl-QBRlj$`;Zv1xF6>FdxmNa+Wr+ZbuzQry zsW2;YB^tN()7-KMRM=^CkG*>h$M_)>j}f4#_K6~`NrfudO}>$wyAD^CMCR56bz|ik z1rDzWMEn5oqkr(Dml{{u|NM|&*>zxDyMstv85k_@QsMFFvabrq^#^dD3bAJXVOoa7 z&N)s0af3VYnENdL#wQay?%Il~b-0S5V!P8?;1+THo=WVnS@eM0D9!o@E z?}sn7H{V=>HL>FE1C|pd0(HOzQ%~_%TDU1Trk`@`b+=xPtfqy9z{?F(6EVf69cXa= zXlY4csY9bE7k>X?zEKdoSNsZQE9X8hQfIAQF^>n!H79lxwyXZ>-*{Bq8+TYe2Q6A8 zz-AG-f`K$PXpK!pEFOX9e8QG3%dC%w=hVw{iXhDKbU^j;=+f16=emvIy^9E z6XakU4qwA;DBk|wjrjG#r(fG~u7_~vy>JUWGEVj$05(^>4q-<)D4T=U{|!Xn?Ftww z)axLS4dX6A8&E+asD4{yAP0&iKf>34oOExuPQ{XmOd>tQ0lB@w2>frx#s`HL$0j{6Rx-Y6oU z(nG@^2EuPViGDesTy4QpD+f6t_wcggZz?Xq68pGAuxN=Z$|ijJjhz?3uTpXO1!yL4 zC>226v_qbyBiwew14;aQ$uM0ablLCfy!w#X?+a%z-zC|AS39}7c234XxI0);I7TpG zkKCi{xVOJWFdzPdj^QQ%2}G=hWe}m|IN|}jJ5a5k;1c(dj=4qJ8$-AE;`{@_R0zs`Q@r5TKT-8nc0foDP+qTayTUYPLPIn*wI8tVNXZ4`PnV;NmU*Ep0 zvAX_^DWFt7{`TP^on6{niSn+T()VQR`Oz}G=tL zS=LK(sa!yOh8QZe*FxiwzW?zox0Vpi6bGrO8&m16C;kyvckDW&v+_6~W z8{J#fh!OD}5Ifu=sJ1KZ)bAs*aeWL23F}PQiaeT_YT&Y@?F-H%G~cI|c%1qYd0~Y4 zizfN3;mN37?C9F}-o!6=9p%se)z@h}k&yjJ#G9%}NBEuj72eA`Iq!ZcqsmNG2rne# z#&fY3FMGm-n;=sNPDXXQwth)p3U95FyxZ(fm>M?so?d9xlo$6Ne_V5hrtzp0WV?oh z%aym(=;9WrC2%JBOYd^x`E$*(@vnX@RUQ(V1;*4Q!@8$Rl_P2)TF97Ca}S5vbum55 zYb%n1H^;8EHed1Td?fyH;jw(A$*LSjTj*^qdbhJ&{TD7#QO0?#g~Fdsw300 z(n?IWW7&Rbjip2;|9Qetq0=o)SgEh>b6pAdJjG5ap=zn`7uRh<;%dA*y~;}5Mf6ik zoEP@7`1VF;sfY!on?+SMv?YdDQfZ!v1^BAKo(QB0g$jtw5$pufmQ(8;H9cXfydwpJ z{I4IjE=PLHmwEkuTxludxqy{laHpm@gQ!Kmw4K^YV(l}BCigI5Gx zL3w_Pyb|e9aVU7I0WWMo-aPRET|!rc#j@)0&Aa+3wz%8#`ST4>SP>oA3bRF zyv9dOlE{Q>vd17eVqK#MxO3WA8FA%vLREPBl!~bPHWD&xce+`=14f~Q;GLTXe|8+} zw{dt)627~X<|d0&cx~C#EM@x3R#v&6?rK^KXbdR|odSlGqsK6pvRZgj6A5tr@C#rq zldgzrJ1lUR$$%m2@J#y9guzhBJS0To!@1;wMQ5$X3ymSA`{uG46UwBQxg%) z2_w!Y-K>TiDl);baj@{nvNf>PWTSh74~C^#OQ-Ha&E3vUmlbkY@156g%50Y5wO_nB zS&F~e8Y=&n^cenk3>Z7d0!~fZ&x6_+efxT;7p4n_Z4As2?RxQXzz*6yY3~xuf*nXu zP;TmM^r2p}-6i7vwM|g>Q{?lEZCZ)Tc7MUH9kO7j00SCItqeaIVnK;~oV*N9n`-B! zCxKbR;C?|ksn!owAL?e#rpvGu%nON!UYT_1Jl==ZxWscowK#M)on?ELoybOjzAGV| z3?2PU!qfDXep@1IP?otqY|_3~5Jj0!dNIO)5?ORR1#h#zZcDD3M5r!@K`>pji*NYp zY<$Yikhd)CvuFP5W^WdQH;LG7_n5&)50ZERk}(_xK6znY_LKVKU2~OrXZmnb&xlO1 zg1F*}P_oLidyyZZQYHLsGA^WKHl$0X(nxVo{i6Rm!2ljb?dKa}D`^f0Q6+ zfzO8b)^JJJnq(IVj;3>odF3{P;5~s4(5BnaS6}%_x6o1Sb_Cf69Tj-X9&2sZBpA8m zeZ=K)_GGHrL_?02ZbvJh(JUt1bYA*f3xa30vR3dvG#YCd(X5bn*>YZ3*rzZcZ+}tp z78$pzqdfjzYVVayuZ%g8V|I6V!P#rd#wV(@T`f2a%H)8^*z&OXa!0|LoxxilCx;P@ z{r4_A4~nT0Sz<>t{p(|>5Jd`14r4uhbT&RJGB6!@Sb}YgZHle+6L#GR8cQ0v%J;V4 z-ef!om$*SJLLVxRCoKJ~Wy5wl)qU;eB{pR@d!eEnZ0O*@N$vXdx4&&}Ji8!Ps%JaRR;jeWk zYDY<$h<aEqKN6cNhYc_3`he*dKeH%u5r|l0~VC7h91%dh7Iz^ zL*ieh$c{~>*EG%^>9I@!3z-f^+iU>SCHnTcVm|s6XSro|QtUo4YJLBJNLg*9thOgU zScnU?Db{$nREscQe>TpW@Ebn*jlb=^_NH9ieaNpprW=Y1Q_#;QPpD zH;qVy>(4qDSry=2r*6!yrwaIlWpU}a-A@fKGUj{@=Y?fkfH65-3_q8STQPZ*w`-xw zdH3LJ4TbM6E%%C_oVmB44Wt_~8JOp#N^+~*j&NHMY~{;d^#@36zLR}%CwcXJ;mh%= zq|kbql(z;>VNXn_*7B2mC0;zQ6DM8PPa|M#7uO;jyN$K5_aEsc~ z&m`==_$QUa5!cimGMvqQy{4DciG2N&X)u6=q$Lern(9k`v8|PNj8ZSjYY#vTz1SLd zjD#W7`|q`i-b{|*A;q~J3I;yVywXwcR_*?K$Eq(0@h1Tij^Gio3?%>hy?W`X_H;|F zdHn{0yrdQhxN`KnHb#2`aZ+~1>RL+c(@ve}mvoeQ;QEzvP9Gj70RY69sXKv(J71F1 zQ|Bv7>6b)Jfi-EXlhbq|a>^c3YSga`uO7kQ^gEo8^tY}kp(5cjc5i7*_Wg+>j5@cS|8nyI(D8GNzQ_oaM9aD^Sa*t$bwS*Tni>#I_c>V3(R z>B)o)UNToaY4^ZP5gnGf$6SQ@#x~hLBK5b@rQnPM3Wl^>fQQQt=3}RPwmXANGUl0_HF{B7| znU-`KEhDB~?Fd0I5(#$#QiKQqF!>Km!IJC(ee&&m>@ZujxX zrKB=n^F(r4sk$m0G_y+3W3(A~0N@9uZsd&E7PUw)*4hpgBS2#K=sY;-adD4v{OF^Z zR$$c(kYc4I7gj{v6P6Lqp>82U>>SEQhGt9)ydWdNE&woM1(?$Loxo%rU4+edI5W*- zk|_oDCwt^=`2P9GihM0H=ABqYwkXbJo9UEfI_m-ee@abH=7<>2=f*^JF5hkUc;5^V z=`nl&s3#L9Kw$}VQ3(i=Ob5RJ<8wkJ2A1T~6#ev9qKkS5fZNKDDNNb3m2u%$h6gC? z(Q>$4xY~q?V=9Gn%S??4*fv%i@JzyPA1Y6v#=~;Sy&Infl;~hjS9fbfD zQ<+fBo|gtJ2B1#IbHG0k10KR_J_A4CR(_&P?vfDre>2a;m>R%1S0&NG^PM3V9bJL6@M7DY>ImCjVh_SSL230wS*R8YJ#i z$*)nYOV$q_?cZ0brU4<5)Ey~VyTQ-7A=33F>7M?!oIphU2pym>wAntYTN%X6XE-Mc zwicoi0gZ6a0zpF*;Dc`8AARmBc)67l_#7g#0-R7mEtG~H_`z?&Wu_Sx{s2$31*!ys zU{0vSGCGb82vPwdDl_T2SEMYs9tF^`BS%GjS;|>RE`(IdKG9g0JmOLxd)sq-pNU9D z`+7Q-1mrxLRNg|U(wTysy;!h0E5Rs|g?c^rRV9LMGCGFT6dW}b&Zxx_K>1n9ruQiI zH-hvFQQtmPx}4q>Z1?uyKL=sdPayv{>bJj-_9)|J1eD@336D3R2EK zGc{R49{k<}rRi|up3u?sXjb~GICu_`;imE?8AKfu0Kp#MJ|9H61sb994s^M-%4P*a zJy>}{7lom_+42zr4%DMQWr69XWZV4tYZ4$$NATmBroGXmK#;X>!=6tosT@=VL9!mt zH{cy-k`DWgh?+{BdLUAU%n6Tx-?W7XbNRO@z*y=;se~Vq!T@PnutKX!{peNZ50B6< zSHbwl9ID8qV_O*T)H(x$w6C%`U_csxryrW+_uopDg+SCL4qr)otG{vp~TCDxJeGIkQ3c$z^Et=g4_bh4KCjncQ0ks7bcB*qB|0j{>LC@cp(%)#L z?N_$+Qc-^=Nu;-(bH^Xb2g}w136OuFF`@JGRt9A&b-yJ4>B>}Ja{BSij2V6gk@a3- z3!(cLaYe;n`Pi838z|8i^8E>w_fTZcK8sjw1PGf}ClftX_M&XLd{l0Fe0#>>egIWL zmnTE<=O)TIL8kklI+GBg3V?rvUJ&@fIGr$;15?{Vh*MDH9)kaJ8kPDWj!c|!LV=`c zh$2I{9o%?kYLgEB{P3y_6em`^gHEE+wCB2Mp=r)(MS-ZON%%Syak}BZ!z32!~PH7R-y1+*FHGo5RMMusKDq&x}Xz8 z1_{-nzkpJKMp+b=O@HHtGJX;6U=1_#MQz2|K1YA5X3i8Y10Z6Ir_%Z8pL`yT##%fM zj&jc%{lvRs4Kw%kDL2h5Q`c2f$SUM6VQTe!jhpd@Y-cLuM5ZhnF7`5#Ec6NSG|+Ix;Rt&a<8J0^jAg_y_#_T(fHVAr$T^ zf@pIw2|kWWdePdyHF8;3_0st$d%wYV(WthjwpORC_t4SyLlq{YAIc-D6UQlKlM&sk zw`kl8cJWzB@8K~{Mag9R{ncA1oHBxXpl0l_3&aeZ+tL2LM*cv`Ks3r`LqGn^%X_Dy z$F@N^PKs$l)?4W>qx&CshKXGlJN99WGMrAZH2?PS*Wt2dcrV-)JS$1|efP#h>M&tX z{_hSGVL{2kN$U8(x9z(JqlkJR_kSDUTqa1YiWI}=bKE$85n>!>gm1>w@zqNuX)EVl zXq;7%|F2U`6?{&52aNvTC|%%4`)of1iakIUXWF>Mi69EO${4wv2S^1qXy58Z#1oo~E1JNfy|rCe|~&@yRf>&J%pzNm*+ z|6tZ9GCXEP05p&(`x{Rm{O43VIL&4~gr{DV4M<<{bqIfXIetfC{fKj;=Jaj1jQqem z(HD)zHsif-?!7$e0GE}zu{_rBZAL#n`^3jR$$z))AD#I@1e=|6CT`l>=)S7c24-4~lK(~@2d?3x)( zX`X%a-p{)e)|Os(W_Wz`8RvG2y>Hh0A@JtL^Qy*w@lFP!w{gU9P{tOcKN;41fVSIx z!^30voD$CLqfgIsE1V51mw0i=##N8S?H)ZLYu_pB@j7tcd)G{oZNAx3Awt4}J7QR1 z`QL)Dd=m86hR41g&b)`_ucF%@lbuv6#o#4IDV_%<7x~|x^7%V2nELVDf#+5)b2HI$ zB?&@k-9EmQA_oCoq?gka^3fI3xr(?_^Oc^ILubA&))(yCEhe&W&lU%U1Yjbq3w4=_ ze1h4y)1PnG8mZdA+z+v7Z)Hth`zYlZJ|jxx$mE}lKxf`n7<4my(N*=MAc|z>l1^E-6@_5n7Ygot zFOLr)7hLroObUUPxKt)Wu80=wqTT#6xQT(3o8)Frg-I2A=nk7Ic^jREe|)}<;wit| z!`nh)*ujDpo3lswC;OFO@|9o>#UqC_n`G@*MjwfO7Q>KOTesG%x+fJ~HS2Tdo>(P} zSdS>zHN@(+4MfYGCEXW|s6Dv4M+s}ZCsA0<-0;oFRKz&}pMB@HUv2EGgDK@~ZNRO4 zY&1vcBi(J00wOXOUYZWN9UO|DNz}WODd(!mOI0MOmDr6xmOe|m^+fGPO_af>t$97S zmDZWE4@QqZ!yk;+<(EvhYIsZ`Y7#c<87naPpJW6YpwgGDzccw6NP%em+uXZYJ+JYc zvYt;5?qNdW0`Bwcyf~2Uk*cV#_&Y;U#5&Wo*P5_?R90tv`1YZdD;a?sfq!{7Qg(mf zC&?_Cx+{9b#)>f7FsmvTZ%~*+NGzTL)MV9l8 z`n_(Wo~o`&H4pjQ;v)S>n!ToJi#l;*JO-q_7=w8A?q{x%s&Y?Q>~{h$61 zTjw6n)c-&5vx{Bqc3j(B=YC0=YveX}ii}E>YACmELl-L9+)2zO3Dpp(R3l0ExkZKM zQs_FjqNus#Qfj~R`TqU;ufIGVjkEW8yxz~(^I4o{8&&<{>Fk($;HGpCp*wbn6hN&POjcawjmW474_*H&HfS^)MGQ9!@ z+>qy@_>;;bz$d@5{9LbpV}`4|O%7s52s6@B>#`~;KYUXE zeiL(zL9#MtzD374*f`ehSNY%vjK8;63lDQXiY%aeg*1+oN03{|1JraojFU`WXG)Ys z^Uk+nPIA!=llncn-LaC3U3pyjtPS}!@^M1vGMjhq4v^>T#-y|QAAX08ePnG5p@{Dp zvzd5OLBC>CGKBzrV>R4k+0B&KB5xcIxx4=&wUf zEjx2I$QCeN)StVdDUkm9S>veF8R~WmUhs`h`{R&e4Q*qt)K?%((X+4f+Es|9Jc~YH z)gq&}_Pw*6|JwuBXn08?9aK-MF_>qZ)1T_q)Y|yqwoiSg2?85>?#o>rl~`{~%}W^G zm^$wSJW0}FJKhMRx7Im6V$~MC?ak&c>Xmrmkj@a!H-rjmoh8J9_wSU$y1R)^=NFGU zBWopr8*+wc)Lo5kxfDh1w(F&6N9?8Dop8hR77UY9 z$aYqVqAJ3WHkNAaJMvGNZ$g!ohTE<>tK(%dv-*4#eRNS~e2wzMMxn~{nC|G6LQs8X zOzmrDbMX%1;xOF>Ss+d&uWvU#xVdBB?$AecJ&3-XhLI){I3J~`V9%ZXP}12Evx$pX z>&3wdb~vl3DWNkfj>}2eU!WP!W%H07%3t*l^OpTr)bFJ$GAZmUB*EVvNjPw*##3_q z^j3=yF9bRHs??Mh8tb;8Ogad(>LudW1#NXVfcU!P zO~ZMF&n)7cko1e8emoWY%_J>QrQ{1;l_nGZjwqT7unjC-iWy#a9=fV`3P!kZd4oR4 zMsMN4j)$Lm83I2&h@w_v3fQNspe7Q_Vc{r2_!ZwtC7!PItR5k8`ta4d2UQ{x;j^gg zJpafI_Gw6b6BRf1W;++a91@`X1mRxGwmQPlC|2_RG3<5mI=^N7RyQa?g`WTvT!%KC zi3w^`K+!|3ysbdfWw5dVSqEUNMYu;Yfrrec>x33i5Gjq1j)H)^t^6%J#uY<7yp98y zD$_%66*Y6r3EI67Z?G#SBBi=n0W#%0Z3Gk=(j#SH$mRqX00i+v%BYyjY-0fnx3@rg ztQ~7(CEaU@4H5>Uc%0{xis(AvrM~j>WfI$et1c7OmV!=ULSiA~2X**fA>nl}QOqJO z^0Zttz`dxPJ@$BFiA|dX#at7 zX5bbn=-+5_nj%^V5Ew8C1ExUDl?}{OjLef|fkb{Dk(#Tvl1HV$2;%T1G^8YB#0b$` zrscJIkD}uQk8O}NN38{}v~EK0io};AhVIBA7u6^wlyfuA?(^vuWqK46=Ry6GrdyDC3Kiv~6&9(B2`3rkqGf=bl`Jfvyp#bh1zcS2 zgh3TYH6ct5glqEmsPbVI1|_PDl2Xq?sGg@ug#jV};3M0h?xr4IxfRMKrkUm)@Hrph zM};eh3Ze{PiqtZp7EFehjS~W7dU6yU&1U$Xcz`R@cY8zC808V?1Z$ zO)P0nB7&mCuxx7(s*<)@gA}el)Zl|CxRs_Yu1=0*P;tcsfN}FwsBnEI+*pjAf=Cet zK}e770Pwt4%n>2_Z#xE(#a*9AIj~`9deOn*BB5Cxfu5%9|Ks-KMH& zonB%YC#Yp&e}zoc5?AZ5Kmp<N^+Wg(oH$gN^2CUBa`Kw67n1U}rH zj&Ojo0(4Y1`@$Hy?`?(e=;VhV>@YPgtAM+^*)3SN(7a!wO}8?N@%0Iu=ROzX}d*3Q(g1 z4ov4${EaWnbv5QluY_Sw3#!cXDd+*0&R>^4J|MNiNv5*Nescg!ahqjzQaODt$CScI=Mz_Y|x~u?fZc6fR&)#q|jZ-$lgF5I!VW zH#6!FZIL?Vd(!LaezSf(B?{j_!l#f_i236R(QY?UTiGS_S4I1a^3Y7=Ayz{fh=0Q% z9W-!ZfnhTg$oYs73fNyDaoFrGxks1m;di$;KcVM8SzG$- z8}*?zh!fB(zJ0ge6^kDiH;e-JuZ-*u%6s-p-13V~nxnOnc9CX5lG+908}6pRDY!Z@ zwuFj_;zJKJ?B7X&Fcqc>05s+%-R-gi%A|O$XPo)9CQ4DCC{c64k0h*Oh_zI?39P3{ zTXLLsB_Dapi?*sI{t{E-?%kSawZ=>nXPES#Vq#J`5yCu&0m3WBw%uE$3k8_XK>Y%Va%YeDIHvdQQQU_1g~<#_1h8AjdR{JPts;#Io4ub`4J2#|htQq)F;+ zqv;)DddIO3vfsg1UC|IAqcQNFaOR*4=P`CGt>mv#L;3+2PK2mq>b?d&M@7t?S#(CZ zr{zVnGp(L*&ZGP9+a)ZLMDSv4Elg8{aleP-w7DG^z_khSpFz?LpSZ+Qc%eZ031wl~ z#BN{WuMpydScRTP*xE?^M62&Zh#ai>3l~zph z6y?pq!z--rWp;PDxlo3Vc?xcvX!UBK;SaRqtEZpN2`S4o(lmqoc_ZZwjZh?!T`%w@ zntj*TtHB<17ry)xyc__1(_$h*<+_CaN*7$FS!&+BYCA1oAcKRNN_&gWc8jdQc|jdC zH%OYQ48G3lsnZ6nMqHx0_yU|+ZbKO=Uq+#2rgk!EV!@v>1c<km933<&MWu}<0Mc>4us(P={=^Lz^n=g)^>p@Zpff8rCs6u_1;DzL}#-6EMmA)ymS z_UlqR>{XnwwNiv>{XW|w0b3<>QlR%OoEQ})w}-Ode~)udw*;-~c@?skwRQ?TE^7t$ zAiZBNScJjxRSYCneEFaBaS8|>2N_}W8f!Xa9=Dz|I8W*L*o7aDT#v8wJs=veYn@{b z4|XTFGNr4W50%q#Eo@x2_WrGI8fF*HYO8uvq(&-1X-zfhO1?=N7l8)Lnz|3;xCr?- z?!Q$HY)xbtcu|6s!r67;ifG5YaLnGGWQKokK1UpQ2L!QktpK5oD!2C@R?iSuv4rmz z>JG7$RS=d+Z=5vFY%b%HOPPT$7o^l6X$2QHPdNT15EdqQpHcHUwoYb;sq6yWwrD^; z;Qof+V8@19QKAkg=E@!m8h4`N1XRKhA9qp0u-yHRRLzdldx?MFi*IHpl?x_r-NQbV z$Ie{C9K0vMJ;@kv!{dc~LYf9Xjj{7h+{SQ(_g+L> z4m{lDrGXB9Nlxl1I-jm`H2y> z078dfDFZdCYG*#_4Mb5fc?@R6UEKZ{-QnihwSF5&GxEk+3cijcagZA1PF(PMJ`APjBs@xc!HJ2vv;t5+w``N0_|p5BO!UWti)-+&5;rN_Yk0vZ>{JsYnX} zT$x%1LG&pO4UGxQKDlk5F2GP!L<|#C!t=^KVyam$bLWy~;WPfL$7);t`hB)08EX<% zz7ix<`QslAc1X6hK?Gtqi%@gr`-Tt1(cOd&nludr8gGq0{`}|6$9M{@D~^Y;-RlsL zXgYLvbx^1ajI4ul4&O!Xl{h0iGU$6Ub0eUUD?p9ZsYo-6W zAB{&wC0*saz8==ymG)Qd_n#AYc6EdcvmHVk@f6e7-LC!u{9E zdcUoh-SvH?vBAb&azB#jm}Q=7y8riE<2S7t8nJ|#9~SkWp2~P#yOjJT@__p1f3xXV z5=Z0HZiW?GhZP5>z)-~tWvxK6RrO7x?#1!EuUC%uX?#`M7qP+tW>b`=>T!Er?p#;; z&Cr(f8LezD+Rc{^Bi}AtF>E~82?a9Wzm3J*+nf}Eesgne9Ikuw)Bhf*~c>1 zRAOyiY9w^Mzr!6@PMn76ZZ?W8m%m{Bw}lBajS= z`&Uydk(3SoqRWlt8xN(6-<(~n_mi>a{E$eg+Zz?2Uj9q+r77wMj*}%ZSB~VHsw(gdHdpXN(j3yRn9wyMgMqA z!)^E~W+Nu~t@oUltNrh7@1rQ;yv*l=|GIX%(?dURYE(zI=cN|ec^m96^!3v0{y z_SC^0?esi-!+7F~ukA>RT)p!s0I2Pol~M{hnVDJ~XKtu#P>wc%;>ns8A%nw8H!TZXBFE|yV8o0z)hR!>uJ9p0hw zczFJ|Ymw6>oz$p64V=O_DPcKTRg(rV%P=qPj*d|pG|WD zlg^;abVFs*zS$g|?n>3~R_RtP#|V$Tw3Oa3+F)rFuZ|xQ0oFswRBE|L@w#clUn>P? zS~MTAPMd7l6q0YgqG67FPzgto1wcawN4k(H+s$^f5c-nNP@xVb#LpQfol9(rUH^#Y z2yb)q*%8bu4F-@vJ)EyB9 zMaIs+Uh}9Y7ZQT5^~?Ty#fXUfOs2flPY|}M%z%4PF`bAYFF1Jsbhnu<&yDkPQBkNn zYhE$?a0>+v=)Rip%ik54zi(2V(CMhclg;eE_{F^aapbP0(7eQi=-ZoHIvluCvS%g{ z>f(S77Z^1KX^&9*#&EY2j}T)s7BrhxZ~I>x$$XKM{vhThce5QU_4LLH|5l?bCiiRl zHDIrdE)=@ky~`(+FIGO5@H@PhHv$?~tvB{XqV0av<-AM5DW8wMW>(C}4j*bk2HOlL z-q(IBHO?k7I4LOKrNAJ1)Q&xlpYM3ZDL$#2P(NH=?YtKe^gP7KBeLm`JD4Fmt83(UGh)wH#Sam<}JN=Js&oIha<18E7RCf7t|?y zq-Kopu4^&8n%#r(JO+%~}*pIvUifJj{FLezjM@eSI<%5a^9rt6G_uLYKb# z?%Fo18m-cni)Uj|0iT>)Y5QPbH4=2+L-V{;d&O|&ap5g%QPlk}8t(0{xM?x~I34^d z6Co4FQTi>weEV{}KW8DY8(H%7hngq-)GiPAFo;6w*KQ` z>5`w5`*=*_CiSO*!&g#n6IRo3HqIdx-_`&NJRpS#}<&ca8YneXPffcPEzze6zct9%!`mz@b242dLj;$t7pMuGDEN<`fjibW7ZU3dp@{=q@ z%loryrH{Wx%f2C5ACU;`xl}E^C~37$7(fO{Ow_v!^w7q-7x8IeR$5|QT4F?66itf6 zvf-U|_zF3niXX+})a?R`RcBL6-)Yi)t8@AGl=o0Kk_`i%?GkTXxREx5kzapGRUx#_ zI|DEs6A%~he`R16Tul#Qifwb=O@Z`eX(_DaX(G8kmx&%k+$1jBBav*za@ry4`4bPD zW8UM!mecoV2n+()o@VwMN7qP{OKj+(+V}_O=X$el1Nm6R z3|YXo$--YL{g5bQ#EEE{ofgJ}{KmQ#cqhwM+yMhvyjIFS=Szv=27{5TL{?hv1_A)fRgTFa4y7LIJjddpB8Qsq#G#l&DF*tS!p>@ohPEmJn@CoD=)BQ- z+@!Xq6>;)hBEPg|ZF*i!dgRV_DXI(536lo_nm8>skOAGJ;M+YA>WPmNDEv=>{v9gwnKu0;d}f33-eMLoooH>j(qcN9Ea4%#_f8 zbe7<3C`L+R83%*hX);U?1UqN+rc2zmEFNF)r}e|To1}d9Swgf(A_lh=j}4cmpXx-< zczUF@y}$`P6`2Tkak5?w2ipW7C)o;gjx+@M1+a6k8s#ly-@ORWiAB238TqWH+ha4a zT^XF!jM(LL`QPc7wd9#$Hca4&gv4|aFp&NVBIxc<0~pBG0K(+rfE~8%yV35!v74@f z+W6&kFSE7Y3~4@yjRCPKLi_p=Hbjs>9Y6pCaFBAr3b1CwU<|e%gsOPJWXT*fRMiAw z%28|#^CfrsRRJdJRTkv(OV24y$(?Lly=#zHgUTy@&Mi(CXqCb}p!1K-hQb}0b8K7< zpf2Sr9cv33z%++baQy9RRTRl&SevIBo_% z+3RA5HcXkFWC)>mR-8l;Kx_go$+P9aWXV;yA*;thzzO-2{zU%yjEgi@z}A6i#hNRB z{-mFL@Ujxj$X$LW<(W|z%*JApj6eqTL!2`>z%rTyslFRHrs5>vT#`03$#4jUT4v(` zrUBzkzJS!X4#WITzn(+yQZiP)+&P!<%f15tUMNsze@Quslr2Ng_) zM0UohzLZpmreVD7>|Il?xg|i!=dqNe3RJXr@hc1l;LJV^UcUwe|HQ$eZ=u9EHi8PH zGN8!kfHpbFXoy3zQ0B#Tb)V|UfO);vhtUMdr@B&di=D4h3lpur8=O`Z0%V>F783!#u0erJ@KV&ZBY?}cHoo~bUC+$e>#dfm);`vXImq1!3 zLa6pS50IxLBze@=xkIVkxRylnS=_HpT#TTQqmXcGtIZ*}5dcF8-eNO2hN8ETI@`6E z0SqGmxo*&Odsg&cPU0jYkC$}=D!WtDKqqys_;#s~UpTu(!74c)N`?+WK}}%$FZRgM zVaLDekWded10dj&`*?eqT_(QR-8iHBcX@ZhE-P-!u9y#z$#JV9W z8TMcr`uK)*RR=U6(OkfPrnnOW*`*4*u1>P0^dIIjQgVeI4HdaeD->=uEA*J=DNT;9 z{%~T(mg~2?WSDF@_S+qQ(f^Tg#n1X4VJ%;Wou<&0Vro3!#}v6ARz zRJ|`COHay&fJz};f%^^z;eZ~Te$@d(%ztu4{-I48<|+Qe)rre6+ev6Dd?Ar9&t%_) zz4U&A$YfEJ@g4vKu<=jCgz%X0wd(2pD9DsGC>N z;kc)_wwdQLOa4pPvf&$3KPMLZL)f1Y`z^UUiLSGa>-$qL)f>`z)l4(8!@NS?GIr10vXD6vLnzZ_5P z4|?)XMyySm$FQ0d05c*7ZJY@vC-^N__3I1aR66YKvE6UYMpDn9`#6Zm$8U2@!{4eVBr zV(+bB=B^s~T^Ul4_V1XEGMWW|5a9;EA*#{%P|~%(n2oMUs!+j9A3!rT=RC$1n#u_^ z>_jF98nE{498|wI;7co8qN9f9%%qpo;ZUB`<3D94{dSV>_I;4l5y^nOQ$eOr_FKc) z+&IR&zv$o5NLLIs7?Xay2Flaj!-G9=Du5{lWFZqDJBbXyq@h-_2)OfW=iwh=Q531b zp;UwDv^&b=5*~U4D?J<&4pG+dVzvZgZ{bbA?tdQN+jSh1#@RpcdzaA{&Cr069A8#? z_~Bc^ve`?~m!Mw}3xd>FA5rgl55d4mjA52TDgKgfF#Am8ju)ttx2AHLkOXe35+dl% z$TV2^AHk5#9z>S8Mfp>5-Hypz@c&kYN&YF78O4e!4&Y*xwQGCSa(Z-b80Xe5;&HOr z$VpU;ReIts*;6ddTHV2$Pouc{!S{5r(N-fSATp1I@-ayNfO%D6Z;#`$^ZD#A6W^cm z1`jNw%|L8$glF3-I_%uHv9+TehjUoV>B@>&Q?+h!);H^zQlehc7epgEQ>iKW3f*NRh!-DXU)5Kiusfukhp@K-pSKQI-(_3=AF;cLHQZ|b}uAqK~8~m(AO<1U=Eu5LM3Olk?^mC>9=kLa! zf1dyBC`uN5`my>WEReZN@;uNTz-lOnp<@%dLo5|8Mx79&)5VwzV(c}s^nEd|LyU)3 zZNG|%JH&f_iH{>@LA~guACt1~v+_G;6~bo~Pt2}KpCwaOgNO5D2ljfo#oXPhzXp%Im2kua^tRd-61{GOdpe;tGch?SczZMt{kO(GB^ z41vJHy2LdW(%F`*cMS*LKg=^rH&%U^H~KW;z1yLk2Iq}-w;Xk2?YtLdiTzI>}h-Ip#2;Rp{iB+T`Pqe{t?Le5$IZVmsn=*sD{Wm=wI3nQF(* zGeY_BvIDPnZ|%2u<1vOe>%btq)RQ9oq&EvN&R*HwWo~=T!)DUYd4KFwxMV$5+uxHm z+u2`k?>AfU+J1hO{weEV<3-^~^EOj2nu+wjl4zUyMW3A4R`VjW&Wk$TX5G}#@pX+r zpS$km&X8A0mAeal-IONQ)C97t&QI*5_=gYqtk9k_9R5xx`#Ag<;8&N{)>{isS_6{G z9<$bg2VIwhq7D8zJ?5=lx4N0;>SoW>%(B-%g1|SUq#+nqZ!H$>b#={0>FMN-;BRHA z{dHqKY3Y&f)y}Jvv9IkvWe%~qPDp?0jHyJf9^x=}*z}T*K#S^K$m)M)eF2s%(#^!8%!zulE94li{NPizc zmkV20zxHm}&%PKh+G{VQT%D<^`&);0!qiWi8{C=I{NkO{S%a$VQLJ9dW0;3_S+VA; zb?c$+&Iw()gWO?@-{H;iO>#RShXPrMGn+7-z=O#F@|X#+u)^PjfEB;fNq zIDdS9Wc$qZwZf%ME;2N?rFxw4rViP&kR=Zi`d#$W>{LFkU*W0m@BWzAn|*}xeHB6N3BVx6(jEpR_u3U54+$MWruYL2?Q-8;^dtA19Cw}I}=3J0;+LLC~HC^OC zI!+b%m^I@>rElfZ+_ z`z@~ZX>0Lq^3bR_7=2cLv?cn>f&79DvvWhN&8pKN#KTPkoV?32~ZVQ9U7QIbG=;8|`T2Bv&SOG0?t{wNtlCzPe^& zQ@~Kmns56lwa#ZZyzQ%6FXLxIC|CBI=0K-ae%|R_x!8#4wda1l^iekW;E?j=P8O_{ zd8~mqVQGT(UE~mtFp@X+@=)fyW_%c90vh;WJodqhE_a68JIhF?_?l3E|}PET(Hg<;6{Fn?}EWm7saydPcj$L5;Fx zduOFVfv1&QBk{xsACt!U^r(xPq!*JtLCfUlnLN1vMM=2_=1|pZ_P2W5y>?v9wq;#o zzl{%G9fHfIHLX>hW=X99L=S}Le!%>JWc8Gh>ZpuXwU*A0B-tboHD{pgJeyhhFZ8rT zRH=S*Hg~XYzv`@2pyRS5>EtRx9qB85aa1Ec`)$$g3CedGPygJ&zGO;ozyVJRx@TRQ zlUzy7_uUg>lAbxc5gxzYk+(LOB) z<f876GC-V9-I%&3`^3b-{`>z5%?Ap3<|CWQAa__a;)JDZ9bE`Fmz~G-E4D+K5gHIM!EAN@F44fG)V8)k^=q;_eNWA;eS5KfQ<= zd3NkxfZ%>0F$ucSv2XVjI|p=&AFA-`%LL#v%nNKx@I7Osb~u@5YuheY{40c7+cSdM>?vFV@tfay?TaWDm-A*%VfG*J4!z``xrZ!?q=6XNRm z*c1Q*@mpmg#EUibA5MsxG>$}MdYO-F=I-eb;0Htz{UZDTjdafpB7=`EiwSCCmbt#| zoly@g064JmL1Wki0e0mJ?yH40^F-v@W~@Yj-O4^V9t_a#rk!?HQ_%N;ZZ;)CpE{oV z7AOJ>-7-7wAbe$$($ZN}KjX|<)Qh4tzg_@G2hcn~jR%dgq+YY|a{V|ce0do#DQxsx zC*^c+2^CI;L5LnC%2N=YeKbj_tyeQiJ_%5fSC5|9W+p8&Pikh!^sopvzQk{I(vsM+ zxW>V8k@QV~fU_vyn+>D%GA3k_CA&^Q{Rc5klh>7(6dW!p%`-tDRs@_(=WF(K9PB9m~($Cy5~~3b0x$M?T*x1F$^TTxyXz>dOpD<6=lr_ zRx)xR=iK2)7;>bDY5?NIdAb0~6N6a{lg_O_B1j?3ZY55$LznN7!0n(%o&350WQbx| zmNp23dJw@m+cYkq@?h}ZT;YB|0mvGyIopYb{xfhI4Ph-t__L%E#ApZtZ3allLE?L= z`D`?W&jMt`IpU$BHj3>ta^d_kLc%+fM@y~dQ5XFDX%7xeh=@z! zN7FnHZgZ8-YQD50#v9XeTP2ww*&1YBRHKMt02dKP$JX(23cl*MWe88Hm>4Ri4#W$< z%n2^>n~1o=+nE)u>$J}pdS2e@;=e+#^NdX~G`Fb*R4@a=fAZ9^{*Q(V$xL{tm^5#R zJxj(l38;ZXM*=m^%>wc=$G|^a@*i=Li3kp(J#4 z5`bN7416M%-LI240(!g|(b?N)*75= zq)W7XOWtI%;i%m8{D-$Z%H=nIgX~TO33L5DMcid!))5-$&wx!?U49h?QxQUQ-=tF_ z>oS^jPLleNh`8SINghoxLB6By&;WkKeZyxp{gL3OZc60`gnT zh~(Dk*Dit$(jzwwYc4I_BWQxQgg^Y(EW!XQJ~$Tdm3jaI@Rs-vYd6+=W|4v(-CGhS z{T35%C~{tG|B9Ez(GQPm=tf6G85{paI?y z2BP_T&dYGf%LzwNk=Y{LpzsP|HvFWr{K|wg1XenuZ3zd^0;b8;WY?T|JZB?m0wi72 z-0&rY1TlB7ZAh~K-^Tn&sw3$$wJL2C*9h4ug(a>Mc8;>Ri23`rUI;vmP8bpr`U1#t zHpW_gMihT*fD;A>1d&t0k$+Uf*G{SGv67ii&N`LF6OWo>%$X zG^O#KG=0q`NKj`9X#vLtseNu##gVnYUswfPt?g&yTZOnZF`Nk8+3+rrB7jyB;#-B= zBs8x{x`RbLDI;9|Q`uh3h5K-r{OD;HYp%3(R^Wr9dz|BB^2r6C`iK)OLO;XEMa#|r z>Anu>{y?&U`aAPKr5=U$VnX@YbQ7?JpW*DG2ej=OEF)Sk5J!^YhO9ut8x;+hcKCothDLbsp8 z{@i8K&)Az*3wI7zk}7Lk+)pHKC3r&&tvM*&BEq*a6Y7ozPS>`#fzY!i`T#fYDs{g*o*Le@g+MzAt^eY1Ax-**R0ZH>V<6{)+2kTRqdoNfAF zIK(t{u?bJP)~*WDN8aELwd3#j5?+J&GQBN6a+@z8f-jn3^LQag*axQ#LAzV02@w99 z!o`+zBm9>YOdN+JW;e?0CeMrIoJO2C!Q|n)UOlh_e+myYj{*8Ltl*R0 zGPtq-gPwqIzQ+9Ho`nFO-lk7dc^3S}pF zpkh=nX-N-!c_%)47gCILzNQsEnt7+08#*QPgIjJGw569q? z9Z_P0J_vJsk#{)&)EA;In@J;jwc#3aYOQy9#@^KsO%KDf znPb8@;unCx1w#^q=@Kwpnj(FXu_LP7#3Th3+av#z*Nt$ApXUgOP+S}z zeeg@zo~x0c!_ZR$C?+521TCdNJT?^u<3X#;IWdtVm|K7=6_YI{%!&`Faco*Vwg`KOHb!Mg3UqI)Ik$Hfc zSSpEbad&|Pu75ZkJEc)`V93_vZ~=)`d4HBog!>Ywwt#|!E4a2X7N>=B_l)=u5UkTY6eomLdzbZ`$;q~#zzX3bp%p8iD_Sv1ARf_~|iC3$u>jh&p=5XYO*z>(NVli66zUlNhk*C*bkKC8Q93 zT=2WTVRO(1r7x0?_Pf%jX6H#VhaA=(1{HtBN@$IU*|o4j7((1DTqJnhT7fH*EhJYPtG6lYd?$RV8-8S4MS(7)}H-HGEIccW{*l6`+$w=>AiVUmhe z6;DRcgT!x=4}S{|lGL9ip2Ys%wIPl*^15B(N-NJCs*hqFu{rm3%kBq<-{idbc6WIB z_zzs5P{Ta4|JpY6>&1OxTa}s*N**R?xzh|D#~=SS`}X}E^{3%a{>{w&ys`^5efTEE zMU13uJsgixy5AVTwlu0jBkY2&X>%nKZMBx~Jf=t+Avj?)&+>M4DOF#4Td|T}ascy9 zw=A(MFr6AdS*NG|2|t&vD%rBYy@^*8^GJb~`8q|Vdu~>jgcoD0FKjc{XiKHuS?Ef_ zYy_M^kAK(o&j&=*xmtw$3w%zA_{TX%JrcG#{nC5smb28)KLXDxCi@wXHm8|d(WQ4* z=W!KxzAdemK)$$Olj7YW7gO@q$cpdw-9pB|Ap~wjTYjr?OS=QJXZ6}eR8{osmHVQb z-EK+Zm2me&%+70Gn-gBrlTg&&yK8oO`Oe*otS)y`3Qx(CmGy|=E%=91>Y2%ym`Ue6 zPk~XD?N0V;dSznqN_e*m_TBT+Bme3SZb|yK8vgdoLU|g`*FN5|JV=?>TI3Cwq~!UP z1?KYNazC~gdTU0GuuraWt4T%$@y4!r2v*TUi7%(y*94#3WcERE@6n$@u>-;A4JZHg zqIHuNM+j3|cGb zVMVBtmo$$G*I)RvL_X$pMJz z_qQd<3Ia~&ds`V`E}GWMJY#>S^hNYL^!y?nr6T=NoJ{*NXhzNC!M(-=@GSmW#F;UP z>MsG>UX(|SO{r9V-w8!NW%9#=DhbP{ilj_IwmPO|^Es`~NGAodALp#Aanx&vHb?Ho z$758(F~XkP!2oHs5@GQQKoeb!FauXGP`dg1Pixm9$o`todtEWlz*(R(4oP^($ZEdEGCtD2+x@;QiA=pL2bcF)Nd+?DcjO^ODl>22YS7zLLEH(Sh+ zID}kOh5&oWR)x1n%icu~RsJ54Y4_HV7*ot}>gT$dU+%@T>Zq_539jl2jSrJy1(VV; zkkXv*Llv_rZO}h7a-%$9Nha5$YBbic<`nOwLJtYgPN!CXnE-kpuUO#BiDKu-cFNAszrJCRZdu9oJx-|bEzwxIEPh;?<({nFN zAh8%!dD++!{32X-pLdr>zx=;uSn6-jow^aBbLJzNz8(u9xAAUSn~n*1b@Nnlindc% zBk3Bs9$seUZgZ8B9V>u}C$x?SjJR{ZJPJxW^;LnmcUwt;K&iqqOjT`T-FC%sMaoF< zgzejVNqj@q?{V(7TaM=@FITGnYjU^2Q{X;rt?Hw3X%g$9VA9F1D&=9pa|>B1LN2JS zl*U+VIs8onmqjO3te~ehg$@E$u6A^zP7s^)z7LRGew@gzlmQC;s8H5dPt zEnBQ<*C$A`8gL}VGso&B#UCxJo3leFuVz(4y~H0IKK@_{pnaJu8vp7t6S?SZ|E^b( zobx-H0@74DPx2O}M~$luc*r`B*9SzVxp7Q{(-043Sq;mN7#}CU=1EB_@?r4%=Mm0% z$}zRB`e`#n(VX_=^d(f^4rX30=CU3La-43J6smk9djQ9#A_d+DAzwx)IBU z_OHJ=i#`P)wT_pyT05=x-fZ6qHW$e!b@p#a8=FCUX`J&7YNqH!Ub(C=0mYk5^vqY9 zfy*9~#CR+GDQeq*NWZ$$sfm4Cqx0;iP_W=-t9@O)Tz||2;Nz8y1EBb&Er!$-q_yXE zAnr!lEGfjx83P1Z+{87om4?c9-dIg9M%Ktwm1KFMGGBYiw%ooSZ>o?7tzUm)8J}ot zRW{I`BwsNhDBOspd@6CxYKN$1WeJ2@mJdUUNbbONbSKx-~0k@cJ6Q&z2UbA z&Ux0X{E_Ky+aqNf#)!2Oa%0SHL`%W;of3VprbDl3>4~QeIs(@9u<+NREZFJv-k^ObX5qbZj}EScFtz0sx-9qRMNxd=ATvZE$}np`D(% z`uMC}Ef20PJ~?xDAy-NOklsj#7e7Z{jjcE~a~Bu*66T9!w5|`m1c>5Su{GK#vnCV#`d5;n}7VxpVU-?oI||Cq@9O9~{+;at^fs z5`)R)@fQ@d4S`x$gMW;Y)520HPm{n}72ivs3)^%R{RGEWItXzj$yzK9R29Tou@z_> z+2!=!t`1exF!H#aF=VV>sbjb>dGdO4Yc@ zGGJ6H3|NNzdl2%(85ri6GCfQ>;rf`Q|D)@@qMB-;M%$eNNl2%6LN9`ZDkvrNB4}s| ziW-zID#e185CViEgriyt&`C-VK=n8vE|;`b77{pQHx<*7v67h>4Y8y@N{b-xX%%VnXZfij zf3Bx;jbH5V0yz_iUNu8!!OhSDhLiD`^}p!AS`Bbj@L3CNuwrKX>6i09pN?{X)AB$X^9L6*_z2#VVPTrD6PPnV!T$2=H9 z(1td}-1+38T+pAMHhyCQ=ZUo!vRC2iV_CIrCJ(~SdV-J=gW>@;J5hiwK3+}70y$-s z2wm_8^!?R^`(5K=M7ID2$An`*mlo8&o>I(jL=vrzJ9m1|n50Dak zBkH*OjqjVbc!(LtvdW4D#B5DmPhI6div<);a~_82(ox}1twPVS_CDbvfQ>FElBn%> zdsRCbvO09J&-E|cNC?+zn`ovRUvg3%cfttyIJ!BHlTmX)T9gK8jJ#n`7+}rw$4NE3 zY$6G{YwQm~s~W1neTm?EWL!`n`XgZk^HM#C8UJe64`y;$I|M}d#kU%1d<2`oLOM&bydW`ypR&C9CHWc~#XGKM6w5ar_;@F&=oVz)nALfJ1 z5~-SzR1H;Z8r1$wxBlwG=wv9-eG>Ttc3(5Ymw@a06d5FJ5;-%-RU#%wg>#L#PuE*? z1hT2vr@?|MQh{U7Ko#7OzN{Cc$=kx(&-ZU8QYX=f@{nOMXta*t5=9?+=e;8v#kuv$ z)nW37hCK{eT2uy!1pwc%7f}LDKC$h9-uO%!b8AjB0SP~bAP7(1$R|BN= zGbtnqQ0!!ADD{oBd+3ZL%KCTd74}O1MUcn?!jOV@6;ag*vN^AeYBG^2n~~UXmW-9h z%LMYsk;^0PcNu#AJ@N&bU?IrB*Q6F>^0=32GcXbJ%CevotNf}MX^;`sAj2B zZ%B+%f4-;3W>i1%9)pC06h8|1$ZHYlOx#9dd0P4ma;mePBu*J4^tF|p*|fWTiZMB?q{+gzOVeCoO48^X!R@5CkJZbNFdCQn{B|ClIM_-XX`JC)E1xRDwu_ zj}Ud};D+e&03G7&wR|tXb|LAf0n*7;AA3nPHwwu1+Wk81*8 z<~V5`q#eJ`Uq>Q{)9_x`=4`lU$`Y-27QhPtoUA*(F^DjiCBKxyq@|F&ANS{$DZCx; zeL1zC_#)%T7X1D9_^pRO`g0OkvPs;OxGBo-sOiaJ2ikVlaUH~|hH3X_j?|}zIkKKf z9MP@25W<)H(vX)rhKV1I4zkwhPYsc1#zOKDR?0C#>Jy!=glYqe`}-38k}g>y*DaBX zkQvJ9Y^FeNl!R1|4BB&K+Hn&lZ3koW(ndJJ%Vwz|$Ry9InUk_9Ti7tF`K*ugtnXal zdB$Ns(O?(XT@f)M95AWO<^^d?2ZXX@!ISLaTMhVAs?5Bec(aPwndB*JXw#|95G1zy_% z=Hsu-pRJld*EoOv)%=CG^B3plFRjieh%V5j7ZSA=80HH}&I?TExxhW)9!D2aQx;fP zz{j_$h4jXSj8_YpZx=4lEo7}OWQ%@cOMlAI`jl(_DbM*+{+>@-SNQ3}hs49n%p-TIrlPu&E9TPcLn3d)&+kY5|Ddz~ zYv5HAq|x60A8E9*7MKtyR5izp)*k7+Vs=y%JN92V?55|PEBD@Si<#*ukkH-=D&t0~ zJYlPEeDwDV>3+ehZz^0PhwmSIznZ;Zn?JW%=JWXe#Q&Jyny>CYWSj7}UTsmkR^`7- z8;ddP@3>{7|EzSLJ4p5_VI5gmh1J~^4Pm@;r@U8>4S7)x%_!vy$BIqEcu}bOh&xyN zGJ6G|XLlIuG#=CX@21t`hqrfBFE5O?-TJPwCpoZTd9VY2kO;uuzAp7_Hn)Qbr7emZ zF|x*)-K7&3S94D64u4bXloxPM-aLw4=a;vdDQ6s3w;H_RcvOZQ#Jy%IR46?o|LDI$ zPc`eS$CaAj2xi=#cRZaMez5W9Q4$1r{8b2u`V$$8*#-1^1z!<$)iS0Hh<+XHb zRh>j&$SsNuJ!!qcx5tC^bD2fkrg$RhkM>m>EV9bOBADI%?U-iqBK=TS+r`Egc*A0WFW6=h;3)Qx2 zpIk9Y(~g)P*lE~8__)=mqpACL<$im0?72sipXIVvd3)Kmh}*C5How_NT5UI_?nKkk zfAV1D?lp14XYwtdi3L#0JleCCyK-|+ACHJf>fdC7Y*~p1BULFSoDq2@3k9-eEj=F7 zf&aB+VAA6!&X2myaoTVOYDiSVAse?M7C_1xtv{5Mzab z>+gHGOu72bI@XTYUB$u1T^d>ZC1(|OG|0m}9G@=i7>g9{$n4P!tt1{C0^VM>nB_D) zu=<(Vh<^}>l{~xGdhRL;!0x_hxeo>xWE1v^{Qxa`U&qZJS);6yMo& zgUMLdV3X}xs_8ldE()g!-oGZ!J~;YkspkIE&|a?5#~xGrB46Bnr|dl{k=CnmZ+6&V zn%94!&nnv+_9Ocwg5!zpvjwO=zed9kuf@NOl{8tWsWFiQ9h-DudACA*c#*by;SH&XMa2<-a&y-Hc9JB4#w*4Zvrd^-%D;CAD~(T@hKmPe&g4u&!xXPX&Q83#B9$FvNz z95Xsa0b}wU(-xA(I(rQxW}s zEyXfQGW+%dlIHfi!1m;J{DqYy)3sWc9dBiKR$j_RG;=b7^CfW8%wwlwbBYY3jf{Qr zJtT^w9XD46DcdZjph1`KML`G*6=9~`y<@B-r40&eLT>tT3d!-iEb(3LX^E0+fy0(h zMlR>;zf_V_L_Syz%C6~2Dy7|av7yKKcJI1;V{^vsU^&P_%_Lt{(7X27Ui1E-vzoYd zJ4}g3fk6P0DvW&$J1M|FVhrJcMwk+iiLhD((-~yAx|-JjB(y$lF_&*zpQye6UPbL{ zZK};m+2GmwkII`Qbp#?5Y$kA;C;j}R+yy8J&$R87oS~~1MnRCt=$Q6LrdF&A%er$4 z8%~D!qm5^h=mnxje?CyV`fSgHygwm5x?SVnOp9uKLft+kR_sh}ep3aQx4mq$?1ewu z=}?gKp19|dqkNc?f$-(4bfgl=nJ`1CkiRA`>UU2M?Zf+ijNPfCoErg`MDlsRP9gn0 zX(GPvmLh6by+4U7OJ=9{B5rECpvZ%`>&fNYF!{I zX4eWzhA6LY9gh-w@5vaU3+farYatHIVxXw9u<({Btjhh; z3{2$<&CYSr`iB~X4$c!G+EK)oZC#qOi|1Y$=trdI9cwMT2nb}t=|Jk>bMty7%Kklk zhSU%VVN(cg)V`bwPwJGo&2}=}^dd$ulLCbQf*MKL7X--O%1K9?FIz!f766zb8udL$FRC3(^##@3Fxg0&(*x|^xtfs+$3i~Y~JWI6&R`$rH z_%q3lO1kj>2BpyKh%X}W{zsfR_xmaHS00ck_{C8pF zdSdN6D1NtCh*NRKCz9fA=ip!jR*46o3E9gQ*+qFePJ05}ufn<>?w=P&Kd#mLS|0L_ zL;wv?s{%Z|RsBv3ewBnFl8+uYy?jk}zoG!5LxpNl!E-{W4$YS~3(?_1EkVs0S;VJS zl+Hz6Yy_=O;GQ4h4hsK=#JaPuVf zH*B%zpyP~=`$YC#VXJJ?q->X^U~Tg21pE+R&%_a3K|5waF5LI7@U<5e)1kk68o*-D!5Er;a><9tpw;tl#5`=+}vrplts3&+~gt{q9A@33l zk{+1@d6q_ibD>=DN|(f1BZRI{Lq7{}?bYr*Y0kfBk&0LFesw{A=u%-1@n6ZLs2D?7UjLCV6;S7{ z$i(j`$G@>e<)r1Kf*{glf*e&tjsRp)aPwRXFl{(PmK-JrP0(Nw~;h!_uA2ViStz_g|85EQ{wNkL4uq-u4_e8zZdp3?? zZ@Iayo^2BPn|ysB4ZjkD{}64~!8QO{ifdd@8F(y`3M2Be3N7Qn`2|R(yw$e4Mi9F_ zt=~<+zNdgJk?A7M9jfYlPunug^srC5Xt%c6t?jTIWK4fF_6^%4P89=MnWhAIkOG5_ z`B?ew-XO3rmQpW@gD`2g*SWZXX#3HD>$-!8fmb5RB*Gi_^U`bxf|GrWckFbCSdkxg zlFGg)j$b0F6p4kxV%R@@?;K2Yei?ux6YTf7!^&tby+W>*?@NO__1Lcz{NwTtif@5I;*OFSqutNej~K|$Z-qWJ5gmITNi`D#*ig)~j%$uI(%h?%6^Sr*_$ zf0u+`YxIz1iA+6+xSF}aM;YG%g>{eHY8qa}p_{4L83E2_3w{sL67G)I2@72Y@Zb2j z-Aj^ScT&b2Kgqe?N%3oBi=7)o?BYW}2cwYl=!-T)jsUTuIzs!g^E@1^h3P+f^}qU{ z`^`beb{vKhYghR=wHZK*n)*G?O8+dnwHEuCil;I0R*&RgTll8EZ~DTO?7oIO9f6zX z;FhSkA&%+`$92|J^hk#;8AgFt_eY5?hahvUYvuZnrf-38-JWrFwVh! zi^d5kWYCueGGkzg)OZM>`J9;_mocxDcp)`0s?c;#~B)yV9Pz&f9# z*4B~@X9NjxKhCZ2p`M2#R!g--1C5{KVTUOPGm+e|8Xnsv$+bKXbC)R z-4`G~@}~sqby)3W&7o*Ca`<3{0Dmb3(+JMJ*;ps9g7*Rt`|=BOK-aguzAYG-J}lP6 zKUyl}gQhfyY;=zhb5BUAI6`qFzQPR9v92{ZF(s7*XnDvV!?%G14_89aoHL3n(in{a z3sRQSV*9X|H~ijxqSg+o*baI^J#4UQ*7IoI5uJ~yBlZZxT0n^nNh$7;2CL_MShhSm zK3q-NZfKgS?pU$qRg;wX0m4|OFNy|#D8Q=|(LP#kno^jD9K8t_Y=1N;pxt3n`Bpo5 zU#t}B_z@9VGBDme2w>CCQ$naKvinVgilgkVN0|OX6AGgOmrbhp4Kot>CY(6rJ619EQmH~u>(xLXc)%y#3U_lU+kO~iF-J5wP zvER{d8h9@|V-dBtgtP#|BYS2j*wKDOI(3`M-j0+{<}cfk8x=@83HcX>w9z<3qr%jH zu0FjkMMa1*4Ut6||9BZAqPCr==jGXxy5RQv{oMh01sAGjTK+ zjOA5o^e%CN3}k%85}Qs8Rcxh-1$s($jp9ZHm;nHjMZ0jGw}U}JZc#tfQz`00g4pvp7|h*{R&2XN7KvB!!gGJ2f) zpaZA3?zA~4RpxZ~;1ro*p|;<@q*$Ki#BJPiU&zIEZz0UHCDro5Pfe*k+{f8CJk_rL z8y7dli))I8gVt9u3eaCzAyy1gj|ac!&aik&c_H#pZ1hdDZjn>!mN|>0bnwZl3Y{a1Cst z15QTjguai&o>(~}d-X5$AymMt4eoK2@Gedmjf2|Zrm5{RUjb$Eiw*%EZ8#g668nwn z{+_3>hXQPlKcBFEr<6?)D+YG)jtP1F8P?}KH#H8IF5gD1h{(Oa=1v%nz~|vsCO`js z;2W)7l`()Q(U5=kVEdbo3u&QWLYrmAFztXStab%HwX*vGL5>gEOWAh%2c9s84%)H+ zFH=qmX|_o2wK98c^r?L^`nX70=kXcHdD{2@VP%Q>3rfU)Bee^8m{#sDMY^=&hoxuh zB6PA9>w|2%Ex{_rP#BG+$4FkotZsS}enziH+Oq9}0;Fh&$F&%}sqb*&hLF@g%Eh!% zL@&PCsOp^n>HBcP@6$q)Wz&3#n{gYf-q^@&xwFubB~|%#-Vh@fH)BYcFIzv6Ujg>z z{jlna@*A#4-OYF7fTgGa1wc{%j{``fwI)d8jG3}t(~jv1M! zWVUCiUeNk_=+V)C&{o*iiKl0lHiw(9;)DJJ!y3JJRv*aOhxKf#{@&Iz?OjDc=r1Kl z$u%DTJpMNhfj_wYJFH#vE42)-Qsna#-vScykSAUY)KS^{ZJa*lbI4vGz8Y$eT zhS~eA{qcwgOVucXFf3XM?{HJ)+iJy&kI z1sPjBQ`~=g467{U64F-;^KbhC3oOCSK=r%9&+x{3jNB^@HrFCpnZvZ?r%4;^o!VWL|Zq+`qN`3Z;XLMjs& zs?K`JRVa7M82J8qy=#kIVJcr%mpV!kF1Uru?6>Lpu8*>(!mdV^r-?oX%b(fuk>x>E z#*p`99Y=+w1|SJp1u%0wH`l8lf3T38(+Mrn&1#7vY|PoUM%p89d_J8XEB9fuOhh%n z{%OA&4#`oK4oLYlE4}Yrj+T7EScX=aw^m&R9JTnRzV9K~pPOnU+wZs)LX_8SViuou z_Ke&-_eppo?yYW=atUcURgty%&_@j?Nl~RZ!9hFP!E_T`SwvBY;&nn^67CmSKZ*ujZ~)@@pA;F;%PguJ1g@$Rr~zYog!ts{U4b&XhwH2b8N!x zYF-}Qb-rq=kL0=wfvBj1-WR96otwN3(}i`N+^iE(J+!sMLKXIQ*Phz_4aqS>*2~1*` zRI7+8jb#^JZ7-*GtK{TnqOlQcS?-m@F4?Xbm1sBTg(M`c_NGj5V+`@yvGUPZ|9CJL z;q?>sMWRKKNC+2J?)Iu0qP{_ftM1-()0AeOR@HrQK&YGF!hCjCP?8{)H}93qPDY43 zNyfBi%Dm{KFd>TzDbG*z1>LHRe|XMCDehUsr-X2mL;3o&zl~ zG7KwywHT3V`C1h>AEK@^NC(L))ntgN#`zl!bSQW|W@n)m{>I(4TQKmH*;Fmme9ymH zzFC)*Fmzn?FCUSD@k+!ga$tu(QlM07dWKVl;u5vTO2Y+&!rBanIVq-3r7l~;>AUd3 z1(;y~833u4d{&nHnO-JYPOq`+UPmy;iPz6Hz3~@IM4&h85()9UAY0f@WTxHaSnfyV zKdjX4ua~l;Pr?)il3tk<60y5Z;?nNqf?I}8_3_}=lc;s98$qL>tad?V#1$F0nUi(; zkAw0^qU)(krT~n~gBWr}w9mz0W7$-dWeXRxgZ0?%1Nzy_r!Skb);hKZ@l|9wb_y@T z8oe>Ds@&-P_P)z^E{4RA_s00{%1pldxxEcxI|9Q|x zyaWyuT^ue)FdK9njOIIO6hys~y+o<(%Vx*et3f49>HyW-UL)kO`y5v7H|xXpA=O@a z{Wj%aI{Di{2U$G(qXMbj+2JbKw6#z#*EounS)j86F4|X!5uF*C)2^4Lv3QpV_)R(Gzb-E>z1CA|;bSjSI-Sm^-MqYcB>m^p zy-S2ggkWbkl}`JhdVZpx3L!}jGbU;|=7m3F^&obXt}l!{SBGJVAHK(1o{(Im+BwLd zQf(=dag-bKOcrW4B(xZ?Ikg#V~hwrZPcKCXW}#wmg!YMRc-_q{-Yw%qd( z9m?plj;`4)wD_DNy^hzAo0soeDzh+U7BFj1yNfNk96cYM8RB|G!A?~dc_*gW9Mvz^ z8~!TCI|v$E1`aL=6Q!F=6;GV|Lxh6x$MQ97M6dbNfhPz*2}bMftV|eq z6ql)p6-MqJfpjXhmz9i?Z`=&MFjCS(4)9vTReGfM6b~D+$T(9y-+Zk=! z+>5tGd)JcT;`EFY`3}locy-mA#K}*eV!)&87IsG9Ettp2tH`1+V+8SiI=?k@<2;a7 zxwogK_HIM;aP94)Ah_5PxpP|w3{103E`xts`8NL+NbRoK1%4} zLTWA(>{+laUoAulXB8I{$VYCaYPO47>=o?VPlK(%+HHpp^;O0Cu=dsQG{V7kJ=JYD3_Qi{ zm0JHE0jFtn;FUUfdt)b`ak#knzUt*8(G09D#|kj#CE^xczOOG$3=6%?Q`&c`-v8p~ zTA=R6^j%h2S##mKUa9F23LOBXjy)0(0Q%$8itvjmhE_L{(18@V3>Yi;_CjTUsj@A@ zwDrRlM*cfh=0n!wF#q@SmIyeY%9a7{AxLx_Cy{Vz4T>$zrsM9?MC8{HfIQ{mm(*(L z7M-p3bfzGY1$RSAuV*~S%O6wFAMY-Oy3*nP|Djz0fCTxF@eD?wi!6YblmL+cnw|hS znJ!lSViTQ%T!S!y8-Sh0Izz5Z2Y1Ck*HIUdApYN8g(3`}j-%6|vUC8jpcDedlftr1D{r(+PbS?q-@E|`nU3moFcdJ1Nlr!1%i_y2l|iC0`*~_4NFig5&UwLei_o4n6RdN zs@r6F$`q$V*QPPtGZ{K-skT%I$g16d(bc&QdSKm?%7|zFOJx4J?W`czN?zOHiYy)+ z-QKKYF3N>y(iriXE*eONIJkag(M1Jxr9v0xpHvMbRCvCpgD}+$>wM*3XM-65Gr16^ z2UK${6^w-v*8n_^KJSy5APY@qb)ogqkv*N=Y$*1NbRbyl`a=Lpha?N^-xRZ6gg-_Yzm^PV)OfgS z(HY?-t@Aq)^<1Ha%q~?5^!y@S?^)NMS^)14-CnD|EkZh7r>z|024**tO1cxmp&B|6 zQKTI)p59cs^R^=k-q|h2(oyR!O=5w_T~gXeGOJ0npWNMc_w^GH0i!Xb*spLGfQKHh zUs`oZPyy{{uNT*Wlo3-6?;_@!gfP&~kgZQAhBJ~~cY^Uoa0ZHx2iiSegHp8kKM1L& z-i^ZTrhih6(^)X2Tdgiyg7@lfTSEfjnO&OBy%Ku62TQ}XTQa)!-`y$2hu&;14JN+numP*L?4NSGRa-( zm9I5GGLN=Xvl^-y?$yoge?CqZAvF>r0C}CQSuEDs_1hRw zcMrWal?EV4egrB+0RZtPMyLmi#D$0h9o}Zh&)x1RuET@?O3nE)CMesGRWujLedGQH z%W79)0_K^Jz+r|G2|^$ZV{~5K?dfw@O$~l-4;@3OXYJWq3=q;=tI)$qGPO#N24Xj($j`V zs{~Eg*7d*LalW@0Fj_rY?lhJzXo7o;Rb57wof@n5WPwtw$Lz5?PKZN%hDFoZ{hwnG zMD|yjy{pxHUvKvQuunllNI?1DR3E?hey3Vr+`aL*AYicKee=ur&xYSWpMC%0=llOe z#<^1CE!O+(Xe_lvWV7n{pwBhzzVXeYurxAN>+JaJN8{Zu$9smyduPY{evZEpnczuH z^lMHGm`w~iO$_->42Mj-y*LzeYT|(<^6}+~ob|p0LGjq|#Ki2xYU6ij})d9e8QI|k&3A?os%QT)Hr&I%fi71oz$2$ zz2maXC8vzP-iIDiMR$gOSi2_~(|L6t`$Gf2;P(NscI&Hj;QupV{cq-|2LO;DmV{Dt zt>v^NAtm&{5@wJc4A}g6);wy|Hn>}V`}tSI;)f9fm47o<>*O1cO+3B0|B1nVvxqmv zMj7x=hwdH_(y=iRsRw-&a9z*6DAPEqN|)CjYzmXLJ2yhuKm4 zi@*Pr{Q$WCPYLt3BQ_vQxW0rKz9_m3Z_G~kG%pC@~p ze^CIUxtqi3rD@~PzSYC4*M8k-xU7_fyEKQ9s|(_u{z-hOd*$B2?b$)XD04ymT$y%u z3d~^Rc5}kg45}S$h5a`cw6y-^r{Ux8Aai8F13%ml+_sIt9VRL0taioFzRr_ZJ+8#8 zWFF?O)T0gRqi%I+KXlaUvF%WFIcU-wB{^X0AoW(xdk!4e@A&@L!O!~FLK{2k@1H?+ zebkqDc>#wxNb0zX)e_8`M?irt4NM3WHMBOA76~4WP+;Wnu!1 z8#udFyyAM@^a|p3ZQt!Cg}45Rc`fD85HtJ6{I6Z4LFI9&L=V%qs)L~+y647Z?9QPy z^vKn#qP2TT@X*#E^(DasOB-n(FPVp+X+TcVnc9M!Lb=)kg&Q^vi_^i{$b8f z)JYxtho5BJ9=!`yBsuPNJ>q53#%}6~Q^2nH-0J&#zQ*wO7-k!f1RA_?17U0+xW8+ID% z3kTOI4hSF91E-xL2F%GD0cL*wE*GxY{J0xU9|^vi^>$Qs#Ta{KC~)SBt=|=yG7q=Z zo_fPZ-aw76$glp-NYce9msI&3LWy);;Rxdn<;+J7Lc)s~u}t#x(n^nMd-{>A z8{S<>AN`W$^Zl}a^N;M-uX>yy4H43oJkp?EaY0?R5*lTPp&}DIzXi)DKeI4Oa|L!2 z&a(@Y7AS}voe=B^f}@7{6v}6@`)sd-Yx7t#I?y#c=9Ge0$s#j1`oaU#?`s`a@Z9W; zCQ()E^taZNOGyxR-$e^kR{+ULOYomjyDGN#pm0)4LjTw&Q1^XJ*V)bx3e5&zqfKFq z;-pt&hZRzjlz=jpNA%&dzsr+lU#@L6?qW#yHD7yrftV?7nM8I;^NIipiqFp+Q4P3_ z-@DSH(l8^)hROk;j4NXsYR0lujb%ddlR2DUBXjt$%7^2xkUH*lSbs&Nd=J;n^dSU) zkp}W1OHMw|#P(D>Y8LSptmcjGtM#!(z0z-5#v|QbY}}E@He2u)hK^tWe}E(mmzLo% zEIjUrhvMYQRF3P)8Z?XCq0Od&0Z1Yf)O3NbZ*-wWEKnAvJxq5q1EHi79GEf^lIFp# zPb+2JvI4D5-j!<7VU|HwH>CNv28)ceFo&(m*m!$ zIZ-3oMI5yh=d!eI6D?axOXy6sdbw1K>L8S=tWt%2Er<#65#DPq3cNfIWoy!bqgZ3EicGoKo_i=2*!WR#XLLBOcNrRxspEc~ z;k>Pwc-d*Yu5TN;*ia4i!23dZD4Pr?trAkrFC>b%sv&{Z*L#UWboAb+HigAnggrcq zm>CV%P%QJmp5%8nR}$|Ww~lflFi1>Q zMIy@ZRfFW($q+Jo36oIHR5ae#LHVADKj`j9+6>=g>;F;xQsGrsqG-Bs;1skY6e;K57yPpi6qBr|9p=Nk0+q;D&1cpWNiv zO45%$o${QszZ7;_rtVlUBHRtXsXR-IITqWMeR1KVvT(r(#@hek=!6V*SiDFM*NUu=L@xp z5B>*X!ni4&)a^4B#UMJbyg^6!YQD|ByRe}Al?=^3Us5L@Z)Qn%>q*X<>U@;tcJ}9n zi=aGwKuwkcK;=vw04hU`Lg*=;sg!Hg4{a4|CFHEBdHp(-@%s38dA;>ii^+=Ob0Ztc z4-!51MCucshZpml(_Ka2{pfFVvv)nuiGDP1x0xi8#WM@HD9r$(l8%nRf5$rydey>B zT`e>A`Z^@;-vvEH<*em-CQ!6`%WTzwKNWTcf?HsaJjAj0+Hm&;TY zI%+NnM9n-PpM~6$wJK3DNsDHP18<8+ibkvcYYg9ZF2-bFSJs)80X^P8x^Vov-LDa0 z>d7-F=-M??8Aq7q_>#3#0o^zNUpLb9w89G zl6oPg7I9(?UrLGIY{d-nu#-IOJD%@qtr@xu|M>_GCln!cTfKc!*fqg}5f*WVN3;oVbgCfT|)7 z`hqSmi(@||V)o$7ys20th1gX5hK7eZ+?A0J5LLlxDb$z(8!Lp_fPM%nM3n;briju6 zqUn6(EyC)9ax3qoJ}En*Lz>Ep+jKQf9Gq!NPNH=9!-MM zH4*V#WC>L)L?*b;>))=c%m_a_8z5G9^fwj1Lh#AhX08woSP4*VG~8me{BmvX4+5SV zgL_YxU*)pa*!W*u{2!r~LZFwz1|Urf!oQ~xI|!!r1TiMbALDl6u(T+64+H{1QY1pI z_E{05f<0#oa>F19RY;&Ngt}fple+?o1<*VlGzoSv48f$>fe}fl-5$_QBaH%0KL=lT z63m?swi^Lhp3YliHrQYhoq~u)!#_~2uG02_c8f2(LU0TF1;B6QPvb#$uS?&z^dN!?c*3f{AK+lj59k_Qkx!-~SCu>9oL57|bs1VRzFuZaRZh|UF%E3;saROm< zp0||2MQ4QrMt=8H6>JV4S)=0opq`BaR1w9Z;#J5oDol!+B&1$%3kJz3Hk1gV7Qq;g z5LtllO@UG?MW&a8joyR%N}=8fI=HXQZ2PkPiy@pD05IGLVgfvl1c8?oIORgXpkX8b zABgo8lnjxBUl?PDmT_tRrSmU$Zk*ORkXR}wj~}8akJO=Wb5U8~UYZ}WhkRB+P-b0K zK>b`$=z}>}n$`Hko8<6cH z^5z$d`Ka5`Thw!HVRg90S{%ae;P!zqi`x|->-3X^(G<8?ac$nvF;PrC{XujKC@iAl zD}wMrQ}PWh%&so|8YBENU4DA7_8S%a0vl_m_kx73;G)vmL1qNV*wcGL&b{K|>;tB# z3b40J$AaXIp9J1`8(x1;*eU4;t`-Du;ZOTh>nFbE0V%Jv{uJxUw;B$TK>P(iM^gE= zfnVp|U5b{k-T*h3xnXmk0A(9;fMJ^ zQ5UhRzT;jktgV3umBfA78N2RsgZtofxvG$>7gdk_`KtbP6Mmgk2g;tjuHFC4Yr33) zn~MgEhuCRd94t`@EdE}M6Up1a%aR+l_BF~1pg{us4L;@r9jDN>^Ho5DXwZ==O@jWM z&9QXo4LcQy3L*j!1qCd!N4dD(Mx9P zguVddgBGWy#6PO1`#*+56zYEC`SUj7T*x)9%9A$LdYXhoUiuLD{xpJXbHjh7;E?6q zi%Xc!e%WDJae%by~sd=LNiHKOe5ugq)%K3 zN4WE4-TYOz3K{t$(AFQrbJ?fP>1+lq-uYzxZ)}?Rxg&A7L z19$#;r26QNa^-r9#?I@eT5aqHT((#s4}#@YWky{B!8ZUjOu#VR0Jiq+&CfiXkCDp4 zZL_9E!u_LCChu*eNst(76qhOneHfV=bQ<(Jjzo)3lW^~Nm=^l}#%DWj>Ql-HZ_0r9 z=K#t$8o;qzNX?MMQA9lr&7~+76V2vpaR&RP)_E@j%SycpijYA^m5UrgcZmKWV!6C+ z_D+UX0OoP+fx4C5Ad%9_-FnVM?7X_+Ns#5bcZdefD~7aS>ajwuNEubEnU4l4 ze22Voo#Im6j3ZlD^)WGcloLU}(cZEW6nOVL*r6?d?$SEHWlJh%^CzZ-y&uu&^DW

hAh3XBQyPJuv2M%Nv_(VW! zcH|7pT|-%l97|NUqLVYuQ)7|sBFa1+&-AzODL|PT6zPhtip5wj;cMrtf9^4J?>$It z3WLSGgO&{?n2LZYZZ$95dmbA77Lm?#I27#rU0m#)sRgLc{4x}zw8!eQlBiEDv_YLa(r9tnDOV&l@XN4g1W;WD*dk z=?JWw-LkO>Ar*mcpFB-NoFI#a(?z`b|9~KApultc*?en)R4pVj+UTYLzu|iyrmA1) zfD`%JvrNYSs@?hi^3JWzx#r%4`3wg|zVyb5#4PQFKyYW4hrP)~28$x&9?@dBG#XdL zn01g4SWdB0R_WT@I+h<+7)!jZRMaG;;^w= zge9XXVJ&Wfk9|jIvE~3EVRJ+I>4Bn_4b03|3PMOm?ecGfw(!q-i65QE#-7D_nw89e zM_Ew(!gh6-YL_(1RhkXFJ7~?_N)XgeE%)O-3$TOgaJXR6#dF+>`OlC%>lyk zfv=#nu71^e|JGLdQK_FCoUuLO%1+$bEnvn6^@4|qaQO~X{q&WMyRwDgLjVTXzx!PP zY)BCiAScwIAr$gHGh?)cz&9c1WlcJGQ-n8zMroxZbarBm_L_-KW!cR9yTOPc3gkVm zBiMcybqH@HFs?rB%tS0zB5Z-3+uiz7wB@j-A>rub)4~8qd^DOz>iWd*+4ZG9YA-gU zMMNjzGf2oOg9=YN;VHOwNeU4AVg2r&{EAoW=|)MQ0|MiR)P~~B2JZg4-*#muhDQ7K zw5&jxD{}rps7OBtO4NoKG4KAF7riXsYrK$}t8*_;?zR~?ycF%>T{7MG;wz2!l^{<( zhmm-;ax8Lvum}<;z~8w~-N}+e$xaGGI$UzkG`Z zmfS|btH~(?Fp@sJ<;p$Zmd)YoXU~rQx4(2V5ha(q6h08NO`l-wHR$LgdEOJ_y!c_Ra6ni+ zJU(|!?dc1_-0-!|H){Vy=UBAQdH=;AXlTyQapmLB)swm6NaYgG z`rVjBM=Z_}MsE9#p(JJ{sJUeuyu3i1D;zDky&#|7TGsjC!#BCR<(K}Xy|Tb|ZGJ=)-Q4bEgr1QBbqOs-2wG+IUj*{mCOI7m8m1#%l39@t(p;v`@ zHLWs1@`-W2w|DuhbUJ?{RZgb_>&)w`QHUvEmzeo1+m zHd2JFy|8InpmxF8Xhy|#l4BQ;ph)KPk>k2nwFHjpdw5#{S)GSWCM z??AGyeNblZo*%*azMDi)#N`nsTJijWGaDE-WgUDSxOra`2lhG<{LKBA0WiUuX2 z8kLgNoTvXeFV36u=DeFXu4{(pxyJMT+@Jg2mgs3*%Dt+0?bu(4-1zBkJF~!<4aj~5 zN;Zo0F%_CLBO7DwqBdK3aEJpuBn2FI-4eCiB-yNW3%g68-A1cqxT4z=K_uFmZ%d4v& zYaVq>wNfAi?wan@s9P0Jw(HiGggbqaH?CJd`MdJ*%4y+sy%*fQ!CcrqYZ4u~kM!%{ z)8os7?v=+LenL#-B<`Cp1rP58KMy#!lbCAj#Pp3+Tm3GF8(RwQd3V}L`wqHvu9zf( zHyESTBX4d0*;Hk&rzea{IOmubE%+qTU8B2OJ@vJZrFaC7Id&r@>E^%Nu0xF|9WEM8 zis8P?vVBW_?)?(Yy92e{-mUi%Qs~HgI014bF3T$0H~$20PWAJ|Zp$bq9OK1Rg?>u6 zSpuhB*5D@8b)v(Cuc^-qc^>W*Gf=G4jMF!b3($m}b4#4t0+pXp{KLsIdsuZYDcw6= zMk4rh*^FeQeAU_8%yE}cVde*lhLnFzcI_LDy!@0!wc(r7cK8s9+Ta=aC03U8oNA@C9f^(;`7!9yQ9m~r5=-o=W(oez6Ig}mm^Uo=Mud(i-O&!p2NLzi8S%Fq8w@6 zA-wHHPRc8g!(zAPy)f6z>=dPpicb>V-2Xa<8&nBeZJ;+UQ?<@@Vgb2I1~!TUQ<@F# zvE!Lsk$idW@?c`O>4J<~tdoAhola*p>6sgrXrWEt9aNj%h4Q$fG)vhwRU;%46zGO006)2Zj*j4 zO21CCNdIQGd8XL?SG?PBuZ%)?Fpz1d7oIuoJ^fWLxd47D&2=Aar>B_}Zdcxj!s&-s zOX_`b(e`r+6D66V(!3=_3~2wt~4cv9thRDqXwjNu_^!? zUb5~UEpl{?ZjrLjvs*kQNqwbM&;k$BQ+3so_cD(}lxFL?>?#6|XU@~it6s4c%js9rLUTn_3dslWiH#<*bE~ZLM znFEz5*$(em$UMSK#-)Y6*G}!5fb59_YA;yYu3z@kw19BO8s5uxYr82nwYTPVYSv4% z?(>kPJrsZ5uH+ZcV-jPU&xq((=%<^QmW5%Y)?T&&&neKM-8+eAs-=xb4ZH0hxj%2cg&feS@wvMey*FJ=)?|~XvAmPcqM~KB z=WkCE1X0iaSVzx)bYD~XO+G@fw?B_*3zJVGLJ-E^-y^*`ks@N$2ybKWO^9Yk*<^O? z(g_}1ncfS;IpX28+`~fGAk`P&%(5lK$qj6X3aTvvt)hy~?!<<*Nb0&dHtyMbcnk9C z_U}axLeDP1TE+Y5aDWUzO17hnsD~|HN_cnsIlIo?VG@WW01``ssc^YQJI^S88`_M_ z&Ma!VkcH{$?AF$6#<>|f`QMtY3B~wxIU)%Ct{4D_bDi{GI_5{(?w9+I!^9ZV=^{yz zKn>fw~$_0NG zyP;+n?1&@+bd+Aj46sOnClTE|4!4^j4to_}8a(=l=A!bcelPV+Bm|M3qJb$vp>!yR z;n)qR2pr)2RfkIPHh?Y9l9T@V=ZLqp&R1lg67TNIi8`b)SngrHYozCx@$w{5j|-qE zCy;RhtkzlYF+NaG(5~aa)d5@a3 zs4xTyfQA!cGB-FdW#WI(U2=?eDRi>XihFwFj^t^RaD|(ZqV(}s$Htqs(_mV9RoE>g zE}Z!Uh&j*21PGlJuI|e;60iXc;dFa6!R$crFO6d@sQ+Yx=$cf9c!ZEC|C|VeSP5Vt zp9K2*{-%~(5%(cCneHo_6h_yLV$Pmr>Jed^JQx6puKhb}Qwd62o{3gw zrh;ueA-%#&MU+ZZ46C|v3?xH8zRCYB8m8G@Riq>fY+6i=tCZ)73CaGy8Rcmt^i*nZJ> z&Z8HNG%d%r&eA1N~iPsgW_%VrMygytrc)92DGIeR6FU=+HJ08 zOX<0WzjL;-1sc<|DHYj=3cEAfSoZaXxlx-3PT>fhxiP%kEDwlPL$(2EI{N1g0wO9X z;ojXo;%Esz3RdrU(vguWxOSE;c1WM}v)=UgD`4QP>)9x#JP0u*fd;FGI)aW|E5_8K z#^%>ovB7{scA6-Ue6BY-=gVSskC|;kL#KL_%a|7gJfKLZ;O5jbrKogD$_3mqY?PCY zd8DYI)GTX2N7IlWCCN#$v9tL?Hhn}k+4g_3MLp_*rDcHHcfpXjCz4Ab=uN~eT^zM8FP zl_nnt{)=cBRe}f zd9zo%dGY<;t4(zA2|zNN0Vd&e^tM^SdvihS50xRSN1q(&cbS3Y{&Psd2i~}!W#o#^ zftwIu6OIHKfip*qwizZmf=(gnH9*V*zyOc(ox z&$4#d=JJq3vp@OMfbIKX`&Iw1?Zl`Jf6|{J$HqYj3gR3%;u4^t^j;q8aDru_i@ivVABrVRyQ{4E^*Y~bu=JwG%#W`==kW)jM3nWqan4UyIMzg zca4UQj_!FM=zMr^Z${}pv9YjCemPO(aJz~Osel6!W0A+l4rYu+T^x(99gArlJJdB6 zJ34mw{n(LB`Uz|DM`gz2wZ{`I#*ev`^(<0tI!uNmXXK8ne;h-C92Lz|FNvlbC7@4_hxtVWJ}b5 zfyUPE>*sa-@232b%4|~DRxniOb2IbPE)a`(dPeHtOJ$qm%aad&%N^Zom$Kgc_ghb3 z*t6RkYfow*|3|ZP*b30d-!pwKtY42+(-Sp>xR5xO7h?8Q+jaKL7`Bu{|GK5YEdk2;@R0$%S$4x&EeX? z!>=Eo!MNY5czAsI&670U^V1(s|5{5vjJtHj!BJ#RrW}FGMhP5{8!(E}OC!zxE&R}c z!F}p8?+YSu_U`@UHk29GR9R;XW8B;++2@e=cm{Oi*dn~i9UgbF3A|rgCDiwq$MY?{ z?PNw%z6J*l*ad5kOdb-g{Uq4C0UR!a>Xv*7A_^e(9({f|J8$1b99+^{Ma*(IEaz8v zB-maH$82gU3V&YCdK~7lzd812HMvvIlAkyGN80C{`}LhKtv}We<5}POod@jJwLX^p zxBfkCJ37KM`eQBfB1jfYs~3K7=r0MlK;dr`?z}F_w$39*d%4@srENs#ev?jBvxWpS(~d!RgTS;A%PX~-lPR??(#q_^HYIA=|Funn)Cs~T z9d$;Hj^&w&I`8L2s1%65*n6gQYya7&><5uKAgr>jvCMn+i&pN2CQ`jLuX@Vi4fs{Ei))-MydlEd$J!#mVORE5vI4?s&Ha5P|e+=Ndy!zSpp z{w8Fmge3Mqwpnei%cGQ;!5dfeE-|y?HrY^cu;QmEC!0(uJKA5I^ z+XL`3G-h6InBDnj-EOC)SNKejeUdiB-a;XC7eBAZ4> z)agH9>CHC(biVN~v{(!#|B4)V$ahv1QAwsITxY~~rI3TIj zwcTJrO-C;ybolo)&^ga%xmBJGD&XR!@;~LVXgH*axnR-v*@hkgX?*vLJ}#q7hxe}!vK#39Xl#h zhDQ`*JLoeNeh@mT__@g6!%$mS=R~R_9gEpzC@Wx*K9SyE28i&?E*ReS?&-D-iBR z3R9Y;W!a;c66e675eWpFN{&k^zNpcCb0C*B36%@^R&IW45Vu}hQ@bKxof`T4uI3^L zebBS2Cs*=`0o$%UGCT{B_buoP_D~#J+mnzkqtew?9ls%NsQ!emwJXJUD<*b|66j}~OkZo(FacKT;|NtH*o=6Dw!2jgU6j?v^mxRq9wJ+;H3 zpVDJ7X?Z${_a#QG3gsp*RcahMeLGTi$HC+d{e`Hk*6a~Irl3P*TR^$wuL6R`D%5er zf=!5>xqQ-5^Wabvq6z=OZ2k;W%B8$k9Ug|XNPvjds5FL18l;gQuc#e!X+-PCAZ?RY zt7i^Xs|nZy$5bKa6^(G+%-&{AfaOdxki$PaS2w8b&zH z!uDNyIs!q^m>%C}oo&kHPSV@zg5fWuO8E_&PJT)kO$;yYDCap}&WPCLs-MVpv_cX4Rx=&>7XW5!;|17*5d1oN=m&w5#btFzlT zPhSo2adDC;5hx!mZbwL$<(db+Wm9!Ag2wbV`l# zd(`Kxi(#HAiLnkN-91`H_*;1}I)*y|N@;xkSY8Kx?tz72s|A$fo3Cm?M8}&mXGk|e zC67)L1Q)|i)9_%tj9D;HC#@W!@BAb`pqFU%kdc3cr&;&H;;jAR%sI)8nxOzoDw9mh zJ{X%Vm9E!i-2d+EZW>v(GCN~)>0TVae5hp2d z-X+qFvd-Q7`047S-4qEAD{p6)S+zs08SUO>2GP=|RC4`JIP2x~p13bqDY#~eAk$w5 z5e+oKeGH)grzc3mGITeqXkgAzP;GauY5^}jSu~T5)Q2MuKmgNu&j3k?7uhL+=9@g? z6!MLrJ&FZOaA_y8PuTdud6VZEGGBC0SDKR&G>LB$=+W_j(*i_Q0A+!LWe%==zeJV< zM!(a^sRIqvpiT=B2~;?eb3$PZwBR7=M6>|(EEBOtNgl&MS|J42p{w*;PU(jbzoRHD zXcWM30C{k&hzL2QM+Es0YqHor0K`k|aw#euLJ2-yb&>7~PKMu#C<=XKY^0>P-TXf9 zS`;il>MItVDb!Hozd2kE%CY`mAQsjIXs$vHpjRh-gwm*;_m zY3`n$II9*;zzLdD6cOnKY8?20grGRk55iQ?##2l1>?|CsB=vV$gaBE>(8UbjcMt?utdE47<>Nn6ajz|`CIWDvcx9ESuT-ja zr?C80Ga>p_=mr-*EWl<$K(&JSoI4V>;-<$3lJ951!ytTx%W%odvLqri`SL`FwmcuA z0=D$H7ia7LO568@c^15 zt3YHU+8{6rqC<$CqT-F6C3wgDK#ppWSa3i260W#ldvU=pT0u!m(rcpBBMiHT9 z^N9o-35eJXAR<9Vt%(XGZMY)BHXb)bF(NqYbaHT@RA3e$XdH8CkusG;Qhvm#jYblF zQVDhOgn1$^L;WAoa)pD=jVlJ%WKI_@gV$X09^EnSf#10@^5@25gfy1 zz7h#vXoSyH+(4W}NU^xrC{nW%2Cl{^k%{ue`b&`zc@E&faieolJ?T=9v=v^&Wx8L( zM}EVPG}Btv;>^WNf5s64rCgPXK(GL#MY+MM&seC-f*LD{+8~bwm;cl`8A;lna&|YwY1_ z`3JTLg@hbG0>ORzMVGBII)r_cTM(L9oVLc5IfK4AOpl0&lTZwvfSQ8st`&grYg^tD z8~??zWr6k&?U>=(fv5F2y-xdqW3TGldw^GgKp8mZN<2I&DFjXdl;k+8(U-|)>xf5b1b@E`cn zK8||sTa%_ZIL>|il6A;s%M%GgC=Qe`+-wz7hv<+Ik$gmM9A=1!r(8XsE9<|`s+xMJ z<)L-2aquBu+Z9cPHIp?y)aY0@X{VT!f1u;@g2I@G@Uuc(!6V$OIGiy<&gyH}Fctrn zCAW1DQyhUflM9idH&h-13y}~BP_uG^Dn3BOe-IK5zAnY-Y*%y6kGb>o)z>)r=mH%j zS2P9I#NYP#k!`b3#W=WVJ}&VyZPRxyewL5x$6QL0*nu;Z>fsvnP9l~yuYNJs{$J^W<8S+(9p0r#b#nb z@Fhd1IsGDTm>8L}LT_P$5#}A6SZ75vjj3Ys*Af^N4ct4r>U(kvC`)+(s0=c6JZ+s#UF=Oc;AKX_ z)KbN31UeP_?Q;et(d)Pg6!uWFPG5(+aid2h)QffGz@|yfs68(r=0r5Urh%O$>fC-N8hxwoQREv#1<6A zPYa?=L)jGI`nc$%BKPt*jq@{oeI)6AA~v=<;9OdG85=zx81%t4Nbw0=B@UQ+z}pa| zG$830E?HxjW{uq4w-{S!C6p8Y(qAB}idJ`*X{BMu1-L#Ano0GJ=<A+SwxHCFe2{mmn@t9SUra`1w|uUUSS8>8-&Jf z1iu3iRX*|w9Xm>kd&xy7k{Kd;_^gzN{JWcj$IM6WAV-FgHv?at)E6_PWW5RL+Ngj? z(4Z^9rB552Q>$$ZTk#8zOk9~n*U8XiJEHrGabNi5L=J{|hPKGZT_;tZ0UD|DUU_jb zN&Nl4j@xO%5j%x2uxysh<5avD;446Ol8AM5^2ZAj`}~uxz3_=TcKy6a=iY5QVsoQE zjE>l{8#f(?r?lXmLUCLGtzP5=3$#lBkrz6GcUa7U1v3{ybx2TUR!Pc7NW>@3K_8;j zZ?GA6+N5Robd^!gNd1cxzB6>YQ9oguCvi?C7ZfRhX0ne@@ZZ8@q9^gAd`vljsy`v- zPJ&wqpvH8l|1tnog%~NaJ0~GM>m1~fhM^ZHW8RESS4pHox13GHSNkgNWDw>55?T$2 zS;b-CDuqAGm~iSTH2(IkzyCN8J_%bPfWEy6pap<939{Z_o#b)Z>hGqm+*b3${W>6{ zDN=w*JO`u=`7J5RSkcF>)s=i)MBY3khNV4kzFH-9DZ2mlLJwMf^h9 zqd)=dfu7A#_$7*B^QokDdG1IYwoV8Y2R>Z3Cyw+kS15i6dJNIvipd>c3@UVHOYSg; zSG6_O)A;L`Z+Z{fMEFXUfiXTW3JJl}o?uh{u4u9}wH1^dyz#QvV=?iN|q7_IGbGpBXgIrk zY(Ua+Iky0HBKi>-H_d6eTA;VygFpLQMZ|#z5!lKkh&8!V#CJN*{7`4B04PKW~|mulW{yErh>d0sJ0ea08wQF)bPD_pcD&jrb|XFffgU-~d!Vh)$^Cj0$jDFW}yXk1GCwq512# z-V(Ey0eg|~SUKsyjIIS#U30};TIHEdTDac#CcU?vao%<5u))QV*PaTgW$&a^uJd=l zVB(xpu)s_oXsQ7RF#j|=VDwGJ{-0*2GhIPi2we5>*Yj_RnwornR=p)!{Lw$Vj>3>z}_H_XqalsQf_Wz|~D%m#A-^9RpQ7g*(4g+Gnm-;xseK@{^4j3XvY{ zc}-r!6PfI&-KE1mIJgl7-wg2&d zh2QLyvLU%%^XtV<@;(iR)a~T%o%Qya((xKWl3^AxgRDO_t2u=%$W9P>5ye5Uwz)d- zv+_$<8uu`B)OXJ>D>%i(i;|^w;#D4{3gA9C0v))q~7X15Q@tyX*=TNlm!kn5D zwpXhpq8?0wP2OrUmJiud>T*s}i$`~qQV6ZWIlU}jR12|R?2@BpTDx6Kt=7M;n7)0R zr^?hjeWF_ChJMzi^aH*-o=E97b74TbuuIziltf)|#3jef(unM6MCtCo`WaIDj{M>> zwFk_xX=2_KXO_ob1w)x-iey9gT4he=^+Uw=+ZBmp@w%#~h!;Go{#!(Qi`2CT^Yqdo z{Q#mQvaTv~=rGUsgYwZalMiKwulD+tsY(ma`TFa(vmp{siEywd_N!Amy+3?YiOcKt z51Z0seqZZ3A%J|nk|M6czmobq+PjLn{WvIYpb~YIqVMYWT)s4)qpO-M2c77qv(!>9&2$#Y z4%p?<6{B)=%3>$4Bh}8#`u0@BJ^dJ|6w9f~yc%N_Ex017;HIFCC6nn{C|!nG&}x** zXZbbRA>oxHM{X|dBz+0VRx2I(l~tIk@ydl&B=MXCsL_+_>W?p9M~n6!doJ-o>A%to zh_Zv>j&01sVz*?5G&+8CA?d?ZZLz|kbf59`r)@YD%ARI-kMtC?u`7Fb1-jtmdGi9# zup7zqWyco>b=8ty>R+o!=foQ*+7?$a=uN%$mQ3+m!j8x3-kz?qyF^VEeHCA)WU3Mt z7dKC&uSp2ij!P$ZASLj-9t!odS29Xthkjj)KY8or6g-Qg`V>X8*WpVZDI`$SznIg3uHVra**p#x~70JG0DUZ?z+fPuE{ zoWWg=m{Z*T%YD5*3@H{$h)|BBquNO**Ny#Bv;^#?iQ%%JMljJ%R8HSZ@USEu5UNpL zEBW-_gItV12SizAZoUgSpZIt#eMwMaXMZB`i_2Zl zOgZ!mX(mi3;#Tz39Sm3-xgXBk0~GlCU5eq899%qoS?Od`md%#C`G=K>>U+;>n7Q~t z(AdGyJ@JmprlvWV=gXSvj(d=Uy7|%lkxIJOW7fdx`C^oz`k#d?@3AHbXk3j|u%avS ztIj82(~f+v&$5|szkSF&0&MTTb=XFQY^^*5Qz>azbVcSo&i$T^#0`TkZV)upTPh577#7ZFE90}l+9`Q*K2}7JWAj+xS z^ReRDeA9?+vXDXMz@_>1ZryG zE8#CzDk=ktccR`m7X!i-+B`C7y%OaAK1SX8*!R)wq1CJB)o7T6kSjN_i1Oj)s&_~n zSXXZ5x&4K;!ZfM!Xntl)(yZq^_mJJ)g8bNpC`F0#0gJkL|0t_)h!Q*YXmN|_Z9c<% zsbBAeq-o7~zx$bZb%EvQ8%n=cUod>`bdcQux;D6e`bl2eN4Mi~DmCWu;+%^Z|K{}S z5pFvuK~`5TK!4{Ms-sQ~_-NNWE&VU;$i#6qr$rN~^ks|Iu#GI`SrBNUS1C^kc6dvD z&8zU~b{S9;}TC2~wmvKaqUawR%llw_BP*eW#yAfizk>M)V6!x9e>48Qgq~|<6 zUjM*YUj1}F=37{g%}YgfOm^3nBX`a)h zKSue2uKDJxqoSlMdpi~Y5wvJDmcW8O6I7i$9N=s^P_n~Z{%oG7ha+5x=y-kh1qq!< zYdn1T?j5;KR?3U-YI<#-FG^HLAQb@sN`KIWWaY*;z*KNORQ;M6%=YvdF(}C5+VUBd zM?$A9>VK9KHLhh)R`S&weg6A<`IEZMApoFo9fGK7&GU5GX{x*a^>}Ou(Meo~*d_)( zb6XV;FU&MiV9Y){H*SOL`usPCcQ#j&UvARI^}2teMnc4}>;}<&Is(+uK()B&>uc#c z%R-oRC;&l`+r-Vm#UH9H>`3bGll@wXwjLD$t|ik*?-ttk^Es;NWI8tH zb@2i2CnOs}&||~xlDJjsq!d)50HTqUIw==Ne9oNyb)^YF%F@5vYf0Iy{6S>^jrTZ& z|4PrM2BVeMvt*Vo3k^ZS0Dyv0owY1ED<+tDlLX-v@HmRZkO+Q;UjTZa(?2#n`@Mv1 zlCb&cub5t6yXt{DJ(x4WFDPxUP9!Nx?NUTl0H7g<1VB+#Ix&vbZU!jprD++#4C+D2 zHbbI>zS*Fy#l}(EC@-P;>PLT+&bI6y?Av-}&6%Xir2;xS8?uQ92GhYWgJ&X8j{+wG zVgS=r$h5f%H6enDGbn<0Uoy1RpryT$TzJk4RlUn*+2d07L|JNyO$JHUKcr5A4mQW2 z2KAk$@)yPG=^^EG=QYr+>Y`1Bf@w095)j6rFaGM7$G9}q(|3B`9_kZ6CE1uEym>7C z5*h_EE==_(Cir$YQ6X^9dqbq7IS}n^raH|nawAJ+4M~`wlXi6lZRBZqp*Fc>ukFe{ zS4~FH0a9?cj=)t1WI|YUB8QBk(N(gUdem$^dN+Yb*SP6+$QFNeKWg+Ws#BxoU_Uc8 zim4R^P3JPOY%ZP%K}|5UqO$$HZ>HXNPx+3Gho*__gYTYnME#eSy-Q2UOrM_0gKBv& zwP;YCHKcNq15UmTJ;5-Lho;BzQUPf80qu0aCHHEj)iIQ@`DLHJXQ@d{15)n=b9ZI= z_Ea_n!C`=Yo>DNr=z_xE_xu>D+Jjdp2CnUX&kCw!-*{xR@J^shFB_5(=h1b5uJ;%qCeh_lyldX5O%zn$ zC*hvy9@<=W8{Td82Wya$+U^Gc^cCG~*G zexJ-XO2s<>uV-`2T0wmx?e86Ss-Sx}5q)jWGSE5O?LY~ZMwg1)mSyCb@J}-XA(qg` z@}NZls7;*hh^Sf{aYmLEU~OiIo2}>aawMElsX2CkP34+$28<}ZyrS(osBW<4r$S-= zO6&&pJ4+2lwcoB^NX|Y8Lxhns*97-st#V)iNXPxM;@S+lvPXv1OD&+=2ymMy>Xq0; z|1#obKI0bZF|g)w#jYveOtY$pL6=zLe@t}y=+eJ8*6q4CbdwdNP=84K`tvj9lK0S= zOY&MV^ueRTVo{N^0s??&S*1Nl%r**SmIQPgaG^^rFE&r*V!3pQ*z6rirs;9{<1p@3N*5~X+MCcxg+%GsxD)?9Ec=qOdJ$%ae{E{ zov|;*=4kMyg&^vgYfJLglZh-)!h?#V!}S0pl@8Aa=8v)Z9*+xYRo`O(=_#0qvWD~_ z-dE~c`&|9R{bN)E_t##Y9=M5 zMC?4&6=mXu3TX+Z{zkfy)2SYq%D`P$;usmM(mi_qF(f2<&*Y7++|qTqo1?oL?<0zY z1&v~_v)E}F^@w5(RWa;t&XfFfkGgbZ!)MCJk>R;o7%r?gfXVa_K!tr#P#<;-p#pooc z_c39ieo9Ye{cppM$JBVn)B~BU*8Hglc6TPbrufeMH)5}+8ne0Sf^E|o*_JfasaIBS zTg7L@#AipnV5q(CFQN{+WDC-#7hC^nc9ut{KfRy+ygL0w?5$Ad?TYr>uNH5=xxW1# z_;xko?T_Pce`dU0yZH83?c4R%x4*mIZj8SD^ZxB$oSnw%TVsp>G8SqEp+Qe*3tRy2I@3s9GcdI}v?l)~A19ueLoQ*lNFy!YgGrhIDF?i+D%uJjvRv|cWuTyzRiytt*YY^e5a`^DcUx2uev-1%Yj z&d<$npQip*WR89~I{XY0du(aC@i(1o1x|I(>clFTJ$?yiN?Uy`y;I1`MoY;y*fi}Q zIrD3=%POeBFJXN{WG1t8X)~?;ZpzY(9s9X?+V<4VnYq!B zy@TI6fTt^U0wz`xPC@6A%y8xxCB6|NjgG_f6JYOUE|a-Yy4B%lUpaXh)RmZS(@PSV z^y)V8oBNV4LNX+`^&j|A36k|X=d2eNdiL3V<$v2@_w&AvlEdG%;d3a!T)?-gZGI$}t;?A%{hFg&5m)W0bDGzN(yimQ4=3-% zyUB+wedH;e_sW31b6CRa4>*XXY6!vN`K>z~ey!C=T&y@zMm$n*;FzSzz|~?ucUaTa z81HNbs^8&WiO9pNq9)~^Mdx30tH7nXM~Qi$T58k%@6diSZ@XoGVrQuPg6Ze@AfM{@ zML!6se|j|sg7#)~vFz91)$k5iUV44~sIC09Y12_ayC_pNLqRH$hq$9++`?m4S0v6p zHw1k*PTA`8$4#I~s7P{dQ#W)@*g@EA*iT;C;#_3@?aw!#)wbW!@v7g+0h0i(q;3(FZm^ZSK_gkbB~*VvYtAHRP^#dU-HQIUZ$-)~)Hx z?sIsG(wZ%MQh@|1Gpj?PUf(RlF8&v|r&h-PcJGh#^l_J0Utfzi(=n#Xf70^IlROPEL-wweKDHtk!uE@q(ZckfTIFuOq~WT6N`2jCr_ny*eudidAphqD_=j(H zSVVd8By?Y$p8&PC0IgceGP(R7(BY(#)9q2G?zmuXXt(E~>wtGtk4-d`2JZktBXWiu ziMt61rij^6p>iWMG%X4yzCuE|FULq_-YnF;^f8B;9xlBZuC|^hV|LKPIm^eS$7W*i z+)a|F+O&a&yo`O0`!7rPhOh{5nLrw+41m3Lj;<)qi%P>vEyex7x9$FAkFV-`IQLy+^M6Pjv!sz&U_ ze#kHuU}~vi9X?fkTfvK3tO`JAgsh%lvUR?)XZbS%nVZE^83C|=deT*(fFix>N$HbH zidz)I>Zv+jTCDTXl^=hZWtkvg3q_p>%$DGb=7#W1SjaUo8+lHgv-PTevWC@KKWXMi$x~<(?}( z`?O-MQ*Hl9p|g{w{;>@4!ku?$6LDQ?zcJSeS69Zj5Q%+ppj1>cD$_Twh&&XwZ|rZ| z4w>X|$(Swhp$TrLVF~ag-pvaN0awnVHlO>Xl6I?y>Xb7XM#xJlb02>$Me{aM9AD^m z=roage;2QcnMc-k{~~OgfvHVRP#R2LT!-Hm!`|nm>tjo8_r)2XX77xF zXG5TV{iJ(|T)6dGn>1JG7JBf@srZF7^}Js6pG()|+S#woi#Fkh-dxOX|8#|7;Q2A7 zuc6ofXcFB$0>*-#wBnsS+cTeU% z*KK)9o&Z`Lv{;^%U^+};1l8mJ+!vq3MTG9yj=H)MPe^!74^=3>@SOZtHY{Mj%@gXe z<(FY5^ouwe9fl1e1-*Ry4i*Q9Mfs6b$Swz2E9V#a8Vhx(6*=v*i@Vj2 zNX3xb9FAC@%#a@wFKwJt`Lk#V~5Sp0tR(@6BKB45Zb@`9O|3IL#3l=O>RGmnd{A<@6(EUMk) z2iVTDlvBe*!shqHt_;FF3no1Vh~j{KH1WF>><9<8!RBIMdyp|~5Otwf9 zF%sW`B^V+0HOqlBL-eU8d|XNPNmtS!VuWm&{l0|H9DD!>Fmdo-Nv1xgvg>iC3s)VE zuH{}#clpZ4DL7)e9841j-P{s5V&)}c!HyIpm&~VW00R2VYd^(GZ9lR4I$xWR1mX;kIfiE>j5k2;C2hl5+95rPsuZ{Mq4 zlBREZ=bPdWJ{?{Fi7TvAWr1IYRk799rW#l+Fv`fr{}dFivzYWneA*=b6D@ZU?8?#c zAL77b3x0)$AEgv=<1kh>;0G2{r(F3QU3akTc=0ai(E#fLPHHnhNcx!NI49QrK*R49 zLgQTR_Mo${Hn6&aHx#(E*r0>&U@HBMcqG?;IxZ*-{}tH&T({;E8~@@IexBImE73G7 z0LRL>SLEucU+N$xa!wqf@vqWXDNAjhDT{A=1=tg<&v38bIj-Qhj{88}SwE8q75Qqx z7+cVaO0Xuv_`JMNK(hh~<#y4&S;Kw+z$T^P><{2SQL8Z%AZdr65#YQTO&Lfvp(Bob zU2iJ7=Ju@oP9juBNLUVOzPO9n76Q>0iiv>4Jb*eZDELCvGR(a^p-*gR+7jxx)z^Ld z%mwDguIAJ9&GRt(|H3i-e2l6i&S4h!w6*#R4fN)m3-#Ke4T4yNghV6pI&wva9=4TunT2?@H#jAY$lBF1_@Qn`BG$IwE&QW%E0gr{kD@ zve{Hz@d913@b$Tu@wN|3;`-ROhlX@Od|)vQlyM?$Ie;YTro4!L_r`AGK}Bc`MFO^h zhYtF+n#KFbm%t#$kyQsypQeDe8gT&egp6$geA0r%KR(n^j&7QwD$bL0`UF*@uXURI z55;^A|*}mkO@*REH;NdwgOo|6_GJL8MN;IUQ%D>{E zTZlemv|_9H{RM37;639CU?-3SMy@L9-UHGKJQ}9^E;j2D?iC5g7N$${_f zR=6AIeOwaV(Js{?z)G27CnoDf2XxC=h6-Zn0+M+F3tdA(SyLea_uF=)5M}8QBmk@3 zDL29<7He!D?Y<)hc~+9yDEg;v7?0K|B$+~#)O z&=J##1KigM%!)n{3xc3R3yJxc)QK)`#PbQXKbiE~LgGg+AJ z5$^Zfo!+TGu4JKA;6V)$=6M}f*ISXxt#HFQ5H5uj-gxk&9kZv9Ms-o9VHa=qQVS?r7HYERiCHOCirhl zgjVXLdLaO0bw_Iu|I9T)n3E7@ zA%yA)AmYN(pN3aF4-;{8D3gAx_S$w>feqaE*;M_2*x)19?120tTB!{8c+{uS`S=P8 z*DgRaIb;4Dc)}m3AqlF&DpPClQf9R&RX{#_UitoD9O_%QZb{rTWC^d*Q}HKiBojB% z4!}(aR__6A0R4oI9p{fuCCZ3d5mxyBTudEcX_^hFksv#wA3EJ^Q&Q&XcoA>Dn1o6g zi9}rgrDMd2tu#dZYcYxAk1xkd(x6NMX4&b@A4e@v*z=j5`x=ms1pj@aP2SI&TF9GX zq)fe;0{pqCQXv`|W^}@tsNhfB(l-U20o3`(r>qX)rrVRIAeou@^9(kI2zW2Q6`g4Y zK6jqp1JM&AKr4R@)&2=v_EHpa_PYStgs;$osB(}`xW+Ra-gl##Wh#DJfbAq9VZ_;J z3Emr@E4BbCPnZXnc#SWZmii!w-rX!uMmz%BizNKn6q%<6x0SX(a8X5Oip@M^K-9@% z=|TcplQ^@7c(p|q=0xnZp@9^n&J)jM9O5nq>pkuf!~i2=^Y`Vki6Q|IRjG7Y9~uhg zmx9GN0xd8vm2&?SwE6^tJvbOxk)vZ}UtjoNWW9MfRR15ieP%I>S?xPxCre`uiLo!K zhE!-9Swbo*qRq_M#*!rx5@QRkLqbK3U0E7SWvhm4?PDuS<~g75^T+dCzu$HFe_Uqf zIPdeiU-!LRX71fJ{2V>413*=^EQCdtssf0l2+N2E#P4^cN7aZREcr+QZ_x=ky+~;1 zVVBjVzVlUtAgH=4rh|w%P4B&zA$?01qQgccaJ*q+^J=xE846y$JRAg)iq5@2WWm}w zdz#2NuUC>&pg@d{8>C~Kc)Vb4$Lj~u(tKzn1r_2HCZvD&YWoVC>iRC9|FZC^qGuF94{s5?8&azi(@IQ;Yx%`Lfc+S^dQ zNc>T=_;HnBU_;z`g?P4@=zWU#ORzW3zr3&*qC^uZjxfDQ!gRU0SDeGKw_{t#q6J)( zDFygy{aaME2(%&9Du+}!V{B|S_kANv&gCkQ<&K+su}pJf7Rj>?m|_}cM+9)@;W{F+ zMu&(@q7v)aMD^FwYm^IHZOqDFxGB>?z6=ev01tXu4Rdg#7xC^g_*>ca!(0?h0BI6F z1basaX2gTnYxbgIcIeXQJN`=5<>2A|HeYkW&k}GT3kPxUjNMJ&^rYK;!2LiS02r7= zI9`ZVcKrWnr&>m`9-VY@dgbMat#5;x{m6MviQR=(?5jWdUX^WFIWphZ{JZ><=*2IC zCvFTJvN%1l>3`SUV7xxq8X@@nD;+SlFiSD@Um_r~6T>W5yj~t^&U5^Gst7P2`|QX=35&(VF8b7ox@IRi57| zol^;AN8Xk@=1wKSU@n1S&k^aM{XEWmeLly_>uIoRH2&%QlZ1xW_6)WCvhYnt6kop1sob)meM_$WgieVbd`%mE1UJnGl$j~>#b-8+k{_G26yOxX>RRXWgEm1r zEA$sYZwx)Zx(Y~$+yC%6WfpY5SYB*eTO(}RntwPxX5oQCd~alT@%a_2%)%4TV-a$} zMKw}|Zcyo%1D-}}kW7E2i>}jgWp+JPr+X|Hl#>2TRT-LWhJHGXhw>Tu0mZQhg~+$H z-M3CQlp5STc{_IJtGEotoP?O7kLf2pBQ850MJ1~XhgexgDEGvUG3m0)e?0aF7iOz! z6^1A~&#OdX%T6kU7LN&dajaM^X-WA}?q}z1qX0}@un;fCV)>>h3pRbvKDsXvadaPSi+q#W&#Z!gqR)wmu%)*LcUP-NKycP&sSA_Wmwc;>A1l3P2o5K# zS1FvG@$c4NDQopU8=vLtEGv&)V4oW{>N$wwPHmqg%{vbzKMuWn*)IQh2Dw!3^sAKP zN^GQ*`o|6n;#@Y(LhX%(V7>aT0$*HfU_RuJmTg=T>sXnBJc)&}} zB|DrzXYX=Yt9^Ba<3SU5)d27ST{lo&;cJA8CAU)b(R;+@zN|7uYjVk+W9Wb_Zd3L> zgJ$vPzNoB^cE2;$0t-lN7nqPmM|tqmPJ#~fsV0P(D9fe^n=0Y803d9r9#y*F7uJIH z)jcNbaIu4`O!zLsc})luO96Og3?iH)ayq?TiJyyjxkdLXE#DqzX+eirlRZ6aP13Fo z%~uD95<7D#09w#thWE1%cT|@x1W#r@Bw!PKxyyH}om^&sW-aNF1nY~G6(93&?M`ut0VVFj6Sb-8hH z9XcQ#0aK~qLuBY*VN@DaY@>Y_xn+ybWp&6ga}8-_BbM8yQSA%*J}BN5%w(>6K`8(n zWdR5SRY**{_b-Stk%5%v07G`W9zGjK89Xh_3OsflrbGu|C<;CNX)bE(S~tuqf+@BU z03~ow2JN8wzP|A5(F-YAq+>1}z7Y?%AVB~d4ns7Cb`Kk3FIPv0lfF?zG(d>ND$5s} zVEmA4#?wl_o|*sz$a-W4m&<~W(MJK4w~m8^GZnb8AMg{>Ps^=*75N8+z{6_kr&}-H zLMV6mAX}ZbZZfv7UV39c^V0v*n%NyFpDucg7%#)0NQ7bm7;a5l3|lr8=V*uaq(jlN z0z!4{c`n=r6}f+fKsKwW$7XZv1Sy);Qhd}dN*ggLVp{(j7m6Oe2V4ej) z?YsWsVo-a?s!GM7L5AnCw8I-PS(ktw!<;u3v9zu$)*mR4Q~VjN+$ZQzgdNHnghmhX z;cjcm;$Vt%OA#AT=1@ei$AWB*Cj0cLKHR>y%)#{PmOfqbS@CoK2wId@xJrmg&>lM6 zGxI6>_9n%{_x+c)nKu@tvLdkoc4=^-x@?XoYY+C=>!8qZ7}}z>AQ3woM}ffQB5ojd zvlHX!@*@>CtwA!6!-K1w-XO&e*;{!nBqs!@CIv_?ZyLdbR>QvUD2Uc*GtNQr5dU`~ z51FFM03_(=lMf!coC?XdpA{9l{4zC06Yg5V7P3D)X7>jeSjD2MYfPirYjz8lBR^6> zOgC2BUi2pMEIU96S|9bnnGDa?E=BKZT0SKl1lvFd-~D`GkCh~zz3W#r7vg)1k>e1O z;Il<_)s!WxFgu23-5d}$nWD8WGAbVyO;T_CdE*wCXag{PkZzszE*GSTP*I81ze0gj6b5(0At@Ug!VYQCV1XUCy79Lp300~6C@WEaUc-?w z;~uhMTV@kA+ftQ}*J&*=dvE|-?FXS$+gJA=IzDR~J1JVj#EJ7vXYHVAB8#ocu4vCfs-S%^{~-{gP^}QCgnF~pGp;IyX#mE!WWYlt7*<+9$qJelrs}ca!>S1m{z0je7i6+K>JO&9s2m^7$yTncPp)j7Pj~r5aUJHQmgjEqB9r%}d} zYnqH{Uebs|?!~)@_mV7qrWsGaim6?|(4zAs$tfGIsepj4+`$Unn*!s@*^^fCq z$iW{a2c|RzrcDPvIS$Nt56lJ*%$*yUPZ(Ip9r#=^@TGp>YsbL1k%8}~4uMkxKjE)m zt08}4Usq7vPU$2pZLk*M$!F+EPSicuIaOz@&B_S1IJDob;p(T+V1EUW>YWfPAC3@ZZ^AKgVoC1~=WxlTJ=Foch?2ZF1c3mR0l* z{=XcThs7-y*Z!DE_Ut)o;}ig*7rhPl+mcNK4Fa6Q<+@V)3M~~g}~Jc=!q)%jhwCzeRId`{oMD7#+ro(!HL?ZkF;F)y^^Bz zbs(3E*kYlSZpqCqFjF@4ZBvvW&jOq-ilp^kX6T4BDI z@7CvlI`*OzI`Du=zd*C!boD**&6O|rKB-tQ_6_d~7cm}rZS!{x)(;iR0#kX1GR(LD zWYQRCBD-(6&xjH|lI=oyo-AgRw60c`(ohY`Vg83pY;|r!X(Tldb_bgKM*F(!DoIFW zM$dLCX1|&Iy~}dn{ZG61FKv91xB0Un5oEvjSA3@JNypLInri7l0C2Xh8Z;iv70!5i zikN-U@)%hk+L@yJz~@!*rQKj}C>3?=9_b9vv-oN~pIJ^$Q2Mopl~`FnbjZ%$p`v1M zW&6Oj#SNH(&0kkHp0y3Y4!ZO0lqHvWol>4n8SXRt>iXIuU}$Hm@^a>bjQgy4?c#8? zZyKpYHCL4w(@CUK7|J+ByJmDGXDig-nwl~4V^rDXV(86X+t#ngvjldKLL+Xn>p*xVb&UJJI$_6}}RO_|9z3{oLHC?9+)gIk3=&W$M zc@QBV!&`f;BORdq%P=tKYCuMEY`RC*@F9o7D{c+(pI@!#Zhvd@YwZ)df7@?iivl3z z0Up#-HhYVX+B+Nv-@4DKX(_^vr9ElTAf})#rnxjpK7?Hh3YJk{dTfj625AQ4XvcZm zhKPCnXiNLA*Gx|4XzjNAVE9=+*HC8U^-s^YFaq|=pOejg^uPSx@mK%iubN(nmA!Q? zUhb`|L5sOkYHPMepFrVEj~#VBIDg7giB7qO)-D~@!GP-zYFYZaZJB=zk99xqGa2%B z7_W%Dh_sHbB0w2m&i~WF*f19j-z)xPVAdf?_FCW+DPE(&IK`bUg*`f1rd7K(P>j_w zvkTmPcK;d#7b1w)y<~?w$!b^FEJauYZNw}d{I5rLs`sV&Wb2vIPT`?s+oL0$5vR6a zYn)W2#9|ldsF`G+$!tS}ogftv>xzfBWtUSv$+^W63aVw)XlrV;9oWRQq)t@gchyS= zC=Bqh(=8IqhHHVe#{+iKHl9Brfz|N`gg&UUOA_TM5j9&+(cnSm?xs-@at5Ssv!!3r z-Cb_Sk8FbOX1mIB1y|^AM&>0~d|I_B3KLRm{z5WQ{Y{M2YG2b`t3>jiB2uZsA`xkZ zDutbuq*K1Q_Q6~^ndcVb)ksEY*-(3loBSM8w56y*Y0ni)d4%!W4aYO!9gvSdt~YS` zWxOPc@i?VhTsqg?8~OlVL~=e3_qrCkfYBWJ+=&dD61F=oxk(g6B&Y(6WI^JTNNYua z{en+|MT{Xn1{`P0PN7^WYT|9FaA*IHDr#<7vedIq!%NxO!5#sDIe%_XP8%84(yx)` zSCFJlV`7X?C;@JSudxg71FC{h53#etjA=lkOwF=0D#VoWjS_;fEe& zF$tIX4pbug5LVstFBD-^T&h=jzen<7U6K0jBxF@XDZ)Du#g{k!ATk5)dP*4B*)&>O zj;fa3i|Wv@SVaFGw7=FfiZQF3!nxlHP};qbykn)7u;&X*MKGGYbJ1OM;vP)ox?ACW26e~>#`%@>e9hT^JY6yQRrmM#5EJ`jerxk^m=5i&zo5~<`Pr$ zPhZxHKI#t_k>5;vb%k$7Xc4V&Uu){tUN_p?Z2V;J8b6^%ZE_nQpovzF!VTqb`ul0! zm-(REsciv4JNq;c&d}Ozi#WiY2ctrRbGZ4H-D~5jO03~ zEQTZ>$n%)IA?i4^7n-JR{{F$%e=w1veCNS%Rn{(En~Zu(Vyb<9s>zwMi-h4KNk@LL z;ou^m3hGKPkrMRSkQ08ek0HOg{kfRG=L{BWhrnO z0V#9>y%c}u&?mV^GjL_|MJ4H)$O)8s2d=UR#ziluZrT4%lq;BK&BY|wk#v*pc;dtK z)fJ{ctNerZG?gQFjLIUO1pQI=#Ekg-;3Ed<(wq0j$cg;eg^%%@KRR5sTuZ3>9 z9$`!KRDk&2Q`*8j1O;ZOBOzWKGpVkWle&kbt|;KR?3jb(X?$&0@qVfoxwT~V!a4P= zn^5e`TLhEpDKCP)aKrMD02;V$AF*^V=9)?0J47^q%HY~mf;-DV)R!sjh=4G~#($yV zr>-5qdK!M`MkWLSntb#u??A9>+!B%WpU#0w_%k2a@rEFBjwar%E281#(M1qYaQ2`h zgXhoWA*w}CyMp}o68AkRrM|2*1ZYryI`|yPXyO<8hLKzD3gaUeyZZqC_YLWo9D>)c zsOmtVM6e6mhJR1TjgU1)1)u>WZav~aP&Q?QqA8L`fIDku=TVUR@k{ntB}q&%2}Kr4 zA`3*UOdbKpZ(OP|P1K_uZ`DG1{UX%RZSxseUPN-KCvK5Oh#n@&CKDF8(7X_9fCFtM z;XZJ|1PlHR2{#1bWX^fb3h=Pt1927!2|e*1d2t@jk-w3IcU){YJ)w~(TF65lY(EnA z-(V65{GD2D3f!HB`aMR@E~4wRl=p0td_$7@K*Q@xNKf7%et4JieFfIY!A{Wd6ItNc zK*%*!F&Ud zOg4Hu1M|hx6iolTkJt`E7w%oU0iLAa0zC2UZYLV1hi^L|E0HSHIXnSI5Cpi_`$;iT zf$M_!{6^zn5xGbG!8}tW$jkK8v97L|5~6xEnHWq3rMDrMO3X9k=Zul$*f8h6lmobz$oybaVtj`E2PJ!QBA@oz7 zEt#h}NO%w^nB(DvY+AHgfm?L$L(hv3>_DKVV38QN1QtxFVq7`~L_u;WSIe%$Fm#9z z^uG8)UhV@eCg528Kb6qoP!f>G{HU1tus`37YUTLRS!>3pf+r130NcyLz%{5gSzy zB?3mkWT}vimn9Es_6l{0O$9d#*78iftY&3X`^c#u*(zVDfpL{lrQW;aSW$brlbCV< z)DEn2gBA%*BoEfWmVL@p8uyfF;b1@VK`9V^YKR76OC{_0&trJ=ar`%Gyjni~Gevhv zfRll0LqkN10W_V5Fr-2(6Cob2Dx|q571$+8JYc7Qa3;%Urwpcvq`hMqd#W@1GcgY4 zY3Sf{U^9!b&exUfK44NolonJ#vmpnsffIAE!Vxsys`QLg`8NQ+l%+9aob`AfZ&iq2 z_#Y6lkcCeX`r*ABabSZ6n(Z&7W9mpjmnkrJE8^)tx0SaMEjytBJj7v>qo_uVkiDz^ zllc_b!Qnf)SjLK{M(Kanz44ncL4v{|RoikPcsjH+D`CPjOlt_!lO@wfO-q$0RC@2V z_Wh4pcu$Smo&BHr2cs*0wun&v+>(5Jw@EjkQmxdxKxG@?&XBz*^jPQ+ue;;vw zgp3;^i=R3s6P@j^?W-sxVOxlpN)pnT4S0SjEKYrZ5QC_3EWtr>4hLOA#C#Uofxj94 z3u&8xt1&kw51o=K@&U$m1r7gEH-m<{S}nYL>qDvi)H^=%z1gZH;xYPR-Eo4Ao0+ESzLaZgxJ$TzJ z^FYjOvXnck&y5)Omjd!U`$EO5#ynRaW3`Mel7=PU0l0Rmcl5MF$AoD)Uu|dxopK&i zaRTgsL+(6#%0EF=B0?0%h+inFIT8^vcQD7i)WumkI%r#qStQZ>MHmOuL&0@$&|k_O z3Tcmi2Zi)!lITNf`7-J0i!k&BgOrkiNf^oG}f+ zfp8$u=+S%^%7ErXi1Q+FmR}9L(}_RVyh?=jO;(k_ehy~yn0z~chP$A?2HerHx2@r$ z+v*OZ&+1?1Aj>w6l%*qsxv=3UkPFS-moE`LpF%S@vP-GBf7kJOWyZ};#EwLw7K^xy zu|tzYnkZPAWB6GCwvZZdk%%6waJ^WD_Sp9-n%rNhk8G(x&`2Vdbf^@!MWVUm{suvs z2gs684IE6p6fQ^)zu}*@B|hqe|F)3SXVAC1cSm44C`H-p`1d?a4N+9cLE_X=9oNXv zTYme>5l3kvAfy0FP>eZHP+o!O19R@JQ`kFV0ul3T>g!Qn+My4H^xmkmCs`ZG>H4(h ziQRBY=A%)tJViQGn)_Y|V9ROt2g(utG?Cp@I9UDDr$Iqt>0r%u9KXN%Z@=uVL9uI~ zM@{aFo!gfU!h7NYcjF5>I{wAbbXGY7rn-1Jfiy zmFYLdA^=f7FnQwUotsaKFAQE%9FXEeA_aupsdM9jl5faSP3?FgSDsT!jL|Gj{!2LW zez!CQFr|q)MP_~#;MJ8#1#S2RFgwM;KIg(9Sx@iWAGz}W-Ie~4>2SbaK)A`?-;Ie1 z|74zX4KK`+dgkyNl&DA?ARM+EgANuP%yt*ef)xYUXkWZgpaLn=UEER;U`)=Z>kDJlGqaSwUyhwrewr*p$z%-laol* z$%3|Ns9pID^O*xHxAobmXGGjSrT35{vtQ_Udw7`L`^mq;OL`Vk6y%;wkB%CJz7lUd5xRmJ5fdwr^3RC49@-TH%^};u4Rn@wtKB?Feul?D@+;kKXGqe>h(53DYix5 z(C0|dS1&dmC_*%;Te3-+Lg3r5T2aUmA~5y+=#x0%_!$)faxR?Gd zzv-R&udQ?i{xZ8ADpzyNV0-YL1NFyWZ#v~5zN@&?TIeSw>`61bi+5b!g#RJHlElMM zPSYVLKtFhQmeJW?9^>_KqnlBGoga{%onKsd^SANm(HBhIC&*opUomX3d%q-^O~-J8 z#-66^JfCrR`*{KX{@%t@2hBsgJ^^dmQ{RtuUA5a!G@8?K@oT(rSaCn6pgr`RXf)>c z&&j9ErA>pG(bp>Gl})GK*Eyx-1$4^^EjHr4cQsm`U;5I2_T4EZtH}2azPEne^V>p@ z4zW$fOFAUt_eY#|e|ne3i31Z+f3@$k-<py0U56@+P3(efRyEY0JbbqIhu5xDdO zhY*w!oVC`qCHH>$JDCsvR){V%^-64{Cx79m?g0A@hEk4cb_Fq8-kT zwB9X|e5@v1=BC!4s)FhYUta0yO(SIg)uky{{R_vY62zQM{VPT@EM)n~G>gzKg>#cn zv`fzSwcfcI9#fgB8Jus_3GE!w9975YN6=Dj%>Q(#9*h{v$ge8<)VMC{ zp3J|3U|;*b>QeqyRMxSApgT_DXL0r{norKI1`-UZb}K!{ z^5H$Ky5aFZ-Esw@ujcM7hy9xu-iljTM@}+3zF0_@h4I(tnbd)~Tc=sANuMr`gP|w* zU89knpsZM}WRVW(n=rH^-=64Hy-_t47vlLvg_aN*RuEhv|ML#dYRShtu7erKfNkLd zKY`n$NhL9bW6{bN-=a_6jFYUGlRI7*+O<7+^NGUg9MwrSYX^$qC{ez1-6b#1dL{8$ z!4X1^{Og9XU+R|{PF0tl$+*vk)PCOpud=;+ySJSS{_rN|ba83O?V#e?-O;r;8YDAL zGP1`#1Y>I*StTqD_81nbRwT__3out_R_22d=+Kh zBqZDD`pJ-4l}@=n+Xm08#~sz>`(xf4m(?PHKx#bv1Re8@RLKON+-d2uqBm8s9+%Mv z1D?JjVCwMaHv*KEKPQJtX2&N=MF58)5XPtSu10Xmm1h^6_g&c65n_5WYWukkz=Hos z+x!bnp_+o`@{-E~LnLp@PPR8JX9jqG)jXE!CyS}8-Sbb~TOkzXWt$YWVgonYB`+NGQayP631Wjr_^Q{V9kb2CK<@7B2%nD(2*pn=GGo` zo8(nocvhgI#_FMMtl1LKZ!tT-rA5DbDsPC9xb1`q$Ej~_(XZ6J(Oxzhz zk&3;y&b1waU*cw4t{U$2YtFq<++{EGqeDd~Q2c-(CkAi;z%;^HdDgT4@5u`JQ5GWR z_EcI^%u2bLyr`NJ=O%?^BlbKH|ko2}zW{NQ@(y9+yjz zHBLhc?eymEsvQZqZy4)LJ`_QJB7Fk3^Ix(mDI2{T^+Tm00yVw4__QXXqB6`Xz*lt1 zYs`%VLr|~)nT9zX^Jyzjw(Q|;)ttz>QEl8Gfc`9!N&QJf_E+2CLS5Tgt{PQ}CPs98;Hf89#S6jehJ8gyk4C~W zPg>8dnd$w;+NSjWOAS69F3VRbI?PpoPvg(Ws4IL7bbHJezZzztE@kFJx%~5M^~4`9 zckjAmKdElQ&3_jlYb`-llXx;2fX?`NrCJGnC^O^z_#_l+q z=8It*eEe&H5H4aR{HX3WT^L$cmlPwemKEsKrSK&AV&Dx3h9BK57Q+BG7wKfanqqUR zGuhc6slwtzWn}39g3iEUD_^heqM(2MB~)1Ss@9_-+>g$SwO%;~6Qk*8cK;=S)C)X> zl%P~Wg-INu04QRss3A2AzqCHGYnrlE2toZi+4g4n9Ll&Ac5Q_|)75D|3c+$m<6Iw- z2t;nJ?Z40X`h)Oqxhu9?h_lCsUqT(9@NE_C#=UyF6Z|9*!}icY;nn&DRm!tQMAy}O zL?1RnB1QmJ=KWxv<3rVS7zk-T?fAQk_Q+2Z=;&y2*v&k3)o~9oqn8qL<`q72^jM^_ z01#0m0Yi@fWCj@mq0o>nuB|8vnept&Gg#&A#_oUL07-D2%O}t9D(SW~<6+jUNcbJNO+#v1aFOh0z%!GLJuc%Q#pb}IID0`|d&STR$J4qz|I6N@ol=(%Wbxg;MH$w- zanvEhmy zbXcWw>Vga5R;&v*NyP1)3-dg7)AUnl!G_CHu?0g(#~254O^{!WGnayS9Na3k?MU95|<)ao?oh%V)=0ZQ^&$~B>;*} z0BVN;F$(~k0*RhOX`-M+I)Hbz68?Rm^Q=)%01{edpVbuKePWI3Rm86+YqOwQu1qBl zD0+rY&|wj20N71Z<-SmsY%To?NQO(va<(U1T#sWVwv=0C&`SNzqV9Rt??)HLaTxj( zsPZ>Ek^lf3IJe~5wk)7@NDv`{DEc|TzS|YF5Pu5Tx_~0kt^|gadYGhq zKum{)j-kg@L)ABs8-KyP5(7%Flc?xGwbJo?=FvYlgV&MrW2lQutlb-qs8)uKPN$X* zOMfjHP25gEF_0Dzvl$dvq=H7U;%i$ErDx#ix!M|BPgK|OG_Gtl)2^B8sQcLeiX?C@p0JOQ! z2YUfTbyrkE=Zc=A)+j?M1Zrm5mhVA-VthwCl`hq@4f`1-rzjT1%o6MQ51GkHcT&Ii z0(9zV(z@>Dc1pw$55LkRSh#1nx-%mIWgV1D1Zvodk^!h2O|y1;-2m091|k2Mc%t-K zD|+tv37v5kuv(Aal57Ag0FXD`vd`g(vK?SFDTDj!o<2&m2Wmiqh)}B-{$>^D(u@q;;hWkITheg-Cw`)RQ@yT^b0e)iGl&p<9#8J4hsPYqoA>!ipwAP9exdJ>N4L$Hx8uF>(h~0 zfC!Zi{$O}OUy9A7DNmjO-#?ZTj<&`zpTvvt{tTJy$N|vRJG!-&+54HK`hmJu z`4*Q(PLIqRPlq#uN;vc(xTrr-Sw(Xwvq#YaUUZdmKW7NuFR*|98a0e7E^rt1Av`99-z%`v68rnc1t_^RGVy)?; zLV6GZ9mBTQVS1B!A2x>Vqfmk#b%%e$j*<%-)VJlnGYu~xTI4MS(jAZ47^nA zVRjL{%%1coeQmC@-YQBk*f*5bj(vuQhxUVQrPaX*a`G6;+ZSvry&rUS-FLWUuZLon z@A5ts+?&C(o;nKqi$`Iu3q4KNX3}Pjf&W+mWLVWQ%iXw}Nq&qa){5(}PUY;+T&uK5 zpvQ6Ob0{P8HKaZ6U54yCJS1sQ?{QoN!)c5a8S+j|>e{9EJe$6~S42kXQlkvbQKp&C zm?|AuL%Lgx9`dM?=O?(F^wDa5em|w(#ZeTJcFRqMu5q=$`xIL~Q)(<*bL^VgSdPL1TGQV>c4V@~@8-RE`xs9=o}^rRcuhtsPrLW__csDLZY9m1>TcnT?k_jaTd& zuM8T$9W`E+I9`2yyry#e&g1dBo#Xf3jNhLffAAh1w>r*|I;f?Hyrgun8haxo5Al$5 zRMY#uj{>BOtWL~%9N*p8pQpN04l7GO8pBu}pEz;jzE7=J!P3f}EUmqDei_zz+3FK< zugmPx%)cLf9rwQZALhWop{M0PHal}%ewOUGL~UH^?fyA#3(x|3i+5b)w%ZIB@4Dpt zZS+OMDWuKCx$u*RuD3D&Ew4V5F+9{5;&wx-*IQ>#kwwro^^l<|pN9Mi;YM%W%GmETQZNfU-`qn-D4}p3+6LW%7Jk6fvmL-WNwwkZ+7mF1Jj*tQeH`i?NH((eF{#dgA1wn4v*13)1Gik>W!mJw@>+vqf4c_mFd-PS_RF*8nB4;t=8rK$rZ5_ z?c4O^om;sfviA;$UebDbWI3eb+IagOg%5d(n&Ch-qt7|mOk!8Yi}$iJcI}go zdkva4qdXCh@j(E1azMUl|OWd8+oXjyH6T^2}O$)vyH{D8ueGUB;UI=tLT9 zPcz&{u=ztOAlkZqIh$!^MnADMflwxPJ9U0`jEvOpHj^>Z))n4(lw6Pcl@k4X;3-nc z5mV7+8)EvQN&XA~eW}$v7usu3gAeSrz45WG*RcPMWIDM+ABKA;SZ~U>T=w0?ya!R* zl4-L^E)bn;dX1nfwI}?+n({0jT{V>u&Amp3$I9;1eH*kbMJ-J)?%QlR!iqa^EI3^en#^_+8ws#Miwz0P%KN+3$jNcVJP3gU0{a|Z?`L(~`MEQ~+ zGkN9*9Se~Gx+u!`owSTwmxo@pCERG?sgalEi?oWhQFh-{K^HTW0Cu(jeJ)H5obSg_ z6UZCoxELToO{)~WI|1ql*X=Bb*1;S+^h2c>CT%P{)b;pej6>9S6i#?2s3Cr>Tjd}9 z)s8#2rQm*Is-owZWc%4{MWc9mw(*gqOH(&6!4Zx{ybfDMf0m!>1Dy2&(0F8Tn^h7; z)On|vDwsN23ew)b0~4s@Jb3qZCE@t@j_F01 z#F51uxScOP#O_5L@Nj2|@oTpPquY3c(~_Y@9U5v=tTx4gkONr^fSLzBXa%2YUyN7! zLqj<`+UM1cBp6?Rg5Dj&%&LhvIvj0edw<`Y%17>~=La!DrY_vg-Ag=73-#)ZC>&58 zg_HX}Nk^^E$ad3$1~xr!nN}K!r_zU4{!|JP+J``(X4D<|oQ*K8x620uTQS7!Op$DTaOl*OHKu1Q+d zY+iGc7P=8MImdg!Uc$>dz#h)k7x{8#hQZ}Y^E=`u}u97?4?a<(Njg2T-5V6emGzp}(TMDxh zX+ybaS8`j#xwUSEE(&Gc2!U$l39!mA>_)&}7x!Cvu zver$=fZ%8y9n#T^!ekH6!Pb-0N0etc@_8htxb!MTp@$*SCTPL$&0|cMz@jH8$vXfw z@m!2Zv0tFXaEq)^$NqEh)d|l`#bxzw5l;mh*I%Em;Ya|$qN`O;rPCDKCFz2MG`};g zKD^$o#UbS+P!fZ0#Ies>Q_;TEcunF+NM2M?J|PTgPd+A|tKd{jmr@Nm?$X;{@)))q_#Bd*FZ-_D19FrqbZ;NGbmCizm zD1YD}%_U2#3zEE)c5PGlk7PmdctH&%zx0OK)l(=(n;#q(t>s7qYXvyv z{=Z_#`M<}7YTJ7N@ZJ#52X&rY5tA(D)|sh{(}&{KIy)2hoJOf#{8dlT`_rw(inja63HC*vgQB>-GnpBgW&<1(FP1%| zWxl9o$1iQCky|TsuTUcXv2g*eVkAZXvlo6bPq%|hJy}!o(V$u9^uO1(6+K*7-zs>H z8#5?l7)5a%lm+ze?L!RwIexoJ^`0GHdh-ZZG9_1^CV7v2sl^3@6|mBv-4QlAi7kN9Vt zPEc2TZ_&Md!OpziC^Y(hcem{Zqi}O&zH3{T%l3*|EbRBRbTMT|G%Z+VW=B{SY=5-> zvsEIHb?G$8rhvV#2EcZ#5_%(c&4JsQMEPA6M6W3$=<(fCYVZjTZk_^eF5v5zzv91PACqgm?aeDVm=( z8r)J()@r9(U7y1Ba4bCsr2_ZjY=U=#QrZqO?jr|36=B#>YUp8n{QDrp88FmCi@kJUH^&Ir4JLcYBgh<*-)%Z(WQDMD zR%b#$@Q5@JGU9)8Eb_Wp7X_HtfQqrE%q30i+!XG(j(YWTPM^!~i-ps`6mhd0iw)1bm6Xo@QiRXg6vs~**xi{R$s=X(G_gTJoS6AI85)UaaH*axjgRv}0K@=rgB zHkbe@p8`_GKB8AB5C&k|xbBx0En}ho5lO3jkd`pspvJFpG8Z}dWil6j@bTYCZlDb3 z3xyz{;szqHQL0&`Z1hErg|UDj#WxTKr;`zd)dhu8oWgr!g&=Osk-I4}13j6gmd-^V z7gz3PiVbnIXR}T>nt5Te1HiVGxaEz4I*0-f>?9zt!!lmW+qgXJdqM0xnLv%qv0ul# zjo`szPfiW~voHd`5P_eg{nys{$;VFs>1M;2I+|z^1r@`GgGW(hAmq=J5)1=!-xmUA zkYvdsuiq$v%8@$2ss|?bhMx*51dgvt?#jIoi-?`4(~+Lxf1QBxHK`3>A}F4KQ{mpr zmb^jB=R~aRB9?X>|09C%uFfqXw0IUACPtLs@-JUFz=4em-PP zm-sgn^6YWN&ZiKJ0P6M#nND@MP4(k)w+&F`Skq<75=FH!0siu7CsrlNR#=@X09=Hx zv?O|@>Z-bf3KSEY8HXV|%-0d@mChqJ@`UYL1kmKNy%0AVfqMfub4}!iNI0HQ;4}+V z0J>S_6!ZZS6kI%$WtVg%6J_b(AMfg9E9xel-I(Q?9%(h|jsL>+vy3H>UTUc7UOUGE zJvngDqS6!q0b5U&Sth$4*^H=S$j2Bw0dtIwFWCkffBxqKBI4S`WSD9)-AzWHP5n~Dt>lJN|{w9%>?yA^NKk@^6D2O9!{ z+tXo0kV65>A$z%qNV1KTF7Y);a1q^p*XBE@5tf8(mEHb?-xTv-A_pG^5tM_Rz_ocY zP4t4QEa_T(BM}qjdHNmaKZVTne>4pCVx&oayybaO*{^5qngHAo?Qshq4Z3G=V0nmL zqn<|8yvfq%`hWk0ZYSn{6X4;s0am~EZ~wKwiA8991MxJ zEKyjOcq0j`7lRW-;$D-mN@uE6#CNq!hm=sZ7LyMB6vqVfp%`La*s}(7YlQ+4vU?gu z55+_6G(@uHsjV6t`_tZCb3>@ct)@~EpFxZG7;e7kWw`5YI<}qzss*sL&M2bz);FG_ z9UtQtjSS2l`WPT_}0YIym0riCXkK_3{}?jMV7bgr|Y@ z45p8Rdmb6ax%L403FL1S!?$f6a8x_1y;JKKDtU>hKz#tNa@AbNAAdx2SG&DAmoodm($LqD@@XEni0FSB=~qs#hwisf zf}@N^kVCG>5NnU~zeUXW5E!TEhF^!Mf8BqQ6ndhNk0baI>)davn8mHVW9U_ufUXM7 zKK+$JoPsdzaP}wP$-C$m?~r?fkRgYHV`xaFE|I-dxFr{=%mE@4yU!GXI2N##-27@$ zLdeMzVVHYD+J0&FoZVNaOh;bWhnu3`0~o0fnVP*i#kPp=& zLGd?$@TV2!;l!GC0)_`kXKUZqAWre+V1q_)j~#7#OZEPV7yxjZbU^oH^CjhKsw77^RW6juD^q6zJ7DGmRUXz_q-P6c z#TBykRq*+{d*zWZRWYiWP8fk)wgS>(`>ss~<)-;WxhkBV2vBB@ZW^q;d{u}w8I`8M zj|r2|RO0R$#v6gsOTkOZFb5Fd1rU=TkiMJisOgTsp%Z&Rym1WB zc6a9F%EM`OZosK0Dh zS8Xu@D{nc%n|O#=@2nr>ixTR-CBUjFf$Y@$s`3I%2?`VegiUKnpSg1V>f;~8M4|8n zbX*;^Q9Un(j&o3gzTC%|PG3Uh+=p+X+jm`heE2tR)Xp__i&RQ#zKa2CnAnyka zfuy|t^Hsjaat$KZs%}a8iAcKG9(>PCc8ut6&idPZCW^<$_#G-iwL0 zRD2~Jq55W0W9b^&FK>-KNc$=KBFiK~-e*snKB{SRbD$hA1P1$r%T&Pk3fy)-KRPJ2 z_5oLFKo@}%OgcP~ud$$PHUm3#L82D1cv2QMxA)|%=Ke_Xn?GcRkKD36Od7=4APKj* zQe=O9n*!A?i3r~!z;R>VhMk%rw2!5?W5<)hO%6nfNVY5%{PEoBk9cqG@x$<@hXH$G zc4FKZ{Z=PeDtDed#`<_CmVoTXW~dzt4n6#M zRZYdo|H+<&7Xv)i`;~p$bzoE`z@+1=Mik_yG~RKEPr0w&h`uxO2!_0RMheAZQaXbZ zSU$Yh%MkR51^=)<_Bu`>q=&ap0~#!N8((9bPU<5TZTt&mwn(o9zwgWuTtHw=;KDvX zb9oEUvTy-uGUgnYyr+RgFa;~${v^@JO+HL_%843 z$Ts@^W1uU;m%DBL?FaVfSGbmi8#Mcdd#fh?a+$8j z(-k(DF{Z!0F=xJiF;RoL5VM?MhcSW*)~YCNWIq@IdJSNo5SOW2P+HDHUIxQmm|(3ERAAI@;*; zGi*3zBnYE%0{qmYnY4EYYtRevx>h-?wyIt=ZaVu?`Jra%uVv-c*;h+Li`g@nuV%W% zRCnB67fOy)wP{r#u!F*}GvW&1J{3^BD56ywQ<=~qy=8Out54?k;q^+bJC3S*Y`pT{ z>WL4UiKG`j7ZXn{+H)h+MXa-7+>h_uV%}u;+^7lTxRizKI565x;Mlm=N0WoXCsLjn zG<33UzszWDGUC%=ZdWcNp~LJSJ?;OHWd`@lYh!2jMSO9i?=Qz|xm2~FM`D5-kS}@+ zaxeX&z&whppoH=2$9nY>fxpHdBulZu-Xe$#ic8WQf9kn@s z&NH&%MEAA1sKgBANTol4;{As|I#Vqq1|O;!!?G_gckHp-5dDs}_yGWP-gZ}9YN`lR ziS)V}u^w3i^Eq<#wPVAc)1x>qN=LuTtBa@14w18fa?F?b(b{@vY9s@@hU z8fyj8$I8&(nTqMIHN8(Q4>&nWRG#l}(MtkhWWa~*=b+*K&UtOKvpWm`SuX)Wy3B5o z!c^Oiz>ds2Ou81qe3p)IV06entT+Dk7ei4i$WBS?kb_q}vh#R;Hf&-h#xt^t`wh{l zRK`QYL4kaAL4N$!DV3)@v}wp>rq+ErV*E4(y^(%Ts{0>+`l3ndN$wfhLaZAbU728cY>BYyeZwj zgj&u?bMzTh%?%3qsE1reKv&e2fCk{AIL1P$x6x_qg)mv3pb$NK_TuJ`?q}0rVA>9? zHD1F#X>PTYX$d8(0b5w>AcYI@$(gh>7Qwtspv^ZY0m_LsKx!F9ewGseS`1jI@u<1g z$4(8UIkHdgyCPdZj0-xBY*jkwtvpT#C2STk3u+hbU~5qUxR;Fxt`P8Hvo^?%oRHl} zWU*DmJgi%hj6U;kri+Dt>mdiMn}kb8O7Q@Y3-y6!S?JAtSr`-}-NUyh_&~S`VGELU z!T+GOl=8c+Q1=t;vbCJV^^VuqNjD3SZaj{gN61`>VzSy2nTEqDqP_sWEyTF zC^rTErMuV&AwWI}_Uf(rNoDMirCz<4hiF>MhUZeSJM~i)W!9m~H?!b)0FWRX#N_n} zY^n3|jtV|>D+=4|`iTf{#6|(i`r8)DsCDmg1rF(Fg1(1>z5sVch}3mzZ{4Z{$71;a zl0ZQQv>D15^3tf3Dk%$n7A9kAV(5+YWnu&S8M4|n#n>tStF~K)aLWTYmxuFKa)`}j zyj0TJbV-q74_4D(iSwVMAIoFo%MYH94B{bn3p(x8s9c5;QmKQI&D^}9mLLZp->zU} zOL*y2r%5yjvVELsFiPWbEIa}_gNoTHWAP7m{A@m} zATfdIZ4JVDFS^Q<@X|0Tlq%Ub?IDubN%VIXOmlWLlPcN5#=bgEW-*bnn2{d4E5)IZ z^4JnNlAkcFeaw*q$dn1v*g8}x6ULPt25Kk*c_+?FAILmsuunHQ6gUR4PFg116ou&> zsGSp*@UjBpCwUfk^jw4 zmVu``#ZoNS_4*lhn=YRC`JB#gY8s@*Jy%@r^BTC<|8=YxtQ zyep33QSM9K>E5qA@V_DURa_E{EDo5d(=5HiOvVs7H$gw&EI zN@McABD(R9g4@SmTM1ye{XCQ|;RI#D>V?DE^(Cr6)e-J`%rwU`h3FHybs8Kyb+L2kFhPM@C5g@yiyi}#?S zCC0KLHgUgQ_EJ2;;W7@46GtCOj#5yHZVon#UtX}sQVB+v=~w=ecQXuir2n|yliDBc z=s<_9wLp}22689PEPMrx8SQ`~fK{K*XC*GG$GQt7HotW79= z7S4^W1i*Ee9K&8XGX72q9Zt!D$>_6?T<9u;l~sE8ej6u+f@GJhm6OdHVYiOdpnY~K z7j2LpsxBmQ0dfVateLIe2GJrM3M5$3XTf<8V8MbG?kumgKeu4XgO_b-*H)J@vCEi! z*bGiX#w-mhF*<3)eGDnAJJ*H)pc_oyjg7;y&{-^^2p|GoMlJV@Tkw`wSZX}P{TDY= zlu#Phj=*2YA(Syn#V(w1d|V#)>vZrkwaE5+o&)IGKU#nHFfB}d-2qy%MA59~58YU>5E6zK>$fDHI@DP74mFvcma%f+rr zdyP_-vsxC`t8PylDv*cTGM?rxwo24-Md(X=#b)`7)4WQMKK%6P9crmMuD^C-C3Fz! zNJBb67M7BXBU}tn)mspP-ItJ|fNOA)&T7(rTx^IvsN@H2Cqo zin}c_cylG}mbUZ{HN-n|1AEOfL&M9{#U+^9)E8{Fa`6f3sr!(}!Z0M(x z@9#So8zI^6x<@HowmbIT?`6Z&wL?Mp>MwVEPXx1>uZA}N%$Qsrg6Rt3=0b$C5E&pu zg$mI}g_v|9_M8w`CzQG+#6LK_(8cI~DI`4|xJ$7m-%^h7bCWh7mUSMM3mBFU9acCx zte8HmbZ%I=Zdm2ku<9-MIDwwp`(ce=!p{PiU-di?vvhe^M3mIJ}tZF5tHHRC3J=PEbf@8Pbltcwx*6=tOVS^Ds~ z&S+=T{!)pG#6a%S&r&V#j#O9aHCvjZR*)MB+J4mo`k#^&jLOU+pD*7W+`6sKwA@O( ztUY9X=lxBxe}?dr95E!(^5{d4QqH{4*K&61W>-uAYMDdu6R zU!A^(SJOHsOG56NpT~F7&Yq`_8g>@gN7|mRrFS+S=|8@y)IaA$Sx8|v)T_~gunxHw znJOn~9qtAfemT6g%fe~r2DwVL5S)kHrgXOY?XAl{w`ZkOWbbHbW(+e^nLRPFxuo=v^lJQFyxD{Sm;fvLpl zC)tdH+gM2NQbIQ#pDdNp&dY})JCp?BT(@du!*F-E@|wHu`p>@=3Xe&WPUaS>dB+d3 z-U?cu*ae;l7_t#N=nD^z9${5Iv_5DdQ0=00`nisT{3Hup^0xZ7y?Er*elMTCv(lj>#8Xef$u{|%{f@_t)9WX@FkWD`|t+czr+pXOV|9ZzyVq7hL>(`ONRIu=VGbBJ*EOE-L?XholV+THA zb^E)R=0()%#=V$$6dYE)CU`hYI&IeR(KvmxG8S+IdaFo^6pn5~JLx2V)Rt^$!a;|8 z%{qOQ%&*$6loBm@o6CE?wrLYW%(PX;Kn8-naOOpCa9FY@_Poz6@=1Ot5>TRJo@a4y zP19L9e_j1+?dA62f_2wbCwne0g^`IHS$TXjHH&)_11C5x5m@ozNEf()c@#X60N&ur|Xn&#%FnMtbJ+2EWtC3Sy76jdjvE&C8c zrpI!%N`BIv%c)oCP5ahFQnFrOEUxfWiZUS#m*}tWXux`G#Y!~x@0sz z?0K}8;kENNpZruU1wZR=46xTE204cbFXw0k5%8|kIl-13hJ@#+Hp|M;%;Iq$M`3{^ zG1@H2n|L@Yb=yZ4WITa^5~U)lQfYSc&VIdHpPk_sO^6Lg9M#BaJst*5U`h;5^B44Y zN8-tTHZ?H9gNS)FowfZjAk$JJ=bm5CwwIQw)Xa0nr<|zCo@ghndJ zop|n6!Qu`B-mL7t9R=4K4SMVbn(}Xa*{CU<1KPftJTvJMuDRTsxuX^F;JwTt00RxR z0cc5Po+Dk^=FDijbvg)#P@IJ>UhNmi20Q@PONiR7!cARYa_rz9)zs&!bGI5tg2;{0 zuXXLE2N4EAXZ~G8(_+sWFRE2`sjuWHWHst;kY=%O+k^ZZM%nF^Az~ z5dOU1e|NWZUE3r5@huJO?=y{#zS)jph~e69lX&y)l1~F-^s=QxkGSa(x6vXm8cJJz z;$y5|1)WJ5mp_Ny8DMjY+wB#+%LqPP)pm52EyDv)>v#~~B}iS2wU^pf!cpNvSF}zq z)Lu4Z1%=yV9R?Jkr)HWqFpPa;byIMZ;BTLEOuA7xW3MZL`==LY+#{aZTwLnJM^CZHytWKliro5}Q2zC73LF+Gm z?QpBo!@uY~NAEhHP64%KtGF-pHc;PL?9Rm-_uhIqG9GtpRtRW7OKlyjfLvLvhu{D7 z7-yyBhMNgh{Z90xb+k=$#`b9b%IYCoe-){eRI7evGHgDXoPl1H`X@TZ`nR8`ThXHZ zzjjw!og3t-{7{G0Hq6F+e@$jmN0N$So7NH^W0`dbM-|=8!9PC=l(6v1r#m&UFq}7Y zM4_V%Yueg$A}UE+eV%`R=l!%Zg$A1{fdun$y^Kolmeo*~nMh%@O4l$Gj z&?-6~caphl+oin;6jX%V-m4hT*RAlZT6CNc!xi8TX5gLS2GQq-XOey}*Iugj*tJNx(xn^ZQ=x(KeL80FO3 zHwjX2rhAUk^- z`3G1?F(7AP$a>0a|LIv`q#x4pH3D2NBOsEG#4yeZgMr_Yw%zM3Pz|>*mf=#~3uh81 zPr|E6>z*pCh$(-#3jO1z7#{9*p^VX_%o)E8kZA+jieKNEe$_u=%^%V?AqkT6eB_au zO^QDY_kE8cp0u~T2jZ)^I0FmxI>5$!=UE8hNc`gw(*)e;P_Q%rw;c;bgF)uPvz#g1 ziiJ+>C}B{6Bw>-}gxepoqkB627Z_x`vTqJW$8b{S_z1p3i0|YRp0X%2bh2z3B$^@b zDlHDlCPAa7X$mR8o-_%P-Y|6s*o0ry4IWM=wjiwQ&UrW+rpl^N0-)_Fm;#U5rF=nJ z2*`tQW=w1v!>NXjj||XEo;(Se`#($QWTk1!#?;(D3{9J#9%Jrc{{%Hwh^I}e=S$-U zpn*6u{iBdX3nq8#Mt`Q1Pl}1iCE}!IdHXo=J|?av%`<$F452{hpbU!;rW#W*I8mX% zuNrz>@%=JY`9+01P0doYCs~9oXKtL3A#{oK27f2zY>%#kQ}=dwRHuS4ZVfUPz=4X& z;u?!3bMCN~oeX|Zh`-}N+$K%>5|e)-lQb#(r$ZTII8Y`PcjPEOWsqQnijeIFl02k| z5z0_CMqEiPi=Zb~K+1&eV0dGyllKC-QjRt*QVFOIgg23C&YT5w|?)o4J#c*=2VRG0gS(@wDN7@4;&kBjpDa0XqdU#uqK8#Q_g?~cHR+1(h2$MP~ zgp-(%Y@@2Q8-!-aW~_kIMYtRTE2j;Y8%?-k(Z19*3JAXw$T^BTE@Hm}nEk>OnwW0k zMVZ2Er-x(hV$a<*sQkhuz2+4@ER@m3%B`gqynzxUF~n$p&TSDcOaMnhY{lKirbw`N zCrnFRe~h-#Z7eoM+Z7HgML-=bf$_I@m#{%(=Wdt5Pe|@Nd}4=FQ4=9DoiGGl5qgr| zLw=PQ!UKlY@gGWDX^n97<%isLx>4sj27OJH;oY}1L&Sc+N zd*$;X_%*{&(g3B!2cQ5Gzpt4P1cR6jE#3hL8j5JT=+YX<{hi%@6hzEkdb@pX(PI~+ z2r<#D2zh&)kmpLlonhNN?ZR&PZjm}Ct?hMEql}`>-Fl}!2H(WOnDPIaQnICPM4kl0 zUI6QPXq7SI2d@8tN%k(c_2iCZbOaaWxAx>qdkA7Nr&w`%jZ%NRmC-jYYvb=R%2ZVG z>y_P;t2KHH4V8{+=d!A4e-IGjpe}&b^eaG=j6_`7rcIiWFu{F=>}NCnKbtRM?AJ?Z zHTW5V@7 zIHagSi|*iGRlo~c<8ndB-k~SL<~I{0ALs!;u9|i}L=|Kq+3o1qdu^Wq>i=P1n2$ck zsfrTv#%P3?6R7oKxULAc-s-~eN9cMGmbFx4pVTMSUe&7%^Eq(p;H~hbTck5#w`IF@ zJCF8{|5haxLuQuFwj;!MblpAD)&$*@j-p^V${!c zt84{gYXI~NmamR0@(O!`j%}=22h)HK6cDMx?2<5sv~baHY1y4Dj4JB^e1$v|(T98u zs@;WQxQJ_K??@!zCMXlekS0|lO{=SYq=tLucGX9+tSHAx%aqdYYQ zN;NfRmxL?Tw@qjJ*tXYVtAHQFCryVjljQDm57hWT5M=C$Ip>nhN5IIRW15EOgk%xy z)k}fzYX!dxeRftw16Xb10Mh~y6HgN(twSftzxk8S*`z7C zhfPKI^u@RbbeXw!%?3Z>Q;|isEWTWbF%-RnI*!VGz*2~T&*3($k}Zuv+q!lBRB#sL z?>llY+ky#)@!`@BmyT|cp}@mM_z7NNbd3SLKm~46*2Kl7iJ`4F5$yDf_fZ8fY3^>= zQ77+AE3Dt9gAez;+dVG6kX~Tvqjh^XI~Lj+8=E#&H3Sg)kKQNO3B(PIC;DjrXegcj^P6ksv!C$Ob z5ir_h+!kdfuur4|(OsWJ@)Y+WF(~qukOMr3?Q{f=`(xWaP>FtH9}}zWJQL%zAvWF& z8DxfHe}lt5Jkukcbs#7f$ZQIQ;d$uJn9;Y4P^Mwl-X-gN@3Tp{|^&_)5d>EVahZI4tLy<-Ld}los`MD(Vg4!%IF7#taJf)^1Xk(_l4C!F5*nJm&9S` zvg_w(^dNZY%IR(Vm$y@9#%}fR6zlwV$}!X?9Y4y+^snC^@VEPVrETJe)|J1lMlWww zNh((k9wT(a>tfaI_T~h!@s>Hr#I@%^TfBJtP9<%cqERSPA>$7*>z8rhxxbw+})`PWI-BZy`q1AsJDEL>7v{tFj ziyY8pW5jpOK^3iNN*r=C(Qa;hDN|#MMQm5W6`81P1ZKCOPUB?R36~2g-?BeAurq4( z$~sqr{xxTyh=oi_8a`F(6qv?!$9lZK7IYwRT!E2bG5Xd?7CXjiJ>U= z(P1iwcDicDx0-yokRp;^!%xAg=9UH*f7CB?C-sU1>lcm~z!blLUDDpGb0H7dn>`yO z9hH3^nd;^^tuvaZkkxBs*bX~bLuoP%u#y8%`{u^6FWGBot7$*#RrYfs(mUKkx}9BT zDBLnSQ}jusNk?A!cF`Z*;atbApk`SKR8)L5f1xb|&%EP7bm@T(s33Im)g2eU^5qlt zFGC+DW)#cIg%9kE$23#)sH@Ux1=6miF;$Uk=j(UHE0v8^fJv`Juh{$hf|Npd1?U^` zpCT}Qnl zc^N^)1!1Zq1EsEm|6M7anT(LyA6BA<7A%Iwn`AMwZIJA=s^F}6gNy8?$qy2pcqc$G zTM~w?FWnn5QC}W69ebdBOH*$Bfg8nDqy4+{TF-53*p@Y=*?&d#k=Cv#%dGKBOOJar zofG(mQ?$@o=Q0Bs@q5*{cd;0cZyAN%-7V!iyZKr`g6g3ICfLcGI_KJO%cNSptlGqf zcb>=K7{JU~v`(W!-${sH2eR>2i#kKQuBp?4a$sQ>L;8+QQ&00F zYD>FK`LTHijv$psL=I=h4y+?Y@nGf&7qtw{!SSw8bJcg58Oypb+!3Y(u@JnS>7-RM z?-i^P#Lh4+8O~MnMi8WSQxG;x)E@i&3>o+{yQHdudir6?NNOP3Lda@V7HMwBzD!;% zBu2W`#AQ$wOpDpMk-5}lla{Bj5DJE~`@Lopov|!ZfR*5QSdJgYy1O7xYNCNP!0c}6 z_{BjSfl_dv1oG%=oUe#Mxd$qYDOB4VdQf148|WxVfBNv8w#FnSS2X~uu;v@I<_GQU z&|+L|adVpH4XSHOYvfQM0D}VnR2O8aFoM-2N2NtQ0MZ2j_zzbB2cc0Z z-YSbNu7K8fmso&jK4lwC}HEA|ZSS&84HPpxCwx4|uwl zQYH&JDz~gdn;d~*O#s*ylWps!weC6|)r}gE92>q@0_g;K;0F1?~ zlGR{zD43C>QwwLhJ#!K zn4SXI!=zZ3fjIFQ*g9&LJDsE8zeK)cQsUIoM@J?whkxx|vkrM;-TqZ+3h}hRfyp99 zCPTtS>giDN0gF9IYnBMpz{7dCb=WmmyqBdxOgD6=7IE&$#)MqR_;;=lzLPtNG(`u{ z9b~5mkQQf{@b&WT2!9sRXiZRm0D}#;6`y&Xai?9b9vdgKs zWDN(|+RrukSI35uf5*#QVTG_Qo(cQyU*KQxXZI4*OqC}Zxysu@(jSSD-fb-xC4T8^ z8(A=|gh-4VfHKTXd~TvIug)eb!cfJ08?KtFHp{(yqnZC}sA37*=0gx@S{mCBKMwumXicuZY zhT|fbhT>+<(ko?B9-Y zpEId)N3LpuF1s7CF3phcpJLKk z#&%jb5(+yW+e=O()OPUQ&hxJRl0vR~WaO5C8@ZdilLaGLKt35px}j5*)cMN0GH9)D zhP26h1}u7|f<8NCQHHAcvqD8IK66IiN%vk)q1NAw$Umfl%^+T>QJMjx2(A9R%F%1! zlx~6RVE1!ytC0;USU^_A@O z8U!qD794`HUIKrn1e#5D>EVT?*=Fp;jF^(bBQ%v=6D++(7IFuG1=w;7wvq)K)MpWR zEWId0Le>M#5E8k!C=E*LfHsCE#jxEJwJkKsnP3)%UWR2{GmdIpk93?F*Rd1}*gSsj zc-D=qjL59@VVea+H$KS%BsF(hEf-W9WF^d{pHDS2Th6qX(>)jHpQ%n+=>dhuqm2g|o*NdCzL^ zGsN!HajEaU91x$j8i?Cx)*YOC`Y5|QA}Sxo>ps}k9W~Y+J>7k1-i4ObeORuC)7uqm zT^#+29&eUqLc{I|X^YY6x!wnm-FgnmWkv?2(YS5vm)cEgOl*{I-hO;-R@F6@f;og} zJ~+Mk=yI0plr&E!;|9Yu+Awo3vu7k*&Gm>FWsKF$o$of7bBnFG%AI#nranIF^!RWK zzsR~fAlUuTeVfmJGiy#hj;Od)*7dkz?D2)^$CdMsFCzPRa(z`gebr`tHBNoCTl?xl z`s$DLT}ta~DC)ah+jpgf+kdyE|6W)B{jvTB)BO+U`~O3F9k|mY&>8438|ZWz=-N8)sKw)Kh}Wf< zfu5w?*aY3jEd%ienSJ;FpP-Ju^5aW{{}Hdzg_h%A{$JxYR8~rCy-nb6-xqdagB3RM z#lxjNVM=z!RxVK`G^Ql!*QZ~HpBn|zB34xYp$ERn$c)JGFQr2%qgMhtTdxJ)KKyQ= z%Jb6o3swnpGf!_GAZz}YAz51K#|(AZA$D};sC%}4X;&HHnLD;dz2I{t7KzKf1Z~qC zJ-?+FxA2NayPEwU<%C9V)%U5`;9S;n;Ec9U{r-vlf6gd1r}UTX3E8-?vn9g*M)bO+ zybAxLUtZyg*6`ohBokNuyj(b}d6R?~`1EG5+>iy!uZ^wM|9ZWr?Flz^clZ6cHz|T+ zD|OD}TN@aa;DIt^c7c{l@;fC-pV=qPYk>yo>Q)(zHZKPTk+!Mmq8GPPUfxe%ciiVS zr1GHuBHKtrHA4aTUpIa2mKJNe?J)CtlWB6R2s%!{I#OU75nHSl*J<+n4PF0^)1I}L z<%%!pl{t;5Q#te0V4r0AJNJ;*FC%!GE^$iRq-%L}@1D8Ag$YLOIS6j}ye!MJ{wdsY zhP`9YEnh2J0N9qk``Cog(HuMKm2}*>Mj@+{8b4sC19SJHJ#cfqU~myKVdxZ0F--=S*_IEMW z8$~{G`O_8T`)y7%xe3Yp3A!3P&C6Za=!*ZoRzldGW92cIvZxvJ?yhQwTdFde`+v`k zud(?3uD@l}VN*0s!tB=wE3?=3HlH{$Ab2;AE_Ae!idv94Z_1NxCQ{>_E zcZ??cLsbS{-`C=cUCW7zdDO@@*g`9OGulu3+Dy7s3y~@acgS29PnPZ?;~Yj8m-(M5w;V8 zCpHZ6?+@C!S4k9ZT3=t8`ewiVR}Is4ajUHT728eMRRP;Cal>}DC$@QKMUrlY)37~S zpm(LkKyT&0md!_Jz6egVl%t{)!=tX5P;x>#a4nH|v)B8YmqYQ1aQE_Anj}f@h23Py z)Pj|te1q>G?s2Qg?pJP5)ztVIl%7#fxXT@vG1{eh6ZH3ABNcT;@F+d5l1%W&=;bYG zI5@!kZv_!Wf#c0%s=75;6r|3^*n7PMJq3La=^X2YGjAv1iiL=7ns_5|IAKcF^IZ|W zw)tGUa+;>pQl{;WGmBF$(4LIY`mgP-c49Zl5o?hDRInSY`{OyjNBTO>rhx}=&MpL1y@=uA=q zm$K=e6z58hsoY%?Dge!(^Q)xuX$a*q>P6b`xXv9#)jr2_(vA}*9j`r@)U=(YUr{;^ z0%F0Df0YiorV@74JI$=e)82$%Wc2Ekf>m>_X?+2aT@<`!zmB$T{lay27hZFG2c%4L z^JJ?*m8C2ct=L3Q8r7-XWl?ejbX()Ksx6bB<#+J~Gb076gg7<6Jzp<`ycN_!4g;x! zEWG5NFj{V?#nksO0e7+rT@z|D=!KU^B@a>)KPNutL>{9sjv6`KYOF(URgz=}dNG`A zWzfBe=W^^c!eri1k(AXj^L6)`u#pfQHAxeD-Tle^hq(v<*6v5ga=>lD(4ssnTkpx~ zip$|l{qwNA$Yn=6cusOox>p_As4pvU^y-TW{!di9^Ky@#-3vWAzIyi63?#Hac6 zuPz6Lbjt<`u}WxjpG}NvuwVId+@^858?hbwg>p=fdo9+RbS!*8BSZ)5Xz{L4BC0iv zGwWG=g*j2SzsG7O_Dn#eGbQCc#%3{=oFdk~wAg^LP6Ed^$pC;1t!qQL32v9zEq-l8 zV8v_~-+ilh73Wi#oCoL)y#ru&427LIPSYsNqi`ZO?Q6`Y=X)j0s|m)xx(!C#NhcWZ zHCmM2F2ACZQ^1h4g|;4@7vtmI(m=Se7`d?oMsSYlP{=KNM)Qt6y(dY_BsWHr@|%)r zk=Blp23ck&5P%BH{?_2KYj@YNrch@YFoTt*XYHrK7FBO3o6~yhGvUJ?pVH__&J#&( zFNaS!sv9nP#~(FiNo^kol%B+7K+YEa_;;xq!^b9GFsv_2M)3j9IfvkgXRqZPA>V~Z z!1!<8KsyiCi*WU63YTvlPZ%VWA6%ehxh;1FBkYGv^t1A6mOIt1NcSFGYA2^G-=b`i zt-4!mHJLi*Nl{+?LI37Dv*GL=*p`@#&8<}Fkcu=3q@Cy*joFctn%^T=$3Uu&vC#I@ z%m?+aiNHny!r=b#gW?q^X#-4;PE2ZYdy)3xY`lg^aA=*=o6T6WEo_!BEHG9^3jR9O z^eq`-48j!!;&gK*PGJrYNp+dSV~w?yMjJeAUQFhNzw%I$d`+$LPrIP7g7~itOrua> zI0HjEr4~}VI50W#Ek08F1mVr^HlfYO*~bbf%#`C}HW4A4Paq>*;~Y!Qk)^J;{}FX< zzYBdXcmgbQ$3gu!5Pp-;q4*`Mr$}rcv-bOxD4;m6<8J}k^xc%Y>`rv;A($XvJtJBA z;K0WhVuUn-*KK?AE!;`OQCp;793&+j%`bRI`mmQm8(-7)nLFRn3mxZt5 ztOi&d6HjJkMs*=HSHwLwv(n__ZNcgv!!xZ}M zPMCSd!fykg96vgQP+c>dgzO=ULE9dIWh*F^OWkG_jE>_Yh0j8RA-KwX<4GR&yqQ!p zLq@{fG!*kMK=PDM80IAr=OUnMUSs-tdwDpd7l(#sLa~1CNcvN*%3Cf896toFBJVuE zdx0*Gsn6JIPtLwY{Cpf)R>jb!bp*h4RNXOZ2P5?Cos8kLH@;=njl!Zac&?>(q#^W=<4oj0y(OsVx3Y_KR zF*Pz|qzBK8AmkIp`Wc*?W{EbC)L;Tx@ZEM3s zgJ?ZwB+4E7!h%POp(IgS6$P(fyfxb*q2A=ER#!ZsV9Pf#+#UsRD4SyUJ4W3k2v~$c z7W5*sf3P?UAo)9R^aJIrsR3ykGCR=EL)nryeB!K-bTXCD^>g1v8V<5U{8I%$1sr|} zUI^%i1Szy~*^h)}0rSeZ~&V8U!uVe$;PRVrqxo!i3K?qn7ZbBT%}r1EFm|A?)>?YEFH zch@UtL%9`6c2S`vbxlq+CKlKymcdM0VngupV+u>sr@qeeUebv}LV^dPB!475+rj7_ z)Hq@g2SKj~GEzsFa49BCnOhrkrPkHm@0q)IEF&bgt}-)08gBu976sP0gBj;S!?MW9 zp*xls@^g-!7zqV6?u@SoFBdG~n#6ezDa4mzVp@;fd%@XWfxgyHdeGx_zCRV)c_(`K zicKP{Cj*Y-!X%VS@ns-hP%R0@u0J4U(x(m6COXB&ccmMDjAQ<^1e0|wwsxPo*=41jnd`AvLrRI^UnTtG zRCe|HZ!Cv~fONd0qjX7gBTY8%yN>*3Db-!Ep;8=j#cvlF19|Qlp_S)8(QeZU63nEG zCqxH*QXLIA2Wn`SM|0FSP2!e5;cxS>)(qIcgbC%U_%5hN+nB(^<})?g>8Gb9LY=EH zT|`F&?z1&^VS9#SUW*f8&CGH!mCB{zO1Zdpf2jw-SzX*suXFHe(#=FidO06wH6Lf# zp#||Wl>(Gr3;-E63|}^5sW&hb2Tm&S5fHVaVhO;)XdZizv@psSL zC$xMdHD!h3CTqTJ41y-H!~sI-Og?K%zEFrSV5BITqxVrzYqle3e7GS4uFild@k*jU z)hjbwW0pFICWIcbQ3A?T%r)NX4-Q~(|C9R&YtUq~mY)QRU6P&g2XZ(w8hZ3G>Ru z_f8SvvSegcV%flTE)5?3^}))h>fR`;R{ynzKgs8_SoL%AUm82Hb6dcqB4t{C03@vH zU=yjY_E66oQxA~diwUiK?9P-6^oOd{D8Pn~l}b!w{MSY|n7Pami_Uq54<+0l6Cq-X z)I`7*F20?=dYl1%pIR;DlP)a~x`f!{LoKd56b%SyH#cv%EFtAHp@}+(VI7X&*Y#^O z93e#1(FiX^d1ffxtBd4sJW}Eh!XqJeXa8$Re_~0?p4U?zrs!0#PD*J77kyv!W35ka z=_AU9A3|P*w*Hqr32Ew?(@?iAiUi>|paLPpZHQ;UNkSOUUU8KQOr3-DOwwMX%PKSn zk9;yqTIvfA>-p+VwiwJuvED8<0fsbc+L-!$UtO_V z4F;J{n%9iRAP8_>%>f2c%Jy{kJvS{JsIjr$yqi3*14IRExc3l#ftT`3#M@y(9DVoh z8I3T17k69;|GZIAe;O9aeY7@Y*!iAbFJJcUDV;yQq$vT(ER>AgkconmpU?D3`9rLW zLR~KAQ4|rlMH%48BIvS+Du`r_;E!CB%U58CtIIh0v7fs2+c#jUEd?r4w)_ahqVysJmm=PN- zP?V@UMLWS_4HzUBGQa;t=sda%XSC#ND*hukDGR{sJz=Lbf1VnEk4=@&z^Ee3Bj7Sb zeCigzlbcg);~LE=LES%yg`DiSA7`7it^Iu7>x^A?O8Zzr)Js`zrLBP+BC) z5_#0yqI~(eNmK?bk@!JKf?6oC%cPbiV&gl)APr9kzRu@^P!G_b_ho~+@&z4m?wMlz zv)SWvucvsQ5iCKn^b>iOqsKpJF<0fI7zOMWh(9pLFHp$dt)$tea~(L9K1i9wd9UdM zcIUyiaA$N)Ad8#p5Jl%f*yrJcqRNf_1I?me%nyGZYQ3B{w4MO=(g@G_-tL#;pnB4z zpuE+lqFhNn2&B)wUx3r+QzZeJ)mC>TyYyLh50I0_KgqxUk+r|AM)-i+f=NRmYws#- z(ga}%3{C6G1aJ87PrP%-Kl-&b5L3ln$Dn=$2=ixR^98#mTz>M?=l=%Tp;^=aO#R`< zY5F_K$6tl(=fZeA#TTOK-$L^Jcv5`MV*6^aUrZQc;@?;PK6VHw*|`pdG<#(LE}ONN z+k=5pjl-xJJ9O1$#GHl637`-pG=jtrBGRuYh1pG{aj-(x^TR?bp_L8)6Zi+&0N4pI zz}%sM$870JPxawmv1725XZlwO0!!>e-%t8`eex_; z*2!jU&JDPo{B`O}P1eEf&4)%Bchp!Jy}h;DHHpe8-Sp+ZnuAJhusgri?{dh$Teo{T zf>3F(P1>(R+ivft^(v>Y`u^cz(eld0V=7y2z~!5=WewhZ8?{UP@gV%`Qej<_;MpT@ zWg+VuB(K?G#hjbm1+^30N^KX(TTFJfW*a5m0Y@Gmc;8mA?)Qs#kMpI!Y%*N&noSXl8gt~Cw_SO@P3zS&0>y=lGb1Mg5=`Zo6O%xk+bz;qL{DQi&Lw!}BHS+{5lVyAOEpEQmVuBkQ zVP$PKT14Q($d0PZ9rAjI`lr_et!3Eeu1 z+0WOCw9c#Q;MiC_==8}W+${mEaX@8H% zP07=)d+cBMlo=@~LDrIrgQF=CkN3V$*Xuv9Mur#+k9Z-MhT56X9;B__w3qJmFVoDo zHLwx0ROq=F%*E;%M3l!*z&>m8!HiC2tMf-Em3Ir4oc_L8yLDWXC9kai?kZv6ifE8r zd~W%S77VBVT@%09rE%g`!9fl}Rk;j(c>p6DVOXQG8|0r0I?Pn+fJw=j3GbcC!oXeo zy9{Ou(XMCO6lcS^2qF~#cxD;<|4EMM*b~va=ss$;sJ#Wk6e#GoY5Wml z(HHm8HyX&_EYUS9jwBvcMfQ*#ev%XNLRBB1%)EIl+aV&c4W$6Q1&I?isB2>4agd$% zexAIIm(FgRl5rsgoa(Qa)umW-VMqp-xXeUUMfuu2^(F2lWNhlg){u@jU=%HwNdAwH zr`OO>e_cc9(`MP}apClY(nGp?SsIn{OaNwg5ETRpWvWf{k5qg-BK4qK)|%$|392x< zkxY~ww3$)t)-_IW)?_xC+S=}+4$5sbm5yn{JHR8BQm8h71Tr}l+G_FzndVWZI0LAI z0FV3xv*N9ebvR~KSdm@cTTgWHQv`tnyiKP=tyL~X0Hc?2(&TrFU{J!3 z9A55%4GnuAxw8sEtcR(~7oA}#>ztM~?M^5fIDKNVU32wGuH)?`>ohyyyx!IntTE$d zX)Xt)%jAx(k*WQDzSgz`r&~pc(Z7^9VR>-{BIB4y2;Gbzh(s9c+lVce*|?Qx zm~sH;(oQoaZHLwMH|uKuD>T3%?Zu}!AyS)jtkOyHusd2h-!9?joPzh%$T+UkvkmG*cYiI?+ z`e;6GYI_bLGAN^P%Hb;uOTPSW~ea zI%h2yOV+9C@T!OU6&#QlW{&c(?g1gl4}3Ya`krod&`==EVYZd#e(xI&qFK;&TDu`_ zjHpN|IZda!bXwOpu!c%Mb_#AG@DfSCUTco*k7AscRd&u}JJ>ZRE^-@V&Z&&>N#v_+ zH8Tq7U4=GI)XTQ_cSOsTi6)YvN2@UO+uW;MiUL9Z)UU(l{(>pks>n^(Xr}7}S(0!a zlUkWoTNxrIn116Z=X}oYJ~XS#PE)nEH~eQmlE+3l{9e*rJEdmoo0^s!#d*pv?!9in zOLYwd;mZ-c#^6dTzYYbK8O{ICM^|E+=KB@7Pc z+QFEs8!FQEsKec>U?#%Q!W4x3Gg@*8RL1Y-CaXQ@=Ac_x+1GX#90@X|9LYo3aZurU zy3`ZbOcOqiL^-?}?U4`M~_eVHJR|%ndGeQ6EFW> zrLt0(a2xKFn?|F`=B)c}vYHzqoiUBfHmY%{Up@9{xzK)fLYnPgO!f9$V8X~nj#&hp z!!lvoTXUp)g)&V-d^!ySYod#in-4u=Z0{aqVl<+pUY*ZED+Xo7&fP zwA;OEx1VTtSZH_5V=?8G?8aY} z$Hs{c?}ZK@Z@?oRyn8rWOtl_)^=|~$@}7lurihK zSV`^rYy}*=XAW1YYy{R@Tim&L@^P z4HD6JX8)5@{i&f;kkN&%od9vXoWK3C;xux-=4oQo1w_ zbOdMXU08O;8^hP@c`@3s<^veKp;kq^AI_BI|6Ccf; zR!Ndrc&=$2(gGO>SdBj83^7*2E!e4M_&C4n)^o=?+(g)xe?T|cVGEW6oU1J^W1Dn) zQ0Z23mZ5>$;NjB6(`9#>TzVbripG2N%EO#4(V$vEm+D^mtDP6%mxKRH&;4@qEGR{9 zs&Zx8Yfcw<$3C-qm-unhnMIt%W@o?Rzdp7W@{!Z`g3g?6H&#EaL$vBmFMVBVi~hL5 zM6<5?>Z&p|bPheKw)xV99+~vcwnIRhe?opk&!mz3t(FZY4;RNr*S|q4ZM2kFhOe&M zaPZ0tC&9%$AIC2RPrmhH&giC9^+h!mm^)7HAIr@Bwr@jRLy^;toB5!VhagVvFImY( z$a9wUkAh{Y90E^f(Rj;pI}Pu?-p0Ou*JVRxb*r_fZ1=nD#68VdK7G`5f-t);?B~*t zsrDs&)@##`xGp^$u&rlyrXuUk0~__jso`dl_~RW_ZfcwfJ`5;AZ~(M!GrOJ4X==c{ zE{&ScSsm0nujf@CdjM~|=9GISqt_1cjQ8%0xk}xo!C0~b)bvy3E{V-IB91DZRs~X# zg_S{lj9WpjD$`%9#_DEr{dIVeM^>pH5L9K7)v@Av=2`!hHplm{>TaE~?1NALO3G8O zE(b|N@$BX>0>SK=i!(7%8uj$z`)HM8Lp4WMxFe2~#mh$%$25`w{C5j=QuweUSI0In1p_01*ANqEgEJzG^QgqOusfY*UX_y^`AO~~@4^?EpX6Qq z2~Ew90oI03^5Y@eynnwtoUC;*InGmaS%9$*DbY19i=iRvg^qT7>^6NLqweP3m2BUu zQ$?wIF;02(m4>XfqA}u@gp@^q2Hec15uWUo)%e52I#a8?^Q^seR%E-KRzl^!Z*VmX z_>9-Fa#lINgtmF!V5PV8+;VxU%VE;$^iitk$xEZ-kl+vMB!|eq8!delRVB6C)~%($ zol74FW1H;xK14SrV2XnKWC23d6Eo+AaSq0|KC*OFHoaedEL%4BpnRfg$jYzZd3*MM zG#?jiTDMZA;-k``d43dg_M7kN1fjONarPxUaum?G2vA=(qqP0TPTrros&sej4wDes z+~lYb%CJFX<+ubT$G%a*q2mFzFayfJiJhLi2jBCx(pGA`3q`@;p5T)^g*R$P=8J7- z=k8)RGD@+_n0(p zo!+RpMR4VE3Py=P>ZtPe?9qc9+<|Ou6>Otmu-b=&pd+7eyz;9Ku8`)+)q;&0S5@NsOrEHJ=TJkv^vnypV;@D$0T{u{I1EI{nc=Ru^cLR;kqBdaufhVKCI&hKy>p8QF+BjJBV8q;$h^3M1<;# z>~My417;(kzxYCPjuv(9^d>Jj`G5c+aJstL2*yX)P}5Z2GOvZ68q3 zP?^{@b0-hHicp`+&RRFAk{{dMuJJWb%j>dE`N1uh{r~b##eDH4ZvC=hRi>!wCL#Kg zy`4AFX6noF5foP@osVRQQxw|3OnprQlG%f|f0_bvw~kgTwR>!~j4{fO5{7Dg9ePn@ z8wdvbe9>HNc0*1+bX8RQsE&SxaX7dw|6ov!%7|33!*1)x)j-C`2!Cc1cYKnZ#Q(Uq zBeK?zFs9C$Dd8LnnwMF9No3^r9P;I{utDOq)ytQmN2U%(S_3Y77*6f*7(Dct{yh8s z!dHb0ezt#2%a3~~x7%)ZNgVYhA1$d-DQhjYxZ|52FRF2z+TZdXQ8XF{ulM{pQ!)K`KwP07v25$jGe5|MyQTYb*_JGN={n7ZIFA% zeeIgXAo-3qOlTh20}iI!$OAnCN7>K9v_OlsbheAE`DrFxD^m#J#DM_#9NH0J4MxPl$6#9+ zzBlU>E^_c~Y`T;etM`*AyO!MbQ)Q(pS^;Zrz>#U^$m8lwj>1en@JS0CXlG6SY5|UA zl2MW5pJ4h=PU=r)q^mv|H3S*63GDy@nzdJmv2j4kUI~gS*)8J>-^DhJp<$ny*>1h7 z-7X?Xe~^bjLN8Y{GT!^>VY1Ke9haKmmq9}JnA+deO%)M-R)?Xeef?f5RaXx(l(5f7 zMb7Gw`xOtI3nPC4iF>7{8Vvv=Rl?mZLYwf7w{8W=De$gw^)Gb>4GfKf20}lCDc}-J z70HXBuK$@WBf=9wo8TN5g8Lx7SweXTYzht_Nkl3=8RP?RLX0L!9aI0M;N3%{uKK(m z5O9m5{3iro2hIP1sJ%2~R7nmN=F7T+DFkJzz}!;{`O$H1B=2Anb~UN9glM{((makU6kuWi zw3Z+>JzNzKBaECdsghkyfJp&ei6%#a^a=j`ngO!32mZtkIiJ7*xk;<~^iKbZdCIixY# zF(}I(WD+yhmp}o@OF>D$i13C>Vz&@%?*1naDdJ$vqW}c~a50^R5e8$mwkhfDz>AUQ zuP`s=^Ceo!4Y#7;V~3@};zu>!KJ&!DKs!7LJI*YvE3`duHdZJhK-lwlykco2sZO7` z-&E;YG)2hMUPq}I6DfDo2oITfi1xl4KtKs7mG7wlR$`>Gl@m+kiKCTMfiQ}o5*q1$ zTdI@{gC<|LLhypmKhO!nQ2YLX(;b9ZC6bgw+KbcWFQ{xvB}38=hO-@!?}=)F$@0z;gxeB)-ks>ZwSE>V`BBLyR{XJ7%jpbUV% zPa_O0I$Y#=lpe<0RvQh9h>+)EL_+8i;}5jy9o}OA;aCq*2rmKR(>IV=7`m=2l_g}` zD`!y!H3&Kk+OC=j(UtAk*+Q9R=~2SoV9tCMX|jln*8$}}t2lJ0Q%&Up~*^-?b`_@dXd4dxA-$XCWT@|MGh=grXC**QwFO18O~*Q za2J@hQ&lcraS#=s?CrOO>VA1&&pLVc^77OgN-YpX1ECDIoa_A1Y18f3NBacI`3dJ6 znO7}aoiA{$t*V?Wc!AAgTmTJjRt9@GeO0EQMjep7d>fO=!)@0-qmlydwQ(g(98W(C zxB>ERbbP)Tn-ZrED9U6|-1?#j8#c>G-WtdqSLcDa^l0_GV3`;uf|z@A>B>!9>rH4~ z?$1kbIEQQa4@3YmXK0bL9exPe^c}&jb47?-ez{Pd;TB6R72sAjN9`Y^sBNH@6x#~| zoK#STBf%DO(4rrNsQ560-o^l!ZzwyoLqMEnGLa3rC>R$rXXQ^hXnPp2i8{RYWZhkw zVFDAIS>&AKva_7YZXI_!0-d(dFfkmAeh4N~g3uKK>Y|$pl1rTX;M%>F00UJiR<=$M z%q;FR{&Yu}6@-wbHLSiKR0NZuH3^yWp9F>704|>9t1-OG#$wf~bZAC!Kl3Ce&)qPH zhH?ZDx&q+cFeDTpKd@~fuxd^p2OL5C5N(T3(`x>G@N>jvC8hF99Wa@wjry!3HqyT& zNXvrJBb4i5(obG^EdO6gCy0Y`6(b#Z2umiygbUY&>J8w3W|q$FEl>9;{9Hn{abrG6 z$kU)P^|v1}`r(n=4`sOUN}w0wCV zOic(2D63&C--fBxO9g-)fc+Ber|`hfyZQ{FA@k9ehnH#rT@d$(qnuy7I%o0p42SeV zLV%=W01rkHK9&{LsB$g_Ot&RXUox|6$I@Zl8#das$zopLn~{)9nn31g^5E4wmnHx` zCYIN){8b;U_sw3bKw4-d8~}iz3Yf(jm}yY=8GL8L1T0QEivP4VGye`rCQp@Y2(kw* zlh}|`#%u~S7RivOY2e;DbXY@WMqc+l(;9>jmERivJW5u|EiSNg#T5i$eS0p2!BnA? zkuCVfRYAxqeC5{3H(++|d%7(ZrXB@2fZF$k`b7Hm^Dfb_3aBQsty@r4ZWvTvO`4=B zwR03nQQe)_RILoLrFi+%3uId1zK_>HD4{>Zx$3fqiovpYpNgi zpx|^zmBQHj{heF8+oS;c4wsM;NP2j!6Tyo41cnyT;8M{OX`U*iv`K}Cz?S*w^Q!0D z8kGU41c~ngj=uwX(zCNAVBf?^!W}6GOMTcMLa!uplW=rm^O&ZnEJs?YP9Fq&x5~O3{hiAryIeq5*L5g z5f+MGuP!msLM=D0tb7UtFOc=S+xqBXvIN+HFtRw+G{k&62;#MPFk`!q_ZwIa&%ovEEk4m7QNiZhYij@yGXS;3#8E$i zJX@QhG2tu7K$IIOYXg)8d{eM+YDGrh!bYziPX*`1PY-pr;hC8F1lc+M`oGdsB$?9u z5gu{(iCcpVl$zeh!#6-T9mOjtNG zpu&rI^z04QnNfvrG0)j;4}iO@6CzY?x6ZZCB*09hx=h3KenWt|$XIJ--ez88H#9 zQN&&eae+?Oeq%K8cQRdh2rjF(0c1_Dz~jUU(R9$k7<{+fj*%vA|8eUfj)v$E<+U-1 zHpj^lX3-2`g0n)Xijlx&VR|&M6r;$t0rT~~%262eS|0O1U z+z$5hG>)y1<2eh6F&IZeE)e1fRf_TjpO7rleml_gLQ7h-Cm=yQk0O5K)=h{>yQD;~ z*(uu~tF!7j1ZT|cG;9M6tNjX8J^{MTf54}ZoA|h4=h3=2zz-ze56_?AbOg|{m zI(Gc@B2I($X8I8f&qP>G?83M+UJ~0U2pLRjbj4oSJV&7+_m)9lG1Av&(l}o} z=mJsR_mXNHG$Dn*J1$v82;bQtAqEW;N&9foLd4WTPYpic#H5@IgnABH2Dgb?j%q{f zx9~B-eV)JDp^LJhGdy@BdTa*Q`W%S<_5qSpEd3k#ZSv|d3Z?FlPW2t{fI0Bg_r(*p z-;Mq8`he=zQ)Nw&FRTB>cFue-3%1mIl&xEgRkWqqWm(o(fKFN<5X`5C_T+0=Ar>eCbbOksD70t;r z_hf6K71gbXV>egI112tDZf6iTSTF=Wt-fH!KW8`gTmO=!l`re^ik;!gy>-A4b3?`5 z)OKn2`f?G*SIu1?rxpsJs?1QT$b*!A+ zd}Cx?f>_2lZF2v%I}ehsjs<9F9LPf1t>Cm4_wWyu9{J+X5fS)+jVF1P03xyGr5M_$ zr3brJV7_NOFQ(kUg*u?_Uja~-im_pQzmS3q#qC)5WJB4vK(;WE0tOQqKVc5Cd z6$wvezxceV&p|5(VOLkD5uJpbm#*s~xf!a`;Zuda`pcKxckSP3kd{oKGP(49LsyUy zuS+8;_SF_-ssyBsrJqu>qsAZtbKbq`^iVHNA4rW?UZW9(Z)B#@VTW`RcUx+voM`P z`HM+&(T;za>mX9qFS@0sD5GCwlt2SgjfG4uQUgm(!Jk0?fy;U=uHqmnot1lKwkG_S z^AD%@Z6bWkl3suW6HRFtES3Y4br}LuL&?qJ6w;$_{Iulfiessv1>R+yGFm0$b}2Rz$RPqRW(+ivW`ObC}mFm^qS#h#%1W@tY_k{ph>&Lcf&;`Pecu zeK8kKE8(WYsl3|=7%2hBHQq0zqd;1M7=GKHHweeONc+?7;i7fqGIsv*+_7Dm4InA| z0WF+q2$hyXv{-Zpzz+SIEC&ZdIXM(-r*(e>IV60bUstk((d!Hi)R!6ph zMJ4G3EjkL4;?=}hUm$McBRRq}E!xpT**f&>$o(UZkRs2hdG6F^>sHQ*RUV(V(hx+j zHO=~SPA5BtW=id*N=?&~8L(4(RIxa|&?UfZi~#jXF=iabhog;*MLe1;Y( z|B1T`R)uhl-8`BXtqzOUwmNho zmPY0>ua|xCy1ms5Za0LO!QF&FqD+g4}eYQTN&H@Flje|E| zEO#M!OQ)^=L>1Kc^OG3ZqsTvr7H4)bk%NOcr|JZI?r{RVIXb)^L4Exu7vzLpbEFvGE9z7 zdnC)?99HWF4l3LpA-ja#eQ^Gihe9Cmtq^HW|sX zhUT;j6gSgr3R`v;o;~)acjruXsCxO8PsMQ~H{d#403~^iwqo!467t)9 zusiekO0*hs9nxEo7an)lB{*#x)iCGp*YDNa*>a&hawer-xh{7{zRI}f8m&CFR8LiS zuee`mUD;Ej2S0_7MOyCvY0ArxQY^E%C0O|_7^wzQ|Rv2RA1iWSVC?3g9YZ)7v9p!;nGueP0q$md8xJ9 zuWn{q>b3`yK6KMx?=|kdo>Jkr!@x!@Jo<-oW-xzeVf@P{oiV3*>Vf7n)AaU0tIaQE z??pz~JRj_gzjOQHfrCdzMn0gAG(WLF7;|o9^t0QMdxH-T#@`)z_dWB-gHQH{j=dRq z|GV?Zqn{5Co%lWSLHfPqOe zd=#C3Wb~sZ=4iL8L(G|T%eoGxN1tvsz89Sr`iX_>vfLVdfWCx8p#Ujh`2Xd@|L<6~@Bb0YLc?ig>y5`> zUmLy^(OpK2yECVGE1Xs!E2lW4DM)UPdRMJ$5U|Fdu_0r=W6#Ullsp1jJF`#Q{It}1 zCG9m&opp>T`)8dE?efb@>>5wqp{A~e3mWG)Ue&j#7lp$MatQH$9FvrW6$trWIO({t zbj8N6qg&+2Ds*^KozYt>2o1rR?bDOr)|C9}O8DP5v#Kr0Q?HcOt;wq&B`vG``FoD6 zS#_E3e6m<t4oWHcKO!0 zrk^+8c!!80H07G}B#$F9Wq19(d%e6l=JU#RDgK?$F2@rKF3aYOdk_Eq2Bv7LGtt9M z?MTa&lMZ=0!#kP<3qGr*eI4ud3Yg>B%%qvQ)9P_UDOpeocxJu+BCN?v$sw=?zLO^$WK>U0D)92qL}%@>((=KwN^cLavQd(*AY&c7|{t>L0~na z>*vTSktHc;Ry3B<<5)v@)q8dKdFkNEvevw*NzMxo|7XmJk{{KPrMEviS9K`j0gc@0 z-#+GpUZEi@dO&W#!Kx^~!n1gi{BAXA-keW~G;!&ZMrLHHqS4*j<0lL6)Sm3UC}n)X zGqhJi$IV}1C$=V_1`!I5f1>U(8<0{g0Euv3D!A$y+wup4rtqENRMb5Zz{`@X{0t*OZt8Aq`$-2e&T8VtdyeL@+t_*6nL z5J|iJ(nY7y@~+5*gA-S`JIX@?!jh}BitHUl1C8f4z&=u+(VjA=EqHb~9q!tDSq=xy z9wGloG?6r+qZFWJu@|(0rPiIFkHH96SYNyb2Rd|O2DAxV>0XCKCBKm&=Tcq9^`w&Y zH?LAJZ@2E!7S(rJkv<#L2;0r9b-G0>1*M705Y0$mOqNUFq6uQUCF6;?MX-$CsR^Bj z0+i`7m|Ti}gfV=0JW^wTYZ7;o7M~z;RMP=joNMVQGyiQ?MK1Y!Y8aoUX?^8SV>s;>M zPt4u^ZO>E82ilc%h!7i}lCBq^=$J|%x!#}ebR3{pCPS-T7w23%V@Q>FXYaYHKtAkG zvlOViJ$nH_34wG8F4`Kw7)nE$Ka0da%xF_O3)iMK$*(!|6ARc_pJiGc<5>>{ljSz2 zYmfVR6K63729z$x#GmA3ql1yjG46S}pHH8tz*J5oz#J6jyXer*kG*`iNz&43kk3cz zGgAn9RrxXdomG07ou+>M7;o$K%$g~pjvf7C@&as={5Ci`^{s|tR8=`@uGnov>}v?-ierIoL7Ca@8eW~+PEuDc#1+lH zj2uAQ&agHc;Gayz!w4aqe3g?nYU^-*Lyt9d%zt6CyvYK{F4chAB1t#g-;lR&^s`n+ zl$-5T0Xezk_k$_dLypf?8A($J%`e0^Wg`Nysl*iXxz>(CPc)Z1wLsT6Xu zP)_5kKE?)oLpnOD9r-QE#3BB{$HWQkF4#!d(Z#XT$2PSq+r!XCe?W}0z>1Owx@b;8 zOq5h8Ak}*fx1*&hO)zDo-Pc{eh;`RJu%wiUJE-=b3-$=6q^i=Ps0}duc-jnN&vaCZ z@sTwto8r>c=IgWUx>=|G8h(VH?YmCKZG8c}p6dVHns;HUq_j_5qefLmGva-7?H|C% zN!I7pn&pifWL$&}c0!?@0Isr3BZNO1NVPW2ZDQauv*fz1hK5fkA+J40tu9;V>;CTi zFMiJZty#8$0-FenP={yDXq)#9*0zcrZ>*;eA6;lzCA^cM@rrhxk;ppf1CA393DVTx zax<;ETQOuC&S4ZKWwrid&DZV29oU#thY}E~_Z#WX8V6>R6SRB#5JK5ny#spyw<|O! zwAH_LxV#*rn2$9<+{WH)xE`V1(ANeH9NL3L@GVgor zrw#mZw-nD(-_OfoT}(m=Dj>q{ImN{_N|?# z6@G-Oi#X_C-Lp9!;^4bukY8t~H~7mC=(Ffbqx(hjg5zA*EKg+_++ukh{R{2Hg{Yt7 z8Qm@eaODxu-Coq6e_YJdToN9$pJW}aWxp?;6E542M-z8@WsP1KO4oWN*lu2*HH$jh zji%(Gi*!4J6O=ri0R!flwZ?KtKvn)6tBc}_|?V*O!h zHqza0vj0>>*H=ZqGNgJRn3*gAe&TQ}>B0VEJ}E^Lnzo3IbIj*I>{klVcS_DO{l?dF zMnhH&aI)+yytJQ>&Z*Bra(8HT3q^OdP$&kP`Pb6h4`TRHsI5L;#XEcy0}4W`Mpbg)k-}9d_F3uATUmODaFhHFG23 z^#6zSEh4^aB~1V+Luq)qW?ZHS({wHcSAdY$0?U{i5o3B2bL8Jqa)+73 z=gb&wCq-JL&Yt--Etj+=-ZjDX{PqdLG=>Z*-GqPM5x>Z|OD#i+jOco}qX*Qp|4c=%bjlq+o0S7p%>hnqZisa>0{EC}Thd zE|B^1yev2HWU;oJKWM#h=6g7KiVMfEHX&F*-;{jN@LBX2VDkmvEy7nxa4CT@m6GGP zvyAbavWZ#I ztIycT1nQozW5`u;XwcuXU>?U2!!eLZo(JPgdq68?V<==xkiB(7mSxM>f3zYDcpfNx;SRETjFbk{B$99GNQ zPu{9RL^;kx{OvgVaTp{j8+Xl-*P7Z6Ia^A(!KhYGbc(W3j*l9|RO6!`Zy~-D5XxxS zJOCG2hszgkZsIuJhbaDn)w?FJ4l+0%2b;;X@}92kVPV~9aLYYB`kHE~Bwi{(CyB!v z8HAVYXlR%}&mfyQU0|NOC}q|}itrr_;;|=$QYK~^0Yzg*NBm_5zThg_uz_0PshnNV z0Y?1v_5=Y&p&6+Qjlzk_u$G>>|3Xy;g9D={uUeW|shI!-iufU}v6!w0ki6QB;G7utOh& zM}SXm6(eQKmzJCrg|I_e_~%l3p?hNiYB!i{b?Uky|eAfdv^0R#Lbs)6)g{0+>fm{fI8Dwu| z9&fG+25fThC)R`Q{-AA#;O1)grmxA1n=Tu(W!%e&6`R336QnO7X=DuV6a|=Hz30~t z%YTb8NwfTN*H6l>^BdbKjlD2<#~qsRmjQ%lOk#yJW0k{4(iEEne~b6yK6q-Nq6!oT zf$MIR$L3Y}S*FWlw_lf`Z@nJ|qq5;=EQw?MNYC1;2@HiPH6p{!kkgefe)1lij z>iyeEy`SWbhFb^E!eARP4+R8Bwed-G{p{GaX-4Qf5NhV2?<}?XM*}uYy?s`o;v9KI zR$)ab@SuZ{+k~%kVHgowB-ZI=7JXntZIVM{|ATVABfjJ>>0mF*TYZ7G+y-;#pmiT< zC9Q5TFv4MjvSqptw0S{rP)$;fjH$L|zi3^KFL6_7auoyjE1=8A7e)+3oSBd})Q!MZ zk-0P1UaSFMt;^ToqjR;0t)NWtdhmG*0YX|_VB-SBK*_Q^#PWCJR3lq;Y~1CKKX60R zBhn1P6|P3lkyZP|6w%qJl{cU!98}nE-G1UI8W#lzCb8A{$0*>fTcbppoEZ#B~r4AY!(Fk~3xc z1K{I$=M^cR9Al*nXZ0sOaMy@B{)i)YQAB8^5&Olv4JZf0EO0d@aV*&JM~!(_3gJG5(k{X`3JAvHHgBTB?kTEKJ4Vn5FWIY(_g4ldG2J!gkA zq2!wlkJvu)nMwW{K0G4O>IaE$M0h&4_vSzO+kQDJW4rMM4^ge8UL&xVNF0%7GpXkl z2bjbsNg9y91w$o8-61A=yn22HK@kc2-+@|Y;F{?X%$UiNB*EymO5hy%ZvB}#0^k4; z&Ug{0802p#@|1+!{EzH@-5f%S2MB=qcSE0AK)M#_==%!MpYcg7zpz1TaYEn<5b6YY zNOLm>T0ku&^Ez*my?h^+=ove<&%PQWjGhwW`A# z43hOh5ftW%fg2BB`z3YbQ0A|RMs zlYa|Hr&;On=(vW2NTCpp=YQ; zIQ}%t0hCtWr}D9yrbO$ff1Cn_095mdXt~JalM=L8g26C1<}-BT-&3a0;AX z``(>(5UyAMF8@a0X7@&{)~Af!ZU>XYwKx4v{7{|*5Ie*V-t+dSDNZJNe16ucP$_~f zANzG|QeLnHT)0XKSJ8Gi2b0ESEtkmjz?Pt4biV{g9aNtdBwu|l>NO(D_Y?YgG6KgB z@ZbWvcr!j_8ZP_LOnP3>Q?cQa(hCHD7O@dhCgPQV_{qVp$CWtjOU#_zPnCt|OW%fF z-0f{T#bbd?#8zPL`>w}H(u#koY?jz5llVWeEFVPzI`#ixm~OWZej300_uR8>mXW=6 z|9;%r`1Wx`U+U&;nlBW~S{`^0p?vd%>xtn;3#b{*#_adhdwX= z%yh#ddF|;;*;gw$g}-lXw@P_g$2$4zdo3%nRm-rOz4=?vJ&OJEj|Rp|Xus|E?}2OV z_O&UK%$365-!&d(eZjuTFsy=S!VqT0e}5ZQ{x8nnGpMNt{=2;CJ-M{dA)!|dMFd0% z9i$kZNXPBu_h@0RLY1{uOjEl>~={)uqT6KRhsU=hy`Ub91Y`1*JnRT;9Eyxk>dc1%1+h z)}5rwPKuv6#%;&bUcAWzo0(71$~L6a9ajzsXS;6hE&jb%buZcV<5{eI1F|WH`l37R zBP;G#sqHJsZqG8^)hPie_7Ug3*Io}|3f2;Trzvb$-~3g3`;pu;G9jnS$%7UzKT>Nz zuw>D6dG?Di0Om>ytLzaTdwS8gMdFl9Ms^xM^4!|KFDro&i}f#6o4ZkZcp$iA{g!<- zA|3+;vU#7-AQ$aub0(Q&ybFW{%K0?X%CU2A?**MPQ;bmXTYly%*hLH4Pd8TohjH7l zUn2oht(BNO1h+|$MELj*<1ELrRpLVF!-m~yRiY%&V<8gTo5I*W<;CMZ{8=)#6xRtS z$Ya@Di~~4ULLo~Qd1TkdTEsD{9^1ea+Cl?Nbz;#Y+pFF@Wh5=V@VaK&pXrVg`P=sd zNjN+p>Vf>WPCMh2(|`3vpfYH1+!ojS@3GD*p)woaBi^AP6lF{XAhv?233c?1al8q}NzH_u##TRN}=7ST3C`5h3SDI)@%lKcwRnjetZ& z4ggQbVcE-bJN2s#l%=OasF+i1`9^e?~=A0 zR!7s=Fk~QdTzloCMGvAyS7%5XX&u(`r_dCHQ=C+WO!Jx(a+VFy>%?VvlQKafe)15F zmPkl`A6%+e<{6T1a%6EG;_<_~^-w~63Lzd|YANxx1bEOtIGhWUEnmP)F=UE1DT7Y1 z;WQ?GOKH4j!bBuxZbF;!wVYhXBTwyZjmADuUKCd(;u(>~;}>{hb@HA!;;pO5n=>+ttie7l4a>B^5^WEx!qkP6Zv#3nI+ zaWfBz{-@)tyQznKvU&4hz_hF2dZM`9g14Rv2agC66#zP66zYij9Tyi=bwbjb)&qKd z72tz8_M`N2o-0Uc!gm6Hs|=%fSEvu^Gyzw zhfKfsO-c)85zr)g_|;u^&yW{G6s;XfXPN}jMF;MMuey@%tj`ixD;{W(5yc;0JvRAt z7laq-=7ePo@+=Whyqp@D-rnBTS6FqgYI86P7}&h9PQ#N)$~e{?cK%1L-eAk-3m{5= z;$GpA6v)lbL#kin!iiJCcE;-0Nu1`*GMY+I^R)(CCKHv{zlWN~aWh|kpt}L~~YVQ1qBszs)4KKh}uKfn!RbV(jVUjeF3B!xIXdBTR)S6njYEn8Z z|DhoU3Y~iWllW}Wk-I$W6QZ#k3=jnX29&@|$yseJvf)PRRX;eXAW>5dz9x0Cj6RlA zob&S|kbUWJn)i|0_jK5BhC_qFno;!Ht=3wMw4op^_LO=~=&Y_Jo8 z0%VP6YIla$lYBRU>CK4X=O~0GE8UsJK;^GZKJoBOkE4UXYtrVCx3(6{l4XA$`j*HO zJTqiuYjMUWSx4o4LC5`{J1>4>B6U-xZB6fjDYD}eC*EVOW)NsPL}+QH@r8?78=1z* zaH-O5R6Fl57bVR&T4XZFe(N|Kydvx3+X=(00jtP8-;}(7$;8w5pYJ}XAX(BSl6mNs zo#$a0ohLt%aUQm9rRkQ0idxdK0-?SHaFs1-pPdssbE)I}G+KKJ0jseLlD%;MKmD5A3KRK8<@dZNb|ohM&)pL~#%4bKNH-sNFFx z5iN2A+%L(R(?si~)^4JI<@m32=MVneK(okQdN%!-e`wF>j}pwODL2RCeHTaPuX>#N zy!pxT*A1gT@1~ua+2eR(_|51-L&vFaaZgT+{@OqK>j~zxG{y1cxbpkOj=h$1vu|Q2 zSIa&{_m=)pSI*tN{{5df9j6!WJvsI5==;C#F$s(9j;H4?zF+!uag|-+nbQjm@Be*I zOIVt8l+ARcE%U2o|DL&=U;6T1_Imt@OhE+G6TvHRKfg3_f&T|g|8My-pNZ4{I{t_7;yO1?hvq#3K>l&D;Fm@Y7^_D4_UbyaG;(QF^&jD3l=V||PU5xs#1=bz> z2{*_r=*-f-voHkfb^aJ(>!yP?c8tOG7nSa`X0<&OHWcFR3C6kilxf;=e|>3qTSLkq5RdF%6U z?|Pg_Qb<1_X{+=pb^CYJSJ1$j?D@C7L1~vmVzBzR53BS0pP)HO1nqAN7~$jf7o9G@ z&ZE_4x2DUfyYCFVyVFED3$Gv0U*W}XA;{nZn5^GxqsEQ;=5a=M5?p2evb~!op7dWY z_r00wD}mxb6}sS7S+~oEwR={zy*&75=EqY<0%-W3xH}Zds4T52+4;h{wcD|yb9E*| zR8;reynd-a$ERq(8mf{TgfcQ6(Qn#avyg|vnQ~N4*uaX@I zySbVSFj|Lb$0O7uX+aU{r;KX6jH=?%(~eC$Fn5@F`6@(<{?YI$VeZziZjN73b#97_>z~9$? zv^a+RxjCO~X=?^r%O3syVxe1XZB<=k9lqX(-()1#ioMp1R^Ktefif-??;z`okcCi= zoS}E>8C@Qiu0KY0JR$v@&Ynt{PcVIB(~$!R{sVuhBpj^HF8wL|-078LrpL z%?tB<`RrKE%7&%fGUJlE`2MgL`G#qO5mFB9397OwQT5O~R6@TDjfUUhdvnISvRW?M z^&~%`3i9ADlGrZ)`0XQWoR>nGlLHS?BIO2RZZER~TieY~9UGEwlf`%3qW6r`G3u}I zbmw8XMxHg$yVn4#o4fSknPK_7Bg+`Db~EADtnRJuR=)IQ)BXoA^|+;0&1ZkpZXlhh zsglre;mu;S92`IZTuh}j<)gFw75*Z8P0eD5w_5udA6K2Y6GE4J6CxC)ZRKgaoC03N zO@|)I3`-=#o{U)%hqF}p!Cx*ny0rCgqN49O^$gw9akrQ za3Txxbt6KQTd{JM?ug8+^c5*9#|n?KCvII4j%ja+Z$=|U9@WqpW?v3e4jxPQB!?gkd5ohnG1^^7i*08Pk)ALhm~U1uDFk^xD=Cw4&(;i0*R3t<%+rK?W|k* zGM)Eh&Ia;7`W<7hKYry^imdGtXeUU~R!fLWh|(lYsW2@87}w6XaHX%Z$Yo*MtQwg# ztFl>R!+)*3Z+s8itrz&Gk`G^z2B!Hb{^?03iU36Cv@eCxG>y}XVv=sK`ty^#^2*hQ zUD1Y$*%_^Gjj3ey6js--tgd<3ful=sQleKt$ZKX0${*qSo|cv%X+AuRvvd^@2t zkvf<;yzsz@9E&y5!WIggTb!vUCR$YyQ<1*1Xl_L`>zeEu6G`0;Yqy~y)FDj|RfzPv zhR_<}qdoXeXYc=BVPUe==4cSyP`NO6Bk7Mb*`Cun)}4XcA$VPi)-ku1(LR%+1x7R? z@5zJfQ&yJ_qrC`Q&nF1VP2tZxKF~bCm}P|af}n%))-Euyn{q)3`i!$fuu~D*tsUX+ zUj@xQ<3%4HeTu_4j5d!h^dPi_IUcKvX6a#VaLVNfFOy~e2baM_xygXGBxp0PP*?9v zUvyGImZ8(+yNKX2rnJvR^0)U~!jbZnm36-<`*xJ8rYu_uAlwDAZQT(woDn{BjeqFzR6diVac%SBO<>NkxB zIqbSEsEPcKNm@Uou(+Flox((|S__i0HQjROqYmh*k1#zPHol_Kw?A-leqJYDsJ^`A zzG7Pv4!wdXmv;Z%M9TE`o$6#0AC1>|Kn^l=on)XG1x}xTuSmNgET7?bDp+Vt4S9j-)n2TBRh7DWSssu?-1m zqWgm~r#G^?R?TVV{Efg2@N{yeR)5s2;}&*C_yI)pD;Yb(!*%1cLyfIk=SHlr?p=lg z+rT1^U%eW_e;l%jJmtTcQuCVdEL#;iN98%XM*QCkJ>wm0Ndaso3{28_~dyI@%-8Q=Q6Q}5>dB%21l)7?D9 zd8)?iJsZeL1jETW;*~6?6jBhjQT-d*;iDWmF1fZy{Ip{&7?pK=-~;n9W}V=NT-HA84=T;TaU%nN zf3!9pWoQ0S1>v2PV4ElU6Ek6+ET=Mg4c(^t2_p+Ex(S{nJ-b>}q($5a%lvS$lQCxE zW7Fl76<1WQ^=XAgY?5QvGU9=3n95Car;O0z^18!2NJ9c(*Kg<5R{?>fb_nt0lc4xXo1BE5w=LES6E&L1JYV)0SONXTvfnMeCUl9;3Pw85RZ7k>$0 zuajmBsVK{&aKa$ww*nzRAM9q3Xj{lRTS8{)!Mo#GcNYB!Ol+PrAp^Dy0fS4rBA-Y#XT?Aew)$tc@kakFPP4BV;%c zp7Udpj}ofcST_(3KpayDyt-5X@k2RaTYX>P=r$Ox6!IrQy*YlM5)F<|!yIni&6zwe z10V#it&_jiHa)e-hEl{T{s-5{aRXHt#ar(Oi&%JI4<537ueMWEYBqhxA-$v#2kE(; zxXp+*m9sD=kbDG^QkNJ0;#n_==&s*1FPR9&{BtBeFIrb1D1F3gU* zpYzneO$RKPqYSWYCz$$UVMmuZsiFRUAD-@e@(GEN1N_#5biA@EqY^`hQ2~H0CJY}Y ztj=E3CGW+#7kptLuZ3&4!b$M9S<}Kv;aQ(fO0;2>0BtP*@FJLolp@c+di=&!Rj>c{ z$8v1=ZW=gi1a30~^TT#L+d_RLi%xy6e?)MRw#b4Sz(9N?44DnP7Xnk|09%Ep1^`ke z%X4)$E(3IZmq-|jCGNX~-{In#EvK3dXf1wlem{mYh2b1QNV`{=Fno1?HB3o@AXoZ; zhTz*b%EiAZ?LW!KY!XqyM-jmlr`NA78V39z6+1JhkBz5(z`oChENZxSI)p>*$>vC{ zY?kM>P}O`3DAj^Z262gOqz-MH7I5oOFJL4>!FlmJ3-I6RVCgn8D<=AzU>5{W^s4R_ zJpkO8gj*e#`#}5=HYQoR+qF%{nx|kHqFV35isk68tHZq1!8o$v2!-S|qa}zLOo71=$vA9#;{5JfH5{LzYY|%=E#$0n z-V#N_SjM8f`3QYBK;qv$_p^p^7QPisDHRcAJkUFz(iaIvojpUjjHm*j@_>?5K&~7l z_OkHMs@{ICAz{0DxD*w%9qBDXSVNmzAzV`!r~(D7@#P^SpgOBuCUxtPkZOX#qSs#I zb+n><+I{+Q^L!YIiJ-fNPKw9`Z^|P>$_$HCFEGpGqF1pHD}?aT&E+F!V8h$4Kp3>; zA(9PWe|JGbF$cwo9sS<7buiZqgt&(i;>0AgVXWzgw29?RDhNSA z?~-QLlq(5EPd-2XZmMxE2JEZ^ORYhruRtM(FUZEeeNZ-UH*4!-wkuvq)23anH z(V5~ymvaVP{7uj7*jbQK31RVmsoMKZ%~H{WF~|chA)I1gzwBe`(pz5p7PKbz<*eIe?|*Pn`lfxk0eqTtePFv0OrUKK9~vZyr>jzAQy+3%ftPEqf9S zmOKM*op`Rn@|oG%4dRK#Z(jKH7tqEwXK9!5Z~ zcWn|MLpoKNSno07i`0DSnwlEhWUj5Mmtdcav896I6C#|5Mf%&UZNETl<8q6I7z4iO zqeef`A4Zo_QtZKpOyh&4TNMW=hqi;4|N2oSFsSd);iHg@A^rGLPV&;LrrpT^*Q&l4 zAoKz&Mc%D2r!Qegd#ajuZVfQ*y89cY7T;oAH6tMXCb|Y|4l+;x=jy@RAavGY$MU}{ zr5^r8d5^q}p6x9#fmbDhB3z;zz87jZ}TlTm7Pr6OvmX6{Lrz-Ecli`!vxsg1HEcUn7&I9IG=N_ zCeIAB*Jd)94N3yr5jRNR$v{825)Ic&)P14?O-FYN=T@r5neI>({%i0 zP^K9}GPcB!OnSHxKlxSy`6pzeibG>7zRyu=g8Q-lJH!tCRe5Cu38G1Y>i|N&fPOzX zn|?)2idl?)4gnfaM?v495Sb{Z`ulIZ3!{5bZ6P zUz?5qoeJp!=s_I0ii7_6SM4b6UgL>LGDOQ?u_S}coDt?%)DP1>G3M}F>hE>;6Y#}b zxO+-GrC1B+*6gvQJuql(zneMR$0v;o$-g+8>{3aCG8Rddr#%0Y(hK6+y+1usgEMb!W>djzNQPxMbg#E)Dor3Fe3W9T_lp zPls||igu6=Kyzj?8>I!qCNq_$Xq0W)Bp+wepD}*aD7^HUYrK$j47HM>r(HZ^f4~X}R&Q|6uD}!TE9=n@kA%4(>JdoBT>T5pM^Unxf8_?gL3K&p`SimE#HYMU z{>~@)STBW{^gpuK*UPW;I-?LIbu9M7(7PwmvKwBtf4i-%B6n_nt!9MF!J!I zrOw*VN>-j6VN6t-vR25RHOhD6?Yu! zlva>g$=LkaP98!HE-BI81&T29siEIX_6titUfPb$4oShI7xyDlRb1sN)~Y>N&-nK3 zOlQgI&t9{1j8=vS16%F|&ar#$hYJ$YaVh7tU8k4;09*r-NQ`S1U1z1NupHlI)ydMG zMP*k-seiV0m$X;Z31EoV^0XJJL=Zr&v3b@;HjMybFql1aEHMF{E=VF(AoFw_mZOo? z%!g;$GMJ6Jyr99g{}FAY*BaUZ6s2zm(B-oF->0WGTataW&VXTGVbR@e-)lxB<@KtMhQxN>G+NE&LYhnYM`@SU>iF>Q-Sf^85B2Fj32_O{VsOt-}{-3yfS^2kfIf-+g8NmqPX zDS^tQp-q;r+h-W%T+_jV%lmxyF|9g#&%d3Yy|DxBhAulpPh~rwF)14ifk*7z17J*2 z7t^E(Im{3wcDaQaa8LWqXXdq^wa``X=XH;ydSw7SnG(N*NmNiJ{b0X`QM~3Me%MM4#aIi%6 z!U*Rxsd=Ky$+#trU0wK-g4@L>$hRyIaE|24d_tMy2pzpKq70u_w>L3)Z|fn|r2U$6 zuEy}zD<@UF9nXz0fe=2*pm76kJ5Y>ShQs8oo9U_ho$+`v@73%EnPdB5_%(I_L-9%q zWVh`E*Iz{%@db!J+)jJ}+rCeqhckwV><&QP{~h9>@vsQk#9EV9;75S4G0~9Liq1KR z-7E?wSK4OB-uj>|<#@t)DqMw4ywoZe4f3O3SvUt8$~qRSaD!og(YN>91j8eAu$O=A zBrY8ze*f;|QF|j`3}<26OrBrhql=mFsMrsR&!f-BE|qJ__-Vf*lX*x!fE!-3Lm?tC z#cWe^?upuWjx`KK-5IlNyX4SNt>2W%%1$_*22;%AuJs-6Ir}&OZa`^xilNQrX(^_K z4m6)f^%}XU8UfG)g`?6RzpQVjn)I8Tq=Z;e-V>Qd@#@6iS?;^CFHD;PSb;bh{mr7V z(e(q-ZU})|l)v0c@UUwf;x`UdyOUL5V2}8j2|pJ{suN5TJCY5;oCw>6%|my7`*p^B zP`|#T!=yY6hBK4HSd8qY+W+3r`mg+S5CCt=sk|k<)Nb||pP%47PKvR8nthqx@2Sdw z$=jM?gT&76H@V6D<97iJo4HE)hD|Pc)%uvlG@a$>N*1?GeRc_Rko?L4t9KJXv6OLs zV3J{MCXy(+fi$`Y8%tS<_`ZJluFcpPnROdgdEY*zY1}o4T_Ql{#RqpXUcu*Y9&@`g z4(q}jsXZ#y%`SLhXl6-DZ;K8yxMwPRG!wL`+)~l4;j>GZZS!luKUpn~XX0;sV&n7W zNTQ6<<`@)~k-=EderII7&-=?w$4QBHJab#f%8eHj>hiA1_)*?!tGBIM_{qHvp%ZoB8FcQ;xh!Hl@F0eo zX4}%7&Y*qQzLJve8d}6%w?VJq4L9BRVDv;a)%?o7i3*%p%xwSTc zOQn6?H`+DGhsBA6nx}Ct6PNbyz*x!O{TNqr$~!w)YCG8BZgcri_Kd~l(iZvNm9<0N z!@E2mzHAi!|Cy}FV+1&4uZ5U9a zrgbYn3JN7pbe9Hn^t^i#Klkz9&9n`>TTd@7PCx9Jd=D>W|4%5Hc6MiHf$xrmnPImK z^=!?*M-LRd3znr`@-a5ezwTeo4lmqfl|y$<{4=vH6O%>vs|?JkSfhMtGC|%LpJ@=K z=3nl40Uv8GEM6;ITK@XsVh@H3+Y|b{m_)57?(WEMZt~=Ou*jyRp%7c-x315J&~T#N zvtHk#6VkymE<1ZJuTC`hmlyY?1hPUWPs&I`a;hKCfTjP+k3`X+aq;rK!}!ggn-Z=o zFMKf+zpqI^iwz*v#BeIXLT3AeXf57kMY4ih{E*uPnc?JD)DO;WU{#6cvkYFyB@X%> zx)wZs2L81aGB9HYcBbf|bjulS>0!k|Jz(++$I;{fvi%n&});|Z0VGlto{G0#`P>1Ssg zo8mp>&&jZndseys#!fiSzX*8gxW&9J%kl5F$!-_nzQ}`Bn(;a6PS1^uw#Mt98X}~c z|I-gVECb=4S`9VF+6g+bVlLKnLfR_7Lm=m|K^8x^!K`jD=6RdymXm}P53Rp=rzG^~ zgZJJAs_X4LH(p!l{BQBY%gD_?VUqg{E1XD6RB+Vawe8w3ip8$w!``Vi74ij!mx z!!OHa*EFV?3t@8`?k9Sz%!eT!37)OEZ(d#*Z&w)Ry?X(ldY{If8F+g4fK&{dW@*n4 z!(?K%&W2Q1sP0^Bq`cm!B(u+vT@^og#Twe=){)c(z|Pgkmh%aZl4yTfo?C=9S-0~L zsF%6LX!Q{8wM%rx>sa@Ld<)_@5USeD*SP6S&;4iw_dOzLRbPgo4aGntRF!Zp3kMAI zjL7j|@)wz9H7=GC3)yT5uCNHYonGR2>|r0 zYML{5F~$|rOrJR(a3X~E>Le5c{KToJwzehIT~s`>oxb1`NJa1!wIl2HLy zD7^?`R@KE4{TMpbAH%2>f8@_XFM*XTF0~PURaVKH2cLpM>4EIp#Fce0lEHC=<^*%2 zy(E}&%F~#JEX8{Glx53k3T*{S#CjjygNMD-?1$yDqT;^Lwmj=_l+s@wd!(zf^5I_R zIWO>rU0fvH2nLNNle8Bl1b0rNV!eHe@s84)-Yl2ZGyYkJ49K%##>}qES75 zbK*RSnOCKwQ;kc*AvdhLEWfHot|q3aTyx{l0jJUG+dWlJO%~%dk6uvYCOl$-0}&X9 zj}}?+P;Pg|v%_xjY}We)7wtb%ops+z$8NA~wHFHp)-Ca}B5gl7wuzBiyX^7Qb;|OA zF4qk||3Ycg061XwhrwFcEMNvTr>`@G7glNa~%uZIz~hA_G|TP;loWA{4yeZqw9 zS(R@yj*GQfV}0eC`pl?lfR%L6byDk(AkFSEj}*xw$Ql$+Z`$HVZMM6csx9~Sa)o%7 zh_&#RJHlx5K_50~m-v%>e}rmVp}6vk0C9gvt{PT7m99`v%JA(oP&4+}Zk=6(vcNd} zxmlRECz|%RIfMBvo8p)3-;JPi>Ea>svAS~gey+Qr!LjA3 z&_URod4Eyo{-LQPdI$>Jb74x`St^=B@1P9=0L0~ZU?V4GWeeS;Tgy| zVk{on@=>TmCFOkHY6%jiwlDq^apd!P!8s__%p>iU z5>*rugR_W-^QX4=l&zhK zeQ*Ljg{ra*#!Xg=Gkrg(&vMgbc2m*uwX_mQ%kb;8haB zY#-sFkie`Zv~fr?f^ezWd>8ffcPaUsH1R8h;uuL^#N-(u7@8`66j;fi(Ikk^<*$N< z!U2%eK7PZ^pA@33-l1 zfppGLj(3PdB3qJ>Ui>R`QXfd#+(L{=lGB?Y)bsIo`!MU6N7r8k{Skn(&>)fJigeO_ z&Sy?aDHCk%>(P;TSV%tz_gb|cO~XDGIGfJ0{1a7WPGm?!eo_ihzH)O1g!|8y>vu}@ z4Xia1;KTutoYAk}MEehV9}yvTM`yF;U~E0i2@qGr$E)?Zwy{&v%93U{YSj36Vrkqw zXVvF)V+4TJHZ-V``ql_oA_i%M<9GQgc|tVVkE{tQUbp* zzy505`b#+*sCMcOY|RruXbI!uu6gv?0+`QHUf_;pZ_CMR4#H`9o9Y<#7tuu2ly zAtZGS=^&RocPW77tU{ z`2$x45`S#8Dhn}s1C4H^?x(WxlneMO+M1Y&EtM=hQ~-V~BDQcWs-U-}8~}RohxY>T z*&@hXt0V-K7-f1vWqKwsqo50N!ZNe2GH79|0+ziP0g-nGi>DrDM=j3r>D~E8p*O4Ko zAktH?sNT02O8C)&3uhusAHX2GYLro?!nsP%fKeIhhYOAM9>A2OaGCI61|L@>gb31M zTui_PSu%O)-nQ~>VBW^Pss@x5{hLBmY%vTJw4gm0POx!ONeaFO(dA+Td6BTtHMf#h z=9vOB%?5CM3HGv3{seGUb^X;7_E#Sb-`sQwgs@qFlyZcISzs&d1TwYNX)P>t6wO zAX7|RJp-QJpP$0NIEL;<;J=#?t$|`zZ)`G>E*8mrQ{$vDI5ZFYqye}Z#SL3t@s0m^z~ga$&z#SBL2khq#K<40R*pXs5UhP=HjQk9#O42HLu9t~>1> zM;?a=DT5fy0JPY!KPRrjtDjViJgKV&=t9g31}Sjyl3k;o!ml&G>i%yUE7huS0>3lP zj);hD0yN5|RwllxlWFYx032DbZhmVMmHi}@Lr|nwtX`tDBPd_^)oc?C8Em6Fv|Xx! z@64g0s>$CZ58O=^|AgoNk+l3uhLO0KCefPpUf}dc_gGcv-;xDFex}41%1+-lrX8kHXw6p{|f@>ZN z2^+DbD`VlWp!P3FtY_dafEaDjOYa)sVj1rH&vvAfV#99=$y$$iq6acjLz~zW4B{)n zelwXI31vZg$tZ4&-UVwQ1~gcMHFAN-=rd=1LFiG`E^rSzTASipd$9@77eJq~aJ6=%@kXs) zA<-cEOc6+kqQS|G*ViR3w58 z-WtV41FQI}Fs0WpvxC9(H&0CdlN211teF}z`bkTIx(1_slFlyDxF@NF4gY&fg73Y( zPN1V@48Cxty2bREF1=Q^yGjD#$y}nc9C?-z@>57|G$OYxQlj!-^+}0q1;F&}aiUzw z1y97^V}4nbjrB`=UopfXESlIS19_I;<8vsdC(-q zb%NyRos>T`%D7OMOI}?vM1*$sPuU2V2xk0k1~H4c{bLkfLEq!_rSz8arb{pkAMp~TOo7B+A$g8N zf#fT0T2p~hpB1A?8v%ea_6?JbSb=zlf{oQ?tBq{`9~eg!x!hD6VOaOD20nk5tS#6cRQwj;MkOnl|_5BKlw1W6gvM}CLE z2vCR|R~)vS#5x)9r+ya3lg5C;aUqGDKpN!smnP1g{Xr~}EFAjYtj<7XqNwNoQJ(sN zTQ}(8V4v3S1!m8@%8_yBh2&B2qpf+b7|L#cAXW?N4`ta~m^Ko1!4kG%wZ;44K0nMD z?mYJ}bWQ8ZC8E?O+3--fTlqJ6y;|8Ba!xKtZ14%6rqvY=41`Oe2a zi@1-Dhh%121A7^t^bjO!H}Xb~OQQPA)4-s_>~drL40>0&yLnLEUU7~8%?Gzsvk*>A zr%@+_Eg804Mc<$^2lm)sMSRr{do5^rf(>pZcLrlcj);ekPbGai&tA2!v&gB{;Py~$ zLR!LLipK9fC}WJbDiU4$?#Z#A;6iIhI~V)R$;z4$4ClITlRfyC^ecAQI$JEev39>r z&X5%yu+2kjosOowdOf*MtyU5EvJS)qkW?|IQ3GFV4M3n zl&hz)8+~()C=sOtASg~6&-7eQr@DH=F;o>1H^Dx>Icd|flVLr-BE!82T`rfJYiup0 zAqj%8A2fpA;#Hm+5x+<9_wfx(NfCMO)(f77E&E~9Nv;#1edBkBO!E+U`(vS6DBTrL zWiTN5u#MEJpZ76HkZkcsdMG!+-C_@I`=gw+;uFh5wX{hZ-xC&c8&ht5qW;vHFWMVcSiQP=Y`GajPp~|d%Z2D!#7Y>l zk%_k%l$4>BU71XP;?u|$pc!$mHxS{s1U%(&6(f0H+w5m|j&FJKhK5lTZe${$OGEMD z-X=i^$zIG%R&uaC$~&d-x&glDqTquz;&wZAqR&J?29ORQ9fra}#1~_4RFClfvI;iZ z^f5rS>(uJS>2nEKp5FZp8&zj-MkN_U43&^Qb7cq$oFTZ0Ss@w{kXP_cnb(HiawCiv zrjq39un!I!G!s8}Y{Syn0xtBi1LDIQBL!U$ALb?FzWGVI5*(!LB%O|fxk>09tkD0F zJLmd~hRsS3jhG3z37)LxRLzZ8E{~*!1-Ob`pbOC;5rC&DcrKo+qp7C#CGNQ^`k?Ju zcuS$tF!Y}xidH9Z&a_;`LKi;POlcjLdj`;?g)=%Q@_JqNZ5?@ZU5l zpOLI*79c31Z9$CC|Dsm;d{{)5h|ABb=Rb_^9(+f>WRFm?Awk zu20)#S>{qWc)lq7*Q;$W;T_B(Vg8jzaMLqX zue!^t4upSk=VA^B5UNshd{cZWVl*-9v3Xy(-ItNP8Sne|Zu@<2NzCrPPJA%dwj#Ac z@b2OPq#G(Y&A#Q~Xo^J6XpotHJp1_0g*z39ojfmV#hBbb3m4B0z`SjdOXuD!z7gTG z^_^7$_)!N!Y0{rJ;=GQt^Ie_wUl?I+gkwhg9E@6CS2BD!H$jSm>k}ExJ$>`r9F55- z?GDg=<@&q;>74>v{;+5Vutagut58P4+{3Z*4n?mApE}*AtT-ZzHknvTdgehs)EX3X z$^PF8#mHl7dH0qmZYs`lI4#foh6AA?n_AUBVXe&VtUg*a=y$&eu02-*8{>&|wW6Q? za2(CvYvkzSaI%VH3taic&_JsFYwr=r?>E ztZGcDBIvyL8&P>t={Exf7SARC#8;4pc_Tf$BQWcd%JXY+cjBTt48IrNiD0NX4~*}h z*%kh@ZP)j#?4|?Zt4D@jrXH!QTpJa+b!7O>|0fOeyZ3i`PMlgevSoe2*+Vw3+)9@I zXEFP7k9{{Y)=G>eOSZAABqUqgSdvf;Nt817ok59+u~f7@Ln`ms3&vzm(jb`g_n^VsdvOvGw*J?T zeU8biYZFthUp1io)&HQdQTB+m(v6XEL*=I7&lossm+Rl{f;v;AWU_OgZ`oOA+Z3yW z9kz2$Lw;*=>?1+1r;!J6ONH_`_dQH|YEx#~*pu|4`G59ykAFcuuFwUmZO;%^mqz@K zKl&FDcI?Z$jq-wji3RsIpDLAYxfLc;L|L%VuQz-MA>=>i>(A_@w_X&`bs~?MIjl-U1xK{Xndv)i?`?DiH5r`p2Xp#DLq0kQB zac9u>ORHG!sI0Gl%~7Hr-Q7uunReeKVca4Z_w_3byWJh1AKB6vPZ#PKt)pY8r@qqq zm|;A7P%X`UGJD;(3Fx#<(5>*^?j+H9z^MPt6^$eb;8tMynLky)oa;ZvvL!5)K(gZH zDf$ul(nDcKAu~Wk? zsLDfMZeU@o42DYk?;R!-nqw_Pw;&B~pmz?gx8s6rj=x6M)j6`to)vBvZqqWOM=@Y?pH0$Tnv!4mbLTkx*$)GJ?dwRXys<@7X z+c$BQ-w9xXav2NzMh6%}Oigz`$I{T^bt!xAW^XG{q+>i{8ajHRsVbiX04-me(Hq=5 zQ0gh}osV=I`yFyOS}TM;+1UCZQ>nOm#lt)qA~scFx1~2Jae5uJRo77w^mK*{>y=06=AtlC9g$$aX*0FBTo_MNG&cetyBD%^5xqt&=EPIyrZm1Tzq6Z} zFia*onem(Y#^eEcmC{cDn!!Y%wsa+#QsJr7bxeZ5?H_#}acsOdYt0B7m{qTEU+?_> zBeXJ4LAcJ*Qv)jFEF@)-bTo*ft_C3w$o>oFv5{I~0cCD0UAdu)-L05lrDbZJk}xaO zywmGy1Jn$~C6A@7z*LfE9o3xy0enTT)D{;CWluPpq$Z930R(^n{)+kTj1=3@RMk=7 zxiQ-wzKokv4%jeG?uxpmi0#TP^Vh*CGj?iJ0-`Pr7K^~>h2eGLBpJ6v>KN#_k`~0 zN}MLLPCKf86_qKkrh<9=4|diy+h%u>^;C*bzt)mT$!<~`2JDa#$IM_SO#0fQUmqHgOeJBNatoNm5ueR1ebH18Dq z5!E{+KP51PY%;**V;~DoA8pbKQL8| z^oHrrxkP(@I zE-*STXLz_Eg5QSD-M@VG^kS;|m;lpcJ@MF$GvK+Y7Lm}&kdg@>^CdQPAf9S+jnaY$ z&o_pvbVs14EQ2L76giB+=)Md}_3Ax8AuX=0iRq z{47HKLxYQH)dV5v&{37oW#}0=s$xKHpy%fAzVmBMdfKuDiI)L;_RsBlExDg&ZpG)46RqK_11XHj2LosXDpGwP=*b8RM zWiCja`tT!@FvVxfF6J(#war6kRo`PWt;Er`$=0*&-#_%(j318p_1)2TwXAOwGgmht z)WN!-DYdqKDOE%RBJbAHfz2$q@-z?QhjFZ1Yns7Mb=)nYPU*f18A{T3RDSIlXfZE0 zn$YsPU{-Pst?2OL@IO!;^J!~_Ny<=V@M@jv)vcK}oo8QoBbL;E@iT>Ul-L@Tc6H33 z-mIU&xnAzIx2I`4>KN3gyA9c~8?BfaUqOm$zX-ikcQ=q%9Jc7Q77mf({{5@I$aS^8OfLMq`~9DWljwrCkWc%=4*8la zq(uElZZnSi@B_ko_6N~hbO`6_Cyn08W#S?cyh(?*BLOkK| znP(vW_1k`Jf+#@smf|AUd^fX*&R-Bn;{M9Q<9rg$9yvRfqVQ zN16f1>(7#xnERk;tAZN|o^s@)v*jf9$ZIwPT!~MagiaA&vmcwsICGeb*pPMRb_y(H zW@|==b%J-=URdZ`PtsS8a*O>5lu`I9e_siEZw?CB!<63AZ(?V3@V5j(u#Y26L(lcV z*f}2Q1CTM!CXRE7uf-bGt;7m9;t=Q1IMgDfrd(#~#k0^u-6?n)JcMl($HZKqf+KUP z7v=~rMa0((ts!6&p*9KKWZ67V!i*dSs8Z{^Et+{I%|Ngtj4%ihLq72f-|+l0@imiZ z6Q^qHqM$|B?=&V1vqT^5&;Rm?Uqd&vbBr`9I-q{!f-% zw_;XpZ}77ond})?(KPZyr!M$NcL*ju2xKIVlRh&~{k;?s4>@bM1hswwFaZf)JN+E>8|$$wRHjcp4;t2v1nM z0y-WvxTXjCr4oc(;xBI!vN?cgq!L)eO?UyIxQHfCtx+Rf)+1>FlTemS7-kU1g~XOV zf`CUqGoe5UaGEeA1C;8&@ z4&NFk{y-{zP2!6b)dSL80L`gtg}L2s2EJQv50r7sGp){FwEbb?h~fheyBmST6s09F!35@75l<4HC1+Becz5w}5Ddn;Z);W#Ar)&{C zAh&NL4^sefL?diDKiY1m^hRl`TW5WZCd_g;ib=T09ByR<6G4H-hb)-cAF`4}*r3FR z!8_{k9d%~|8x?t*6si9qTva|ykC_JLA=52zcF_va+RELdBp;&_Ph!EA2{N?dJmChi zD8PZ*hTK3fKL^zzuRS3@F)p5JU%<8QyriGfgiWV3m=r5&-a_|mzR^C0_7lSa zHlWCDXuDVHM}w(Skk>akxHW4Y6-1RXV4YM08sC1tL4@?tROs`O$`8g! z1lY?|-X;tY%943Tub)UwI=KlHLj___$HG8(0q>vJ5=Qn9HffNBuk^%Kar9z5HE-yl z^X<|3LFz2A)YeF;ZPfoZu6k6sA_!AqH%d4#qui$8rbe^~fz1uH>n!yCP23)&eT6P} zRa$<3&R%&wY_99X$9huZa6Ckb=a|q3$K@oWqZv{zo=95(Vv`uI?+Mpt!L@~T&=Q-% zfgSk*+qJDR&`Q1{5T+xRI!Z;ekKqS}#Ay!c2Tyw`BG$pY4LNiN!i%&VVgkxGpjI0a zGJob12S7p!^|m7GOr>YPht3P2ZtANB?&muN>mPLAZC!#-3B*U~-M_13RG*D_4L|^pk)I(+5btTL{&B7==^EuzH}fM+aK}A?Jwq ziu`mx7Ne+A_n8Dpq`%?1a@ELx;^{bFoStWgLPeLX^sP*17tBzF&j1LG{aUC5Y!vAm z=gzT~?qUmKHw$M7RPT<`Ap#}PGH{due&TF^yKh(H1C|Vn8J_7^&(r^Wu_UV=TKxdW zabbt|=pZC4cn*sbH550?Bdx3G$2P&xVt6DjWfBwR(!O+|-& z!ZvcBxY2~?eyZOG^IJfyAKwZm8pl%LzG8C3CEfcBE$#W?K`L>SO+3)i8QBJdP7vaS zgZ4JWx157l<{m(c+4tN6$VUHA1U;PYX|@43oOlg4(%LIA0;^%2DA*?PN!vqDZX!Fp zjCG*jbAN`P;VgIkKPu!`2T8M~#8FYckc-H=@D@dZ>4{OBQlpS_Zw=qlcr zyKI^HP~6pfmb@$^sbn1i+K4Zp)&sjFgaPP&dyh!&XRy#2qR~7@4R?nZ?T4Sos>sJ0~j1rZyn$MU2lClm?tAeKYizfb@|?+O$Td8WW*|o+b`l37n*p>NiiAIA>{f zDbRPG0gDs;Dz}3lpT0oz(OoROkay&#L=Yemc*)+FkqAegafkyv`{>vg;xeUDo-XOe$BM|pF_z6zCiGrO& zdePlzeG-VQ6piUZPq3b*jOW72L0N~(i9X?^F_46w(|NTZb>H@*k`Q=UWsitfa&3NX ze&`@NXnnFR$oC?v-TXM4*-jK-C&Y!2_`|Bv^t~Ye_8B5|lJTQw2a>h+aSQs2+7bbk3$&wl<(I@~-Z zQc|NSS4PUnB3Bdo9#T-zm!3y{{ZJcT7y)k)5-!Hy`sxYQ4}SDK`>|8W?B5iPb`TyO z@d>gOU?};xpo6HbB(QK{DG;1vT>F@_S6u{C^MtpsUyg~1pTvH94ZszTLj#64pj6fq@w?MZI?l~wEeHbe@^44Rp~J3fWomr&E^bJ$$Q$ZSX-&q6X7;gzg=hV z$*+Bd`wcTP-Yv(MFI+;BnzEW8N7)|p6LSv^boFvCm>!Z`c0TnyPswzXlKJQE3%erw z^VRDYX~-=jzQrqljG})1lV1pizBO*)PNZ(kL(C?A=_RSRCXF|&p8Bc(>fgxWs@2`T z`4oWc_ue+cx)|l?Tx2)@w{K9x)<8lx{>lcy9FH6*FD zbo3=khxFB)c66D$Tv+3F!D4mogzx)*eeyJYnBRvT(n;!TN`Nq7_q~L~rtKBJPsJ?< zpRH}$_NFf)_UCQ|Oi(}O_rr|UpD!0EHHS|X%QKt+Q8i+1ZsNk>f$~iL;f8>%$_+=X z$mNIVzpogr86-a9$h{kf*qfsAfork0uRdN+n$7)CjpB7N>TysY7ZC2tLRG{}uKQRW zrJUD$C#ftbOew7PcQ7aEWTerSLbK1;ZDh{Z^`U9gJDWAJ$`%0dHJ;gVHmW!KplbbE z&5S)&ssg2CEia~~u7Cfve|rJ_(7MfMN*&Q28^}x*u@V@j;LzG%g8+;_vk==4EtZac&RUG6Xf$)esfD42e<~24_X-1e`QY?q1_H*GghN!oH`wlsQ zNF6P&Q?49NdewNNs>j6FO4F_jA{O6~T^G z0vL7hk(O}{8`r9JN-UskcR=~6=>wP)PbrF-7S^pn70VQp!EvvYlEh9s3+fermn$CX zPiX(>FfF9-HKp&82;m?{K>4uhh_w>dNnQ9|ar$@f{;tR!t(`p_U8iL1k40^no9EN? zA$GkBGI7@dNK7cRa>|L6P7fiUUL@wL=m|&;;q8=W!))oV{kFPP7y&MOblGAmy`hIG z)iS~vKQ*rnYy>uKBI;cBljNOYR!47tM0vjd~U22j>KgzB>HZmA6y*#|fXkOc$|ZBCZ$7N8C| zf04A9aeD=%pGGOI^_#o2O`jPv!*P1dR-J1BPu4DL->y&hoiy5j&&sC-%UnRNq$UgA zJxv-|EZ^uNP1^a}J?h^B9HbU=<8Z0GF~8n1Qzu#O1tU$ZH{HNhpV4(*>i})2$H3JB zP~ODSR(UC9xF@tHwUVj%;G@kj%p)YTau1^Yzg%bAHl=<@nWI?Ge6rAv<=)@#_a{A_HH%dVaSTqOk3e z`+mK8@h>WlpKkMYt6%B($G_+!g-@%0*c|@2;di%nMw7y=>F=oP z`YbwwNJj{h@8}8h|GL%^LKnXHO8*2HYQ zz>LDaU(NO7Ry!vDtxaD>iyHn5)VlQWFy+jHgH_w>o?qW!655@ysv=J)3)tVzepxK{ zWb}$>mGx=`GJ9yNXDmF7nQ=Sipe=giT?Nt=|90*Z3EDr}W~-_ijfv$|)wKt^6}-7dF7a$;uNB2ksU~T~2xO={=+{ zmc_zH4;HFgO5U~nzLN1r-Lc$bxbybk{rn%DX@?}%y=CRy{bz3-{_FZ(V{>w~M?tTbOZDmH-jD4n{|BgCLG-J~ z_0PE+ABAEGO5uyzZd%%_j=4b(yJw%+g_Uc+V{~I$1`^Bin^vbm29DRu>25-tI|Z8Vd-`&~fY zK{w6Q(h9oe?#9_$!EZ|$%%Ej{GO%3^DFCb=1oheJX9RE6H^4bRiAhbDK_fi>McwUm2eJ@SU{7bIuv&vO+*azO!Pdjmc$PQaKaj>30( zy7v83lx3g;sh*@CuhyLP-nxE2Irgi+RSxRaT8-Xu!AFhSM}2R=;Ir=`dFroOuq_X* zjnEeX)5aVWTF^l{$xU_t#F5J=%0CFCQfl};)nP5UySX{?cKDv3#dVeBc6+B-&;e7~ zdv?*N8yUj$P?h{-W|2NcIwIRD%3OkQHj(N|$u|n$X?;!65#O%a zyoY0t=$@5T*1AEAhH9yVARSi=xO84>_eJ9x?4Q%M*^Q#=jVn$BhwYjw@O6E58H)w+ zqq-WqwcLvTH1(XBPF0UFey^w&3}`faQ7Nos%4H7P8H~2%xP=)@CA-_NM5z31=(D`j zRPy;7OZ(IvQfzuLsjSafk~ubw+ODCCdzm(+$}Z z&}F=%$vrQq%eq*vw|(7KnXBYe*F%)8EM4@G9oRc(oubPdWSf3+G97)dU@&^)PHMxl zfRO32E@hWW>7NXXl`c}^O9U0ufpLp1K6AOmdAzri5Uv`b@}AMR{;fTkz2!3%b9&Y~ zXBwGfkOm-Tll2E+g(sa%)WzZG%@6HKCt9U79zZf&vHf_b@*O@digkB=40XGR<}bmN z2>nOV9^G`yl5Paf_=U@J4qIx^vTF_re$Ar4gXFE9Mpre;-fr<#L-v&vgPSZDA*tVf zZq~oA|7&ug)|_Uk^91^6(4=pg|0rfme2w{LDF3m$qw?@Afg4P*;?W>YDvkNt>-6r$4FN$ciSzy z=I+btQG)LwTRtu#`K^VVK){aJ|11)oitY05(RSNOx8E2im{J|%xcElQ5F*mL4!`}= z7q@`0mNQ>;`{mW-wMcnzILnXP1QgNf_HI>^6Z^xKJLqrY*8yjFm=MJ)$^+CZ)U_@G z|6YxcTv0a5$Vh&D;`z{qrF=H8tD`QU_>s?L?jMnP7Xrq?SVR+Aj@L=THmUqDs%@%@ z>F&BGSgN%RPptmSi`pV<5MagE0{7&>$wieP)$2_z8uB@NW(Uq*NMNNmu7)(~(6cHp zyh6LQmzv>SE4`3JOm9<5VOS&-UjU8CTx`;E9C)6p@rdpgo9n{ogb__b5P@+1_UUCBR|bJ!o@ zV2IlAawdb0gxZlO2obyv&xtBT(NxDw30rYvrAJ<5e5&%utc&Gmgh7(qGWGhMzD;z- zsVSHM!4*q24^MV_eGXR|56`rG7Nqfa6rujz6D`^NEU4hyl~mRDZb=sMm1{>^G}Z3p zE4*}R!a85yOLPghy^wn$^%H>ts?B2|BW|$Q*23hi6Cyp2AmwLqWP9W$B@}=bC>Z#h zjvT_P(1OEvlAx945{LW~_-{}#0Z~MD%3Bd6)JrK3N_ovDjzG#tVCTCbd=p!`OcuR| z58HYkd;|?GIj9IKy2nSgj)k|$#CNdd!ZlM>{gvSzU)VZ^4ZKM61wSQB(m~K10b54*l8;Nl8TLn<4I-$A_Z_pTn#HrcAd#GUKAikT zNE`==&xC}4d4o=ozLB?P=mL?k%VO9Jm+y$uW&rJrnYam<{U|D)iK!CHH}Uc9f@9D# zy;~#DvXm6p1L}0`1(5_aD?K3uB@n1J)@^PPnoa= zjX16sBooF!VjtD;(j+!bfWUhCJj7(_00%s!un^L@%QT~;5Lg(kZ$k$?hP=NEeS2;n z-Y?#Khei8if-|HOwvOWmIT;%qbDxOt5RVFUqeTs6S1*%?ges7Cxl$mdCzLH)F8quD zwn+fRI3C7y;z&C{fc~*~Ay%%pH`}zuKGFwi(nVQ7D3pMjO~Bc`yOc&ngbsm;=A8DW zottfUZq8mfch{Z}5rhk(dOn38`%P|RXYMN2)1y!xXZj;nViq}I+6oy&{wzQk%D|Q_K@~x&B7|wca}f7=4-)c(XtOI@f{Tv@SmIuH zg>2|>5A!xnFxpW(EgjECsxtsN0Zg7+E#bnDHPum;;JhVIU1%G_r{6rDcY2sGB+M%B zAT99D>ml~+t~Y*uKo&&GqKE8}_5g^HQ{rAm8}Xn~4DvFyMzFvVz2AT--_pu(X&t#xZXLK0Z-a-kj@1S5H#Ix0L=F08mK!gsI() zVaoQ#X>m&Tx=5$XhSebLFOZn^3)$X0!li(Ur<2hf&$`pVuB3Ym zPLXLh4iy2SJh%u$s00SWewA0};~HIqpdpuSS3eydEtBG~JA8rI_JIU>!P^|k@)v@e z&uZwTUPa6`^o&4eQEc-c@>SEgAL27##l(lq!;!Tpme9+OCFKD%XPF4(HiWk4{}^?0 z8@xtfa_nkry&IlIymNoZZl-0pW_1XAHOOmVyec1-LG%uOVua9gk3_$yuZGdho79YW^E1+-qt)cZzB>P*wA_e?9A`NFiH94Fno){Yh@_bi1I{)3(-wtf^pd$k0Kat zJ?1{2@It7Lpk&uZpJ~-WON(wv11*k$)vWD$S<%I zfm&@A2{(S%UkmJ_LXY{X(^YQRSG4}qWvK^$o3Pcc6 zOQ=^{NH~l8MRYlj-FrUXCvar%LZtC?5%C3wxa3Aq2*AeiA55L<|#ss@13W*O;LU@tCs_rUnN3O*YB^|70ErvVjHPSuaj19OJ&l1stcR?*OcwCpvY z%?j91v*V6<&u$|SJBiH@!w0^~I<5y145=DT)<`1wmP(poF$?Kk{gE&=G1*p#Z^vOS ziSPq%O6QV^_WEEY4`U!EtMZ?@Mpx^2s$Jlz5sH+43~jBWbb0Bus6WPD=9JqV(kp=_ zKIO>o>)gJ_6OI+#0&jq;N-#?n=A0yW2otS$>y}yY?TyHyCoc$%YC@Q{=MK9^_s6)z zF^hFa_mNf_=#8X1q z(~uK)FCrE^j|e(#zDi~m=}ikxA2{5HXd-`SlBRij1JVlFg{uZO}Y@pEQ0{bY_W9 zUYa9b-2VOrH$x~Sj4|6@MGnabGf7oq-=z>tnZS;R&+tMG!ae03$x0W7l-hQZH=S{AL@UuH zy+`Fl@K!NlSU6FcOrB#ag<*QbM=}PfnPXI>UI7T5ge=KEm4Nsbs)%80^>sqMv~T0B zv(7I#6su;HTV8u|NrZ&suAc$&FMtgBI}~(!5k8dbt;7fbSbg&eN&E1x@moqA=vS~6 zDLX6GF_dRa2sR=--@B)M0RE6c{>vrC`qzj#XB0|_0^LmC6v~JYofCLB!X2@3jU0e5 z!cmlv1)sk~$K7B0puNEAXT1$g4O3;-KI9UwxPf9S2~vbCT_le1jAkZ|<%q8D7<$wH z1&-GQ&v^X6Ow9VNk%N}W#eduGZ1@Krr1x|L9p}(TCp~!1Qm;>9-JcnoFVC8 zdSz)!SK}#?|4Pts3iso{8`v}oTLA=UC4<%uAm_}W**@9UuDNitdXgAnIVqDLPMU`_ zFSOobNX&1)JisIvh&8NtRR2DNTpkUaKeBoBEyXe!d`AV_4z%g*G+yN@kMJ#;eeaoy zC}|9-m(;{L<{t^ijDBWzVE6JfHo=k&$XCBwY6BP&v8C@4xrV!`I|ix_P$<#h-a8+N zUjli5rHFq-1`l8A z>*OICCNAH(96S^;`{g}9Lr!ZD3O z_aDE!zFOk@Ex<8+pp3R#p6K2+^yF!EX4ynFcGD@0eXz>onj3qG+n!%kJYs(D_>aj) ziT#&P<05!)0-bsEIs&E$Y_{+IovD`4@Mxwv>2mqyt6^2qVM>D!m-|xZrL~4yh$u0v z&{j4(?Y5V9!ne|-P?ZdWvzS+3Xy@0GuhfV#{$^I65l;jIl&!K~IIy(9cZXfU(_a11kf;y4_9v~S zd;^gGK5$FH$V1okvu9>ABo|`Wu;_}2`i>_iKh~l%uKGBMSTv@&6h4(`&4m{xsaks2 zW`@RQ8D!tdZg3Svq}*1gB~sIN=4dUu!r&nDCW>O#*jv+3Ule8)R!fst+WnJNlcISz z{U?2g3fI11c5SZytj}7_fv0AvO?s7CvrU;gnSYe{wAk8wH@K8EhF7Ce3UJaRdZQ0k zM)+TyQErbbuP3T+)e~2fTtdw!k{ALWocs`i%g$QGLkg_#6|)r?@`oD?(~X9+I6$c^ z3kC2>YR|4~%$_L^+FDeXCB4<+cQwL{wH$I$p_f;qI+^8vFG`Z|bT|K1vTM~zF)Zfe zqWUpC4g$&YlmM_wu)EMAhue`Rg=`h1p&affAg&z$u7n`p%xa~1xNLPUJ(5blQnQ9y z`0_PQMl?qIAgw3TxJGFOVEe3uA`Mvw1`|LKMt28gSXqcZ+9*bc%hm=R%QDO9-gJfb z_)n*9OqQM}0J}<*pV(VO#_*EK)?z^oN!j~ZZ2Cr4cq+z$35{Jvr=ULHE96!4&ufhz z)!(XhGE?!&lD;UCEfs)h*p>F58P@U7IjECoY+p4eN;*hms>a$!p1sxIf1P9uy#Y!c z8q|_UuK`eAw+ujFcpSJj4~Q`FN1F-mFWXlH7{!K5yF;&qTHoGM?l*Y1dE3Ls&z_DTWAnE-yt|xid|to=2Nj32jjor5H7Z%Ty{(*+nH&@()MR9foC~bUC2H z)WUAzK!srbqa=40($Nj>v=!UsGt6+>xs0Yg@5JIVq#VeSY}aXH=#I>Pp0*V;gK&%2 zlBUwiNryV^!WhY6>+=F*X1g3)#yoi4RGcH*Ov zHqYcaGX5>JN2)0h<2rDmrPa`NKabn@qn&gJds9PDs#vES7YmE$D+=>^+6vK*vvzDAP?;RJQ-|Fj?NqFI+{pu`g-OvH zN$}7inBupDJIGxXj#an>-ECjmm>qu*wr92O@XK%EFz(-xEt9t%#P`e^Iw$z4S_|L} zNJCydVjn35zATt)pQ zH^=+3o0x#&e+^s!xj)V@(PRx|b54ZSkl@vl$8UoTOzOo}3%pE;Zrz-K! zBu~)_6M(F#xAK0D?h$15qQ?>@;D+vDcSjHY=(+Rvy_8*ir@}jNrfcG)+`sX?=I`bT zGZUw^?GhgQy_-MZmpHTO--Kr;{y%|Qo0(IUCl5BiTN?2tqxb!5;*)ane+6o-{`Wxb z4{J;J{KOga_rC`-&n#ZDTW#B4^5^-3wV3{()vqTsJYWAh^IxELc7tRd2K!%|-2XdI zu5nE6lm4k3es%O;?`o9CpSyE4eT7uV9Mvt&q5WZ!0?JNHegBT#Eo+yQKOACRb}K-x zH-2>M%3w7!wN}e53X0OAL&}x=*U8i;r6GUT$h2G?yXK!%>-6)V2IhV@V!`9(9V7o< zfzNq9eSGJ}>$@mT9Kz+-d#4mrsR)P2S&gdXqXPmp_f~QL!9fmDWjyl5&D|JXqn!2Z zjTJ_APKxga+7_5$eWhFQF8Ye&yCKl6d>kD1V4j-BIB7Z|fx*^eG6g^7{30%0$JVai z{it!#Ofow9{9DP09b&+e>>t1Qp1%&N_f1a)8cW7m!>#pX4clv+SN`GSp0-e z#iS9{YDHeh)YtCdSsMli93fyvN~fyOYoaZt3r7 zO`qs;$H=cYh3=hH*#ZFV#E=H`LSwd@3H28Sb@Te?3qxAL&~5sN-{}6dXsus`1kALe zH|glg0t#~FHJ32MorjBbDpq8+vYWacwv`K<773fQ)! zGYl=fiB|I~x4sv_U#1qiA|zddwkwL|-da6PE;}Df68k8$9Hz9Wz($F!LI~2T0B^;L zf{d#r?D;M07nY<4j0d|{2F>A@BwZxPw_ImxU;5eP(-n9EC(k->Dz(ruf8LBc_!~$R z+Wua-RXFMs`MuEU0qvGz6xZU)7A=Y5yju6cb}uB(0;Sz4t16lL#0+P@aZyeB^hqQ2 z4#70ie3Gg6-M;+cPO^PU_20!Sd%%QeRqLS zB+S$XK|}B6n4jR4?Vr_`nVR;^O?g?e^&aYxsY=sm&YxZBj;OL1c8MaS!RSp7M3bXN zXPA8Xc&$SAXZh@h6eyUgrM@`cCnuF@k?sRX?@sGgP%_a8W`&%R_`h?wqx(3Czm2-E zjJ93Qcxa5BCWebgo9p=iDf%+pDy73NhMJbduJMR*lhZVl&hb}`QSA3eZTdOWkOV~@ z^sd)C$}=(hd4tqeFyro;eL>ZA#Hrjiyp~vCWcpx2O2R)7OQJ$dm`3_8ljVG5&NgVW$gnVXtDreZIAN~iB_jol4{psm3?xc`oRSjw1vh=K~J`Ggdn5vy;qc@d$ zT}Tp6%9I00>aPY5{G4DrV#vuQYC`&azF1>ev+`O071Jo6EKB0@6K34R<9&;8g)YTj z)A5>unEGPc45p7s)gmSDX;B`~BYJP`z`D$i;^Z(5%n04AeB?pxK315}8lQUf6coMY+Y>v2>y-Mz48!oCqAjw0 zgwT?i?b!L+ToL?q?z$~@X0C<%OsSjw6y3zWVR~V1j%go2SM#4a+{0@j%KVENrnMAe zxWszurldc^c@m~}COE)GM|(%XNEzDj60o}JyIBC0lz}@sRO1_(6qP=qZ zSx?$7r;;NP+#D7)RsQXqlb#tRSBKt{jth7kv$qnrGyI#z9e&xJC)#i3B$Ge!&1F}XXBwPLI-3>!z?jGB$TLV&?AsXWqo$dIIk|!- z6K&&o+O`XY2z4oKUC*UmR%Nsw(V6d}G%Vu-FeWfahCAL#8-!p4OD;~dUF9#BshxEF z7;~ADcIoei!0x`C#vwI@ejinSMvfx6xSbA4(loKIAI%{MODue#@TVfWD;iV z%+gU5JmQ~a|E>DegML@)I`}Z>A`$}RVhP8=%f5V+rdZVhiJENhaHmNEPoytC_zlNOZ=N?;_Q@}GJo3@_PjH6f<-GXGPr)>`iQF|u2#B#WjiztW`^ zp4+DrnK+#W(m2?5D@ytRwb&g-x~zyzg?Kl$z=0>P()80%={&pF!l0p9$OkKHkfW)L z6vjlB>hhU5?TisRx0;*g(2${Ru|vv=B6?Gg%%($$YhN~jBs!*97{^uGhz-q(72tn1{}vQbR&7`aBsNm$+JWJ&$a$&ZRfMdNpVb%aqdz z*fxP} z0WOD0`?4thSyoK6anWnazpf}m_44p5{eZ`zhKT`@q|N1U$WS1r9da6l(yX}PO^nS1 z#bMTZ>?{>gV+t(cJ_*^CUK$a`Gh!KP48vBt;a_~n{}+^&Q9KQ1Zx!qJB1fS-hegCV zxFz1wD0=h&HE|EFQEl7 z^_5b^?@~6ZmpmXQQiQvgJpoBPbc&Qui0Io!(q2C<_KmQ2!PFpk+InhiK<+yExr8!y z);hH$8=(rw9fZ>{+3Q>sjmwcwNOh%qU}%*xH6a*_Ox!SEQMURtlT<^ed=OCIMnPXi zK|wbuLxPeQV)C&W6ix&#JC^23hxK2>1MC$cepJLz|H7#bh=YFv+OEnq%0gnZm~<$E z`hy3}3#bD^-&^C=h!_1Ko%~XO0oZ4kset!72o+34&0&iFBeve)QH)zHDtN=X)*ac! zsrs;t2u7x|%Y5CTpn<$WadjV1zpoC5XY%ET0C$OoN!G@9b$l66d+daDSv)+Cn8*U; zlwpHcaafhK5uryi-vDUVZpAzUT6|LN@TN%0-&807_J;Fl5;T|2j6DnYv5ywK3?X~N z6&`-+QPhV_a)(giXSuVuvDG=yAs7S2rkc1>}d!>i1h@ zl<5bk!o7zl+JomKadpP0L%6;MI6kn^Z{lTz&2n z3%b7V%q|lyW1QT>ZD^CAD8d}tl#c$<=WltrHnHU z|G7mOWKsN0U~R{yO%Kp`Zqqkql-pPkemLtZgWVGe%EBn_0@)#)TDx$Qvsl+08r8+d zpoN#;5AOb8Xzg4R67jk!{et^Hv3pjwnxYuc=a9PSBzK|O7ywCxcCXe@2IbB--`sF) z5xeSX+U528C@l0$h^)owqmwUJd=c>erm6jlBRynqIU%rs1E+v!$O$q@NiF7A9l zG5;v)W|ZtFL2FG&ZQ2t^$W%!Y1(3TzEfMJv4JhGxtxiXT zJIp2&1NZ4*?S_S>G(WdCHt;a+TFV>+Ff?L?c2f+f<2I#xuCAA<_kz2=UzoIPXm@i8 zKb;YH+(7oCiFuZ?P5Bn%B{t+NYNtdfvwdM#=4IyAT)pdoHx$l37smIo47C`Kl-YUZ z<&HMnVXFz){x2klPb!e703F%EAVtd5M@X`R@QCdi>TBkDKNI*ldz}Z3w44jx z`doPK7qph8&J$|MJHyMeVDHt`v4KaZ$V68(k9e~C}>$CC5V7!Dwjr>zr zyb!)Fhm^}Q34D11LEF{>#bW05?t$}9Qs58#i-KR}L3Z#ZlWtiNfamC%O0WbDXt>1+ zwUF^|l2nNdBydq<**zEwe#&p?L@4al*?@27+m%@HqqVg@0SY<*l6XaW%no9rlQFjw zCLN?>P3fqamz%rP1EpL?{qFNZm1m^J>z&6Alxzd~K!C#PMh&Bn&36E2zwW4B0o*s6l` zNA9RC9N0+$!hDsd8{e3-oYJA8|F9a30F{AN0@;^c7b9~CA|$N4Etj2 z@4uf{1jVB$3k2Sl&v8^lnW2PsfSn9>_XHt87eF{7!Sm#$Vp3%Eone)Y$K8+5>+Dk^!!Bd#x z33~~U|81iBot8eRUD$sz^xPpCme}yy=j=jsiT>n=!mpup48*x~$sAVZatyfYxdNKo z58C_wyV%CKsEZ?Rd`u7n)35{u!I6p$BN7*k2Okr{!fxC&hAqb0N&pS+HE87lP2O^9Vi39J;msMY!E6u$WX7AKR0W5=zP_bjYJ6Z76MK3UeCx;vXV+Lb7flw= z)_#=Zp7@4NtIX{Ej^&`;Sg_%9jC~Q@eE5$Hty{bI?ljZfar#&5*C9Q|yY^H#VJF&- zfy59Z*GcpK;(-X@w9*vU*1qk}~yR2V_WL^z)jEv*bawP~+o$`7f) z^gA~Hj=OmL)Jm=IRf|8Tr7x|#C&?;tzrBV}eO=Wg11CivPrdr*=*bP=JdDaxIYeH) zR7d_9x{$oxL;A{Jvx7WHfIO%NF7nsg4`s?l2Fmv~%O=QQ$sjPe z!_~I1>bTrWgS5=63D0ZrKKiEueR&GfC!Qzco*w&Dy}ztOHh_|t5UZBdpLqVMS*LoR z+U})WyqDvlcVmr!U4o1jzb-kmXSjODTJMw5 zWpVYlVk>q%c8EK(4^eNcQ*n;*HAf9@$JZ8lJAUp{UaLAv@wDe$cr?%mop;V;&F_5rG zPCMT4F6ZH~of|%Lf&T#u|LSa3 zJavmLL_)oWWAeyfIqN5Vq8p^&U%&kN{-G$9Bzk%#;58kvYUddro`+PM<9cKlr?M`I zjnYfhiF$fQvFp=z(4}jdE?gZ?{WDKYo_XAZZ#m?e zZEeu$x|NyYMbXI-pvW%Dkyz!eU0~PR#i7i1E`KNcs1&KQ{7A0*2?>#b;0vWrXUqC?UiE3denua4C-iDk4rw|WbCqHcDMPp8_7q+)b20Phz8 z&~Nyt`utD=%XNu<>V<3PLT2^3or@SIv5q`jv`qHcBIJX9H2)$J{mvOkBAGc>)35g}32|FP^2 zGvop9cS+BzyDm?4ZM!#Td69Wxy)&%Gl|fBp>}b-?BF4?ISW#%>SlF;Ce|3}zX8aM^ zdVtXX-F2EAy~@3l*uTp4G)2$zCg$T47|1d4SdRf+ma|=J z3fDYFR0sw;A&T=3$#{zOWc z%K&kBa@-55fD7t)veF@ke%?c+T6V@t=lTB8{VV1&SHAdEweJYz`fn_w$Qfs`@0Y>4 zauo6Hom+Xh++@c%yc_o&&QEXl2b<8hKMJuPj+*rG~(E4JP%Mp?%S@&>?j=5X&zmlhZDPj~| z1fNp4>1MV!r!-PVr#PLbdnlnC?`B=A!Zkj&^Y~Up;DflZcjJ`CCxVYneQ?1JK3a2T z;b@ZoxstJHZ>tq0A6*yID)(9IvzsP8w4VNe1|8gKsCKlb)J2}?{8xyH&4pA&Y@VH{ z-NmRo^UIb|(iTFr>O+}MS9%KE+?ufmT@JZ?3x;-Y=N~|YwVU4#E==w6&=}0YSyu&X zZ2cRhAzP_kxzu~3x|k5pnA6?RmZ-4?sS=vfaaC(#-@m>R8Q?#kTUA{8AuZR_ zm;)uY%)3-7^jaS60HyFUG@qvRDXYA3c+nfBStZvs8S)$2>+eN}&gx}85P<-lzY-@A z%B*KQXvq(2ZDzdqHgck6O<1GKpybrb>xtg!Dgdyq726j0koKVKf#O+DAC=Vdo+y=@ z+kTWCWuv=qe?Pp6J`J$Yc$A#MX*a4%%6X;<2-6A|4-=nrrE0)&}ltJx3`*ew>@M0vue9_2gL_W??wF9Np+^W2tGn~g}j%w{C zYl)|{i}sX0RCCfCwtf{+ur;Dq`mDbUVJ{YEc1RwD#MNT7=S65gMQ>S7iTFY}DEqglgBsGMr(vG-RZHWbPGJ5K7`N#xlZ+?uK$EmJC0>d*w zH4=#OP7TXexKT@I&WW#Rn*Wf|naj=zzumg~0^KDLllt$WK~FuM;;z8UF0#sB(2%WwE7Np> z{;c5m9cg14K_YgmxHiW$H3ytjKv6WJ7 zi-A@v`KQJ3sdN=G)_dpi|E3LNk;gR_})7K&3V^U1D_n^KPAqVgz zuMV|$b87JbE`otwNyi-MLR*WDBA*;YJfa8>?bvfLq*Z4LdF&Nf?R^Q-kf=;6og9}! z{l;?-_zBGjGCJ9$MmE7&j54RA^o8Iv{T#e_4~2IK5sQA}vyUpvXZ*-@YXrQw>-xl$ zPa>)mfXa;E837gX^#+9GdNvBj$d%m=Rs4tA*;G+y`csNk*P>RnDU-Y z<@V*Ff@8bnC|ztBQxTvp$hB(3qkc?(CnweJ&^$IIK?)0*K>VPLj+i}W$w`_(uD%-Fm;md-VKv%1i;lv zUUDK}2IwSY9VcspO`WJJmRBFZ6A#+ZrD4>50V0i{4L%=F>OGRVPoEhkXU-@=mdnNg zdt-S+*)b}TjT+#Rn|Wvq=eSpx^-@bZD%2X8xvK=ohvXD-y5)%UGDLj>O$}#Y^C5%$8z*%Hd z_&C%L8ZtiE3sY);$0Cz@RSe>4prW-LK5h&%goM))Vq>picNpA+NAnoE&j4~gL$~%f zG{~|#DQ(_Y&cTp?Qv(TbiHbhb7VRjh`q2WSVQr*x*a|Cjahz>*t3L0kT*G2Yj8nT8 zAP2y6e-x?ZLVW&Ygd!`H&5OzA=vFawUozdL40kErznV{6Cju@j^U>{vh?j8VI`Q&x z{^y~C<`N>0rc2`Eh#agF-^3NCWm!TIBhBd(6HkI9$mK z=ocyta4CaK%0oJ-mMv2a5DdhCqJRfFrs|qta$(}4m5I?C*yuGhCn|leppO%yD_{~* z%DlkYg2deVk?5o#cC6vF?Nd+&NTE+1d3MvZ(aPkbyVAUb8uxo;iS#paVJ&ARdw9Ms zs|5>%=TKk&BzMCUR|c@Yyy~kGsq-d2f% z+U|0YB1R?AZJXS-oNR2+yk)P!K)w!1R!Nj8fz^^QZ&GB3N~G+?#MTJFYME*qF1|Dv zjxmv+6RtWQ18M@mu3qwy8fsQ8RGt$xU;{sAQkuCa3Oh$K1h|N|AqT$?!&l7N0TDbz z?xRcrAq&6>yalC~P3vNzaf~eR;-T5Sid!4tt&1x)nLwnN6zLG~1CH5%xq?m;NCgOD z!nm~8fhL%;graG^s=QHAwcB}> zfEW=TF)Rngh=@xapS_HBt3)-b_A?12QK2LOq%oUNiSeI8mAc#@;vWcXHv7+DQHmJ5_bp1fES&+!X+yzLjNQ*D9r>Dg;V>0?M$6I!mYioP`i5 zcxW~T-Aj&O0Fx?w9dT81P1YP6`n4YZOqX@FLSgb{s*`c^>Q6a{zo-C+HNG?@=R4*{kuO(}42ckxBTqtJCW zfjI|>LJfcC;DvM)nvJQfM@F1o-mr~fzT5XUTZ+GuJhRps5)zkeX%F-l(|xsNW}Y}hor2#t4k>~7C`X0->Pqq?^oEI!9D zVCX)br2uAdpA1Dgjn>PS!823cEAmBkmPgg)^NNalAT;B!MO@hqIW8#L-|qnctaPp zmUwa!;I*mF>$^U%13;{SiARutDbo@q0+XC!4d$Tx+lb8$INigFv1Y7eM({jKwDaW= zC^1yEe=WrnrOE|J98i@HB1Wnb&oj=NU#*d&Ai&HwK2EB6L$rb4J=!=GZrHu>6xDc2 zlL6594AvEJjq)Y~KIrM5(zfDxx^w}RYX?^|lkAGAj}JqOLg&)-H^+Yf5CcHLpf>y; z&p^!}PsSjs29ydv{?Sl6@%DXnPC+yy|q_yeK= zE-gbzj9!gKz@@hUbNXW`0>#_!P$HXVg~GEppX$97sUxI>^^q(Di~;bj&p{~@um>>q zFj|iR!YqKIdVlWUFp;LT;BOn(?)Zxb{biXwlFh&ZpdO62g)ve(P7elX;*VGk4jYVh zW221$lv}|VrAC)9a|>7e1T(yXL}qMH+p~K0s2+e}NuU@OZi@s8=ruCUINYiL#7eCF_9y-jmwYBGCwmePcAb?v-viRc!($3cvXQUp!b?TNW^PWk^nd#%O;H7NF(C;F&Yu zalxQI-xnRcoH+AUDx!RpFbCFr>#X{QfFGHnk5Wz$%tnWCB?D4T>?#1YtY`*bQxugb zw}0^*I`Z^@?x-Aq2^C`So4?8wjoLxr^ro*?5XS!Musy;Btdq&X=Lf|somD?DiJ}0@ zRD`>GY{vTXF#YDR{N|Z&ALa&JF#f<#Rdey0qVMG4`wH3KDlA|XjEz|i6Cn)3Z_@t# z@cI60mn*2``V&WcjBxW<^ z{7?#Pn*N8P-J1uAXF}wjxwe-4hJawYx4eNg`>#itr22Rkjz&#eSWd{nE6Q)`C<`9_ zk2oB`Jn7AN5U3qg<$0|4fq$Oeart*CqDc1~In(-%@-?5HXR7H)#3~{2?qsRVJJ!o{ zMDKFHGU^i)#xt!Z^a}1h%MGLKyzX9AG;gF@F)KiKY4;+7C~M>t!sQCZUm|X6su70z ze1bQ&5!WsK;WDxcQdtbk3#+|Iu$rL(GlkFGx%p|b1-pTb3W|BID8pJN1UzMszOeEp zWIQM{6;e*_;-$?_UpggqvR;_E27PVQfWtXF<_}j{sW)SxNBA&1_0)b>t*378MC*+; zzhVk`?HQsZtMy&tL%IQZub=Jv>-Ncc2hlTcuikx4-J`RL{=Cu`VTYDVzh5&HFK2@I z%iAwZ_x{$9>*l8OB45R&pdGYHTFei z>jE+jbLov-zv+rEr4*?)*^GCU#e48O&Np-Qlddx>AWr`|3pvZW&Oq0%gw-sce^ZsV zYIKEjyF@eN)%L5iY;+TQj@?{aK(~0fcBAfeyvoK@?5njKN}GJs*ujny)ppiNiI2Y* zDqNJ;H>D%n=B&(<=QkbNuAQGs_Vn%Fu2J_>E9tS9-NrqyV_G)u`v7ezKBBon+=LC zS>^2zb7EcWt(a4rvmKDQ<^P{JyopRqM~DOSiOQSFi?QSNa9xH8{|NI2x{*{0L1){pIfZv`$kTZ$s5)9whe^_W! zv2b}ydlV)Mi^ffFzP7PB`jMs0R9{1CCB{8{?uE$J?eP5Hw^8TE4UXFHHks~(KDNbc zC(CH~HyL>tYe*dqB4sg~_?{&%{rRFnK|$MrpATZXUkO=N_H}I6u<`#ze{op)H*0Yp|LVv4Tq$KCu0yG@PRe(vQ2hGQGFn-hFgH%qTNaKAIw9NY z*XQb;&3>FeJ5g}D4>chEeae`_KC*~eT4)j8{Q8!fwQ$^C5;huxI+`F~mi+qu`mTVq zm=(wBYRb01ZAe(NsCD{_bcAp`?@s*vBdD2r>6evl&TgtL=iKEMwyX3$=2amlC8ct z^z~T0@RcKnmVQmjJKUH*;3-3TXv@)A=v7aA4LYw%DsHGQbaR~s#_(Zv`WH& zV!OiDF1<;2Iho8CL5I&wnYd*xNlP-;H$@ETGwuLKNy~Ik{CMJe<{$c)4&#X)UNx~{ zCWA=$i=J{@u{4X?bNKE7*!ADSEVOBY&#k$6zBxQYz1v#um~k7Ro6p=Z?4G~u0`J^M zy+Z!}bLvTdYrT~nau712{QQCl@UkvD&%E+^Ou<}Ao?T@n4Vf*nla_geG)w1_i*%(O zGUmbPrp2$!J+F*ePYg+V=_=j4(H=%^V0u_Cy7zjZSxu(L_(%bM;gWXqqP(v7`fZ8kL2q7i^}a6%490mCtEMzlo)1A>y;T#gpXZ!bfo!c znO~4UCb-<#Of;_Wk3G+#&hORJ&dN?g%7hYvi6m16agiqCgvLo zpWb26OrI@q{MtIY(rF-McaZICfiC3ymNi@8yeL@%IS(=K<{PJ1c5J&_+q&Rqc3K(P z*|R!P|5(9>Dpeg%33s=>!i3O1A3v zQNzHQB8=s~!c+>V8)m=xCrZ|CVoD0MJHQ^M%9TM91R(-Bql zd+_LMqvT~?JHI&XPwTXtGQ!+6dbzO8 zU2STTXoP8B?`OG`p?C-I9;k9FICf%GeR8mm`7N@jG$nsK{ah9@fmL*%qgJht``GIA zO#W76ZfrJ1Z`DHkvzRg{dymV`WZ59 z*=X&H!EA?-VvC)!(OM}_NcK{i+Pkl{TE{P+LpjuVNny`5*N+J+t0t9z%S;(eWQ?1= zKI||J!nw$3tGk8Fnsd*U9x_X5LhyRNL53NCv0W4`5QSEoZ|yFOd|K)zg2#iS6YuZJ(8QfQnhx!U_60_%eEETu)o4^rn=T^ZmAS@fEEk)@#+o;{QDS#vZSN*Q z>8y@V&c!m};t|iToNT+R;qnECGcJiwKXBy+uPyqUVT$|t$g<4>+SA~%@9hJh6=R8A zDZx zhSZ|EqR%c1$s|QwHnL}3dE?NJ>=#OCTCAj@z?Xj}fQZNHQ7-XqQ ztZ7KGmnC-k$9t+|RV+66*f9W(al2Tnr8VCyd#5PEB}zGvhPUmf#q2AsReOyf7RNW_ z*c^gNhkf=d?T7lY9fikHenqz^H8>jo__(nZS3Xb|&%FCa4^`81VrLr!ZgvB{tq3(q zjc5&7I4s|VFtyC~{M`FHHKrMzwg$hIBj1@QN4)Z1K2fW%p@FB`P0v0QZz1CkkC3z( z8(yrKOtWB9q1q)Mqb-q@=Zriz$P627`Ud8s^IhCgrniQ-8<)p+EHVb!4faow!B6#3 z-3?*E>oBQ#8#v?0puX4gR~h8x$2#N=i`%~jZA&+fE!MAVeI)Hqxy#%5){8#RIV$Hp zZ$eIS-*}xpW#}KA8{DyOYgfu+>xSEu1bVH~JngVfntIppKHW$eg72nh{BW`yDN}$^ zq%+=rasmXHU6J^--Lh9Y;R~yeNcm1{O7^A6T2f%5d$V~t!|_i$5qZR{P#{})Q+g$- zchk8Bk+O52Oly$zu{JUhM{A)Y_nFvcI{<`%IJ-3QaczCEe+rv$T1Y(FNAep^NG|^G z%zR7KG6gZnW7xbFkm6PwT%qmq(X;8~?MIIP>qHrq=ZF=s;%T}rk3lT8B$i8vO~~Uv zAD8U~DAGY04v;yhw0qQ~p)@CMpAXv22#x&zpTx#<*`AFY@8UH0H&3o{hS;#zWB{f9 zRzxZUHlg%%O9U>bBDKc7jf*)3g)9ReOEJ!kur%Y6%@5hjLn{F8$SNCEk|#8Rg$DTw zto%m{(BrcFrw#eC99TFB(BOiX_67aQpp;#Ji?p+pC?4d6te&J@T_^wMdc0JKrpba2 z%LYioPjS{xhTTpqW|(EOkry6h@!Twh?{$!i-z&n)JXzkn z4*4tKvjs?&4az6{2Vs=CdyzzpR1B`+roTCGmxu++LxgKo5T|SoK;aK8Z~?N4gzdV48BV>JUs7Z1qTs zCZ$1|(a5t2y*Q2fypPf)An6+t_QLqRaH*Rg-lm-%3nPdJ%jRGM*cfjy+FJ16tQZv; zkmG?07fu8}fx{j06>Q-(H_UPER0q%x)Aj!19)5%Ka8fUYr;ibvOzh~hu3gH#(Zr;ureD- z?vW5NNTXO23BKJ+rl2E_*S#sevv_$A2<#GO6S_jALS;-ZU&vKC&B1=bT@jneFIbn_;LR2K1Uwz23Itbs(@?{ZPIpo)9vLo+S9(kN zz@<*}sgpeFXFm0_Af-d9PqBf4^D@^vK;@emdl6)1&Lq92Q*;KXL62=-+@QXnPt3QV zYzBbYr#CReHDotxya~MY2+sWtZIm%bLSPx%m)F!$e*$VqS#W|yeQyA_@7uH`6I}GW z$t_-uE8)$~%G$Gvao(bngl1yQ6i+@XZuAF@G>eiAVOk=b4yv5>$ zs3}LMMi8k_HOP-TN*Q}PLech*Tk*6N1Z~LmAUq}9xu^oL1y@Xxuc3OW_WtnHlrq9Y z{BtgTu7N#r;q?iy1g_hA?u3j8M}8>(35M2xrjEeWVOFb|G3Di4;Vw3yCb;3OMkdr; zCQ5rRp(CLa+k#biz(EdKD4-zYUEetnQX1;x?LdKTy%HvZM~=qd_Kt*bpvQD%HE;)d8d)UO7ka+A%G2H9~Es^TY@Y^exv`{muU&O7~K&MD5=tPty1c0o$b4mCZ z1&moc1c!&Mv5<;x=F699^N9hCl-ImX(@bcU51j9e?5$C@itZSPgW951j|RNs)L}%dzi9t^5*T&Ad-N4&O-wd^hZH5y5^aFPw=e@WdwAnajM0+ zD9UQ3@h@jWbO?KNu!?eluoq=^f1Fn1flVSfe z8W={7EOmGEu6`!vjAM`ug;Fg5HU(Z=_f*BpLUen`jK&AenJOO;uZUUIeo6kBm|SQ< zIVb=$h4&g%k;GC2X#=9!0n&6phmBv4hQ11r{kp5YoL2$87rGflBS9-EZ;&*6Z})9m z6y0#G5T(SB8Ad*EpZs(%t&2%QGMNTIck$mx7p4Fb(+J?Ayf}6)3^KB6zw#fsEEm6q zj)}zsuLi-hlq=y+bWLg>Jl}%aPA5O4M`ki`&U6%t1Lj@2cZ+g0trgg}%upo>eEtCC zz(SjHKqcTkiH$OlA|LVnJ8JQhH$zS+HlWHYhFEWk3IHXbn(-bqxeTgUo*CH)uYFr9 zk4R#D0KyNHg#gF~WF!ERA8Wk=s?uSTd<4D}{<_yd20$|M#K8y160r5_@unF7dF~~A zL%yMiQ8nTv^1wWtyAp|>X5mYez%ordtKwSWQPy)O%8o?Ki*cZPDega?+y8=L& zu+dBgh~X9^tOj{M4u>)Jd=!EN*H`(UoHkg1qc`jgV9*PsPznhXdQk$jE7_jF+t=wA01ec z#8LSAR`|2sJ zQtTaf64U8|31y=pSYFBs4i!yJUd1?ZM}G{xbLQgHg#=XERT7PIUG))are`T3xZND~ zV8A$Y_{L6jnB>b9Duz~79M9HsXzVP@e_rEdTTI1-a;87Hz>hb5Gv74x#ARwd7PV{SnFeUU@($uoOP zL9zrBOou0zAOeI^_zBr^W;9lfMXC*Z@#UT)HKUqMia!x0XxK<1+2b+HhrVI*3qSu_+ zvN&eH93ce1SpbH~!yH}?``sT$E=PX$?b^uqnZa{bQg zY4$Ejz~+DL%VDyVGqS-&*SnGGH{JPm#3YD5B}JGHAG3Pb%+isWKpqAW6`sEM-4e-9 zxnxM@pu&VRKuvVc@l=oFdcRLewB)janwaetX&^dFVcGvd3shD|IUmpoO6rj8%FNa9 zT?+kus!m2OJ1E|=`~sFxD6ebeZ?6(E$vW#*p!t=M<^~ezzLkTZXTS-wu+t$9wN^MH z0ha$;n-em<{<`Nq#8`N~<;iurQ?h_30W*lYE5$jv9*+ow-47q^P+Ko}vcmmgOr_nR zE{>#OnY=!nFT}udOU7K$up6F|yCPMyg3`ny8>{S_bez%3OjYzR%GNk&bSrgI8okTx zOhseXF*&<;J1f8i$#C1U@SK3Vle@;BopC*?`O-ayf3|jWr)HT)#`ODpsjq!0e^Y*F zt%+5yn+e-L|Fzg#E|s>y=GV`!sdv4HJkQ)+Yd(6eM0fW|;%GNv>Ti6R>6qAx<%ZX9VtGJb)}r3L zL!VjpUT*$^0w1i+c=aa7ki^wz_kI@TJJ|gD;mfKSW9v3~hrR?u*2UZmUAI}o=2j+w z0K78ZCOW6K;ov)d20{x?+OJI4Z(bi&^Pc~ zykVEtiJx!3jZCe5H(BX>(J} z$*=dqMlaz-QbhMAD&(zN1(iY zp4yF}$`N{$f}E2+810z72AxZ--|BzH|K`Pk?B!cDYK<7RH_|$?m*kA$Q-Sq3O3;@5 zH<1w{4$Z|ZQYK84`l510o`FQ!m)(w;e`8~{QoTtkx(m)(Umfk_)oF6&w-3FD?Kr*c zi#`fKx5rktB71thIJI?q@9`7<6CMD~ zvy4-mkyp7QKRTd#DFxtaH6B5&i|t8OrxQE;CTPcK4Z3L ztYe?CD>Qb=GL|f*jHpzqK_n@oR79Dv??zNYHI}4(l%!IPB_zw(O8Z!fq#Be|GWYr4 z`{Len?!E85nK{of&-s17-_Hlu&X^U4_FBnClyd0w0r+d@r{@kmH!NcOF4!-#TP#q5 z@Ewyb-eWS8ao*s*IeBttBxlgWqb^@|d>!wvlLjgEh&Qu=Op+m!X)?t4EEU5kg@ zNLKG~p?gI z4E#=<@Ahc+Nyg}1xPI1KFTc1xgI?}anW@9BUA*mT*%8oZ2p>|{2T}w5d+cXx5BFGZ z)s+qUSiLDm6gYb7K8hV+{T=sp{O!}!*RrH>!rZbAxRXOWY9v4BpInk~O7+`@3K(E| z>jujaZu*vAFRL}ZgejxBZCL%msz}|ljb_8q>ieaB_j<*8U@bS;_F*l3yfmErH?H}ds_X02 zrZQyWw9x&)+38nfhtqosaSx&O5LE2lG{MBo|4YG}jJ$VkbIA{+SI5a~Wa8{7ga~(C zJ(+avs)IZ{drzol?ct32$d6Vp{*5R6;A0%wUIl8)x>~;k5KhNjad%sbLVDnaNLhee zN>b+rCsJ{jMD{z59NC4Q>&Sm`G<#e6Z5W(I!sW=@g=j`dvY_> z#%IZK-K|<5IB0WtXpZlm5OUm~3^fr5V}^-oA0W<5Z?H+?lAoDOD$?WXwd~}3G8>Gt ztzN^(F>Q#*iIk2tR-f~a#+}mqg8gVe0%L3%7}w~tOHVpjD7O*mR}jAFNn9?}cRB|% z$J}3Ux6qIm>*b@p(P6@E1wX5KCPd{Pm}h#N?iymJtMLu=Ttm1|PORUc`Pr*ub#MQp zq{MOcQP6XB7o8MSGOj)56~^Ywwt7kY3NqY>T~cj`*~KYagc-TIG^(Mu(s=r_IaDP;t&*APfxyML5rMQ^BGJu`X z7>jgkfi)E}4+bxYI;hKj`dC#qnWj@~5<PK3KW!w}VObby+9dV<&a=bczRF&SbA4@??(RZX)N}RkjQ|?gH z!5IsUuT#~l{HJ2FW<|*IcfGA}Lvg!&wJD;gjh*P+fEK`1n#YH#;>ugAkk}tCJyFzQmdhQw1 zE-aZXb8JqNr!rxx9Feo4XljM?FW;nWTyT9;*vE!8t#a1vjwLTXN`nnMalQHI<=MO_ zF$830r0Og;XW8uD`lxCowez(*)9bHYZ@H3(FY@MN<$*Eu$Ge<=#H~ zuOMvA-&cJNBA46)Gjf4{Uyt-I+*JvAykn>SJ{e~;R1M^z%VTNkV5c`(gxCgzp7=P@ z{xJ}Vb#=JZv$N=K*&k7~!w8I=FoMvU;uqU>!pPXOt%^a=s>$dfZRia1&OO5e_THmJ zqrY47J>lOZueQ?0%)D~3u3SW?9>PfGnTfIyb2VTH&PP_q>QYLUt)PMz1EkUp^?Y}< zVi|u*a8n<1&#-H9A^I=65S?f|q#$T)z^tJyYdxT{lwy2Mx%2Y39KMu--1oag$wiSi za|N$A&3OgoLX2#-gDz)AtY=@mB7a|-&ZxjGMYWroZq8|zTN{`xOau@rO>C6WqDXi- zf5AjS4?*O&I8V`hS1!AmpkDc_%UsCmn(jwt<^M7*80XQ~MGB8O9ug?ri|ekM|0%>c zbjRd{x49|=1@iFgKsdS95l#^;hGG&mF- zJ`9p3B_!nHi4_r~cM?Jeh(YsV;kGG^QP_nS=x(tu%nq#Vh%x=S!maaAgc#om5cTZ1 zMsaS_Kw1xja6$~*nwiFcA<9K6ucYK(dJ5*_N8&?Z8Z20}Koervd}46J+T5km^er;o zj96^a(M98DTI;7%b7tlKV{AnZ2{t+{%avn_MCs6Qv=pZbM(!$RxWn*;NiTK}z zjKYJ^LHT?H`?g?hKe!pT&9_;I_Z+~OKn!2t6v2F-e=~VV)?tVj!7noL2P|;;61<8Z z*uyWpB*Za{i>$7IoGnVktd-D7h$2GWW<|%c4e3*iqGZVnuohjgved=vAB``pMb$S}uz%}m{>V9Am znRhm~GV#xuXau7uQB~!S^z2u87&L=$WvdQ@cJW67ZoNGI4M=;%B=#_fMF7yb_1sp< zD!JD9@12J8_h0~s>5~ME0^|>tWazLzQ5`TM(H{Z%P@`Pyb15RY2=7Ol{E@p`<=~y) z&@XW|r~^yRge9|8tB-m^^pbDV^a+{3581zUkdG+(U8pLKJ3w(-1TP>fQdS*0sY-*N zlM;NDNV9x$jwLw307q!xRySfO6X>cfH|=*cv;+VAu$rS?oK!6L8w2zuxGg9m#E9Vc~qMB0pj3u zta~Lm@}xZGYW_#uz=bkGPWq`C!dvj&QOB`SV{2gO{6IR@`Su4k@#LSwN7+WJp zNxfo+=X{Eq>+XAtWV{s7#vw0=0^AW7ko~@cT+=mmltB^dv-edj&v@?&aI!icLs_-R zAby*tv@n#z)@dqBU}zBnl1@pb5Wt7@ot6+(N_@%sU!w=Yb6Og7P`-{kMPVqJSj)dd z5cF&=YBB(4;pQHIDELkO4hlX5-h_Nl#jONWJ7O{b6z{u^4Zew>Lw(Zogf0OjOP@)@ zcN?qC7vA#VnmVOJJCyA|5rVkUsvGMleGHruE5qt@AeMe@4X-k31^7iKO11o9B^}#9 zZ>cjIgCY65J3*q$JaN|$NkJbRl7tQbmFkpg9e(-qz?4-?47XtqF(ykU%usxqA(N19 zzPz3jibu%nuwZlzCg3P?TaNUbWRUORtlW%2mr=qMAnJ2Xz7k&}l7GYu#+OMi%T$ly z3avhHc2@r+GuCKpfB<`e%!PU*Qu3sG-OZomw{{>@_k=)582-I!Doj&^I&G^Ue@$Si zaOf|m&bdvQVsY70qFxw=S5zeXtl-O-#KZeG`yR1|wl3CeAQpbg3DC}?D=1w`QPwN? zJxTVyLoA|!9dGJn0HT${!+`h+39;b~abg|ONTx>Ymk@?Ud8ItU)as^b>=hICT^aZ& z@UJ{i@1mj6iA{r6zl8?yQ6#wqhGQbiAtARIxDACFU@knSdWgTK(VD1QN9mU!zW*sq zfuld^fU_$VVhqW(^TjvAFo$SJnZR+r5GDt0tN%^@iQ z!EME#gW)Bx96x#g3exuhn}%A(9|jr$!qr)o_c~!--62MIi2suPJhP1xM+v(NDQ-Cz zb~W)M4dao8&8GA^nIQhW46~|Gp%E>C@qW`LZ98n>Xc?CnH%@HzE`C#?(huNtxH;=z z0cQLdnRG9ThySIfaDDv95)DPJcs$!5i=_eAf5WwC`1cIbEQ9p)RsEU@1>^gK1|~+I z3)5ztA$x=UIpA@4c{#YpQFIgY)v~I6r73Z5pDV?eeQF&Uc{D*lp-Jy z+-<@sDDZvtM{C7q5Q?a;F3Gc3f(v*DeCwt8VAz`_kRm}^8v(mna+KjK5d81hB+`ln z=Wa@+0=#ccFy89_@J_i59D0++c3W_;6kPT>|C4#*ZnFIfHEp9~z|8>*B1adxe{Ygt zi)2uiN<$cMU@L;)H!T3XAWHFHA^9H6RfxItm+TnUckONYr0970W!@cc%`GJ~vrtW> z6p+yXtQe-kA69{I-!%A20j$0ri0(dXO@-R|=wx=Zw*h#Cz00g_6?={4UkC7~==z;< z;DP)goev-d0D=!_vPKZi!X^0f0^4c#OAu6Z#5SlGLN%v6rT zPl`Mr@mYreVPp6x&1JGC3E6Q1qALP+{Qp||yO^jDCTg1$nU&hQKW~HB0hCoN73|Zc6;7TqRv@kQZGMr6z>QK^Ji;Bxm?sk&jdmy@%pw z6bHVU26}_j>j0E7bm|8l7_2+44;ErzY6RSZn%1 zFOnwsl+^|pbCJ)!efjilCVp2+!p-u5PxfXNUxWS<)0VT9V;OU^AI-&Ix|}9`81ObT zP)SDq?k$-K-1&Whbbl57EVvSc-}<<_tlEC1=J)Hs3O?%7&6y2iq#g^jTm|}oGsXfy zQ~KXE9(@5^e($Tec?uo#vTnAw6?fx#Hwc&r@JR-FEmW zaef6@HxS=oq&aW~zFzxh*G;530N>X)tS9{@%|}Kj{iF(kRUig6`Tz&xm%qN-_bm13 z&i5x}WMkIk2L6wVUL<|v2SacgRS3lx@R`J)GR`KIDfuHw#8+Zp>LrPxvnCjr!u=q< zauKzSg$g?eUhVtybw-G1A`D&H3Bi=kb)d``{GBK*totitz(u6#CmX?aGRd5ZFSt$g zXXxu6cwK94Ie4sJei1Afj)t*&0B!K|#hb`aTAu}G;A>y-u-5X$g!%syLNw}{PSjj} zJ{t|OvCFiUTaQAMfD|<=2Ak{t>&>vkJM>;m^JwLb7(F_4Zd;hp1L z-JhXw*%L=k=j&amuI{Q@Sw`A7XTf7#-F!oSM&c%@xVBSsyHGHC5lv<;Z_bhro9I8a zzVN~g`8^%ZAj%@{Y1zGCq{8ukW^K^EM^4F(8*t^6{`%7fKFij;T;zW_f*i#!Z?=to1`ExgP1jCh7F zISHbkb+I+kIOC^u6`BMl@vwsT5ncCiKfLY8ygO~?30fj?AO7% z$T=+g=_zbchO+S>_`yNJPhr{X<-dn)hvW_naLr|(~fiWj~C z+@61}i<^?<+Px1(J~Pq^x@s)AcLf?KcdG0TX|PcCt^Ze2vGMR@+{1C5KvCLCpMWXl zZOf|qMcxis>3c6{SuzDgWv@(GQ8G0vzU=69{Db}a_s1sA>>sMg(7M%^PbuAo$<8=X z|DndWJLzpjnIK-$zGKZ{Gqw&{i`0-cluq5Iubj)H9DduNsYa;%Gq<$VIh@p&+%9~=jEegACg|4 zKu8{LkBJ-3A%6S%I`5Y8ur?xGAh=TUy=$&7?3Z{@e$JOLl8lZ0XP5`r|y=lnVau zImQ2%%47flz-yrU|FN?O&h+Xy<5;#hQ)(67edgbqhPnz7t9*H1@`P8Rw+nK1sR$8q z%FtiN!6|z9&~Eddms%gTVZ444g?$(A-Wh%I@kz0}2DPjH%HU;|qx+u@A6k9*z)cIc z_PQERUztr<={heyjkyB%*e}J?uV&NjsISwgs1jyKo89~FXY;D{Ny8_X=M6|#T~5kC znR-}b-FSzOEyJ~DR{Lp0XX9(7_E>rEwX%hoI^D~8YAKMO5dQc33$xwL$^Q^G;+q?I zn@=o1Y{+9jNcyVrU14hc1JK!7@lnMqXecr)(hmW~|Dy3^28W*htBs!a7( zctPccs!dP7TJI3tN^Y&zewfAAm^dl>@o~rAmc}_5Ktci3$8RSH9>sT6x)Zd_=L%>i zmO?YsB9>a)l^h^&4|!{@%Px%*c5~2)|D6SE)eL=N*trKAKxDli$=DdWIQolh3j0($ z?$Ys(xt{TSPqiPT534|cYSiwX&L<>vjJm987DZGcAVp}MOjfeuW!?hW=LT`lb5jF@ z2@T&N;3skQM`}$8bMft9dw%REJ1$I?DtuFdb+`66qhXk^U^kU~sNklag zCW)x>m+(4HA)o487s8)zx^5Dz?CxVJ_DSh+ey5kw=iEMKJbf3jr_8hfsW~|%R~i-C zWpHm1PGA^~x#BIo&7j|gJBJG0FokgLHR!XZxE90BExcVWX%u%kceY!Bj5fx6x7DxT zke=dKJt8IP<#gQMst4iMXWLcrZOJ;lHh1uPRg&b8{i*NaxyF~c)#799A&$!Jy< zAw9m*az8u!{&Qz*N8LPTf5UI86Q31S=YLGgR&*2o*b%*Qf%hl*1iXk49VQN17O59(#6 zp!SW~x#$@b?{l5QR`)sE7+Ae^{#EVoI=bHSrvOV(9sM^%%Sz_oFn_)+f}l@(c7e{(he&7cR*=(@l?o-P#;J9LEwB{j z9#)5gbhH3%FXe%W63&l`g7~Ob)#vOtS`NY2c@h(a3r0^3uyq+ddkxNL>Y9Ex3^P&xRgelreYmskWl`_&?d>g`z(XVTes=3`Nm`+nNDk_^YW@xl%5>+I4=iq@)tvkdc5)P3$tM=ww1y?m%p>YDoFa7e zE(EuoN(?*W%^8zh6%i6zZIH}L4<>}N_PCu=mQVfx_d1F5xg4I_b$n=C`)}vPe{%Ad z*?~i{pS+&qR1_r>Xx=5wKSEQ!-7+`yS&F3?l$nC{}FjQjx`%CH{YRA zM-YWgb;O$*q0~uxv`x1kDW)lOd$dItwJ)L_w~6H(Glp@ftRsW~p(+&|dH3~G=U2z@ zPBke;Pdxd?BIh8N1OEp^n(j`pi8ymo>F4CMyN}@#9ez# za(<97aoDPA5O5bE(qy@#+InGGnRXP{(9udWc!fuF3x#wn_Kem~HaqWyH&`{4qVezk zXBQhTX7>b=`WP%`M%3kmMIruM(>R#fg6B#PYfWtqIX+1*i0iC6G}nk(T^h5UJrbf= zG=kV3qmJ>Qv#)Q=bt`@^T7~=RLgBObPfWE?B5JSPERDV8DEFrTt<&c5?9q)_qCC$w z@vzIIMOCvXO3p5+!~=0Od;}tUBqhgU_<%|a z1pRs+Lpt&nA#*;Pber$>Q1mL1e30l(|9i7?#@1Y_}9vkPesYYK1jrIK1tT zjQKAPT%5OkFq*d`M_1$Fw|4v9(NMvHtMWy0s*XYZZkD0@7ToM-cIrLiA#v#8ZhfzR zFS1~J5lp!TL0Y4sQqKK79MxAsi`5pZ{g3dg)Zd6atUsO4JMg1MeX-$~%~g6Hr#$7V z_2;!F-#%dnma1UATRQPx(=P48y_<`FKi8kX%#T{R;Q$jvxBMOp}2IQ_f~<^M$)<%5trDe z2w_t0QybPC;y+St89|wK`AnN%+OP7E`=&k1g}8Sl&GEK0RWpJW_?TP`b8^n3J@`#t z2=G*!Df76je37rKrKtTf6PT*rfoLb_DqUoE8$m3O9gE3S*YOS3rIg&AVpru>xg?p% zCc24#$%my!aqU^l6r zRER4F0%u%Z?H z7icJ3YXAcQw`uTFfN;y5SjW|rS4#7v%GJ^EV`ttE9F8xFAxg}C5R9CakKkdqbGk9oRBIbnR|j$sT} zi18P}k7vRJfw1Y?{HaB<5)FKJG#yTXnF-MKBk3q}E9l^W?2mn#vHCBUydWX12UlEb zgdun^XjMTG@pS~)$6~@O+JB}078>@|9(3_1Y(AKkEwnuZV&2kE9im|}T`@6C%xHy? z6R-tZ5n!`m%50e26~1MBk*#c7k^Q!!fiM_~j*L)p!pxe;jppQLXfJUfx}Fn?0&Luu zivyIPQz$eVk(U4zs76b}zDOf3O_3ax@m-d3(DnELTP+&I=wCS{4M7J3=-nceKO410 zh;)UHdmx-70G#5Bkmf~mwII~yUMVO{;DV=vLH=H_Ocyjcv+)lj1wIO$^<%V;`=NiNrBLB zvdyc%3rS-Du|=oW zBqY&ST>8(sLL<4g;#PtecU;w_O3~9>snaw?UmjKQ*Wq1%5DhY5+XvthydrL$9{DSG zFQjLwfS6zWvZSjTBi;zTIX6T_+=iIqfA@oBIAFCPeu7E*0A8x<%K5}1c1m$30^s~r z4f|3=jZk5!c>gr0(R=P1diEk(3cn)36BI~ICF{;#a{nSMI2$QvB?00+ujd!SFu>Jj zwmO31PJo`Z)!@YDUFt{A6S?quA>kg4u=Jz$Bg>z6%NxVLU0NY8SsY>?B z9dpC?iWrFI=uUvJWk1$|drkE0t`;RdeYAk~mpmCjUZ+@Zgck&H@u^Hqvc#rOpx*qH zg^9i8AOTc`_Y(JO4hv`zJkf~QmrR`Bey4+L zk`FcV#bxInf(Gl#Lk1Mn6F~RZ<*oKt1nIB_IJ!o><&p^ZA}x}5nsT&1t0bxH5#F3TFym=OAQ3D7=3 zlUw%c8n~9B$TO#=#gMwTkt-6w?8|ZbwtELIJ;w79o#5RsK&a)BwOa#7?}f#4%EV?S z0w=sH+fjjPRwL9A`$M!P_Sj3JAIA898??nYiQRLI1!ji)cGKR2gwXXW7A}tQETSQ2INg8Yk zi3{Jq`)p2TxKf(ds*%5kZk0igeS)`b7)(P9#Bm9Y zLc;t1%q4+w+q+r~?|RM<#2kXY7#P|A48to&`K>`WSC)?#EC!RSbHQ?xb@CDzRs4Y7 zPn4@BBeJ5!@ST5c=6jiGw2d+@ss0lo{6L@*kUyS>Hp!?n`6KbfmcLZT^!|(gKS- z2}DWLi9JjI5!Rvsz{jCC&s_In5NLLt{6V0eL??nL{KZZ1i!yFl^N;hDr)|`mh<|N} zm@xujGcg|kzV96<=nt17;{Qo<`b#OL4q!QbP>BY=A|@_^H^yks=lC{_C2NjGbyR?` zCs9Kzb6t9A12TpzW~;380*7P#DQx&XF=0s3KPn`hS0c^KoBVB1=oJ&LhRf-*@9(*x z(Y!x6Gnmwp8~b(4T}uM26yo;~s6j)!9vXlnT;h=6q-sE2FB88~3}Cm7u>8Wl>yjgS z;ua(txL+eCOrvST#E(Ge2a*3nD88m${XIl@3?ML!*D*oah~Souex&D#4cVhDDLj)R z3*&*OFp}Wra|z**-+^zNsgHu&BC85ypk9ZJk3frIX_^i8V>u31C)LlCnb7dPTtc~2 zWfZ({9O{aAVkeS#mgr^&+3zp|Aw9Y3#;d#d_ytiuHzrTXhiuM7XJQ#6phgA z0M>#2E^mEjJ6i46D|wL1CHe_$q~q`IAijBw*w`w+E9~;~N3#UiO+>ZuA~v-YJQSpC_j*BOMZr${!Y z=2yE;IY?EeY0#51HN>nNWLUk6>R_{zUA|E~EN?D^qJ$?+@!nG%qwqc^ai1IM+|Ca} zqIa8{3HGB181n_R4`>>u2JHk#Y&3>A0G%}?ZQ~!`3jl1m7GLhA*x(~=&8C&015CW2 zN!ZPTX@g(*!B#EPCE>4`5FC*EI2g?})DeENU=p5QA~EZF7>{foF>nV&h)2)A<;Ogi zv7b&Blf$#AEkbxGO~>{lG*c;-u@D8xn11oz+lPr|U-1=e%qAiHK?tBOhJ|W&AcT8z zL&019poL7w{mf4T?<}&m{g;i!Fe1Yy?=}<*8ev%o(1q|&f{PQOteLAc*`|2bcaL}Z z!BX;ixGRdT5Pcr}fWNs;(c{tLeaFxFbyRC49Z+E+ZtjDtaDn5;U`Ei)2LOIo^3&cO zIJpswnI)U|fian+9=Y#Uc1_Yfu!==;)GENSzz`43f9J`X(!~PbGFce#T(q|=!wM=jtYV+X0BM^OR*k6C_yuOMcwM)-R=BG zr>DOaqHqcZZpC}9oJ!_l1!OPg@5}D&Q+k^Nz;}W-zmG2<*CzhHJaus_$^Tiq?#Qhw z&z`UN?EnLTKDd~Xm2}EZ$dspnquOM98XY?aIDdV zvo{rg5+017CAssnsK^$EY{Odbs{&+-2Yu!0xQXC{{k&N9(O#2|a#+VI7r?cCR?gvv zHZj}2Ytv?hY)M8kHFTXfZ|c6`MZ=3h^<4Q9kwqV(%C6q!8&m0Y6P<8EG}OB#?1caw zlvzb?6K^{ts8e?ALg=-rhX{;<{>(n7KypOv#Ul~T(Z+c$)%ShmBf3fMIv8& z&<=Hbdk&QT@|d?&ch|i0lXpGg(W;^+C(E}{S{5_-yfX$^YH;SZcGX5yVPU~BY|hO3%i5`8Lhrd)tG`+9KgcZ|bWS!z*IoS{)k&l*{|;Kn*x$F4-_ z$2WJNe{eAD-G!@_xarz??OUY)iYAeG5CHM7($hRr0F#zLOVw3WxHWeDii!;D@un1( zw~y5-Gv}-B{QSD^s>(JlOb(jzZv;~`nJ!kFxpYDWzlh=kl`W#m;lsl`^wRiF+9n_4 zWj~D+k&jy2mv&nZ&l{BGD(@1%Vn2JDAW2aI14{s$7@n%>Fp8wvWx=WZvfR&%oztpV zJ&TI^6aqq37UyAwOwNN!;@Y3sA*~F)mY_TpW?Lpg$^k{I4hV8_tE*L2tTpavx~ITr zX)e7ks>ehK=jg~19BLCci6(}Vd;~g}O)ar`WO=k-*>{^?1-i?j>U@gV+T~fLiYpmB zGN;@~!L=(qFPg3z)Q--w1qW`p(ar>HHL?}iz5aX~dPfH^)P}3(6D0Xk8DqCgqB+F%1uR0Em<>(XVqW+OHtn}5k{~*dPgmG-Xm*I zmTz)R4g&A}#*9&W-)l@SjE9CCn zk*~JAa`jrUI}OF7j%k-McC6qlzHCxHV{7TXmpmBQzzh1O-N4)=YwF#*xpm7KJhqypKJXsj04WZF0*!y8K^^nZ+M+baCs04{I}HQE(-m zU6mSW>h)gqUko~-0Us$CW;He?D@zwF50^>%Bk8YyFSL~|PX?8rm?W#Jy3(O|`wwv}?K z=$$(p#->PS;DWhbi|4`$|Ov^FUQW!9r2K&*Z4!#yju z##h3I%xT?GsXL!U`Dm{wuuzlTMkRDsD@3_wke{SIJnyE|HJ3rF59UnCM z5`50tF>=${*F%>*j$GaRD00ia*Tc8ck6aIP+`qj*O?0>Y$ju{<_V4=j`sEXJ!=_yt zQEh~>kzUmfyZlE{!qaZAy3>!=Uvm7~^R~1f_J8>8|5vX0|Ki8d0W*=DO~S&hS5Lw^ zmx+H>2qmj_KjOT*y_QjIxKU=|5>oBOzUY)N(^;r6*;58ZOAv1D`Bq_42Qpl-^ZMA6 zz2fB!tqaj*_c$MyEB?MbC}>JvQk(vA`TGh0L2S*|T;DL`3T)+?DlE>ZTJ9S>b7R=f zhuXZeA)^1!+362P8_TUWBv*U!A^H4NXWc80yz!)?gbjZbuStZ@TQeyp(=!qE`(!0Y z|9afius?$Sf_r=R^yuTHzvV{)*$oX}-`s^QAtZWZ;oHWV3HaL`k=>iq;Llt4#DLL(eNRrUTzII`&xUSq%ow``WUGw<@{(${Z#;|6aV)gO(B4A8V_% zVnqi}NDg%ewFSM%&8NST={!HDeze3}uh6a~lb-y8=Xo@;Dds62J7og`op6X$XC67` zZEW*8R)mFnkEAp9NmJWXiER&lkU>Z>Zryp)6aR2}l)a-2{ zLjKfed^A-kJlB0<&Nm~a&OMW6ZrYx%wsi<%%E_?YsN~9n06HYsZbz5%>CgK7U9|NH z`21|RCBdSX`$aK8R-AB?`MbUWbiV%2vY_}|%eBMFXoBQUANohG7+}M=t|nt6w{d38 zQF>ythb%<*uA1CAZ+20=x7U#;=@b(chX`QyAO=Q@Bt?(VGj)rwk?UOQ0&H0Ix-z%h zjOPvt8yaPaGPi?kzKP}wBL8$I@{@$WtNNV#t=J2_0n0P<+)Ayo>vgE$$LfHYk!z3j z@^WZbgMGd`-aGo@P>l}euUdvilrR`dqRfMP+xt=i}wQP167SQdO%Vn}EmKdmF~ zc2l_3D)ke(o%f-r@~N@j$|Z4z(>ERgVZ=%Z@e{WxbCcC>a#2RL&01$FNO5m<(-!%= zoMh9%1;?qgnV!`dKctj`11u!|jM#R;a>3x{6=5qaT{kmnag==S={Uwec{C6Ua8;Oa z)xO4b`(Bs)gF#iQ@8UcirV9&B%v5RrWmPyicz5|Nv}&il^>hk3Q*hYomg+@Oiouw& z(8|w19-H8uH8z2uWX42=_HRJca4YSgDGe9Q)S=E6cv&5mN6xmP&bFHGn5k4b8q>b% zPfc~QWZXLB3Wo9NQYRHI!oCn>II?gBhxp^_Zv^c&U3K~KUIo?_0d(VS{<23W&2ApQ zT#d0V=MjQ^l1Zi1G~=5MS;=c#6fc188bL@jqfv6G@fDyl#(!kf=0b}TwK@ZINF|&~ z;d5)OJpHoO`p1-=czV{zG2)@>s-P(ytmETC#O>3E>2fQY8BM{YxXy8nL5_zdV<0y& zwd#WYTSen*9clr~2yNq;z0Qqu1&N7OmK|b0ZHt&wJHB4EKf$Rn9MVhM^IOrD&Tml{ z^Bs8(pQ;eA+_aGu*al**LKPM3n_hVDQdB6dmY(BaVO<+= z)sijNdGT`Jif&xF;Pm@d>C2%R?H#-ft25>Vb{mx0M(756#GZ#3jxb`xq6-EDZzX8} zh2hv%rkKfRyP(aJ8Ax57*@vPnXcZB&-MywT?;yWbWxIm`=Dwx*!Q3>MR$?$M z=IXT^`#%Mkg_{R1uxj&!&zd5mTBE}&UO6AvpmbiK%AN+XPD33|>!2AVRSdNTAR>7p z?V$D|ZO&n$P&=MlDxURKGgFKMT^eN(ZYf{> z6g*homsbiz<*~1NPNz$0Mgf`mIhl8C*Kd&%-vIA=$m46QQ;a`zqPGAW3gScvt?wMq zHD`Ke!taD?PJ6}L1b*4QjiVzUm#Gl*QN(0Nz6LZoF2qCz%FJtV?bMl8Eo3v6an@D2 zQHnBWZ6QWu+o0?I3fI~djy+zhZv%mFGj~_heLJ5kw*`7wk3iXKcj)o`XD|+e^Q72v zgyv@>%)U-PwZo168ecdaHYMit-C`ZZG8rvZW7!;H-!W}v=^6lo23Kz4qOBKs3dkRq zlZ@co$x^-~Y13O^VyvTRbFAGwHMLMolV^*9#{5(B0YoV;Gt_x80t@w& z3yw%>0SPKzL}^_7$Dz*c-4F!b^6_Y1WO?YTX=%H4b-(_7;bqlP=K_ZKu*KbCU3H|U z$ElCuSgRnbzjE{yW@75Y!8PzgIlE*+Cx_4~CD48lzY5lsT7W;fiK2U!a67q2QnKl0 z>&O289B)?8rA_npFRdAYxTb4J}Hp_!{vU$60@PNRmUTO;1o z?1qP?Ifp0lbu_F83-(~tl{p1ET7zY57i5e@Pv}uE3p+x;nxNSD4GWfFxWa&ed(322 zFmR;;1L82=25#NVw_Q%AZ=T1MQp2~*=W$`w#W6gzH_K+Ap8U$VZv+yVpeZE~S+VMa z6cRn`-MLwL5r||R1E^4bDcvt(;JzBTM9EWYIJzH$5B2oZ8^%1!#H=Fz%7ew$MH1X` z7|xlULlgtPFY|+E;fH9E9#pwUHed&v;!7t@GRfEKz&~e{esjq0m>Uhl0lW-^VZ@ln zLc(4{0$w2zwNnL}p-L@vz!Sw6FtCKCdi z0M%q*!zH20?o*rrPB<-`3=ekwZR0g`j2tZux7!A#gg}D0XhgcPgTp#XE9N!hF7OQs zfzyvdG!ytGaZCkEm*5u^j58aK;Gd>K(WwN$3A`?EQfE`F;4v#M-!_4L@_{!;LKB^z z$|Tw^^0_&3=3!Uk*v&6N*qRg*?X05JS+FN6m`AMi4-g)WL%b+J2Q$!-ASNLUdmVud z`e7dN;6Guu{Yx4?}2?ph`TF2L&`njK8;H4LByJ$FVK`An&H@diHVG+ z)yyH>GBTcU1^?BVA!bW!KWcNgkiCzYjCkssM1t?Hlwp8fZIG9VrTyE*eSt%sW0OY2 zgomJ9G9O_A@%ccwmJoK-81^3?QCK4<0U{z{8Y0-tt4dS|TtycY7t1w>@gjk$A}TRLLLW0EbX7f#cX$D;`u|*}ejbFk9|o(gECfuyPur8cj)yZm4wz@ht$+ zAk!Znqx4@MDK82apk-Ho&Q1E zdj&Q1@Zr`wJt5i2rguo_ozOdk4%SdqRMb#Z#6rM^f)aX{P*gyL0D_1uC<1~dbX1hk z1S}X36nj8aY~<|!`(1oj=i;x4d7ORNfe!bfZaH7Eq6zFv;x2ZF zP}!F~Rz3bNyQ5;i{xv6PQ<&AyBV=tmk~0Koh;NJI00*JsAU7VDvdZ3PL;Z%E*$vG! z5k5Kq)Qi_#D?|ChBUk(+9cuYc>v#N*8C;n1ra@7=6g)m?o-(ld&1x;2yKv+(et_#f zKnK6S1$T~vub3b#@Vm(;zQvPI$>b8OqwC@XxEhw*9D78xX~HZ-uVF z>y`+qIVvU{4N)%SwU@qV4<3dMN^(5O73hx_G!k)r3R3}!kvY6zUZIp>5O}RmP6(tV zR251I?gbA6x-9$&3kA!X82t1ZY-}wPR}lsgucW9o3rQn%@G9YvlLIPfiD+?f&oC&;Enm#cw!o_BHUTwkrFm7O7&V9gnv=} zQW>er!XMLKKQ7rxZvJq%`sY=ndOK_Gtpt+icc}kfZXHpCyeDcKr@DFC9{ywf*D z{D(9_$Dl-r$Kv!1jazVi>+TnVe)z>DdZ3xI>SOph?VO zWj+uD*R!bGKQbs)I#tWqflGb%dACRgY~UK{DLS^}^;U)NH2brO&=0oZUn%T;aqlFI zkTTmASEWzEmNw3DjY1>@+d#*g` z#?v&g3zv2-sJs@+u3*yO!x;@IB*p@K_MNBdaKlgQxCIo(^TKr4L%K+5T>c4> zg!&XWEkX||OGIO!MLLgW2h78sOhUg931{=j=W5}ZvMA;FurSPOOnI1tBl2GcUWc5k zAC?F77yyA7xzr9rCC(RgC+8ywqgo#vFAb(@J zP0@oIa8t5Fy4(_iXyd!WR_OjTwIu*_U?L9u2>N1ZC_)15!f+Q*#v{1hgjuXee#HYvQNU(L^kYcnPNRj5=PMn=wnO7p~_CHOolA|)A#CD|UD z7vD(DBq^J4&?>?6eNyTtj-@FUPBH5wa%dJE0n6s7fLtq!3M5lE^F9fxwDht_60fug z(XIDen)gd$rQ|KPbRPqM-T7CVjL4L;=TN1C>PSU|5OW=%N|!IP4DXJjO*7tQR4SaD z={bL=syd@}1@R_}`Mm4m5u5cU-0D>deUf^nq4q@%9;8U9+$gQLHm3~&Zq`q5e!QL= z>9Jb>OTT~G?9CHOIEOo=XmE$icE zhEgAw`k@4u@TtWZBP{&uV#tt0J2-FAc|2xJ=0 ztQFXx+AVuqifYd{*|G(-je~XiLDwl-TfXHT@7Sly#R#g#h5&&cFUvh$L63?UO&dUU z-rV!?B{e0f)jq4xzdZ2Lg`~xHU!P;j6ID{UbBun+*X7H`xoOf;$Y-11S`@Z>_#~4L*(N=N{VVtgGcBH*}g7 zKQ_m3%5tb$Yd<+Uf6CDwz{O!A#gdLR)xQqI)T|?IzT^R9myh4`oOhaRJGH1(R5&A~ zzjB&%oTk$tW~5}d_i{5w#FOT|w{I~!Kg(g#5+;lqmLH{tES!nUOH~WIGG1#d_pK7= zmqo)HkiV`ar1_p~f)_~vEnWK5-E* z7G(a-LTm&wT%Z&yP#NoSCYBq4uTjkEj`RxOP?$uQc1T<9(-Fn>BrT=55+>74E$^(# zV)0OzJq+}AF4r$oi{|Z>Wpd;@C5V}N`avRIRzgd+b&lK`q3UCI9J6NE$;gPjtZswE zMli`{q?{^Q@bR!d^knbNH=3{6es+&yPaSTmDSz3dCwF3*yN@AFd*QX)SurmEz+Y|k zPwWfMckVn*7c6KpN#T=Agf+2gsg)oB=a4Ygn7rMJM7rZ+TVNo}Sg}-_VWPGBYZ_?^M@1BYszwtYYf zFO2mZIP%!<)W_(vhBI`Woz(O;9$Qguj?=5vZ!Cwre$?P`d|JZXURqqdwcDtrw+KMM1L_OuIYun~&(|1UYPv4Zk5_vVCQsGO7w*J#| zcKe@y3R}7nY_b(yNC>s%hIgg?IQd`fseY&irjK)Fuf4E~dn+U)>a#UmQchrucRUS+{g%Ke;CZH0YfD9u;n&~0S8r^1a^B{Iq@ueY z>a^XFHY;vSBPv-(&jY{D7PT{2f-e-(vxTcOyNA}G#@$|L1#NO)RQoyT`p^2ED0RRT z5KwLcBP1(St&Q@|R=ixUVO1LJ9^~3r<2Mts;eTtunxBj}uwOXM_%4kuGPj>8)!f@H z{4p3b#Dt-~DW%d=?%zLsU!Usjf}1WTlldG*P~OeQ7D#o^4d!aGzK=6&(v}PKbk6Ae zX`c8r4Y?baE)-D9phHBn)=wV#7ushXlut_feO?5OgnG_0KK=E4>Gu8aVW1?BY|BBQ zyo}}$I3+RVqQvjF5HMMJ(`EW3US>6YCH)YQ-o;%iFsx<2opjSvks$pvi4OkUT6s3D z&kfEVeQ;}HXBP9Dw`|`-%z3vyGvgz9L0uie1(DV;g(L{x`{ z`*KIY$xoh|CZR>Hj}ZCK2R7E7P10ApR2b$`xevlMUF( z62PYbEu)w!cw?{sx58azl%jV>tZ}bY29xfAirUwuCXV;D<8_dBjrJ-}P<;uQVcv;D z1?i?szHUp??M_Ex-B-B2Hl*b2ta!3%rmtMn} zqF}}W#l%(pPH#J$zUpRDLqmnmS_TD4qpUpAF*0zUO^Ql`SFR{+OSPcY`wqQP>)S)q zQ0(qgXk)wI|AQm$Xr&}_-yG=@qz|iEnENUrcSu+Sjo%DBUC1jkR?*HWpU>7m;-{qK zh5e`iPA(y)^*CQ=c(#TwHbCwRp<-PD_Qq-OD@y)%MzLbJcbL; zzJ8zTk9_D`UDQo^oxa|GIZszTv5~ZggmNpnyvDpVnS4B}M*Z&Ur|ahoTRWb3vN;!)ktHHMZM}}{_09pbclCRm&jyyK{|0wK z5j9QXG-_u`Mu$qR55cg{X}&S&wnW$L^cLs3y?br2YS(-kTU))49!Vxe^RzW)v-;L* zM^lD6we!DbU3aQm{px*ls`?jRrb9(+UjEb!4Ci@1KwDFcO)mDN_NZU5dr)1g0r9MAJq z>F2EqQP0FR=DCBG6Pl}E87U;s6TR03`#H=k6ddB%YHoI}btmQRNEwg`>1i9-nPr@p zM2%2=4`n*e#1`Nc4s=dY$78x1^Y!e?Lf1aca2!YuYY=HERQ0FnOc$rF8C%w*L;W%& zEjVG-rHb6VyXtS)y)P&3NK)1b2*Q-NW?Q2SyCyl?9bQU5KUxZ}x~)Dobyer0m42&C z_G4|YyXXI>?VRStWhBSuh9ri|X7IYM+y2;S0U$ihF*ey-HE0*(@y0{bt$&^_2^r> zXSuAYLf$aTBCaGqOyWL0j4t%CYgnM{ON>ZgdUE7i9F)5~GJQiW|KZu=w7lK>P^y!7 zoa3WLaF0o<5pa7|__vZv+h+|`Ciq#A)&D4dkcX5y^Qh;i9O6S0l+wM{SB&{{2eMVY z&e+hs>H830)?X#N@gz&>)}(v+>_ZVMii%$vPhy>>-!8KpU3;z1Tacn|70AZ$l52fF z#jcSVkQ3PVo*GszRUB0UXp~-yz(&W>?7x;5qp{WvLwCO!4(RA^ex3R9^zGnfEtSi^ zhV|tF(xCp~H-yPltq{eWke4Y_F6051FVdH$r;CH=%U<+~X`=7C@X=yAW*5uX>6&(p z;*N5)c#i<7M`d?EoENP!Fe3j7T$4i7V#^FoADD4nqjeaG@b_Rpf=+zesjkO11@Lr^ zOgvKQPGNdB)q)`7fRs6(g)!abyQiVO!KzHy{inC<&%&B;+0KG=y*lXknqL=|Fvn1# z@3nJ3FZnxcIy?fuVsJT_eH_{Q{GT>aRave|oe-Dls_#KNvL~iGvyh#pt<-`4=Nl+p z7>Ng#Po9Dw4ht}5EJG~SXFT%+YXKWCG_K%Ewa}H1DJqr72NUZ783+MaGTyg8=O z5=j4Wi+WKkl&~qyM+qSV=Yp8XQ{32wBjh=}u1Y?{ORiIt)Hz%85(G-RF?%vU0>+YH|cc%peZ~q|zarnHXutLBdaMG$5oF z6M+(CySM)LI0|-!sfsDR1_U%r8L+RC!WwRbaXz`&H zh~^OcxqIPey%?g_V5bk9NWgti4mn@lz4CSts zK!jp@==L{COd%9K5__TUl=S~BnImFwUQ{H3wv=KhAH?wR=a(Y_)EFgRdrIEh=lgD! z`%gnC*xz)MP$N*k$Jch1Ci{jP^jJV;_HqggcU~5ZwPTuLwn+@W6BU^#ocRV&KC#GC zfP4-c7&RzNS3a8(hLENrS$yL(0sekqvSv0^xEZqkvGYR|5XjaYjv#+#KvnWEI7fcX zDU*L+_GAb_6rkX@i&OAM!z4#`g}YCmi@5_+hp0ypF$KRUSAK22qf8bG?KSyj19#Mv zm`HG(I3}U0otNM7IT(`hhUnO%RTF?SizuLayk*(bmCuY${s-~F5LS%<0ZpEJ^y_?lt%3L?LzNA*!poPcj|xd^8ZiZYL6V*)I^3e~*I_sa;2RXOImvBdiThzJDR zEx;!X(tVcHc_Ge(2W)Ap_31c}nSKNtyPiP1SnsvN+zVo)um7-2F{2Z1ODw?7v#QA0 z|4fX`Y2sx*;dect#=GPR=NlNP8mv;pmWw{mfjAa%NI+6eCqA_VGkw6x_Xo6Y#QyZsFmh__#8N_=E}$NL}d{1XKudR=hJ~&mjknwKu}kLpuHR?enR%r{Mi9 z79w&1!j(o+zQW}(?gar;>TVwjDMA1$Hzxb{Q-;eQ1VQI)u9_o(K*+j@PpF`i2Kl77 z-zXz=()KxGp%sPw>nnf$g+!X`PCUt0B8ZM_rp zlV6VMXin8dsMBGWDQ$=kGUq728E4=K)Osn!aXN@Vg5GRkS3C-~Pfez=xfVw}6gLZ-Hk=f=F+S z74sRAgY$Rq#FSa_#h*VY!w~p{3s&#}%9SSFI=a_TkuiGx8V`!15u~`~jD*|%=Mns5 zAJ+*H2ZSIz1N~uBj!N9gvrH)b4e2RFG~fX>TTAIIT!zrgN4ki3`)*dC!6)hiOaM9N zV-**kd4#9?YAJ9BYMgzb&!)`R#O{wF*k< zyap%i&U48hgy0aD{Dp46BX`%GgJ9knCFMpi0)7^MsY#84i14{Vtcu0Qw$-Z!{7k1L z=I%mS=q$_U=t5Fo1e8}|Qq#lDb0T*MJ0>R9slbQN5ozsyjF1RWL&~m33%={6f)lL%f@N@QU@>C3eQ3njCj8Sd(t-4wA zhjMxIEuRmFRsjhp+I!5CV)UtH&If!d)TaF*RfzLywn8?RCMP?56Nf0T*iHky*oQtO zZbJHfKu7Bkxq4^c+%xAv{u4M)CYwzB=h&viMCZ%6F7Tu!Or!P2fjmN2jDrCR25iU}HQxODtuXo(j8^iwG61vhk26c=Vpeej3$ROA!; z0e-&UCdrfAS*Cc;5xW0|e7aEOW`yR;-xL|Hu%AUdBqU)Li{2?HhQH_(N*F_m9wY~t zUCzIEn4<5N-#fFV>M4RA3(e!$Z*N+)5^=GDMs5sJtkX?=bl9UxV^ zOK$cu^p={q<42x4gs6mwAf(Re-7NwXM_IR@=`zp*tRpwiZ{W9Fz7q08mKU+r&SJVG47fKF}FOyoW*sJ=xF{)wzGDR}@sLVz+5 zj&zkHjL#V|6~Qq&d67-de%r2?EWLl$$Mr2zn%-so3EhMwtVM5Sm^vBr5xK)$cU^=6 z4CZT}iX7hcIpR>MJj}^4 z{Xr4@(EuO`v&&B+)S<8HBG~#_K%@erDxW37Vq-d%!_mSW+El!7fFuj zC*S;HTP1-(aUsmxorL%oROt&iF+c$jT2$nr6^f!JLWK@#Xx^a4oPw1Q@eDksbsRNB z^O_#|KDKCR{jxg(;oyd_-T|<703_BacqPQp5wfChkocRI`H}|f+l8_vlRtT&A?8J- z%H>oQT7X>Pd*-xu#COqW^)5h)4TQTPjCe?R22*5Z0RVCvfN}a?7K#cWWa(dZ=}W4n zkl-Qm)mvku71=jV(4u(L+ij)+FD$l5A#@;=6NKK(gfm}gk{AHR0Kh}S_RuDC>}D=z zHw&dKMtD`uUoeO0W>6$T1+z|W*yF;NZtoL?&EuU2kcZqY{IgR6m%m`wC>J)D=TQKp zz3|VJg!1|ZMq7k9CzapkGH}Bw&rFQ{CQZOip8yxetaCkpp}`#wPD)4`|KC_AWx<*k z1HSS)Ycg~KiZD_HtcGJ6i>|dwHqXEO{2D|@*8`AZVV$NN^ma|TO;~t6btc!{my}@B zeT1vl887+p@9}Q7=)now3zki+4pt`G=%&(LdoO~FjFIH(UYYa4Nn>ei@ZnQ&GBag% znSGTzrb}INsC(L0n}4p@(nmcG9bfyP)E3UA>6P0X+>@n7eXS&juA~rd%^ROeCKmD_R-2=dxjN%aa%5IddQ$xT;jJWRi*r z$*O7c|DuvkKRPpg%1}o>C%X6HKn`C@O>g-ff+umd z+KKImaKW4HPTpXqj_ylDtTS;Ez3D%wM9U~D&JhTheKz&}DV~+r_TwOXi06q>Lz4@*Dgzc87OZl7@ z7yPdqcb*AuvyjyO4IYF;5*NiPS_Z4d>ga3T1x*!FTZ!!Y>a^SoM`z!EdFpH$@3+J4 zwukw)9==gAL66&y%tSfTmswkG!OmTq6&gGZLMmd@n6SH+MxZrIL@-);uP7>btTw?5 zy3PEWObXtpoQj3bk=I)uIrvI0q&6g48NGrhvZ}igTm?rXKr~dHbm%VU(VxWZ~ZDo+D#&v~d172_G69k77tH zuA$_`fYOJ!%fgOsiL#V*pZoKwoA@*QckxBU{*j)TlW2}aPxkWa}Dhi8zvuV zl&hD8nO#m3!z;8a=A%8-qhWZedv(rAvA}I(xbtQEX)m?ExbBr$VyaNAJhbe~tkCbYYM|$n3O$>4&8FCSnXXfR zN%SZm>Q35MqxxDY=g-w=zN^;BY*Cv4C?96B{MEb|l6ee$C7GnRlByDKg?Hc`<)Q6J3=7VZ1*_X!?hl`pnjSq(5~a{ZRg_DFZQG-N6h!>(QXb}IXh_fG zA87h|c3ct~gl0k+PuF_LN)dEH2@On#A1saWu(o5_I;5)$nhE028y;2FJ5{7rezgWSH2e@R-`jrm1Y9( zuj)sfwhs);DpDwKi(2I#aq+AP54{mS)|Qj*N*Z`bZCTECPn^!({?bFCN_b{f`tLF@ zp0!uHp5bwK543hqpF$Hi-Ow7*7UmUK&sG*}kW>vNp_ep+SgG#l=}P~7DYEDLz4Xvk z*&%DX)Z|8@Ll?BO8jZAM)>mV!9tD&f6KuGil>S8jKrCrD%TsM$bZ%)oE~NL_MObr( zmsr#_g0ah(%>15xYlDC0XQ;hVe)c!h>H3+?!}sSZNDjXIr6C>anr*?LV52-o}OQM!j4uYt_`jnYbuQe6?s?+B95% z0I!^UokC;@Hl4*T+@LH>Jc`BJUsq%HJEUzrg>{}`& z8>weE`EY$kTuH6-PNNpZ&JDYs6B_dzF0*1EuPMIa^uT$S<=M%B-987)$L{X3ZJB%$ zlX39;obztS@yVx0dk{|6zC#sBUC2D4fe!ZRq~FWcZpPJe1LXp)nXh0+{^2D^vfg)&Z^f2p?$DZBJJk zhKMyO6>M)`8G>nk7%e;pbAOS3+{do*^WA%D>UOPl&alka!ta}CjF50Q|Mgv{v`QAP zY3U)9o()LdI@u@@h(ynv%u~Vc(RKK)-Ve85-8QZJh=&;J%Z13BF zNvo)l`VD_to}6oq3%DdzqA%2NP5#%q@=ejK)3ZsCO2l1P=+WQtWXeq2mQ;GM{T}=K z>C+7*mx{|RDA}W#{rj-tljs*&d#LVBuZjm)pAuVLq-}>p2Gv>r>%vg9@Kg>j_T)r|d~9&9zrp4H z;j^YK;+~iXt)H}Xo4dL8D%MvVz7INl>{l3cj%s+g!R=3^{Mw9xU4N@?VUGzsq&J1a z(Y;L}vFUQo%l}Q5O(tDLlVyNl^O0+n&pcOB9lpK&P(rRrZK+o2stk+a!0;p1bv|k= zA+@s}C+z?L9^H+Z)Z&*PD@>a5bOOh>{XD#SSGfZ`xDI%Et}UIV=ZW0llHZGR8L5i} zZa?QoaJ|Y$CH)I-$r>Vej27EsmCXmyo57j9H&3W8-$&sE^IKERDHqvix7OL#q*vn; z|F$hxn>WVGro5?*zdMw{*w`vW6h<85!KF_nnQXm^M0j?TbZgxeBMCRYPPF4c z5$Ou7_ zUltuKxbb`ThMU_zlk4kUe~WOg0}FXOKY2jsxIH!7gNuS+cFLwZ9L~Z z=OS_LXc1%Hc?NNOoaHhL4)brQNG7okqA&{Uvu9FtU{H^d?bYk^p2mMdUOLt{=ItyE zr&L5$8EW0mUdz@}sI-3`zN-^^_#xa$*ms8ENXJ;$CzDSwy>$HImDjRo_vP#D$Mk;#Iq!rcmM%Z>0Ko5dklL?tv_AjfLf2t8!^Y|8;Lvztqq0 zo9$PxeE+K1f_RpyC)azN1*>7j7}{@Mc0i&>sPsU&{%;7Uk&gfa<2x`>o4V8c34k%Z z%k4}v&ci;OTHN35W?gt;Ej3R60a2p_zp*RrM8u}goUQIDAzaq?H@T8loXaR6xz9vi z!neYF_keq^rPiB$gCVONW~%DKpDgC=`R&_i^rPqc#9HHz9IRzlSgz|5ZLd)n`Y4c$ z^S+oCnj=VU_mWowmPLp6b5R;ARawdQNEr#In~It7(J!0Pe2^-mlP!}E(`-fWcvFl6 zsoYPXPSS*!7)Da`qwTWHn{;a5huUh zdhI%&oWIlll3e@*O51A{{-9}wUbG-pCC%E1Df12&Yo8VVLl5#49!e`0b?YCQ(b(d= zsM*KvwJx=!9^~pK{O09vcq@$+td+NKW%OEqYOAj}c3X8R3g`Giy7!V~s!OA|%XE&a zcxUPvDsFkX*C)9#H-L_%99z33a#V=bzsfl>`jU%?W6CZyO}E`hK!tpwk6cksk>=9h z-AjqiO+t5RwM4IS7;fZ-`v+5x72{mz-6=;+YRWHd^W(L$iQy*NN=F~&nuZVMvKSHS z-$LqLwMr-n!U%X%%}mq2OC>x;omM>6*I4RK0!C6~Q{ewvo#Ig7F7d(O@eW1XxxR9_ zSqsZoC@Q`R?-vQ~=rA_7Kx={f{(7o`(>RxvKkE0azJuRZpJA*;C?4&2Y!>20 z+`Mm>@@sCU!?WaqmvG5%k<;fiHBGi`e>1RqDy;m)(5YhrPl?J~Os}cWG~RIu?-CX7 zNe1W~XUo;-)yux|TTCG9Wj|_kJn9S5!DAiopt-^CJ}X;eu9_CwL!4m#Y7w#HU{3l& zQtYB>-Fat)$xcP2v9|5ZG4k<53(fDGOs8j6r?y-|sehpN?Ug!2K2%x*-xT#Z9@uzx z`$Z4g93Z#qH9Z6WH^OiF4+Mnr)10-R3(*U2Fw;6&Nu|Zqc7~j{!TbD625ARmhgY2w z2T%_3MKQc}Fk%1r#)+Oz#Xc(5x+2-0)wih8xIOdwg9R|g-W!fB_JS=P;scTL>hshi zn^xOpyWZ^}MF1$N(eR1;$~?4dDN<4Rtzi6n6zRFdtLq~hNr*k^L7n^VXLT_)A7P>6 zfg9@M5~RO23PmoVL86)iL%F8z5vp&g@lFG1%8&hTRK_?n)`2zU`yx@Q6ZKe|y6L&z;!;h7) zs(n1(J5r&$$pMSIy)TeTyvrH(O4rG@H8rYZ++M5m9i-Nhd8OU5In0wtQglhg?XG3t zEB1wf4tV$HS>{;?BMyv0iZBk#2&LxiOjjkOOrdG|{lvzIU4BEVv-Vj*@|HUucDvGy zTU$&8xk4%tHhuZcHOCK=5Pe7+%z?rTugADqhmmDIOV^rEVF5UZzswLeh>P3HQZ2D!7C) zu6h|jxXhC3(kDIU1>Bd2wD!swjxP}O<&;)O`Hj01JE4p^0pWxQr9rh3XJp_S5uv=b zapC~4V5pBz8s>suVd#-Xq0FS>7rejG(`uAruzWyXfWIdsjq`~mmV{n=LJmv$m&YLi zhsf4ZIuMz4P6Vr7^SHvezIs9(kj)XGs_<}tJm+{Yvi3XHemd%kJ@lC2FQJmW71!I3 zZ~wz|yPTPUVgvE)4Wx16DIt!-!squA_UJe#S!hciQp#g$CwSvCSa|Da+*d5=aV7BNe@c5e@JKJ+j#k`l1^EZltuea)zH_?{i#dh2VV& z6(2*5;IIMO)RNX43wD&X~05i2@zT%1bmba(gBdIPiDas0fH<79$h{!5%M0D0U$$x z$gEO0UR7xe4ITqX9aVL|s_F>Rs~l$%x1;b-Qv9YMr%Ua-9UmCK=Gv4ES5cz?ximZ9a=|etSD&5OA4-BXMkb zP}*x7f_+?N6)3JlH6oCb0K|@Hz?DiAz_B(dI|W>lkDi7- zXAStFT6HnSnH@7kXWn&GCCX5UBd##RYYG8ZJ~X^;s2#pcli@ZbE>Vt%LeP!Mo`v8m zs@KfJJ?P~1s6y34o{*H7LI$p&IvS?65reRsRY?4BYv*009XyLoGrh0jw5X@D-;FDSfD6#;t zJz)z?Oc`_}z^r0#v_i_y)YZ8NBUR+-Nz#=)S4kYv26zH|ngNU3qtN`=uDEKst_!QVJsX9E!lGaARa34iM zc>A}L8j4;nRoL9M8tMoSK+$dt_B8=w>`l59y^~PK-f>y_aG5@&X-fza0wKQzU5yAz zKq?M#vvWvq#^AoS$RS!JQ%gN3;oCBoNN+Jo=lGqbpE^5}k$K{vod}byu^S!i+E#l< z{@7GkWseca66%;*du!xa$lYDMwDWv4AV&B(t3|QRcgJ?P;?q`nZ+R+s2@dS zPZdgdGx;^(eQgPzhJlPkh3p<^nhGrhuV*^nD3)zJkb{6x%tkTEWf!^Li?RT1d@tUM zECNR$a8OKw$5?XcBVtEYL?bxO4PLte`UmXYz89g+g40w?muB)0*2YCDdro|mgu6Gw zp~nJ1TkZgfhJ5a&aQQE#%=)HV>4Snvfd(D0rjwcz!Ltz?#XRzTh4!z%DI-+yDHE&| z)X%?!Y}g9xW657bZwO5)q;q*y%c#dp@I)K=J9pz(b}On;#m53{<|Cy!Lc#?oxsLXe zeFKZ2pr?mtN?~daMvEDw@@2{gI%RojuS5(=DIP|49P4MIuzW=N0Mtjize7M%Ij_1u z<=XZ?2(%b;k4IoiQ_f>4Q(PE*2Pc8UBVvjWSTiO<1FYeQ!qJJx2eH%A$Yfg1c?i-9 zSXwH>cJ!Og!^J~fw}>bdz~*OiOD*|JIeW7{q*$Xl&cmX_SM^Uoa9+#mFyumm|+4Bhb^Iys&;9W<96f6kRg1W|6H{`j)*eb;zVUwgG<8Kn< z5hX5ROtfo)nYq;Ciul*%|0oN&K!PhiIa^*KlWzvH;4??%9h7tfq#@wP6LAi-QUwh6MB{0Q-NXy#O+poxgQez5txQbo!19P_+W=EB}pH; zf&hgO7_nCR$Y~Ug_l&T1Zo46*;~*D%4dPzCr7S=wu$4pPsUm;MocKEH)vRLIv7KHd zH#X3l@Md8fbjAki;782)&yF$uGhPa0*vcIYya#FZnM1)>+`%CU74&aB7BfWJB%ByE zeJ$e*39Mv{0w?c0x#xOj%4{D3mTjJ*gXds982i{lFxf4CA`Aq}$LDtefI9Tv?j+PK zG&*pPG^oy*|AeSKL9*s6yyb!)c{{IGO?6z|tOTwR^00ifkBb+ovC_JaQ(rVp&7}Tp z3EYoQVCcAVMR%ph1NUt8%=U}|y9G<669CZX@X?HlvpK9xRddG2K0r=KT$3iF@b|ZV zKuFOs>%UQ41(Uc%xy_qEmBT}0Ts1vQFopN!>B@u_5Bou-NFwN7s8amiuiN}rGm#vL zA1ZqDT%c2Km}R-hWy`x9}vuX)^(`Q3OsylusM{JI||y%7C4p2nHO)yEW5FROD(G zNc=@3!2)XCCWq>f>pu!DZs~9tuf+*>BZUYbDquz@y%3QXN?cJiFz5P3*ju3oM+NOa zBL6$p!AS)8)BX$eaiiU`qyCacTMr3^-`GA^4xCH@Mt-2aEMofU$@<^808_?#=u zTVh5Zz6K-BqVQ@Z1E2B49Tf~sUeHu&yyBcHS0bT2$Hdd z+g9VtSOO+OQ9|xlXDfAJrqmtd#jH-R)Uy(9n@`30_e11OfAQ7zr!UgO`%445f5f~P zKC$x2zp4sb5Z5OYZ&wNmI58-~in{pK^o~SOU1rDfZiddWm4Ch(`uJPL9Obu_JI^P- z)r`J=`SJPvqlSGC>R5j=`AI+s11)-KB}#tnRqBuW>k+x%jj-NpNQVV)8`V*zi&V3_g zmnGMfBoE(RaP$ALP$?Ha;ZCqv#}sfdTeRKtEFbaUjgklZOQrQnv#VV-caAk0N~Awl z?mpA@uJVLqbyh`Q$SYp5TuOcCh~-`J3|CfWUWCM~WGClXc5}{1S=@yAN(k6zv$em$ zYnO74(#4O@d@Tf`N_2343PG=$WtU?_m!D1{>v1^SbW4=N@jBI6$%r?P#%x)a+J0XW zH2N(1h%WYj7I9>6_S?PILAGs5?RZdG>m9@q7VMVo_JvH4ZLn%svPux%5 zoSLi$ROeJk!m4+vVZ)2&tGD@-^?WFaE1{nJ`wMqqztwUkTBk_hG-DJjrj8LbVC+#3 zE9E4mMx{UXzcskA^h~m2M5tkpJb;kWU7234%#KjCc{jR?I1iwDD)XEV&p!V> z@{lA&rDY`)FTYzf*;o31`g+fxCjPK(dpA9hWS8C{bWnuQJA^7#LKUo`sMteORFu%W zhN9AhP*ku6MZoqqC<-D-5K!zvP{A6iph({JdER;N`_ns_$;V7)lSzJi9oKQ5%=F8e zqjf}HXPfc_*>COU`4UUFeS>S|On^+PnZ7}R+RD;K3{2&vad{7onTrpL@XoqNqb72a zoX>O#!Ote=oARhEo3wRb4)&xk~OIqgOvoteoEJ*e4Vkj!3A=ve|+(mO~4 zKgyN}8LCFvp36kKU~+6*(=arFtCFX;4BF5mweOd{vJ;r8BB}XjM*e5hM60 zj1J$^6}Jb?Lb_yqMlo0aHV~aL@0{JS7*!4zP!ev{3`}%i>6uOm=miLRH_!&LbrKOh zuCl`;m@qR&ewLrwo=l!6cOMH2#z z486qEe3i$g)XG4yAgxi~qj@Le)ve-No|V3!B6X!W@0NQmb#L&L&)!TsVWAE>v0OByt)w6IY;(FS@rABBD2qEZt|A-R?K~=_*LW_r@i^~+N(wJTN$bKz zrdO?{<2xQ!n1XD7ECqG;)Jk<^H?NYpXs%)WV`ao2EX5sg7~? zCB;>3?xS40_2%s!-y9VrEbBq*tG9a+3=6glRz@pDGEKJMD?T2%N%Oz*vtN&{`LoHZ z+~r=;jj2?u1G7Zguk?u)&0D~zDCx>CO7>?3m6VqxHc{d*%>Zge>J35vtU@Pk^e{1= zLe5URrgLClj<#}Wx*$|_BKAuD%g5l|o{o#bJj58i6RrMhwA*=$M1i3+llp|y>QSSI zW2O~M?EH^tFV+e-wY}#{Wd7KK#G5(oX(o#m1A{E!%JM635w9{?8Q& zPyQFJd^wPcOZ@*LQ}u|p#_9hnGIdI=yZl*F%iP(`=xG0gzXPfl5}Q06cloSVe)7Kq zPjwM4_8RC100IIoiK<>aZf6ETX4R%1-q<}*94m0u6TG~Z`h*LrEI{Q~Pu#`4%GVWy zG^JKs{e2?qEv1=ubU~0e>*?=eFV;I6-*f%E>oM_f!x`^?4kg7mS-S0#()9vyji%)D zK;fE=Z7UB~&6||zr&X+YAYrDAS|{=39i_!j{wnE56*bR1VZC=wGFE@~_DMUEoqhDM z+QzoR5BDNf@$c&8R-f`tTc!WE^kNT(S|NV75NekvDfX( zizYlhB$m$1u`2e%Y9A<642`_MGXKg05ha7{ZT}AGz$MyG*uRAl7d^?!tIaH^Fo6kX zOZ$G{i$6UXc)#oM_>f68nS1vLfD=N=KWl{9w6;4hgN7v)X&3l}R==?0MIZ9wtNf(% zHX&PbIrPNVG@MGTS4%o_1ufX%^}oR=#V=|j19a{C*WGi+l^CzxRvFU;pxho|8eWY_ z9S8BO(Yh^q>=r+pcMdXrI?Z#aAg{JLEnlPN6lsa{3ObTDI_MbNy#Xm!!$_i*OCw#j z-pba^*IJn^+8wiSa_ls=j)BqXNHz~}nCX&%97K&7{#GgbuKQb!+Kfw@iQXgx*uS=HvsAi6TeEAq!V)IJyE?1||KRx~iw~A*W2TbU9 zj*ZPP3zaobm<<%$L5l<_Q$>#q^1xC!`35~;w)ETm2NII9U4QxJ{mxzGt~r|32G)5A zVphL*1akY?Be%b*H{PvXQm5NFohD6m?Yr3vTOP68+z|keP@kBN?73b@%f((FwD^8! zsL1Y@ET)AnX?>^i*QFmBC#;{4(0w}l3DRwEPt|4NsfBY=kJXvw0KY#W@@5V)1@w>& z?dLqQ#JJidS-7(>;PdI^k~`rfv~r&)Yi&wPfzI9rm1(cFwiNlYRMpiQ+1I)qzePfa zhoduf{OTMj=Z(fic3 zZ_|*TF;5e&b6J(%LSoKE*~pbWbZ@IWo{S*F#qt-R^5TvxlT&pj2|Vp1sLr*H6KUteZq1zhi6EWf+@k36s|wAznaL8U zZ0Yh{_UDub6tnYi8qyCpY8vJ{SBIZC3S5jhwaF_xjFa!R8M}J)n+J`PM!t6@LtV;k zoBi_^$^lM-8lvjiJ#Rjq)TDjpM{c(jr?YrV7b3xNGEDoK;+zn2kfWNYQ}I%CcGSK{ z)Y}eTMlr=FGjh>+xItAXVc>~WhlHIMDmGY1mDEX>y9SMZ3oAJlN7}yZmhp+E=p=G^ zoK&8nI+kl_+bczJP8vV=zGup+Z}9jY`bUjx|AH8qrD?}H(OZHBPWv%1=F}Kc0&%VD zoD`I1z{^lc%Eh}5Uf%cEwV+MpF>Vlld_NNKIL+;LcolejKeEmAqA7dRQW^O!5yN=F z!C5`8YiBYz|I9$m^hr0VWi}z1nK_&it+`%}z{m}~c}WX{uA?%dgQlU4Z%_(i z8=NKL7Vd6*p!PF-t<5#lqF4vFz<$;v^DTc!vEsgk8+|s}=1=RakJD!~ID9u1=?xv| zTs98Xa$jL`ds($|<2BM?(>BRxY-H6y_SO9>hB1*6n-=&2!@Qbd@Zlg)svF5wfGhk@8%WYJ z*RHf&W+*n%uJJugYFvsweUw!hpn96@0h@O_nN`%0cA7M5!ZCdZso7LFNnlx6!)c>l z{*c#KKP@DY`IPjQtWt-ulR;h#`TwXm^ZZjqyXeu1+BG53=k7Ebo=3&B@UqOkJ{N4< zlO?miCk-C%cWqvEJ~KWGOO=7 z{nI!3sQSKBV%=yRLA8eg^nO#AGK&e1US7*O_gbAchf*36dH8BcwRyR_%2at_ z*R*<*n1x;R=7JlSf=}n!H2jWE!F^Ln7J?eVhaCue2#$j4&|iLOiKBc^uiw<%y5U=^ zseg7E)wB{%(LcO8m+h{j+DRxjtbhIXlY7H2YUYBf6>#n4;MFCRk*V>7`qJo}=iBR< zn@J7I^e~Rm}$Zp6F}^& ztx*nb9Xr+U@VKP=*;|r3eyEOWDGp6~zJKmQ-pIPYIzQzG=+_XhICFre!FJBys6j||8NsAij zp3^D)=TqbvY;04?lO1gAVk#1u0xq(_4p^#3K@Rr67zu4n(|Y&|ik*QJsj&D3BCMdQ zgp!EY^N~yWDS|?E;Tiss38Vo|An61EN=&wx1KKsQQGsk*8>Hj!FxhnbRa28sb$YbYJ%lKV;Mz-MAHd~jz^?$-qioq7u>Oj|`neLF|~%(gJHfsq!!PXh82 zWZJy|Hg*(j%SQgW@OruAcWn1*uIH}#^hrK*aYX5kjk;X9daMX6)Xdx5Bg`41lhv}xgAAuuKCzgI zMa3Qe=B0p;m29N@rYVio8B@d8|lF#G;({gWF42t zq=Klt(m@^bE<`kK3zX!cnul=dY&?fb8idQlG`oT5vT80)lbPdJ5qcnU=U@z5l?Hgw zBzijuwFgeTV5~=su|8VHSsHPd5NrrPrCDM`#^uEB^v0DVbjS?pmuq3D=8STlP?17F z*9}sVNDAW97pIRkui9~QUzQT+K$CbiM?wUmw>+}sDauy{b)+2Y{CIzDk^ry zhXzJ$mrw)`@JWLV@;hYMy%x$CrF`dQzU6Q5Xutuy+}4OHw2N!?PB7L06**WnNrgmV zkg-Q_(62BzL)%qj+5O@Qz4n`NN?gF0DWMQZ{zQWwyLyA@VA@d3Gk$a{6BV6ZF-}xj zmzntN5MUyZj0q=C(x8(K2S4+fVy^WlJ-h7&$%2{j`(|xI8ofB{AX0y10gyhq!S-Y#B_(iG34qHlWgh;b&ZpYUTf=& z&|}atHI>(~@8=?VfFCu+3Y%p^KVZuCdFUmJ9H&cedq_gc5w$uRo5q-rpFxLD!@lD3 zP&FRlODE6MDR*h~X_f(|&f1Mgc6ju!vsIS?lD(>8@@1ERoF`qBDf*Tax1H)pcbHB^9ohmBnqrkkGJ2Wyg#qo=g^$_U4GK4inL$qh9Kg_iB%#uj87ihi z!!$en-%K+fAcndYsbhO7B1_(;SkFUAhw868+&yg z?Jgw0i|iB?o@KeJB7IuG2JZaEh#R@<*`)DyWUg)Q`=o8-&W)o08D&a7#{*1V z+dW${e^OIJ(B;}u5XWuj-gb=2V-#ON9-~4T8_7w{F+(h}p>nH$E~(A~)V!)pSaxEr zv@$xxVUYZuO8LZVTQXDQFwHk1lLOctLnr)=DDcY>tf#Zf|Ki_|#fMo{BocMm85HA|aV&2_IUJovx~1&jW6G)fodO`81;A9oWZ@ z?7TV&A9o>KY^mk)r@cfIqap`N0#Ya{#)OKx%}$@DcbhoetIwn$-RP_bdv{Yx6U3 zAs%$16Y8fnAVPGq5M#kZ)-5!ZX3`q$Y9x_2sSWq0!I3KW1cDN@W~jxRbi1!Em_RaF zcwD1{zH&ZAf|ZDvaG&%56bHRkgbhM+m$~5Pc+h~SwjZCaPz%6W?X{LH-ip&qBAuhOEJG^3mZ)O12^$w1=dhBKqRcwBw_|ws zB>)u}jz;1c87O5YVC>rNA%rE1;0ZyKh?+>7hdBU-hmGQ3834xW|4MM2 z_X7WR#7^AH!{do6QL;t9?gJzmXw5@=aj;SU#5ck!Iv~#)kzu1FM3C{14^dpKjR^YP zUu?Y*RAXU}u#~6b>blV&L_=-hU?b>QhB`KihsLtrE6_kJjFD2uMhGx|B4{mB#cFrc zl|b}(F>=34U*x{N5X6R&3O+W*Uj+H_F+KuJ1QU$~P+5N=h>70fgz=_-7BkT@H0|}` z*X)(gU|+8CoS>H7Os7@q?fdVu7X$0Z!Bjd;TCqMf_XBLF&y~jTS^(4(fc?9hR$hQ) z20BjkvN`U;k4NWz1+n!gCxgm!P?Vdb>K_lJ50kmZ1$D+&HpuC{12%=R4%g^ z+I_j%F1ylatlvwyxhCV75f{=xi1F?@fqa_lH`EQOmC@}yl4)&K5?1FfV z+*e{4J+|`E2f)m{{fu>nV?V_Y{(;T{W*#;_p;Sx=ALAy#xY017Vm5{<4+s2XQORk%m=5*%6Hgs@ho-#M2P$DmV2@bchO1HAX$zqo zY(_1%!5GfCf{Cx4-|#a{OQ3|mNxb-`I8p=c!$vOOJn$Z~<>?Z(4&%a}-~Qzmj*f<; zdu;uepxRmX)uo);rLis8Ix+BAea35^dLSW5Q)%H6Buan!HKZ1^9a=W7or=E-+z4p5 z`k<98uxE-z`s^uV@t@oiuy5`64K$R_o5e`+UuZQ?UUN%nWGyQ5D#nKjR}U=Zn7~O} zu%TQmor?MR^zYwaP!Q`k!E;HT4^Uw=(1IqErAAx}X`Z=Cl*#t13`x6&#uIT^#pMU( zf#aUXk-$@oQqV+Cu_A3xxbQ>2x(mnazkd#;GXX10SB!JbDxz+HSH4{v#}Ek;sx%%m z@)JTO&#b%_K@Vgdj?nha%!PanEA+NcWQw?aGy$eJ^1+E7A}l8tGbsu%Tz@O6qOvPi z_|VxQU3J@snDsorQu+V3Gx>n)2ciT;XJte34`%O4>&mW8oxS&*#99%!zf$J7o8G2d z`Zysd@1eTQ_9xkzs3I$|m|**CZo{wGPQy)QE*h8jxHfO8?Be(z&$Jl&x-ajOs=u?^zN+})o%oR8 zq_5ek0Rh`a%wnw$pAU`re*cq7f>%*e*ybA-KGnuQ+ljB)oOASoYGS&sRYXPo<4+n1 zqhONRwzbmu#_df@IjV*6XTo0Yy4oqDbD-n=jtZ8+g+ zxAW}j?YDNGug$jG)qMWkt%O|{uRgNdefi}R=2!Ukg593uo$^N<-A)?W@4fM2`|Z8$ z@3Zaq-TZv+_P*OcAKCA}TPlyAyeq~zusZSjcUU+6T5Y;`MrM6=Tz8Iax9UELL(7J& z-n8w-y|o*XX3w8G)Ri!JRlEC9YP@&H&-l|ycbg-*l7#=!rv868gfk$f*(g8ni@2WJ z&GAstD`Z|xZ^j)~ZrUl`kj7paD<0>aeR3M}>+ewa4A56)lkmlXASCmmpPVA9>V)cS-nis+*x^lwAO>tOAZCPLS*ve!^z^a+4A)Z1&ihgIR#W4zx}OAZTUU^?15gJ9O+fvot!f^S_u(OYv~2hU1sq z*?!BBKvAFJU`+YRJ_N-~>?-S1JKIz9F z`@LumS&Ctq$LiIEQN8pVcG431N54%ER7Fo%J(NIyzZk5u)pQoJe7X21z)svT8{mLR zyTx#hdYeJMPc)g^B-QCK?r-;!G$(I9w2UZ6bIT7-4842WWq3^GbB>ksVsdhyFzV!lAM54MiKXz$*~{0{_XCU7rD2&iW?!8v_yz(!)S(~=w-Fj<)hqPf{_oDS+`uHa zfwZv#!6-ZwxOQI_I>2tMr(w-2Ge@PDrAuAMo9X^nwBu;kMqP3)8+>=cs~zz(`zn{D z_2=Z3_E)_G9h8R|@mUY~Om^>H@f#hIfujLEyP ziGKM9-bP89iK}H+>=%XBFdrjBa72w>N)wzDmtF2g6&Y-FnrqcRzWM1M;l|28iZiOl-_jL(Y<%(xwTkxl zG^qVnIYk$D1+^Vgj8hkLa-^{Jx`&q0>LIUiW_IZXfpFCN?6F>FJ{65|_{7}U9H{ar zyxeBgMc3+U#+`MpoYQ|F$ZL3e*>jSeW~PZDOC8;fpQN1Zo(gsa^9oG9Xu%tM?#o{+ z_OusjQeLE82*4fccGg)s?(^RRweplG$G#R))bay`R_;q@mN{(67it~|+OmPwfLkLy zL5}CSVX*fJ+`r>8sJ#9_xSn$E@3{KT@llhrb5KfofX0_U4I_7*RwHK@Mk;w)AM3%O!igH}H? zdtZihSt@B<#r#Z^{o2kv?>X?4^W-HiP6#Rt^YOt#l=3^_Nvq{qvXyU%>#8I7uib1= zdnBvnN;^N2PC{~Pxetw9XP{ueJQsAw~zIiC1UzA4OtUB)8BrRF~-z%6H^0%eqqbGZNIN1AkgawDM;yPkVn&ImO z5%bK2vOZerwa8OUm2k@%#cOmBf)0Vm2^)x3Y~gR)Y9m#(S#V#h(A`tBDQS5Wnu;WiIc9N#U3xD6s@Qb>8(=3$3NPRDptd;c~NEI`usxpbLlRdPB(E(PJ= zPztPL!=_HsDw`@R9cmUcgIC7#!j9aRy<|HyArfXv({E}P?esElv;J`E+tle_UjB_c zCP6RYfzn`ZmL_Q|*Ncvlt`KJGdA%-Rk}9a24At>MeYp#YSL14c-G(1HXy)5WC$pX2 zC!gL0T!9Bs&vN_KF_F36d$eAe9{1Q2=I*$5@wHT#ZJw5_l!+^8lT<0YS4jbwa*_G{ zhB;X3M*H}FhQfs!UgKJkEt2J@^o054$E=U4Hcyn1?k3<=@QfFv31EO>zwYLga6V})@7-_Rgn58 zYP6(@c_5PFBg`MSNtNnmkBLlke&j z)@aF8*N2|YMTRhdEkDmEmU76z4J8H9Esp*ZK3IS}H~*sIp;|L|3{_B`3|KHFx)EX_ zB7bMX(|pRWq-||{lms7qI9dcN6d=gKNJPBPiycE|X7r$G0Q$~=($AD$l3ref z5b$!Gp>PiAk<%k18GS&qTrab0I5U8TZ^;$V&jdc;FiT>#<1cOv4Au-MncDt z5rs;6QnH1;6G`Y>v?;Z10p+;Kex0RWFX7W2pbCIAI30QdkU9YJGaA{z++u(mbB$i+ zxm1?hR2&97$9R{@(=!1W-^O89^NH7lq)2m^ZtENwL3Ci2?JqyICKANaus&&|>z1mY z%~S4va%$-STPKO6=lG)>i2=k-@h*`jAVv_el!1m{o<4RHR!T;46Sba)DJ`UxZx~4r zCgR$K#B6qEqBl7{lzi~z7Q}Wl0f4nj6(pB}YMO2KPMA|(slo!&MjQA}}{=w22 zH5S12IQ^Qv<_{a1W?OuuQjA9|hpGS8+nr!w%}ef@reZ}t_BfZwe$FLLBfV|d9)SB= zK;bt+C5aS7>G6DEfS3=l{F0M4we&?)GM`{}NdBGo0eK;aW@87CvMpZ2f&ls@qzFbG z-_c+%&x&+@t@q(GkCxE+fa5-$l(Fmi2r0<*M4AbM=c&3wu@tp7C$|R%ViBo@QEjmc zUeDNnVi4N@B}-leV#IX9T_N$ADDX-&UBcq?X9|L1~9nh3#^b_97%^SUXxju z0F_K+DIq~yd;%$v%;?dX2O9NmkPmuPR90>jFwm0JrZt`1Ee1$JBMKAhs(3@@H$4b5 z?a0^;stPV3)9-gI@@EkxG@W8NLTn3R!wFw{y%;7e8 z11+#_R;cNT=Ai~p(szSe3<(EA^8Osk3;_MjkNze@{y!OfB->u1Ccif03!q8cW_??x z#GQ_*gMJ()N87_$OKVk`pdM4APe>X75YdnVUElDU@09nadNEi+4+iO84Jr298gI#r zq4O5TC|Wz=b>4yU3{(rV{w*6ZQE$$0H`tuxBuJ74B4pri(IG_PMK{T-Kou5tedFHb zXGVi8DV!;3gD!YwHTfR06t7L0Y6?QN7@$ns2Ur_B5eY`j=G`$Y2!@k%8)XtPG_(}u zKFt&r7UOZ(D49`I4LCmgrU)b+lfyuw7JZ zRjiN@Z;FZpq@GS5f%OzzO4j8e0k3G9Z-dGt`pr!ldhemLyI~PM1|4|8ys=WuX8}l` zVSeYz{RhLetUeAoX$itS!Fs&ms(7K3Va2azb(G?5W6bQ5#0dN#shRq)rOxkB1c*li zzBIC_F7%#5cD{Mn!FFR(0qG@^c3b?CYe3gVnKlpyNu{=AWQ=^lvS`Y_1DQ|nmDu*^ zB~aEG`iw{ZOohgf7EwC#%SV1DEPH!|Gz8DkE z&F%u)jOj-BIS}E2eoF6EDkQ(;?@rw%g=!%Qc$n)BwZ1noVrJ9xaoC9%j81#}FcBUD zi0w;I|2e<)$p|?BKsK-%mV8a4OaqN^uWyS*9nZM2`7lb2cE6UGX~DyXYr-9kaG&pE zR9f_2xo%9F(+V5%t0NS0h>0S!d19W57Zu>6f~kO|pznvs@uW7{puczNq(nLs^KY_F zy+eKlN{N}MSla&l2gLW6o?xf1qoopQIx_PY3DH!{YJT>zSs|H<4rLq$vPbZlz+U2@6iV~)#zS!5ZwRzViHei} zVARV9`TWOeM7j>&8lG83Su#-s-YYS6Kvyt~23}?4r;GX6*++y0`Iisa&SLJ#vcA|0 zHy)P+K{CkJ0TY!i4|=H?S%ibVZ-#LQjVRH!8uL(Kyg)Qpbv8MgX40Ij#X#?3d4vX+zHT4>efcdS7onH{L<4DSP^h@Kit!+hH!QIQ zR%8K)wI_E_W=u<7fFvUeuGd~arHdeXI)W=QRd}j6+7U65=!Xy+E~xkP@S1&D-~9rN z17(d}oVZaCLW)lJn~(qy6Za2qjOl|4f?*(^r?H z_p{YcNg3Ze01cJXPKN{9B8WkUw^4Bj=uqZ@P5aPMH28)wZZiv|DguKlrYxF-hND2( zYSoGRu79XdbEOdyJ&R?b#SARMTLS+NQ8DKOdhb9IfC?2(26F%LfE_Fp3I04r{^q*` zIk8p0tcK^gIi1(OVY#SKHpZKV@#bJc`4~e0)Z$O511LHNQpY) zo=(^LX$T`<)E{CF#$SLjq=9-{UQl67C=FgZh9jDwcHf*adM_-#F_rcdqkM1L;XOtl znDcoDqPAjHOyJ+@Xl?ZiMyc>u$`@2x?N-z3QhkHIb*P~IbB-sbU;Y4*&N7dyv))|n zDiNR#PegBpm0<86591QrEF|_Umpxj75N3qXqAl++p)eXX{Y-`iqQwyQ-t6J4z?PL? z_+l_j1m(%>t)*=UT9(_Ls=vk#g}|bvnxFn0Y#9Vb8l%eZ{S3MKa}@`ug?{6T(eaGM zQtr^1ON)xU@5d3oAe={-%qkA5?Dzy7_@RB`XX(#B{D53_u?Tzou66rd#hUORUZU@t zP2f<@iWg$;i=Yk6xv_PBh`hhJVh~At*pc~qNA05dP7vs1gVMS_E99lqH1CpC5f^k) z${CTT6p1=py8eelm__1^kFIz;>oP3!I<;nVdMlqx=NS0FT4f!y$FQC^jnZ7N<&u5c zqe%T|1?ZNkaTG8uiCrZZbRpFAQ3!pu*1yUol>$nhs$*Q-*027S$9z~-P~&+f>yMcp znrcbbn@|qZ9#~~c=)$Tdj|UkZ0StW6$R`0a*t z;o=SyX~mn5TBM}xM6do0cNP2DxX@@zWyPnL0Fqm!WPi zGeaUixdHNcQzdPvvj$#gGi#N5&DUJlEFd#g(V_H$PK5=h!|L-lYMmpa$~?evz%@F+ zS&Xp|2>x51sek^|qFLz;J=NZG#=jRh|naoE{5B8K~5^UBVV&`3)&{Yn`HSWD9_d)tC`f?58y zJ6Lz&{o{_658L{2;k5DE-7-(C-e_!Q7Qk@>j&Xc!ENA?6D%IV3ix787#`nFq_zY=J2HH&Fu{~O1koqZ98|=9Gb|}SFg%B@VGkZ&7tlynVEXG zrZ{cHZq=mcaks=@I5nMKQ>hazw{{m@nL1aUI6C-h_jQwcy}E?aL!bAwn`rI$-uB+< zPsQ#P!_Sj#pX=;Du!+{O_fEb4pqk{oFX>FUmsHX zBw=guvoc0-dF9C5l_#c-Nh9m6XBf}7=DZESQN4OlkWSBJ)#%5Q!SzW`U*6pw*F#*{ zM8Oz1Md8nR{deedZI07nHjyCI@M&~z$0h5ca#ZiPbcg-Q^ugatnH^Z`e02WBj(bOc zz0Ywzw)FY@y<>lVb~~s3{q^~t`1#*j=}UkO|9TvoZ4&j&*(ZsPvl661nM{nXjf+H> zAYGx0iL>l*p&VfN*iKMu@E$g<(x(KO`tD;tT+8n_q@2j|j2n~OHrc?cMk}8vAM>q$ zROB)t(ygDZ^DT?aqsp6FeBius-eqbBA1G4t+>=M^k%9jQuOM;<03r{7fC0o<3}FBN E05SrEL;wH) literal 0 HcmV?d00001 From 8af693548e3afc82f74818ed7a20abc117236592 Mon Sep 17 00:00:00 2001 From: Daniel Ritchie Date: Fri, 22 Nov 2024 11:14:25 -0700 Subject: [PATCH 04/24] Add support for Windows (#494) --- lerobot/scripts/find_motors_bus_port.py | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/lerobot/scripts/find_motors_bus_port.py b/lerobot/scripts/find_motors_bus_port.py index 51ef6d41c..67b92ad7d 100644 --- a/lerobot/scripts/find_motors_bus_port.py +++ b/lerobot/scripts/find_motors_bus_port.py @@ -1,30 +1,36 @@ +import os import time from pathlib import Path +from serial.tools import list_ports # Part of pyserial library + def find_available_ports(): - ports = [] - for path in Path("/dev").glob("tty*"): - ports.append(str(path)) + if os.name == "nt": # Windows + # List COM ports using pyserial + ports = [port.device for port in list_ports.comports()] + else: # Linux/macOS + # List /dev/tty* ports for Unix-based systems + ports = [str(path) for path in Path("/dev").glob("tty*")] return ports def find_port(): print("Finding all available ports for the MotorsBus.") ports_before = find_available_ports() - print(ports_before) + print("Ports before disconnecting:", ports_before) - print("Remove the usb cable from your MotorsBus and press Enter when done.") - input() + print("Remove the USB cable from your MotorsBus and press Enter when done.") + input() # Wait for user to disconnect the device - time.sleep(0.5) + time.sleep(0.5) # Allow some time for port to be released ports_after = find_available_ports() ports_diff = list(set(ports_before) - set(ports_after)) if len(ports_diff) == 1: port = ports_diff[0] print(f"The port of this MotorsBus is '{port}'") - print("Reconnect the usb cable.") + print("Reconnect the USB cable.") elif len(ports_diff) == 0: raise OSError(f"Could not detect the port. No difference was found ({ports_diff}).") else: @@ -32,5 +38,5 @@ def find_port(): if __name__ == "__main__": - # Helper to find the usb port associated to all your MotorsBus. + # Helper to find the USB port associated with your MotorsBus. find_port() From 20f466768e88c6c68f8232b6d52ca9627fffe814 Mon Sep 17 00:00:00 2001 From: resolver101757 Date: Fri, 22 Nov 2024 18:15:58 +0000 Subject: [PATCH 05/24] bug causes error uploading to huggingface, unicode issue on windows. (#450) From 975c1c25c34d47a359d7abcb0153f41c1d4f297a Mon Sep 17 00:00:00 2001 From: Jannik Grothusen <56967823+J4nn1K@users.noreply.github.com> Date: Fri, 22 Nov 2024 19:19:57 +0100 Subject: [PATCH 06/24] Add distinction between two unallowed cases in name check "eval_" (#489) --- lerobot/common/robot_devices/control_utils.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index 08bcec2e6..d2879c960 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -324,7 +324,15 @@ def sanity_check_dataset_name(repo_id, policy): _, dataset_name = repo_id.split("/") # either repo_id doesnt start with "eval_" and there is no policy # or repo_id starts with "eval_" and there is a policy - if dataset_name.startswith("eval_") == (policy is None): + + # Check if dataset_name starts with "eval_" but policy is missing + if dataset_name.startswith("eval_") and policy is None: + raise ValueError( + f"Your dataset name begins with 'eval_' ({dataset_name}), but no policy is provided." + ) + + # Check if dataset_name does not start with "eval_" but policy is provided + if not dataset_name.startswith("eval_") and policy is not None: raise ValueError( - f"Your dataset name begins by 'eval_' ({dataset_name}) but no policy is provided ({policy})." + f"Your dataset name does not begin with 'eval_' ({dataset_name}), but a policy is provided ({policy})." ) From 96c7052777aca85d4e55dfba8f81586103ba8f61 Mon Sep 17 00:00:00 2001 From: KasparSLT <133706781+KasparSLT@users.noreply.github.com> Date: Mon, 25 Nov 2024 21:05:13 +0100 Subject: [PATCH 07/24] Rename deprecated argument (temporal_ensemble_momentum) (#490) --- lerobot/configs/policy/act_aloha_real.yaml | 2 +- lerobot/configs/policy/act_koch_real.yaml | 2 +- lerobot/configs/policy/act_moss_real.yaml | 2 +- lerobot/configs/policy/act_so100_real.yaml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/lerobot/configs/policy/act_aloha_real.yaml b/lerobot/configs/policy/act_aloha_real.yaml index 70da3c561..7c8094da1 100644 --- a/lerobot/configs/policy/act_aloha_real.yaml +++ b/lerobot/configs/policy/act_aloha_real.yaml @@ -114,7 +114,7 @@ policy: n_vae_encoder_layers: 4 # Inference. - temporal_ensemble_momentum: null + temporal_ensemble_coeff: null # Training and loss computation. dropout: 0.1 diff --git a/lerobot/configs/policy/act_koch_real.yaml b/lerobot/configs/policy/act_koch_real.yaml index fd4bf3b59..6ddebab14 100644 --- a/lerobot/configs/policy/act_koch_real.yaml +++ b/lerobot/configs/policy/act_koch_real.yaml @@ -95,7 +95,7 @@ policy: n_vae_encoder_layers: 4 # Inference. - temporal_ensemble_momentum: null + temporal_ensemble_coeff: null # Training and loss computation. dropout: 0.1 diff --git a/lerobot/configs/policy/act_moss_real.yaml b/lerobot/configs/policy/act_moss_real.yaml index 840a64e14..d996c3597 100644 --- a/lerobot/configs/policy/act_moss_real.yaml +++ b/lerobot/configs/policy/act_moss_real.yaml @@ -95,7 +95,7 @@ policy: n_vae_encoder_layers: 4 # Inference. - temporal_ensemble_momentum: null + temporal_ensemble_coeff: null # Training and loss computation. dropout: 0.1 diff --git a/lerobot/configs/policy/act_so100_real.yaml b/lerobot/configs/policy/act_so100_real.yaml index 3a0975b65..cf5b1f147 100644 --- a/lerobot/configs/policy/act_so100_real.yaml +++ b/lerobot/configs/policy/act_so100_real.yaml @@ -95,7 +95,7 @@ policy: n_vae_encoder_layers: 4 # Inference. - temporal_ensemble_momentum: null + temporal_ensemble_coeff: null # Training and loss computation. dropout: 0.1 From 32eb0cec8f322a7d93a1ec2008dd1a11ae6286b3 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Fri, 29 Nov 2024 19:04:00 +0100 Subject: [PATCH 08/24] Dataset v2.0 (#461) Co-authored-by: Remi --- .github/PULL_REQUEST_TEMPLATE.md | 2 +- .github/workflows/nightly-tests.yml | 8 +- .github/workflows/test.yml | 5 +- CONTRIBUTING.md | 2 +- README.md | 14 +- benchmarks/video/run_video_benchmark.py | 2 +- examples/10_use_so100.md | 9 +- examples/11_use_moss.md | 9 +- examples/1_load_lerobot_dataset.py | 123 +- examples/3_train_policy.py | 2 +- examples/6_add_image_transforms.py | 6 +- examples/7_get_started_with_real_robot.md | 10 +- examples/8_use_stretch.md | 2 - examples/9_use_aloha.md | 7 +- .../advanced/2_calculate_validation_loss.py | 36 +- examples/port_datasets/pusht_zarr.py | 222 +++ lerobot/__init__.py | 4 +- lerobot/common/datasets/card_template.md | 27 + lerobot/common/datasets/compute_stats.py | 39 +- lerobot/common/datasets/factory.py | 5 +- lerobot/common/datasets/image_writer.py | 160 ++ lerobot/common/datasets/lerobot_dataset.py | 1070 ++++++++++-- lerobot/common/datasets/online_buffer.py | 6 +- lerobot/common/datasets/populate_dataset.py | 468 ----- .../push_dataset_to_hub/aloha_hdf5_format.py | 2 +- .../push_dataset_to_hub/cam_png_format.py | 7 +- .../dora_parquet_format.py | 2 +- .../push_dataset_to_hub/openx_rlds_format.py | 2 +- .../push_dataset_to_hub/pusht_zarr_format.py | 2 +- .../push_dataset_to_hub/umi_zarr_format.py | 2 +- .../datasets/push_dataset_to_hub/utils.py | 57 + .../push_dataset_to_hub/xarm_pkl_format.py | 2 +- lerobot/common/datasets/utils.py | 632 ++++--- .../v2/batch_convert_dataset_v1_to_v2.py | 882 ++++++++++ .../datasets/v2/convert_dataset_v1_to_v2.py | 665 +++++++ lerobot/common/datasets/video_utils.py | 146 +- .../robot_devices/cameras/intelrealsense.py | 4 + .../common/robot_devices/cameras/opencv.py | 4 + lerobot/common/robot_devices/control_utils.py | 33 +- .../robot_devices/robots/manipulator.py | 36 + lerobot/common/robot_devices/robots/utils.py | 1 + lerobot/scripts/control_robot.py | 157 +- lerobot/scripts/eval.py | 2 +- lerobot/scripts/push_dataset_to_hub.py | 10 +- lerobot/scripts/train.py | 14 +- lerobot/scripts/visualize_dataset.py | 26 +- lerobot/scripts/visualize_dataset_html.py | 62 +- lerobot/scripts/visualize_image_transforms.py | 2 +- .../templates/visualize_dataset_template.html | 2 +- poetry.lock | 1534 +++++++++-------- pyproject.toml | 6 +- tests/conftest.py | 7 + tests/fixtures/constants.py | 29 + tests/fixtures/dataset_factories.py | 396 +++++ tests/fixtures/files.py | 114 ++ tests/fixtures/hub.py | 105 ++ .../save_image_transforms_to_safetensors.py | 2 +- tests/scripts/save_policy_to_safetensors.py | 2 +- tests/test_control_robot.py | 127 +- tests/test_datasets.py | 138 +- tests/test_delta_timestamps.py | 256 +++ tests/test_examples.py | 27 +- tests/test_image_transforms.py | 108 +- tests/test_image_writer.py | 359 ++++ tests/test_online_buffer.py | 64 +- tests/test_policies.py | 10 +- tests/test_push_dataset_to_hub.py | 5 +- tests/test_sampler.py | 2 +- tests/test_utils.py | 17 +- tests/test_visualize_dataset.py | 18 +- tests/test_visualize_dataset_html.py | 20 +- 71 files changed, 6109 insertions(+), 2229 deletions(-) create mode 100644 examples/port_datasets/pusht_zarr.py create mode 100644 lerobot/common/datasets/card_template.md create mode 100644 lerobot/common/datasets/image_writer.py delete mode 100644 lerobot/common/datasets/populate_dataset.py create mode 100644 lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py create mode 100644 lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py create mode 100644 tests/fixtures/constants.py create mode 100644 tests/fixtures/dataset_factories.py create mode 100644 tests/fixtures/files.py create mode 100644 tests/fixtures/hub.py create mode 100644 tests/test_delta_timestamps.py create mode 100644 tests/test_image_writer.py diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 4063e395f..2e6fd4490 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -21,7 +21,7 @@ Provide a simple way for the reviewer to try out your changes. Examples: ```bash -DATA_DIR=tests/data pytest -sx tests/test_stuff.py::test_something +pytest -sx tests/test_stuff.py::test_something ``` ```bash python lerobot/scripts/train.py --some.option=true diff --git a/.github/workflows/nightly-tests.yml b/.github/workflows/nightly-tests.yml index f967533ae..bbee19a17 100644 --- a/.github/workflows/nightly-tests.yml +++ b/.github/workflows/nightly-tests.yml @@ -7,10 +7,8 @@ on: schedule: - cron: "0 2 * * *" -env: - DATA_DIR: tests/data +# env: # SLACK_API_TOKEN: ${{ secrets.SLACK_API_TOKEN }} - jobs: run_all_tests_cpu: name: CPU @@ -30,13 +28,9 @@ jobs: working-directory: /lerobot steps: - name: Tests - env: - DATA_DIR: tests/data run: pytest -v --cov=./lerobot --disable-warnings tests - name: Tests end-to-end - env: - DATA_DIR: tests/data run: make test-end-to-end diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 9d51def4d..5de071750 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -29,7 +29,6 @@ jobs: name: Pytest runs-on: ubuntu-latest env: - DATA_DIR: tests/data MUJOCO_GL: egl steps: - uses: actions/checkout@v4 @@ -70,7 +69,6 @@ jobs: name: Pytest (minimal install) runs-on: ubuntu-latest env: - DATA_DIR: tests/data MUJOCO_GL: egl steps: - uses: actions/checkout@v4 @@ -103,12 +101,11 @@ jobs: -W ignore::UserWarning:gymnasium.utils.env_checker:247 \ && rm -rf tests/outputs outputs - + # TODO(aliberts, rcadene): redesign after v2 migration / removing hydra end-to-end: name: End-to-end runs-on: ubuntu-latest env: - DATA_DIR: tests/data MUJOCO_GL: egl steps: - uses: actions/checkout@v4 diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 822197ba2..b8c198568 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -267,7 +267,7 @@ We use `pytest` in order to run the tests. From the root of the repository, here's how to run tests with `pytest` for the library: ```bash -DATA_DIR="tests/data" python -m pytest -sv ./tests +python -m pytest -sv ./tests ``` diff --git a/README.md b/README.md index 5fbf74f44..9331bdeca 100644 --- a/README.md +++ b/README.md @@ -153,10 +153,12 @@ python lerobot/scripts/visualize_dataset.py \ --episode-index 0 ``` -or from a dataset in a local folder with the root `DATA_DIR` environment variable (in the following case the dataset will be searched for in `./my_local_data_dir/lerobot/pusht`) +or from a dataset in a local folder with the `root` option and the `--local-files-only` (in the following case the dataset will be searched for in `./my_local_data_dir/lerobot/pusht`) ```bash -DATA_DIR='./my_local_data_dir' python lerobot/scripts/visualize_dataset.py \ +python lerobot/scripts/visualize_dataset.py \ --repo-id lerobot/pusht \ + --root ./my_local_data_dir \ + --local-files-only 1 \ --episode-index 0 ``` @@ -208,12 +210,10 @@ dataset attributes: A `LeRobotDataset` is serialised using several widespread file formats for each of its parts, namely: - hf_dataset stored using Hugging Face datasets library serialization to parquet -- videos are stored in mp4 format to save space or png files -- episode_data_index saved using `safetensor` tensor serialization format -- stats saved using `safetensor` tensor serialization format -- info are saved using JSON +- videos are stored in mp4 format to save space +- metadata are stored in plain json/jsonl files -Dataset can be uploaded/downloaded from the HuggingFace hub seamlessly. To work on a local dataset, you can set the `DATA_DIR` environment variable to your root dataset folder as illustrated in the above section on dataset visualization. +Dataset can be uploaded/downloaded from the HuggingFace hub seamlessly. To work on a local dataset, you can use the `local_files_only` argument and specify its location with the `root` argument if it's not in the default `~/.cache/huggingface/lerobot` location. ### Evaluate a pretrained policy diff --git a/benchmarks/video/run_video_benchmark.py b/benchmarks/video/run_video_benchmark.py index 46806c075..e90664872 100644 --- a/benchmarks/video/run_video_benchmark.py +++ b/benchmarks/video/run_video_benchmark.py @@ -266,7 +266,7 @@ def benchmark_encoding_decoding( ) ep_num_images = dataset.episode_data_index["to"][0].item() - width, height = tuple(dataset[0][dataset.camera_keys[0]].shape[-2:]) + width, height = tuple(dataset[0][dataset.meta.camera_keys[0]].shape[-2:]) num_pixels = width * height video_size_bytes = video_path.stat().st_size images_size_bytes = get_directory_size(imgs_dir) diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index 32d7f22dd..70e4ed8ba 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -192,7 +192,6 @@ Record 2 episodes and upload your dataset to the hub: python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/so100.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/so100_test \ --tags so100 tutorial \ --warmup-time-s 5 \ @@ -212,7 +211,6 @@ echo ${HF_USER}/so100_test If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --root data \ --repo-id ${HF_USER}/so100_test ``` @@ -220,10 +218,9 @@ python lerobot/scripts/visualize_dataset_html.py \ Now try to replay the first episode on your robot: ```bash -DATA_DIR=data python lerobot/scripts/control_robot.py replay \ +python lerobot/scripts/control_robot.py replay \ --robot-path lerobot/configs/robot/so100.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/so100_test \ --episode 0 ``` @@ -232,7 +229,7 @@ DATA_DIR=data python lerobot/scripts/control_robot.py replay \ To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: ```bash -DATA_DIR=data python lerobot/scripts/train.py \ +python lerobot/scripts/train.py \ dataset_repo_id=${HF_USER}/so100_test \ policy=act_so100_real \ env=so100_real \ @@ -248,7 +245,6 @@ Let's explain it: 3. We provided an environment as argument with `env=so100_real`. This loads configurations from [`lerobot/configs/env/so100_real.yaml`](../lerobot/configs/env/so100_real.yaml). 4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise. 5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. -6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. Training should take several hours. You will find checkpoints in `outputs/train/act_so100_test/checkpoints`. @@ -259,7 +255,6 @@ You can use the `record` function from [`lerobot/scripts/control_robot.py`](../l python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/so100.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/eval_act_so100_test \ --tags so100 tutorial eval \ --warmup-time-s 5 \ diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index 4ccbb93db..55d6fcaf9 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -192,7 +192,6 @@ Record 2 episodes and upload your dataset to the hub: python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/moss.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/moss_test \ --tags moss tutorial \ --warmup-time-s 5 \ @@ -212,7 +211,6 @@ echo ${HF_USER}/moss_test If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --root data \ --repo-id ${HF_USER}/moss_test ``` @@ -220,10 +218,9 @@ python lerobot/scripts/visualize_dataset_html.py \ Now try to replay the first episode on your robot: ```bash -DATA_DIR=data python lerobot/scripts/control_robot.py replay \ +python lerobot/scripts/control_robot.py replay \ --robot-path lerobot/configs/robot/moss.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/moss_test \ --episode 0 ``` @@ -232,7 +229,7 @@ DATA_DIR=data python lerobot/scripts/control_robot.py replay \ To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: ```bash -DATA_DIR=data python lerobot/scripts/train.py \ +python lerobot/scripts/train.py \ dataset_repo_id=${HF_USER}/moss_test \ policy=act_moss_real \ env=moss_real \ @@ -248,7 +245,6 @@ Let's explain it: 3. We provided an environment as argument with `env=moss_real`. This loads configurations from [`lerobot/configs/env/moss_real.yaml`](../lerobot/configs/env/moss_real.yaml). 4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise. 5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. -6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. Training should take several hours. You will find checkpoints in `outputs/train/act_moss_test/checkpoints`. @@ -259,7 +255,6 @@ You can use the `record` function from [`lerobot/scripts/control_robot.py`](../l python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/moss.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/eval_act_moss_test \ --tags moss tutorial eval \ --warmup-time-s 5 \ diff --git a/examples/1_load_lerobot_dataset.py b/examples/1_load_lerobot_dataset.py index 3846926a6..96c104b68 100644 --- a/examples/1_load_lerobot_dataset.py +++ b/examples/1_load_lerobot_dataset.py @@ -3,78 +3,120 @@ It illustrates how to load datasets, manipulate them, and apply transformations suitable for machine learning tasks in PyTorch. Features included in this script: -- Loading a dataset and accessing its properties. -- Filtering data by episode number. -- Converting tensor data for visualization. -- Saving video files from dataset frames. +- Viewing a dataset's metadata and exploring its properties. +- Loading an existing dataset from the hub or a subset of it. +- Accessing frames by episode number. - Using advanced dataset features like timestamp-based frame selection. - Demonstrating compatibility with PyTorch DataLoader for batch processing. The script ends with examples of how to batch process data using PyTorch's DataLoader. """ -from pathlib import Path from pprint import pprint -import imageio import torch +from huggingface_hub import HfApi import lerobot -from lerobot.common.datasets.lerobot_dataset import LeRobotDataset +from lerobot.common.datasets.lerobot_dataset import LeRobotDataset, LeRobotDatasetMetadata +# We ported a number of existing datasets ourselves, use this to see the list: print("List of available datasets:") pprint(lerobot.available_datasets) -# Let's take one for this example -repo_id = "lerobot/pusht" - -# You can easily load a dataset from a Hugging Face repository +# You can also browse through the datasets created/ported by the community on the hub using the hub api: +hub_api = HfApi() +repo_ids = [info.id for info in hub_api.list_datasets(task_categories="robotics", tags=["LeRobot"])] +pprint(repo_ids) + +# Or simply explore them in your web browser directly at: +# https://huggingface.co/datasets?other=LeRobot + +# Let's take this one for this example +repo_id = "lerobot/aloha_mobile_cabinet" +# We can have a look and fetch its metadata to know more about it: +ds_meta = LeRobotDatasetMetadata(repo_id) + +# By instantiating just this class, you can quickly access useful information about the content and the +# structure of the dataset without downloading the actual data yet (only metadata files — which are +# lightweight). +print(f"Total number of episodes: {ds_meta.total_episodes}") +print(f"Average number of frames per episode: {ds_meta.total_frames / ds_meta.total_episodes:.3f}") +print(f"Frames per second used during data collection: {ds_meta.fps}") +print(f"Robot type: {ds_meta.robot_type}") +print(f"keys to access images from cameras: {ds_meta.camera_keys=}\n") + +print("Tasks:") +print(ds_meta.tasks) +print("Features:") +pprint(ds_meta.features) + +# You can also get a short summary by simply printing the object: +print(ds_meta) + +# You can then load the actual dataset from the hub. +# Either load any subset of episodes: +dataset = LeRobotDataset(repo_id, episodes=[0, 10, 11, 23]) + +# And see how many frames you have: +print(f"Selected episodes: {dataset.episodes}") +print(f"Number of episodes selected: {dataset.num_episodes}") +print(f"Number of frames selected: {dataset.num_frames}") + +# Or simply load the entire dataset: dataset = LeRobotDataset(repo_id) +print(f"Number of episodes selected: {dataset.num_episodes}") +print(f"Number of frames selected: {dataset.num_frames}") -# LeRobotDataset is actually a thin wrapper around an underlying Hugging Face dataset -# (see https://huggingface.co/docs/datasets/index for more information). -print(dataset) -print(dataset.hf_dataset) +# The previous metadata class is contained in the 'meta' attribute of the dataset: +print(dataset.meta) -# And provides additional utilities for robotics and compatibility with Pytorch -print(f"\naverage number of frames per episode: {dataset.num_samples / dataset.num_episodes:.3f}") -print(f"frames per second used during data collection: {dataset.fps=}") -print(f"keys to access images from cameras: {dataset.camera_keys=}\n") +# LeRobotDataset actually wraps an underlying Hugging Face dataset +# (see https://huggingface.co/docs/datasets for more information). +print(dataset.hf_dataset) -# Access frame indexes associated to first episode +# LeRobot datasets also subclasses PyTorch datasets so you can do everything you know and love from working +# with the latter, like iterating through the dataset. +# The __getitem__ iterates over the frames of the dataset. Since our datasets are also structured by +# episodes, you can access the frame indices of any episode using the episode_data_index. Here, we access +# frame indices associated to the first episode: episode_index = 0 from_idx = dataset.episode_data_index["from"][episode_index].item() to_idx = dataset.episode_data_index["to"][episode_index].item() -# LeRobot datasets actually subclass PyTorch datasets so you can do everything you know and love from working -# with the latter, like iterating through the dataset. Here we grab all the image frames. -frames = [dataset[idx]["observation.image"] for idx in range(from_idx, to_idx)] +# Then we grab all the image frames from the first camera: +camera_key = dataset.meta.camera_keys[0] +frames = [dataset[idx][camera_key] for idx in range(from_idx, to_idx)] -# Video frames are now float32 in range [0,1] channel first (c,h,w) to follow pytorch convention. To visualize -# them, we convert to uint8 in range [0,255] -frames = [(frame * 255).type(torch.uint8) for frame in frames] -# and to channel last (h,w,c). -frames = [frame.permute((1, 2, 0)).numpy() for frame in frames] +# The objects returned by the dataset are all torch.Tensors +print(type(frames[0])) +print(frames[0].shape) -# Finally, we save the frames to a mp4 video for visualization. -Path("outputs/examples/1_load_lerobot_dataset").mkdir(parents=True, exist_ok=True) -imageio.mimsave("outputs/examples/1_load_lerobot_dataset/episode_0.mp4", frames, fps=dataset.fps) +# Since we're using pytorch, the shape is in pytorch, channel-first convention (c, h, w). +# We can compare this shape with the information available for that feature +pprint(dataset.features[camera_key]) +# In particular: +print(dataset.features[camera_key]["shape"]) +# The shape is in (h, w, c) which is a more universal format. # For many machine learning applications we need to load the history of past observations or trajectories of # future actions. Our datasets can load previous and future frames for each key/modality, using timestamps # differences with the current loaded frame. For instance: delta_timestamps = { # loads 4 images: 1 second before current frame, 500 ms before, 200 ms before, and current frame - "observation.image": [-1, -0.5, -0.20, 0], - # loads 8 state vectors: 1.5 seconds before, 1 second before, ... 20 ms, 10 ms, and current frame - "observation.state": [-1.5, -1, -0.5, -0.20, -0.10, -0.02, -0.01, 0], + camera_key: [-1, -0.5, -0.20, 0], + # loads 8 state vectors: 1.5 seconds before, 1 second before, ... 200 ms, 100 ms, and current frame + "observation.state": [-1.5, -1, -0.5, -0.20, -0.10, 0], # loads 64 action vectors: current frame, 1 frame in the future, 2 frames, ... 63 frames in the future "action": [t / dataset.fps for t in range(64)], } +# Note that in any case, these delta_timestamps values need to be multiples of (1/fps) so that added to any +# timestamp, you still get a valid timestamp. + dataset = LeRobotDataset(repo_id, delta_timestamps=delta_timestamps) -print(f"\n{dataset[0]['observation.image'].shape=}") # (4,c,h,w) -print(f"{dataset[0]['observation.state'].shape=}") # (8,c) -print(f"{dataset[0]['action'].shape=}\n") # (64,c) +print(f"\n{dataset[0][camera_key].shape=}") # (4, c, h, w) +print(f"{dataset[0]['observation.state'].shape=}") # (6, c) +print(f"{dataset[0]['action'].shape=}\n") # (64, c) # Finally, our datasets are fully compatible with PyTorch dataloaders and samplers because they are just # PyTorch datasets. @@ -84,8 +126,9 @@ batch_size=32, shuffle=True, ) + for batch in dataloader: - print(f"{batch['observation.image'].shape=}") # (32,4,c,h,w) - print(f"{batch['observation.state'].shape=}") # (32,8,c) - print(f"{batch['action'].shape=}") # (32,64,c) + print(f"{batch[camera_key].shape=}") # (32, 4, c, h, w) + print(f"{batch['observation.state'].shape=}") # (32, 5, c) + print(f"{batch['action'].shape=}") # (32, 64, c) break diff --git a/examples/3_train_policy.py b/examples/3_train_policy.py index c5ce0d184..935ab2dbf 100644 --- a/examples/3_train_policy.py +++ b/examples/3_train_policy.py @@ -40,7 +40,7 @@ # For this example, no arguments need to be passed because the defaults are set up for PushT. # If you're doing something different, you will likely need to change at least some of the defaults. cfg = DiffusionConfig() -policy = DiffusionPolicy(cfg, dataset_stats=dataset.stats) +policy = DiffusionPolicy(cfg, dataset_stats=dataset.meta.stats) policy.train() policy.to(device) diff --git a/examples/6_add_image_transforms.py b/examples/6_add_image_transforms.py index bdcc6d7b9..82b70f5c1 100644 --- a/examples/6_add_image_transforms.py +++ b/examples/6_add_image_transforms.py @@ -1,7 +1,7 @@ """ This script demonstrates how to use torchvision's image transformation with LeRobotDataset for data augmentation purposes. The transformations are passed to the dataset as an argument upon creation, and -transforms are applied to the observation images before they are returned in the dataset's __get_item__. +transforms are applied to the observation images before they are returned in the dataset's __getitem__. """ from pathlib import Path @@ -20,7 +20,7 @@ first_idx = dataset.episode_data_index["from"][0].item() # Get the frame corresponding to the first camera -frame = dataset[first_idx][dataset.camera_keys[0]] +frame = dataset[first_idx][dataset.meta.camera_keys[0]] # Define the transformations @@ -36,7 +36,7 @@ transformed_dataset = LeRobotDataset(dataset_repo_id, image_transforms=transforms) # Get a frame from the transformed dataset -transformed_frame = transformed_dataset[first_idx][transformed_dataset.camera_keys[0]] +transformed_frame = transformed_dataset[first_idx][transformed_dataset.meta.camera_keys[0]] # Create a directory to store output images output_dir = Path("outputs/image_transforms") diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 9db7e2521..76408275d 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -778,7 +778,6 @@ Now run this to record 2 episodes: python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/koch.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/koch_test \ --tags tutorial \ --warmup-time-s 5 \ @@ -787,7 +786,7 @@ python lerobot/scripts/control_robot.py record \ --num-episodes 2 ``` -This will write your dataset locally to `{root}/{repo-id}` (e.g. `data/cadene/koch_test`) and push it on the hub at `https://huggingface.co/datasets/{HF_USER}/{repo-id}`. Your dataset will be automatically tagged with `LeRobot` for the community to find it easily, and you can also add custom tags (in this case `tutorial` for example). +This will write your dataset locally to `~/.cache/huggingface/lerobot/{repo-id}` (e.g. `data/cadene/koch_test`) and push it on the hub at `https://huggingface.co/datasets/{HF_USER}/{repo-id}`. Your dataset will be automatically tagged with `LeRobot` for the community to find it easily, and you can also add custom tags (in this case `tutorial` for example). You can look for other LeRobot datasets on the hub by searching for `LeRobot` tags: https://huggingface.co/datasets?other=LeRobot @@ -840,7 +839,6 @@ In the coming months, we plan to release a foundational model for robotics. We a You can visualize your dataset by running: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --root data \ --repo-id ${HF_USER}/koch_test ``` @@ -858,7 +856,6 @@ To replay the first episode of the dataset you just recorded, run the following python lerobot/scripts/control_robot.py replay \ --robot-path lerobot/configs/robot/koch.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/koch_test \ --episode 0 ``` @@ -871,7 +868,7 @@ Your robot should replicate movements similar to those you recorded. For example To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: ```bash -DATA_DIR=data python lerobot/scripts/train.py \ +python lerobot/scripts/train.py \ dataset_repo_id=${HF_USER}/koch_test \ policy=act_koch_real \ env=koch_real \ @@ -918,7 +915,6 @@ env: It should match your dataset (e.g. `fps: 30`) and your robot (e.g. `state_dim: 6` and `action_dim: 6`). We are still working on simplifying this in future versions of `lerobot`. 4. We provided `device=cuda` since we are training on a Nvidia GPU, but you could use `device=mps` to train on Apple silicon. 5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. -6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. For more information on the `train` script see the previous tutorial: [`examples/4_train_policy_with_script.md`](../examples/4_train_policy_with_script.md) @@ -991,7 +987,6 @@ To this end, you can use the `record` function from [`lerobot/scripts/control_ro python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/koch.yaml \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/eval_koch_test \ --tags tutorial eval \ --warmup-time-s 5 \ @@ -1010,7 +1005,6 @@ As you can see, it's almost the same command as previously used to record your t You can then visualize your evaluation dataset by running the same command as before but with the new inference dataset as argument: ```bash python lerobot/scripts/visualize_dataset.py \ - --root data \ --repo-id ${HF_USER}/eval_koch_test ``` diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md index 97caf2ba8..c2c306f07 100644 --- a/examples/8_use_stretch.md +++ b/examples/8_use_stretch.md @@ -128,7 +128,6 @@ Record one episode: python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/stretch.yaml \ --fps 20 \ - --root data \ --repo-id ${HF_USER}/stretch_test \ --tags stretch tutorial \ --warmup-time-s 3 \ @@ -146,7 +145,6 @@ Now try to replay this episode (make sure the robot's initial position is the sa python lerobot/scripts/control_robot.py replay \ --robot-path lerobot/configs/robot/stretch.yaml \ --fps 20 \ - --root data \ --repo-id ${HF_USER}/stretch_test \ --episode 0 ``` diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index cf5e1ceca..1abf7c495 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -84,7 +84,6 @@ python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/aloha.yaml \ --robot-overrides max_relative_target=null \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/aloha_test \ --tags aloha tutorial \ --warmup-time-s 5 \ @@ -104,7 +103,6 @@ echo ${HF_USER}/aloha_test If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --root data \ --repo-id ${HF_USER}/aloha_test ``` @@ -119,7 +117,6 @@ python lerobot/scripts/control_robot.py replay \ --robot-path lerobot/configs/robot/aloha.yaml \ --robot-overrides max_relative_target=null \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/aloha_test \ --episode 0 ``` @@ -128,7 +125,7 @@ python lerobot/scripts/control_robot.py replay \ To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: ```bash -DATA_DIR=data python lerobot/scripts/train.py \ +python lerobot/scripts/train.py \ dataset_repo_id=${HF_USER}/aloha_test \ policy=act_aloha_real \ env=aloha_real \ @@ -144,7 +141,6 @@ Let's explain it: 3. We provided an environment as argument with `env=aloha_real`. This loads configurations from [`lerobot/configs/env/aloha_real.yaml`](../lerobot/configs/env/aloha_real.yaml). Note: this yaml defines 18 dimensions for the `state_dim` and `action_dim`, corresponding to 18 motors, not 14 motors as used in previous Aloha work. This is because, we include the `shoulder_shadow` and `elbow_shadow` motors for simplicity. 4. We provided `device=cuda` since we are training on a Nvidia GPU. 5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. -6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. Training should take several hours. You will find checkpoints in `outputs/train/act_aloha_test/checkpoints`. @@ -156,7 +152,6 @@ python lerobot/scripts/control_robot.py record \ --robot-path lerobot/configs/robot/aloha.yaml \ --robot-overrides max_relative_target=null \ --fps 30 \ - --root data \ --repo-id ${HF_USER}/eval_act_aloha_test \ --tags aloha tutorial eval \ --warmup-time-s 5 \ diff --git a/examples/advanced/2_calculate_validation_loss.py b/examples/advanced/2_calculate_validation_loss.py index 1428014b6..00ba9930f 100644 --- a/examples/advanced/2_calculate_validation_loss.py +++ b/examples/advanced/2_calculate_validation_loss.py @@ -14,7 +14,7 @@ import torch from huggingface_hub import snapshot_download -from lerobot.common.datasets.lerobot_dataset import LeRobotDataset +from lerobot.common.datasets.lerobot_dataset import LeRobotDataset, LeRobotDatasetMetadata from lerobot.common.policies.diffusion.modeling_diffusion import DiffusionPolicy device = torch.device("cuda") @@ -41,26 +41,20 @@ } # Load the last 10% of episodes of the dataset as a validation set. -# - Load full dataset -full_dataset = LeRobotDataset("lerobot/pusht", split="train") -# - Calculate train and val subsets -num_train_episodes = math.floor(full_dataset.num_episodes * 90 / 100) -num_val_episodes = full_dataset.num_episodes - num_train_episodes -print(f"Number of episodes in full dataset: {full_dataset.num_episodes}") -print(f"Number of episodes in training dataset (90% subset): {num_train_episodes}") -print(f"Number of episodes in validation dataset (10% subset): {num_val_episodes}") -# - Get first frame index of the validation set -first_val_frame_index = full_dataset.episode_data_index["from"][num_train_episodes].item() -# - Load frames subset belonging to validation set using the `split` argument. -# It utilizes the `datasets` library's syntax for slicing datasets. -# For more information on the Slice API, please see: -# https://huggingface.co/docs/datasets/v2.19.0/loading#slice-splits -train_dataset = LeRobotDataset( - "lerobot/pusht", split=f"train[:{first_val_frame_index}]", delta_timestamps=delta_timestamps -) -val_dataset = LeRobotDataset( - "lerobot/pusht", split=f"train[{first_val_frame_index}:]", delta_timestamps=delta_timestamps -) +# - Load dataset metadata +dataset_metadata = LeRobotDatasetMetadata("lerobot/pusht") +# - Calculate train and val episodes +total_episodes = dataset_metadata.total_episodes +episodes = list(range(dataset_metadata.total_episodes)) +num_train_episodes = math.floor(total_episodes * 90 / 100) +train_episodes = episodes[:num_train_episodes] +val_episodes = episodes[num_train_episodes:] +print(f"Number of episodes in full dataset: {total_episodes}") +print(f"Number of episodes in training dataset (90% subset): {len(train_episodes)}") +print(f"Number of episodes in validation dataset (10% subset): {len(val_episodes)}") +# - Load train an val datasets +train_dataset = LeRobotDataset("lerobot/pusht", episodes=train_episodes, delta_timestamps=delta_timestamps) +val_dataset = LeRobotDataset("lerobot/pusht", episodes=val_episodes, delta_timestamps=delta_timestamps) print(f"Number of frames in training dataset (90% subset): {len(train_dataset)}") print(f"Number of frames in validation dataset (10% subset): {len(val_dataset)}") diff --git a/examples/port_datasets/pusht_zarr.py b/examples/port_datasets/pusht_zarr.py new file mode 100644 index 000000000..60df98405 --- /dev/null +++ b/examples/port_datasets/pusht_zarr.py @@ -0,0 +1,222 @@ +import shutil +from pathlib import Path + +import numpy as np +import torch + +from lerobot.common.datasets.lerobot_dataset import LEROBOT_HOME, LeRobotDataset +from lerobot.common.datasets.push_dataset_to_hub._download_raw import download_raw + +PUSHT_TASK = "Push the T-shaped blue block onto the T-shaped green target surface." +PUSHT_FEATURES = { + "observation.state": { + "dtype": "float32", + "shape": (2,), + "names": { + "axes": ["x", "y"], + }, + }, + "action": { + "dtype": "float32", + "shape": (2,), + "names": { + "axes": ["x", "y"], + }, + }, + "next.reward": { + "dtype": "float32", + "shape": (1,), + "names": None, + }, + "next.success": { + "dtype": "bool", + "shape": (1,), + "names": None, + }, + "observation.environment_state": { + "dtype": "float32", + "shape": (16,), + "names": [ + "keypoints", + ], + }, + "observation.image": { + "dtype": None, + "shape": (3, 96, 96), + "names": [ + "channel", + "height", + "width", + ], + }, +} + + +def build_features(mode: str) -> dict: + features = PUSHT_FEATURES + if mode == "keypoints": + features.pop("observation.image") + else: + features.pop("observation.environment_state") + features["observation.image"]["dtype"] = mode + + return features + + +def load_raw_dataset(zarr_path: Path): + try: + from lerobot.common.datasets.push_dataset_to_hub._diffusion_policy_replay_buffer import ( + ReplayBuffer as DiffusionPolicyReplayBuffer, + ) + except ModuleNotFoundError as e: + print("`gym_pusht` is not installed. Please install it with `pip install 'lerobot[gym_pusht]'`") + raise e + + zarr_data = DiffusionPolicyReplayBuffer.copy_from_path(zarr_path) + return zarr_data + + +def calculate_coverage(zarr_data): + try: + import pymunk + from gym_pusht.envs.pusht import PushTEnv, pymunk_to_shapely + except ModuleNotFoundError as e: + print("`gym_pusht` is not installed. Please install it with `pip install 'lerobot[gym_pusht]'`") + raise e + + block_pos = zarr_data["state"][:, 2:4] + block_angle = zarr_data["state"][:, 4] + + num_frames = len(block_pos) + + coverage = np.zeros((num_frames,)) + # 8 keypoints with 2 coords each + keypoints = np.zeros((num_frames, 16)) + + # Set x, y, theta (in radians) + goal_pos_angle = np.array([256, 256, np.pi / 4]) + goal_body = PushTEnv.get_goal_pose_body(goal_pos_angle) + + for i in range(num_frames): + space = pymunk.Space() + space.gravity = 0, 0 + space.damping = 0 + + # Add walls. + walls = [ + PushTEnv.add_segment(space, (5, 506), (5, 5), 2), + PushTEnv.add_segment(space, (5, 5), (506, 5), 2), + PushTEnv.add_segment(space, (506, 5), (506, 506), 2), + PushTEnv.add_segment(space, (5, 506), (506, 506), 2), + ] + space.add(*walls) + + block_body, block_shapes = PushTEnv.add_tee(space, block_pos[i].tolist(), block_angle[i].item()) + goal_geom = pymunk_to_shapely(goal_body, block_body.shapes) + block_geom = pymunk_to_shapely(block_body, block_body.shapes) + intersection_area = goal_geom.intersection(block_geom).area + goal_area = goal_geom.area + coverage[i] = intersection_area / goal_area + keypoints[i] = torch.from_numpy(PushTEnv.get_keypoints(block_shapes).flatten()) + + return coverage, keypoints + + +def calculate_success(coverage: float, success_threshold: float): + return coverage > success_threshold + + +def calculate_reward(coverage: float, success_threshold: float): + return np.clip(coverage / success_threshold, 0, 1) + + +def main(raw_dir: Path, repo_id: str, mode: str = "video", push_to_hub: bool = True): + if mode not in ["video", "image", "keypoints"]: + raise ValueError(mode) + + if (LEROBOT_HOME / repo_id).exists(): + shutil.rmtree(LEROBOT_HOME / repo_id) + + if not raw_dir.exists(): + download_raw(raw_dir, repo_id="lerobot-raw/pusht_raw") + + zarr_data = load_raw_dataset(zarr_path=raw_dir / "pusht_cchi_v7_replay.zarr") + + env_state = zarr_data["state"][:] + agent_pos = env_state[:, :2] + + action = zarr_data["action"][:] + image = zarr_data["img"] # (b, h, w, c) + + episode_data_index = { + "from": np.concatenate(([0], zarr_data.meta["episode_ends"][:-1])), + "to": zarr_data.meta["episode_ends"], + } + + # Calculate success and reward based on the overlapping area + # of the T-object and the T-area. + coverage, keypoints = calculate_coverage(zarr_data) + success = calculate_success(coverage, success_threshold=0.95) + reward = calculate_reward(coverage, success_threshold=0.95) + + features = build_features(mode) + dataset = LeRobotDataset.create( + repo_id=repo_id, + fps=10, + robot_type="2d pointer", + features=features, + image_writer_threads=4, + ) + episodes = range(len(episode_data_index["from"])) + for ep_idx in episodes: + from_idx = episode_data_index["from"][ep_idx] + to_idx = episode_data_index["to"][ep_idx] + num_frames = to_idx - from_idx + + for frame_idx in range(num_frames): + i = from_idx + frame_idx + frame = { + "action": torch.from_numpy(action[i]), + # Shift reward and success by +1 until the last item of the episode + "next.reward": reward[i + (frame_idx < num_frames - 1)], + "next.success": success[i + (frame_idx < num_frames - 1)], + } + + frame["observation.state"] = torch.from_numpy(agent_pos[i]) + + if mode == "keypoints": + frame["observation.environment_state"] = torch.from_numpy(keypoints[i]) + else: + frame["observation.image"] = torch.from_numpy(image[i]) + + dataset.add_frame(frame) + + dataset.save_episode(task=PUSHT_TASK) + + dataset.consolidate() + + if push_to_hub: + dataset.push_to_hub() + + +if __name__ == "__main__": + # To try this script, modify the repo id with your own HuggingFace user (e.g cadene/pusht) + repo_id = "lerobot/pusht" + + modes = ["video", "image", "keypoints"] + # Uncomment if you want to try with a specific mode + # modes = ["video"] + # modes = ["image"] + # modes = ["keypoints"] + + raw_dir = Path("data/lerobot-raw/pusht_raw") + for mode in modes: + if mode in ["image", "keypoints"]: + repo_id += f"_{mode}" + + # download and load raw dataset, create LeRobotDataset, populate it, push to hub + main(raw_dir, repo_id=repo_id, mode=mode) + + # Uncomment if you want to load the local dataset and explore it + # dataset = LeRobotDataset(repo_id=repo_id, local_files_only=True) + # breakpoint() diff --git a/lerobot/__init__.py b/lerobot/__init__.py index d462c7337..3d5bb6aaa 100644 --- a/lerobot/__init__.py +++ b/lerobot/__init__.py @@ -181,8 +181,8 @@ "lerobot/usc_cloth_sim", ] -available_datasets = list( - itertools.chain(*available_datasets_per_env.values(), available_real_world_datasets) +available_datasets = sorted( + set(itertools.chain(*available_datasets_per_env.values(), available_real_world_datasets)) ) # lists all available policies from `lerobot/common/policies` diff --git a/lerobot/common/datasets/card_template.md b/lerobot/common/datasets/card_template.md new file mode 100644 index 000000000..7ee27df95 --- /dev/null +++ b/lerobot/common/datasets/card_template.md @@ -0,0 +1,27 @@ +--- +# For reference on dataset card metadata, see the spec: https://github.com/huggingface/hub-docs/blob/main/datasetcard.md?plain=1 +# Doc / guide: https://huggingface.co/docs/hub/datasets-cards +{{ card_data }} +--- + +This dataset was created using [LeRobot](https://github.com/huggingface/lerobot). + +## Dataset Description + +{{ dataset_description | default("", true) }} + +- **Homepage:** {{ url | default("[More Information Needed]", true)}} +- **Paper:** {{ paper | default("[More Information Needed]", true)}} +- **License:** {{ license | default("[More Information Needed]", true)}} + +## Dataset Structure + +{{ dataset_structure | default("[More Information Needed]", true)}} + +## Citation + +**BibTeX:** + +```bibtex +{{ citation_bibtex | default("[More Information Needed]", true)}} +``` diff --git a/lerobot/common/datasets/compute_stats.py b/lerobot/common/datasets/compute_stats.py index bafac2e1e..c62116994 100644 --- a/lerobot/common/datasets/compute_stats.py +++ b/lerobot/common/datasets/compute_stats.py @@ -19,9 +19,6 @@ import einops import torch import tqdm -from datasets import Image - -from lerobot.common.datasets.video_utils import VideoFrame def get_stats_einops_patterns(dataset, num_workers=0): @@ -39,15 +36,13 @@ def get_stats_einops_patterns(dataset, num_workers=0): batch = next(iter(dataloader)) stats_patterns = {} - for key, feats_type in dataset.features.items(): - # NOTE: skip language_instruction embedding in stats computation - if key == "language_instruction": - continue + for key in dataset.features: # sanity check that tensors are not float64 assert batch[key].dtype != torch.float64 - if isinstance(feats_type, (VideoFrame, Image)): + # if isinstance(feats_type, (VideoFrame, Image)): + if key in dataset.meta.camera_keys: # sanity check that images are channel first _, c, h, w = batch[key].shape assert c < h and c < w, f"expect channel first images, but instead {batch[key].shape}" @@ -63,7 +58,7 @@ def get_stats_einops_patterns(dataset, num_workers=0): elif batch[key].ndim == 1: stats_patterns[key] = "b -> 1" else: - raise ValueError(f"{key}, {feats_type}, {batch[key].shape}") + raise ValueError(f"{key}, {batch[key].shape}") return stats_patterns @@ -175,39 +170,45 @@ def aggregate_stats(ls_datasets) -> dict[str, torch.Tensor]: """ data_keys = set() for dataset in ls_datasets: - data_keys.update(dataset.stats.keys()) + data_keys.update(dataset.meta.stats.keys()) stats = {k: {} for k in data_keys} for data_key in data_keys: for stat_key in ["min", "max"]: # compute `max(dataset_0["max"], dataset_1["max"], ...)` stats[data_key][stat_key] = einops.reduce( - torch.stack([d.stats[data_key][stat_key] for d in ls_datasets if data_key in d.stats], dim=0), + torch.stack( + [ds.meta.stats[data_key][stat_key] for ds in ls_datasets if data_key in ds.meta.stats], + dim=0, + ), "n ... -> ...", stat_key, ) - total_samples = sum(d.num_samples for d in ls_datasets if data_key in d.stats) + total_samples = sum(d.num_frames for d in ls_datasets if data_key in d.meta.stats) # Compute the "sum" statistic by multiplying each mean by the number of samples in the respective # dataset, then divide by total_samples to get the overall "mean". - # NOTE: the brackets around (d.num_samples / total_samples) are needed tor minimize the risk of + # NOTE: the brackets around (d.num_frames / total_samples) are needed tor minimize the risk of # numerical overflow! stats[data_key]["mean"] = sum( - d.stats[data_key]["mean"] * (d.num_samples / total_samples) + d.meta.stats[data_key]["mean"] * (d.num_frames / total_samples) for d in ls_datasets - if data_key in d.stats + if data_key in d.meta.stats ) # The derivation for standard deviation is a little more involved but is much in the same spirit as # the computation of the mean. # Given two sets of data where the statistics are known: # σ_combined = sqrt[ (n1 * (σ1^2 + d1^2) + n2 * (σ2^2 + d2^2)) / (n1 + n2) ] # where d1 = μ1 - μ_combined, d2 = μ2 - μ_combined - # NOTE: the brackets around (d.num_samples / total_samples) are needed tor minimize the risk of + # NOTE: the brackets around (d.num_frames / total_samples) are needed tor minimize the risk of # numerical overflow! stats[data_key]["std"] = torch.sqrt( sum( - (d.stats[data_key]["std"] ** 2 + (d.stats[data_key]["mean"] - stats[data_key]["mean"]) ** 2) - * (d.num_samples / total_samples) + ( + d.meta.stats[data_key]["std"] ** 2 + + (d.meta.stats[data_key]["mean"] - stats[data_key]["mean"]) ** 2 + ) + * (d.num_frames / total_samples) for d in ls_datasets - if data_key in d.stats + if data_key in d.meta.stats ) ) return stats diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 96a353fbf..f6164ed1d 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -91,9 +91,9 @@ def make_dataset(cfg, split: str = "train") -> LeRobotDataset | MultiLeRobotData ) if isinstance(cfg.dataset_repo_id, str): + # TODO (aliberts): add 'episodes' arg from config after removing hydra dataset = LeRobotDataset( cfg.dataset_repo_id, - split=split, delta_timestamps=cfg.training.get("delta_timestamps"), image_transforms=image_transforms, video_backend=cfg.video_backend, @@ -101,7 +101,6 @@ def make_dataset(cfg, split: str = "train") -> LeRobotDataset | MultiLeRobotData else: dataset = MultiLeRobotDataset( cfg.dataset_repo_id, - split=split, delta_timestamps=cfg.training.get("delta_timestamps"), image_transforms=image_transforms, video_backend=cfg.video_backend, @@ -112,6 +111,6 @@ def make_dataset(cfg, split: str = "train") -> LeRobotDataset | MultiLeRobotData for stats_type, listconfig in stats_dict.items(): # example of stats_type: min, max, mean, std stats = OmegaConf.to_container(listconfig, resolve=True) - dataset.stats[key][stats_type] = torch.tensor(stats, dtype=torch.float32) + dataset.meta.stats[key][stats_type] = torch.tensor(stats, dtype=torch.float32) return dataset diff --git a/lerobot/common/datasets/image_writer.py b/lerobot/common/datasets/image_writer.py new file mode 100644 index 000000000..9564fb591 --- /dev/null +++ b/lerobot/common/datasets/image_writer.py @@ -0,0 +1,160 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +import multiprocessing +import queue +import threading +from pathlib import Path + +import numpy as np +import PIL.Image +import torch + + +def safe_stop_image_writer(func): + def wrapper(*args, **kwargs): + try: + return func(*args, **kwargs) + except Exception as e: + dataset = kwargs.get("dataset", None) + image_writer = getattr(dataset, "image_writer", None) if dataset else None + if image_writer is not None: + print("Waiting for image writer to terminate...") + image_writer.stop() + raise e + + return wrapper + + +def image_array_to_image(image_array: np.ndarray) -> PIL.Image.Image: + # TODO(aliberts): handle 1 channel and 4 for depth images + if image_array.ndim == 3 and image_array.shape[0] in [1, 3]: + # Transpose from pytorch convention (C, H, W) to (H, W, C) + image_array = image_array.transpose(1, 2, 0) + if image_array.dtype != np.uint8: + # Assume the image is in [0, 1] range for floating-point data + image_array = np.clip(image_array, 0, 1) + image_array = (image_array * 255).astype(np.uint8) + return PIL.Image.fromarray(image_array) + + +def write_image(image: np.ndarray | PIL.Image.Image, fpath: Path): + try: + if isinstance(image, np.ndarray): + img = image_array_to_image(image) + elif isinstance(image, PIL.Image.Image): + img = image + else: + raise TypeError(f"Unsupported image type: {type(image)}") + img.save(fpath) + except Exception as e: + print(f"Error writing image {fpath}: {e}") + + +def worker_thread_loop(queue: queue.Queue): + while True: + item = queue.get() + if item is None: + queue.task_done() + break + image_array, fpath = item + write_image(image_array, fpath) + queue.task_done() + + +def worker_process(queue: queue.Queue, num_threads: int): + threads = [] + for _ in range(num_threads): + t = threading.Thread(target=worker_thread_loop, args=(queue,)) + t.daemon = True + t.start() + threads.append(t) + for t in threads: + t.join() + + +class AsyncImageWriter: + """ + This class abstract away the initialisation of processes or/and threads to + save images on disk asynchrounously, which is critical to control a robot and record data + at a high frame rate. + + When `num_processes=0`, it creates a threads pool of size `num_threads`. + When `num_processes>0`, it creates processes pool of size `num_processes`, where each subprocess starts + their own threads pool of size `num_threads`. + + The optimal number of processes and threads depends on your computer capabilities. + We advise to use 4 threads per camera with 0 processes. If the fps is not stable, try to increase or lower + the number of threads. If it is still not stable, try to use 1 subprocess, or more. + """ + + def __init__(self, num_processes: int = 0, num_threads: int = 1): + self.num_processes = num_processes + self.num_threads = num_threads + self.queue = None + self.threads = [] + self.processes = [] + self._stopped = False + + if num_threads <= 0 and num_processes <= 0: + raise ValueError("Number of threads and processes must be greater than zero.") + + if self.num_processes == 0: + # Use threading + self.queue = queue.Queue() + for _ in range(self.num_threads): + t = threading.Thread(target=worker_thread_loop, args=(self.queue,)) + t.daemon = True + t.start() + self.threads.append(t) + else: + # Use multiprocessing + self.queue = multiprocessing.JoinableQueue() + for _ in range(self.num_processes): + p = multiprocessing.Process(target=worker_process, args=(self.queue, self.num_threads)) + p.daemon = True + p.start() + self.processes.append(p) + + def save_image(self, image: torch.Tensor | np.ndarray | PIL.Image.Image, fpath: Path): + if isinstance(image, torch.Tensor): + # Convert tensor to numpy array to minimize main process time + image = image.cpu().numpy() + self.queue.put((image, fpath)) + + def wait_until_done(self): + self.queue.join() + + def stop(self): + if self._stopped: + return + + if self.num_processes == 0: + for _ in self.threads: + self.queue.put(None) + for t in self.threads: + t.join() + else: + num_nones = self.num_processes * self.num_threads + for _ in range(num_nones): + self.queue.put(None) + for p in self.processes: + p.join() + if p.is_alive(): + p.terminate() + self.queue.close() + self.queue.join_thread() + + self._stopped = True diff --git a/lerobot/common/datasets/lerobot_dataset.py b/lerobot/common/datasets/lerobot_dataset.py index eb76f78d6..b32cf7095 100644 --- a/lerobot/common/datasets/lerobot_dataset.py +++ b/lerobot/common/datasets/lerobot_dataset.py @@ -15,202 +15,946 @@ # limitations under the License. import logging import os +import shutil +from functools import cached_property from pathlib import Path from typing import Callable import datasets +import numpy as np +import PIL.Image import torch import torch.utils +from datasets import load_dataset +from huggingface_hub import create_repo, snapshot_download, upload_folder -from lerobot.common.datasets.compute_stats import aggregate_stats +from lerobot.common.datasets.compute_stats import aggregate_stats, compute_stats +from lerobot.common.datasets.image_writer import AsyncImageWriter, write_image from lerobot.common.datasets.utils import ( - calculate_episode_data_index, - load_episode_data_index, - load_hf_dataset, + DEFAULT_FEATURES, + DEFAULT_IMAGE_PATH, + EPISODES_PATH, + INFO_PATH, + STATS_PATH, + TASKS_PATH, + append_jsonlines, + check_delta_timestamps, + check_timestamps_sync, + check_version_compatibility, + create_branch, + create_empty_dataset_info, + create_lerobot_dataset_card, + get_delta_indices, + get_episode_data_index, + get_features_from_robot, + get_hf_features_from_features, + get_hub_safe_version, + hf_transform_to_torch, + load_episodes, load_info, - load_previous_and_future_frames, load_stats, - load_videos, - reset_episode_index, + load_tasks, + serialize_dict, + write_json, + write_parquet, ) -from lerobot.common.datasets.video_utils import VideoFrame, load_from_videos +from lerobot.common.datasets.video_utils import ( + VideoFrame, + decode_video_frames_torchvision, + encode_video_frames, + get_video_info, +) +from lerobot.common.robot_devices.robots.utils import Robot # For maintainers, see lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md -CODEBASE_VERSION = "v1.6" -DATA_DIR = Path(os.environ["DATA_DIR"]) if "DATA_DIR" in os.environ else None +CODEBASE_VERSION = "v2.0" +LEROBOT_HOME = Path(os.getenv("LEROBOT_HOME", "~/.cache/huggingface/lerobot")).expanduser() + + +class LeRobotDatasetMetadata: + def __init__( + self, + repo_id: str, + root: str | Path | None = None, + local_files_only: bool = False, + ): + self.repo_id = repo_id + self.root = Path(root) if root is not None else LEROBOT_HOME / repo_id + self.local_files_only = local_files_only + + # Load metadata + (self.root / "meta").mkdir(exist_ok=True, parents=True) + self.pull_from_repo(allow_patterns="meta/") + self.info = load_info(self.root) + self.stats = load_stats(self.root) + self.tasks = load_tasks(self.root) + self.episodes = load_episodes(self.root) + + def pull_from_repo( + self, + allow_patterns: list[str] | str | None = None, + ignore_patterns: list[str] | str | None = None, + ) -> None: + snapshot_download( + self.repo_id, + repo_type="dataset", + revision=self._hub_version, + local_dir=self.root, + allow_patterns=allow_patterns, + ignore_patterns=ignore_patterns, + local_files_only=self.local_files_only, + ) + + @cached_property + def _hub_version(self) -> str | None: + return None if self.local_files_only else get_hub_safe_version(self.repo_id, CODEBASE_VERSION) + + @property + def _version(self) -> str: + """Codebase version used to create this dataset.""" + return self.info["codebase_version"] + + def get_data_file_path(self, ep_index: int) -> Path: + ep_chunk = self.get_episode_chunk(ep_index) + fpath = self.data_path.format(episode_chunk=ep_chunk, episode_index=ep_index) + return Path(fpath) + + def get_video_file_path(self, ep_index: int, vid_key: str) -> Path: + ep_chunk = self.get_episode_chunk(ep_index) + fpath = self.video_path.format(episode_chunk=ep_chunk, video_key=vid_key, episode_index=ep_index) + return Path(fpath) + + def get_episode_chunk(self, ep_index: int) -> int: + return ep_index // self.chunks_size + + @property + def data_path(self) -> str: + """Formattable string for the parquet files.""" + return self.info["data_path"] + + @property + def video_path(self) -> str | None: + """Formattable string for the video files.""" + return self.info["video_path"] + + @property + def robot_type(self) -> str | None: + """Robot type used in recording this dataset.""" + return self.info["robot_type"] + + @property + def fps(self) -> int: + """Frames per second used during data collection.""" + return self.info["fps"] + + @property + def features(self) -> dict[str, dict]: + """All features contained in the dataset.""" + return self.info["features"] + + @property + def image_keys(self) -> list[str]: + """Keys to access visual modalities stored as images.""" + return [key for key, ft in self.features.items() if ft["dtype"] == "image"] + + @property + def video_keys(self) -> list[str]: + """Keys to access visual modalities stored as videos.""" + return [key for key, ft in self.features.items() if ft["dtype"] == "video"] + + @property + def camera_keys(self) -> list[str]: + """Keys to access visual modalities (regardless of their storage method).""" + return [key for key, ft in self.features.items() if ft["dtype"] in ["video", "image"]] + + @property + def names(self) -> dict[str, list | dict]: + """Names of the various dimensions of vector modalities.""" + return {key: ft["names"] for key, ft in self.features.items()} + + @property + def shapes(self) -> dict: + """Shapes for the different features.""" + return {key: tuple(ft["shape"]) for key, ft in self.features.items()} + + @property + def total_episodes(self) -> int: + """Total number of episodes available.""" + return self.info["total_episodes"] + + @property + def total_frames(self) -> int: + """Total number of frames saved in this dataset.""" + return self.info["total_frames"] + + @property + def total_tasks(self) -> int: + """Total number of different tasks performed in this dataset.""" + return self.info["total_tasks"] + + @property + def total_chunks(self) -> int: + """Total number of chunks (groups of episodes).""" + return self.info["total_chunks"] + + @property + def chunks_size(self) -> int: + """Max number of episodes per chunk.""" + return self.info["chunks_size"] + + @property + def task_to_task_index(self) -> dict: + return {task: task_idx for task_idx, task in self.tasks.items()} + + def get_task_index(self, task: str) -> int: + """ + Given a task in natural language, returns its task_index if the task already exists in the dataset, + otherwise creates a new task_index. + """ + task_index = self.task_to_task_index.get(task, None) + return task_index if task_index is not None else self.total_tasks + + def save_episode(self, episode_index: int, episode_length: int, task: str, task_index: int) -> None: + self.info["total_episodes"] += 1 + self.info["total_frames"] += episode_length + + if task_index not in self.tasks: + self.info["total_tasks"] += 1 + self.tasks[task_index] = task + task_dict = { + "task_index": task_index, + "task": task, + } + append_jsonlines(task_dict, self.root / TASKS_PATH) + + chunk = self.get_episode_chunk(episode_index) + if chunk >= self.total_chunks: + self.info["total_chunks"] += 1 + + self.info["splits"] = {"train": f"0:{self.info['total_episodes']}"} + self.info["total_videos"] += len(self.video_keys) + write_json(self.info, self.root / INFO_PATH) + + episode_dict = { + "episode_index": episode_index, + "tasks": [task], + "length": episode_length, + } + self.episodes.append(episode_dict) + append_jsonlines(episode_dict, self.root / EPISODES_PATH) + + # TODO(aliberts): refactor stats in save_episodes + # image_sampling = int(self.fps / 2) # sample 2 img/s for the stats + # ep_stats = compute_episode_stats(episode_buffer, self.features, episode_length, image_sampling=image_sampling) + # ep_stats = serialize_dict(ep_stats) + # append_jsonlines(ep_stats, self.root / STATS_PATH) + + def write_video_info(self) -> None: + """ + Warning: this function writes info from first episode videos, implicitly assuming that all videos have + been encoded the same way. Also, this means it assumes the first episode exists. + """ + for key in self.video_keys: + if not self.features[key].get("info", None): + video_path = self.root / self.get_video_file_path(ep_index=0, vid_key=key) + self.info["features"][key]["info"] = get_video_info(video_path) + + write_json(self.info, self.root / INFO_PATH) + + def __repr__(self): + feature_keys = list(self.features) + return ( + f"{self.__class__.__name__}({{\n" + f" Repository ID: '{self.repo_id}',\n" + f" Total episodes: '{self.total_episodes}',\n" + f" Total frames: '{self.total_frames}',\n" + f" Features: '{feature_keys}',\n" + "})',\n" + ) + + @classmethod + def create( + cls, + repo_id: str, + fps: int, + root: str | Path | None = None, + robot: Robot | None = None, + robot_type: str | None = None, + features: dict | None = None, + use_videos: bool = True, + ) -> "LeRobotDatasetMetadata": + """Creates metadata for a LeRobotDataset.""" + obj = cls.__new__(cls) + obj.repo_id = repo_id + obj.root = Path(root) if root is not None else LEROBOT_HOME / repo_id + + obj.root.mkdir(parents=True, exist_ok=False) + + if robot is not None: + features = get_features_from_robot(robot, use_videos) + robot_type = robot.robot_type + if not all(cam.fps == fps for cam in robot.cameras.values()): + logging.warning( + f"Some cameras in your {robot.robot_type} robot don't have an fps matching the fps of your dataset." + "In this case, frames from lower fps cameras will be repeated to fill in the blanks." + ) + elif features is None: + raise ValueError( + "Dataset features must either come from a Robot or explicitly passed upon creation." + ) + else: + # TODO(aliberts, rcadene): implement sanity check for features + features = {**features, **DEFAULT_FEATURES} + + obj.tasks, obj.stats, obj.episodes = {}, {}, [] + obj.info = create_empty_dataset_info(CODEBASE_VERSION, fps, robot_type, features, use_videos) + if len(obj.video_keys) > 0 and not use_videos: + raise ValueError() + write_json(obj.info, obj.root / INFO_PATH) + obj.local_files_only = True + return obj class LeRobotDataset(torch.utils.data.Dataset): def __init__( self, repo_id: str, - root: Path | None = DATA_DIR, - split: str = "train", + root: str | Path | None = None, + episodes: list[int] | None = None, image_transforms: Callable | None = None, delta_timestamps: dict[list[float]] | None = None, + tolerance_s: float = 1e-4, + download_videos: bool = True, + local_files_only: bool = False, video_backend: str | None = None, ): + """ + 2 modes are available for instantiating this class, depending on 2 different use cases: + + 1. Your dataset already exists: + - On your local disk in the 'root' folder. This is typically the case when you recorded your + dataset locally and you may or may not have pushed it to the hub yet. Instantiating this class + with 'root' will load your dataset directly from disk. This can happen while you're offline (no + internet connection), in that case, use local_files_only=True. + + - On the Hugging Face Hub at the address https://huggingface.co/datasets/{repo_id} and not on + your local disk in the 'root' folder. Instantiating this class with this 'repo_id' will download + the dataset from that address and load it, pending your dataset is compliant with + codebase_version v2.0. If your dataset has been created before this new format, you will be + prompted to convert it using our conversion script from v1.6 to v2.0, which you can find at + lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py. + + + 2. Your dataset doesn't already exists (either on local disk or on the Hub): you can create an empty + LeRobotDataset with the 'create' classmethod. This can be used for recording a dataset or port an + existing dataset to the LeRobotDataset format. + + + In terms of files, LeRobotDataset encapsulates 3 main things: + - metadata: + - info contains various information about the dataset like shapes, keys, fps etc. + - stats stores the dataset statistics of the different modalities for normalization + - tasks contains the prompts for each task of the dataset, which can be used for + task-conditionned training. + - hf_dataset (from datasets.Dataset), which will read any values from parquet files. + - videos (optional) from which frames are loaded to be synchronous with data from parquet files. + + A typical LeRobotDataset looks like this from its root path: + . + ├── data + │ ├── chunk-000 + │ │ ├── episode_000000.parquet + │ │ ├── episode_000001.parquet + │ │ ├── episode_000002.parquet + │ │ └── ... + │ ├── chunk-001 + │ │ ├── episode_001000.parquet + │ │ ├── episode_001001.parquet + │ │ ├── episode_001002.parquet + │ │ └── ... + │ └── ... + ├── meta + │ ├── episodes.jsonl + │ ├── info.json + │ ├── stats.json + │ └── tasks.jsonl + └── videos + ├── chunk-000 + │ ├── observation.images.laptop + │ │ ├── episode_000000.mp4 + │ │ ├── episode_000001.mp4 + │ │ ├── episode_000002.mp4 + │ │ └── ... + │ ├── observation.images.phone + │ │ ├── episode_000000.mp4 + │ │ ├── episode_000001.mp4 + │ │ ├── episode_000002.mp4 + │ │ └── ... + ├── chunk-001 + └── ... + + Note that this file-based structure is designed to be as versatile as possible. The files are split by + episodes which allows a more granular control over which episodes one wants to use and download. The + structure of the dataset is entirely described in the info.json file, which can be easily downloaded + or viewed directly on the hub before downloading any actual data. The type of files used are very + simple and do not need complex tools to be read, it only uses .parquet, .json and .mp4 files (and .md + for the README). + + Args: + repo_id (str): This is the repo id that will be used to fetch the dataset. Locally, the dataset + will be stored under root/repo_id. + root (Path | None, optional): Local directory to use for downloading/writing files. You can also + set the LEROBOT_HOME environment variable to point to a different location. Defaults to + '~/.cache/huggingface/lerobot'. + episodes (list[int] | None, optional): If specified, this will only load episodes specified by + their episode_index in this list. Defaults to None. + image_transforms (Callable | None, optional): You can pass standard v2 image transforms from + torchvision.transforms.v2 here which will be applied to visual modalities (whether they come + from videos or images). Defaults to None. + delta_timestamps (dict[list[float]] | None, optional): _description_. Defaults to None. + tolerance_s (float, optional): Tolerance in seconds used to ensure data timestamps are actually in + sync with the fps value. It is used at the init of the dataset to make sure that each + timestamps is separated to the next by 1/fps +/- tolerance_s. This also applies to frames + decoded from video files. It is also used to check that `delta_timestamps` (when provided) are + multiples of 1/fps. Defaults to 1e-4. + download_videos (bool, optional): Flag to download the videos. Note that when set to True but the + video files are already present on local disk, they won't be downloaded again. Defaults to + True. + local_files_only (bool, optional): Flag to use local files only. If True, no requests to the hub + will be made. Defaults to False. + video_backend (str | None, optional): Video backend to use for decoding videos. There is currently + a single option which is the pyav decoder used by Torchvision. Defaults to pyav. + """ super().__init__() self.repo_id = repo_id - self.root = root - self.split = split + self.root = Path(root) if root else LEROBOT_HOME / repo_id self.image_transforms = image_transforms self.delta_timestamps = delta_timestamps - # load data from hub or locally when root is provided + self.episodes = episodes + self.tolerance_s = tolerance_s + self.video_backend = video_backend if video_backend else "pyav" + self.delta_indices = None + self.local_files_only = local_files_only + + # Unused attributes + self.image_writer = None + self.episode_buffer = None + + self.root.mkdir(exist_ok=True, parents=True) + + # Load metadata + self.meta = LeRobotDatasetMetadata(self.repo_id, self.root, self.local_files_only) + + # Check version + check_version_compatibility(self.repo_id, self.meta._version, CODEBASE_VERSION) + + # Load actual data + self.download_episodes(download_videos) + self.hf_dataset = self.load_hf_dataset() + self.episode_data_index = get_episode_data_index(self.meta.episodes, self.episodes) + + # Check timestamps + check_timestamps_sync(self.hf_dataset, self.episode_data_index, self.fps, self.tolerance_s) + + # Setup delta_indices + if self.delta_timestamps is not None: + check_delta_timestamps(self.delta_timestamps, self.fps, self.tolerance_s) + self.delta_indices = get_delta_indices(self.delta_timestamps, self.fps) + + # Available stats implies all videos have been encoded and dataset is iterable + self.consolidated = self.meta.stats is not None + + def push_to_hub( + self, + tags: list | None = None, + license: str | None = "apache-2.0", + push_videos: bool = True, + private: bool = False, + **card_kwargs, + ) -> None: + if not self.consolidated: + logging.warning( + "You are trying to upload to the hub a LeRobotDataset that has not been consolidated yet. " + "Consolidating first." + ) + self.consolidate() + + ignore_patterns = ["images/"] + if not push_videos: + ignore_patterns.append("videos/") + + create_repo( + repo_id=self.repo_id, + private=private, + repo_type="dataset", + exist_ok=True, + ) + + upload_folder( + repo_id=self.repo_id, + folder_path=self.root, + repo_type="dataset", + ignore_patterns=ignore_patterns, + ) + card = create_lerobot_dataset_card( + tags=tags, dataset_info=self.meta.info, license=license, **card_kwargs + ) + card.push_to_hub(repo_id=self.repo_id, repo_type="dataset") + create_branch(repo_id=self.repo_id, branch=CODEBASE_VERSION, repo_type="dataset") + + def pull_from_repo( + self, + allow_patterns: list[str] | str | None = None, + ignore_patterns: list[str] | str | None = None, + ) -> None: + snapshot_download( + self.repo_id, + repo_type="dataset", + revision=self.meta._hub_version, + local_dir=self.root, + allow_patterns=allow_patterns, + ignore_patterns=ignore_patterns, + local_files_only=self.local_files_only, + ) + + def download_episodes(self, download_videos: bool = True) -> None: + """Downloads the dataset from the given 'repo_id' at the provided version. If 'episodes' is given, this + will only download those episodes (selected by their episode_index). If 'episodes' is None, the whole + dataset will be downloaded. Thanks to the behavior of snapshot_download, if the files are already present + in 'local_dir', they won't be downloaded again. + """ # TODO(rcadene, aliberts): implement faster transfer # https://huggingface.co/docs/huggingface_hub/en/guides/download#faster-downloads - self.hf_dataset = load_hf_dataset(repo_id, CODEBASE_VERSION, root, split) - if split == "train": - self.episode_data_index = load_episode_data_index(repo_id, CODEBASE_VERSION, root) + files = None + ignore_patterns = None if download_videos else "videos/" + if self.episodes is not None: + files = [str(self.meta.get_data_file_path(ep_idx)) for ep_idx in self.episodes] + if len(self.meta.video_keys) > 0 and download_videos: + video_files = [ + str(self.meta.get_video_file_path(ep_idx, vid_key)) + for vid_key in self.meta.video_keys + for ep_idx in self.episodes + ] + files += video_files + + self.pull_from_repo(allow_patterns=files, ignore_patterns=ignore_patterns) + + def load_hf_dataset(self) -> datasets.Dataset: + """hf_dataset contains all the observations, states, actions, rewards, etc.""" + if self.episodes is None: + path = str(self.root / "data") + hf_dataset = load_dataset("parquet", data_dir=path, split="train") else: - self.episode_data_index = calculate_episode_data_index(self.hf_dataset) - self.hf_dataset = reset_episode_index(self.hf_dataset) - self.stats = load_stats(repo_id, CODEBASE_VERSION, root) - self.info = load_info(repo_id, CODEBASE_VERSION, root) - if self.video: - self.videos_dir = load_videos(repo_id, CODEBASE_VERSION, root) - self.video_backend = video_backend if video_backend is not None else "pyav" + files = [str(self.root / self.meta.get_data_file_path(ep_idx)) for ep_idx in self.episodes] + hf_dataset = load_dataset("parquet", data_files=files, split="train") + + # TODO(aliberts): hf_dataset.set_format("torch") + hf_dataset.set_transform(hf_transform_to_torch) + + return hf_dataset @property def fps(self) -> int: """Frames per second used during data collection.""" - return self.info["fps"] + return self.meta.fps @property - def video(self) -> bool: - """Returns True if this dataset loads video frames from mp4 files. - Returns False if it only loads images from png files. - """ - return self.info.get("video", False) + def num_frames(self) -> int: + """Number of frames in selected episodes.""" + return len(self.hf_dataset) if self.hf_dataset is not None else self.meta.total_frames @property - def features(self) -> datasets.Features: - return self.hf_dataset.features + def num_episodes(self) -> int: + """Number of episodes selected.""" + return len(self.episodes) if self.episodes is not None else self.meta.total_episodes @property - def camera_keys(self) -> list[str]: - """Keys to access image and video stream from cameras.""" - keys = [] - for key, feats in self.hf_dataset.features.items(): - if isinstance(feats, (datasets.Image, VideoFrame)): - keys.append(key) - return keys + def features(self) -> dict[str, dict]: + return self.meta.features @property - def video_frame_keys(self) -> list[str]: - """Keys to access video frames that requires to be decoded into images. + def hf_features(self) -> datasets.Features: + """Features of the hf_dataset.""" + if self.hf_dataset is not None: + return self.hf_dataset.features + else: + return get_hf_features_from_features(self.features) - Note: It is empty if the dataset contains images only, - or equal to `self.cameras` if the dataset contains videos only, - or can even be a subset of `self.cameras` in a case of a mixed image/video dataset. - """ - video_frame_keys = [] - for key, feats in self.hf_dataset.features.items(): - if isinstance(feats, VideoFrame): - video_frame_keys.append(key) - return video_frame_keys + def _get_query_indices(self, idx: int, ep_idx: int) -> tuple[dict[str, list[int | bool]]]: + ep_start = self.episode_data_index["from"][ep_idx] + ep_end = self.episode_data_index["to"][ep_idx] + query_indices = { + key: [max(ep_start.item(), min(ep_end.item() - 1, idx + delta)) for delta in delta_idx] + for key, delta_idx in self.delta_indices.items() + } + padding = { # Pad values outside of current episode range + f"{key}_is_pad": torch.BoolTensor( + [(idx + delta < ep_start.item()) | (idx + delta >= ep_end.item()) for delta in delta_idx] + ) + for key, delta_idx in self.delta_indices.items() + } + return query_indices, padding - @property - def num_samples(self) -> int: - """Number of samples/frames.""" - return len(self.hf_dataset) + def _get_query_timestamps( + self, + current_ts: float, + query_indices: dict[str, list[int]] | None = None, + ) -> dict[str, list[float]]: + query_timestamps = {} + for key in self.meta.video_keys: + if query_indices is not None and key in query_indices: + timestamps = self.hf_dataset.select(query_indices[key])["timestamp"] + query_timestamps[key] = torch.stack(timestamps).tolist() + else: + query_timestamps[key] = [current_ts] - @property - def num_episodes(self) -> int: - """Number of episodes.""" - return len(self.hf_dataset.unique("episode_index")) + return query_timestamps - @property - def tolerance_s(self) -> float: - """Tolerance in seconds used to discard loaded frames when their timestamps - are not close enough from the requested frames. It is only used when `delta_timestamps` - is provided or when loading video frames from mp4 files. + def _query_hf_dataset(self, query_indices: dict[str, list[int]]) -> dict: + return { + key: torch.stack(self.hf_dataset.select(q_idx)[key]) + for key, q_idx in query_indices.items() + if key not in self.meta.video_keys + } + + def _query_videos(self, query_timestamps: dict[str, list[float]], ep_idx: int) -> dict: + """Note: When using data workers (e.g. DataLoader with num_workers>0), do not call this function + in the main process (e.g. by using a second Dataloader with num_workers=0). It will result in a + Segmentation Fault. This probably happens because a memory reference to the video loader is created in + the main process and a subprocess fails to access it. """ - # 1e-4 to account for possible numerical error - return 1 / self.fps - 1e-4 + item = {} + for vid_key, query_ts in query_timestamps.items(): + video_path = self.root / self.meta.get_video_file_path(ep_idx, vid_key) + frames = decode_video_frames_torchvision( + video_path, query_ts, self.tolerance_s, self.video_backend + ) + item[vid_key] = frames.squeeze(0) + + return item + + def _add_padding_keys(self, item: dict, padding: dict[str, list[bool]]) -> dict: + for key, val in padding.items(): + item[key] = torch.BoolTensor(val) + return item def __len__(self): - return self.num_samples + return self.num_frames - def __getitem__(self, idx): + def __getitem__(self, idx) -> dict: item = self.hf_dataset[idx] + ep_idx = item["episode_index"].item() - if self.delta_timestamps is not None: - item = load_previous_and_future_frames( - item, - self.hf_dataset, - self.episode_data_index, - self.delta_timestamps, - self.tolerance_s, - ) + query_indices = None + if self.delta_indices is not None: + current_ep_idx = self.episodes.index(ep_idx) if self.episodes is not None else ep_idx + query_indices, padding = self._get_query_indices(idx, current_ep_idx) + query_result = self._query_hf_dataset(query_indices) + item = {**item, **padding} + for key, val in query_result.items(): + item[key] = val - if self.video: - item = load_from_videos( - item, - self.video_frame_keys, - self.videos_dir, - self.tolerance_s, - self.video_backend, - ) + if len(self.meta.video_keys) > 0: + current_ts = item["timestamp"].item() + query_timestamps = self._get_query_timestamps(current_ts, query_indices) + video_frames = self._query_videos(query_timestamps, ep_idx) + item = {**video_frames, **item} if self.image_transforms is not None: - for cam in self.camera_keys: + image_keys = self.meta.camera_keys + for cam in image_keys: item[cam] = self.image_transforms(item[cam]) return item def __repr__(self): + feature_keys = list(self.features) return ( - f"{self.__class__.__name__}(\n" - f" Repository ID: '{self.repo_id}',\n" - f" Split: '{self.split}',\n" - f" Number of Samples: {self.num_samples},\n" - f" Number of Episodes: {self.num_episodes},\n" - f" Type: {'video (.mp4)' if self.video else 'image (.png)'},\n" - f" Recorded Frames per Second: {self.fps},\n" - f" Camera Keys: {self.camera_keys},\n" - f" Video Frame Keys: {self.video_frame_keys if self.video else 'N/A'},\n" - f" Transformations: {self.image_transforms},\n" - f" Codebase Version: {self.info.get('codebase_version', '< v1.6')},\n" - f")" + f"{self.__class__.__name__}({{\n" + f" Repository ID: '{self.repo_id}',\n" + f" Number of selected episodes: '{self.num_episodes}',\n" + f" Number of selected samples: '{self.num_frames}',\n" + f" Features: '{feature_keys}',\n" + "})',\n" + ) + + def create_episode_buffer(self, episode_index: int | None = None) -> dict: + current_ep_idx = self.meta.total_episodes if episode_index is None else episode_index + return { + "size": 0, + **{key: current_ep_idx if key == "episode_index" else [] for key in self.features}, + } + + def _get_image_file_path(self, episode_index: int, image_key: str, frame_index: int) -> Path: + fpath = DEFAULT_IMAGE_PATH.format( + image_key=image_key, episode_index=episode_index, frame_index=frame_index ) + return self.root / fpath + + def _save_image(self, image: torch.Tensor | np.ndarray | PIL.Image.Image, fpath: Path) -> None: + if self.image_writer is None: + if isinstance(image, torch.Tensor): + image = image.cpu().numpy() + write_image(image, fpath) + else: + self.image_writer.save_image(image=image, fpath=fpath) + + def add_frame(self, frame: dict) -> None: + """ + This function only adds the frame to the episode_buffer. Apart from images — which are written in a + temporary directory — nothing is written to disk. To save those frames, the 'save_episode()' method + then needs to be called. + """ + # TODO(aliberts, rcadene): Add sanity check for the input, check it's numpy or torch, + # check the dtype and shape matches, etc. + + if self.episode_buffer is None: + self.episode_buffer = self.create_episode_buffer() + + frame_index = self.episode_buffer["size"] + timestamp = frame.pop("timestamp") if "timestamp" in frame else frame_index / self.fps + self.episode_buffer["frame_index"].append(frame_index) + self.episode_buffer["timestamp"].append(timestamp) + + for key in frame: + if key not in self.features: + raise ValueError(key) + + if self.features[key]["dtype"] not in ["image", "video"]: + item = frame[key].numpy() if isinstance(frame[key], torch.Tensor) else frame[key] + self.episode_buffer[key].append(item) + elif self.features[key]["dtype"] in ["image", "video"]: + img_path = self._get_image_file_path( + episode_index=self.episode_buffer["episode_index"], image_key=key, frame_index=frame_index + ) + if frame_index == 0: + img_path.parent.mkdir(parents=True, exist_ok=True) + self._save_image(frame[key], img_path) + self.episode_buffer[key].append(str(img_path)) + + self.episode_buffer["size"] += 1 + + def save_episode(self, task: str, encode_videos: bool = True, episode_data: dict | None = None) -> None: + """ + This will save to disk the current episode in self.episode_buffer. Note that since it affects files on + disk, it sets self.consolidated to False to ensure proper consolidation later on before uploading to + the hub. + + Use 'encode_videos' if you want to encode videos during the saving of this episode. Otherwise, + you can do it later with dataset.consolidate(). This is to give more flexibility on when to spend + time for video encoding. + """ + if not episode_data: + episode_buffer = self.episode_buffer + + episode_length = episode_buffer.pop("size") + episode_index = episode_buffer["episode_index"] + if episode_index != self.meta.total_episodes: + # TODO(aliberts): Add option to use existing episode_index + raise NotImplementedError( + "You might have manually provided the episode_buffer with an episode_index that doesn't " + "match the total number of episodes in the dataset. This is not supported for now." + ) + + if episode_length == 0: + raise ValueError( + "You must add one or several frames with `add_frame` before calling `add_episode`." + ) + + task_index = self.meta.get_task_index(task) + + if not set(episode_buffer.keys()) == set(self.features): + raise ValueError() + + for key, ft in self.features.items(): + if key == "index": + episode_buffer[key] = np.arange( + self.meta.total_frames, self.meta.total_frames + episode_length + ) + elif key == "episode_index": + episode_buffer[key] = np.full((episode_length,), episode_index) + elif key == "task_index": + episode_buffer[key] = np.full((episode_length,), task_index) + elif ft["dtype"] in ["image", "video"]: + continue + elif len(ft["shape"]) == 1 and ft["shape"][0] == 1: + episode_buffer[key] = np.array(episode_buffer[key], dtype=ft["dtype"]) + elif len(ft["shape"]) == 1 and ft["shape"][0] > 1: + episode_buffer[key] = np.stack(episode_buffer[key]) + else: + raise ValueError(key) + + self._wait_image_writer() + self._save_episode_table(episode_buffer, episode_index) + + self.meta.save_episode(episode_index, episode_length, task, task_index) + + if encode_videos and len(self.meta.video_keys) > 0: + video_paths = self.encode_episode_videos(episode_index) + for key in self.meta.video_keys: + episode_buffer[key] = video_paths[key] + + if not episode_data: # Reset the buffer + self.episode_buffer = self.create_episode_buffer() + + self.consolidated = False + + def _save_episode_table(self, episode_buffer: dict, episode_index: int) -> None: + episode_dict = {key: episode_buffer[key] for key in self.hf_features} + ep_dataset = datasets.Dataset.from_dict(episode_dict, features=self.hf_features, split="train") + ep_data_path = self.root / self.meta.get_data_file_path(ep_index=episode_index) + ep_data_path.parent.mkdir(parents=True, exist_ok=True) + write_parquet(ep_dataset, ep_data_path) + + def clear_episode_buffer(self) -> None: + episode_index = self.episode_buffer["episode_index"] + if self.image_writer is not None: + for cam_key in self.meta.camera_keys: + img_dir = self._get_image_file_path( + episode_index=episode_index, image_key=cam_key, frame_index=0 + ).parent + if img_dir.is_dir(): + shutil.rmtree(img_dir) + + # Reset the buffer + self.episode_buffer = self.create_episode_buffer() + + def start_image_writer(self, num_processes: int = 0, num_threads: int = 4) -> None: + if isinstance(self.image_writer, AsyncImageWriter): + logging.warning( + "You are starting a new AsyncImageWriter that is replacing an already existing one in the dataset." + ) + + self.image_writer = AsyncImageWriter( + num_processes=num_processes, + num_threads=num_threads, + ) + + def stop_image_writer(self) -> None: + """ + Whenever wrapping this dataset inside a parallelized DataLoader, this needs to be called first to + remove the image_write in order for the LeRobotDataset object to be pickleable and parallelized. + """ + if self.image_writer is not None: + self.image_writer.stop() + self.image_writer = None + + def _wait_image_writer(self) -> None: + """Wait for asynchronous image writer to finish.""" + if self.image_writer is not None: + self.image_writer.wait_until_done() + + def encode_videos(self) -> None: + """ + Use ffmpeg to convert frames stored as png into mp4 videos. + Note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, + since video encoding with ffmpeg is already using multithreading. + """ + for ep_idx in range(self.meta.total_episodes): + self.encode_episode_videos(ep_idx) + + def encode_episode_videos(self, episode_index: int) -> dict: + """ + Use ffmpeg to convert frames stored as png into mp4 videos. + Note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, + since video encoding with ffmpeg is already using multithreading. + """ + video_paths = {} + for key in self.meta.video_keys: + video_path = self.root / self.meta.get_video_file_path(episode_index, key) + video_paths[key] = str(video_path) + if video_path.is_file(): + # Skip if video is already encoded. Could be the case when resuming data recording. + continue + img_dir = self._get_image_file_path( + episode_index=episode_index, image_key=key, frame_index=0 + ).parent + encode_video_frames(img_dir, video_path, self.fps, overwrite=True) + + return video_paths + + def consolidate(self, run_compute_stats: bool = True, keep_image_files: bool = False) -> None: + self.hf_dataset = self.load_hf_dataset() + self.episode_data_index = get_episode_data_index(self.meta.episodes, self.episodes) + check_timestamps_sync(self.hf_dataset, self.episode_data_index, self.fps, self.tolerance_s) + + if len(self.meta.video_keys) > 0: + self.encode_videos() + self.meta.write_video_info() + + if not keep_image_files: + img_dir = self.root / "images" + if img_dir.is_dir(): + shutil.rmtree(self.root / "images") + + video_files = list(self.root.rglob("*.mp4")) + assert len(video_files) == self.num_episodes * len(self.meta.video_keys) + + parquet_files = list(self.root.rglob("*.parquet")) + assert len(parquet_files) == self.num_episodes + + if run_compute_stats: + self.stop_image_writer() + # TODO(aliberts): refactor stats in save_episodes + self.meta.stats = compute_stats(self) + serialized_stats = serialize_dict(self.meta.stats) + write_json(serialized_stats, self.root / STATS_PATH) + self.consolidated = True + else: + logging.warning( + "Skipping computation of the dataset statistics, dataset is not fully consolidated." + ) @classmethod - def from_preloaded( + def create( cls, - repo_id: str = "from_preloaded", - root: Path | None = None, - split: str = "train", - transform: callable = None, - delta_timestamps: dict[list[float]] | None = None, - # additional preloaded attributes - hf_dataset=None, - episode_data_index=None, - stats=None, - info=None, - videos_dir=None, - video_backend=None, + repo_id: str, + fps: int, + root: str | Path | None = None, + robot: Robot | None = None, + robot_type: str | None = None, + features: dict | None = None, + use_videos: bool = True, + tolerance_s: float = 1e-4, + image_writer_processes: int = 0, + image_writer_threads: int = 0, + video_backend: str | None = None, ) -> "LeRobotDataset": - """Create a LeRobot Dataset from existing data and attributes instead of loading from the filesystem. + """Create a LeRobot Dataset from scratch in order to record data.""" + obj = cls.__new__(cls) + obj.meta = LeRobotDatasetMetadata.create( + repo_id=repo_id, + fps=fps, + root=root, + robot=robot, + robot_type=robot_type, + features=features, + use_videos=use_videos, + ) + obj.repo_id = obj.meta.repo_id + obj.root = obj.meta.root + obj.local_files_only = obj.meta.local_files_only + obj.tolerance_s = tolerance_s + obj.image_writer = None - It is especially useful when converting raw data into LeRobotDataset before saving the dataset - on the filesystem or uploading to the hub. + if image_writer_processes or image_writer_threads: + obj.start_image_writer(image_writer_processes, image_writer_threads) - Note: Meta-data attributes like `repo_id`, `version`, `root`, etc are optional and potentially - meaningless depending on the downstream usage of the return dataset. - """ - # create an empty object of type LeRobotDataset - obj = cls.__new__(cls) - obj.repo_id = repo_id - obj.root = root - obj.split = split - obj.image_transforms = transform - obj.delta_timestamps = delta_timestamps - obj.hf_dataset = hf_dataset - obj.episode_data_index = episode_data_index - obj.stats = stats - obj.info = info if info is not None else {} - obj.videos_dir = videos_dir + # TODO(aliberts, rcadene, alexander-soare): Merge this with OnlineBuffer/DataBuffer + obj.episode_buffer = obj.create_episode_buffer() + + # This bool indicates that the current LeRobotDataset instance is in sync with the files on disk. It + # is used to know when certain operations are need (for instance, computing dataset statistics). In + # order to be able to push the dataset to the hub, it needs to be consolidated first by calling + # self.consolidate(). + obj.consolidated = True + + obj.episodes = None + obj.hf_dataset = None + obj.image_transforms = None + obj.delta_timestamps = None + obj.delta_indices = None + obj.episode_data_index = None obj.video_backend = video_backend if video_backend is not None else "pyav" return obj @@ -225,57 +969,56 @@ class MultiLeRobotDataset(torch.utils.data.Dataset): def __init__( self, repo_ids: list[str], - root: Path | None = DATA_DIR, - split: str = "train", + root: str | Path | None = None, + episodes: dict | None = None, image_transforms: Callable | None = None, delta_timestamps: dict[list[float]] | None = None, + tolerances_s: dict | None = None, + download_videos: bool = True, + local_files_only: bool = False, video_backend: str | None = None, ): super().__init__() self.repo_ids = repo_ids + self.root = Path(root) if root else LEROBOT_HOME + self.tolerances_s = tolerances_s if tolerances_s else {repo_id: 1e-4 for repo_id in repo_ids} # Construct the underlying datasets passing everything but `transform` and `delta_timestamps` which # are handled by this class. self._datasets = [ LeRobotDataset( repo_id, - root=root, - split=split, - delta_timestamps=delta_timestamps, + root=self.root / repo_id, + episodes=episodes[repo_id] if episodes else None, image_transforms=image_transforms, + delta_timestamps=delta_timestamps, + tolerance_s=self.tolerances_s[repo_id], + download_videos=download_videos, + local_files_only=local_files_only, video_backend=video_backend, ) for repo_id in repo_ids ] - # Check that some properties are consistent across datasets. Note: We may relax some of these - # consistency requirements in future iterations of this class. - for repo_id, dataset in zip(self.repo_ids, self._datasets, strict=True): - if dataset.info != self._datasets[0].info: - raise ValueError( - f"Detected a mismatch in dataset info between {self.repo_ids[0]} and {repo_id}. This is " - "not yet supported." - ) + # Disable any data keys that are not common across all of the datasets. Note: we may relax this # restriction in future iterations of this class. For now, this is necessary at least for being able # to use PyTorch's default DataLoader collate function. - self.disabled_data_keys = set() - intersection_data_keys = set(self._datasets[0].hf_dataset.features) - for dataset in self._datasets: - intersection_data_keys.intersection_update(dataset.hf_dataset.features) - if len(intersection_data_keys) == 0: + self.disabled_features = set() + intersection_features = set(self._datasets[0].features) + for ds in self._datasets: + intersection_features.intersection_update(ds.features) + if len(intersection_features) == 0: raise RuntimeError( - "Multiple datasets were provided but they had no keys common to all of them. The " - "multi-dataset functionality currently only keeps common keys." + "Multiple datasets were provided but they had no keys common to all of them. " + "The multi-dataset functionality currently only keeps common keys." ) - for repo_id, dataset in zip(self.repo_ids, self._datasets, strict=True): - extra_keys = set(dataset.hf_dataset.features).difference(intersection_data_keys) + for repo_id, ds in zip(self.repo_ids, self._datasets, strict=True): + extra_keys = set(ds.features).difference(intersection_features) logging.warning( f"keys {extra_keys} of {repo_id} were disabled as they are not contained in all the " "other datasets." ) - self.disabled_data_keys.update(extra_keys) + self.disabled_features.update(extra_keys) - self.root = root - self.split = split self.image_transforms = image_transforms self.delta_timestamps = delta_timestamps self.stats = aggregate_stats(self._datasets) @@ -299,7 +1042,7 @@ def fps(self) -> int: NOTE: Fow now, this relies on a check in __init__ to make sure all sub-datasets have the same info. """ - return self._datasets[0].info["fps"] + return self._datasets[0].meta.info["fps"] @property def video(self) -> bool: @@ -309,13 +1052,13 @@ def video(self) -> bool: NOTE: Fow now, this relies on a check in __init__ to make sure all sub-datasets have the same info. """ - return self._datasets[0].info.get("video", False) + return self._datasets[0].meta.info.get("video", False) @property def features(self) -> datasets.Features: features = {} for dataset in self._datasets: - features.update({k: v for k, v in dataset.features.items() if k not in self.disabled_data_keys}) + features.update({k: v for k, v in dataset.hf_features.items() if k not in self.disabled_features}) return features @property @@ -342,9 +1085,9 @@ def video_frame_keys(self) -> list[str]: return video_frame_keys @property - def num_samples(self) -> int: + def num_frames(self) -> int: """Number of samples/frames.""" - return sum(d.num_samples for d in self._datasets) + return sum(d.num_frames for d in self._datasets) @property def num_episodes(self) -> int: @@ -361,7 +1104,7 @@ def tolerance_s(self) -> float: return 1 / self.fps - 1e-4 def __len__(self): - return self.num_samples + return self.num_frames def __getitem__(self, idx: int) -> dict[str, torch.Tensor]: if idx >= len(self): @@ -370,8 +1113,8 @@ def __getitem__(self, idx: int) -> dict[str, torch.Tensor]: start_idx = 0 dataset_idx = 0 for dataset in self._datasets: - if idx >= start_idx + dataset.num_samples: - start_idx += dataset.num_samples + if idx >= start_idx + dataset.num_frames: + start_idx += dataset.num_frames dataset_idx += 1 continue break @@ -379,7 +1122,7 @@ def __getitem__(self, idx: int) -> dict[str, torch.Tensor]: raise AssertionError("We expect the loop to break out as long as the index is within bounds.") item = self._datasets[dataset_idx][idx - start_idx] item["dataset_index"] = torch.tensor(dataset_idx) - for data_key in self.disabled_data_keys: + for data_key in self.disabled_features: if data_key in item: del item[data_key] @@ -389,8 +1132,7 @@ def __repr__(self): return ( f"{self.__class__.__name__}(\n" f" Repository IDs: '{self.repo_ids}',\n" - f" Split: '{self.split}',\n" - f" Number of Samples: {self.num_samples},\n" + f" Number of Samples: {self.num_frames},\n" f" Number of Episodes: {self.num_episodes},\n" f" Type: {'video (.mp4)' if self.video else 'image (.png)'},\n" f" Recorded Frames per Second: {self.fps},\n" diff --git a/lerobot/common/datasets/online_buffer.py b/lerobot/common/datasets/online_buffer.py index 6b093cda7..d907e4687 100644 --- a/lerobot/common/datasets/online_buffer.py +++ b/lerobot/common/datasets/online_buffer.py @@ -187,7 +187,7 @@ def add_data(self, data: dict[str, np.ndarray]): assert data[OnlineBuffer.INDEX_KEY][0].item() == 0 # Shift the incoming indices if necessary. - if self.num_samples > 0: + if self.num_frames > 0: last_episode_index = self._data[OnlineBuffer.EPISODE_INDEX_KEY][next_index - 1] last_data_index = self._data[OnlineBuffer.INDEX_KEY][next_index - 1] data[OnlineBuffer.EPISODE_INDEX_KEY] += last_episode_index + 1 @@ -227,11 +227,11 @@ def num_episodes(self) -> int: ) @property - def num_samples(self) -> int: + def num_frames(self) -> int: return np.count_nonzero(self._data[OnlineBuffer.OCCUPANCY_MASK_KEY]) def __len__(self): - return self.num_samples + return self.num_frames def _item_to_tensors(self, item: dict) -> dict: item_ = {} diff --git a/lerobot/common/datasets/populate_dataset.py b/lerobot/common/datasets/populate_dataset.py deleted file mode 100644 index df5d20e56..000000000 --- a/lerobot/common/datasets/populate_dataset.py +++ /dev/null @@ -1,468 +0,0 @@ -"""Functions to create an empty dataset, and populate it with frames.""" -# TODO(rcadene, aliberts): to adapt as class methods of next version of LeRobotDataset - -import concurrent -import json -import logging -import multiprocessing -import shutil -from pathlib import Path - -import torch -import tqdm -from PIL import Image - -from lerobot.common.datasets.compute_stats import compute_stats -from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION, LeRobotDataset -from lerobot.common.datasets.push_dataset_to_hub.aloha_hdf5_format import to_hf_dataset -from lerobot.common.datasets.push_dataset_to_hub.utils import concatenate_episodes, get_default_encoding -from lerobot.common.datasets.utils import calculate_episode_data_index, create_branch -from lerobot.common.datasets.video_utils import encode_video_frames -from lerobot.common.utils.utils import log_say -from lerobot.scripts.push_dataset_to_hub import ( - push_dataset_card_to_hub, - push_meta_data_to_hub, - push_videos_to_hub, - save_meta_data, -) - -######################################################################################## -# Asynchrounous saving of images on disk -######################################################################################## - - -def safe_stop_image_writer(func): - # TODO(aliberts): Allow to pass custom exceptions - # (e.g. ThreadServiceExit, KeyboardInterrupt, SystemExit, UnpluggedError, DynamixelCommError) - def wrapper(*args, **kwargs): - try: - return func(*args, **kwargs) - except Exception as e: - image_writer = kwargs.get("dataset", {}).get("image_writer") - if image_writer is not None: - print("Waiting for image writer to terminate...") - stop_image_writer(image_writer, timeout=20) - raise e - - return wrapper - - -def save_image(img_tensor, key, frame_index, episode_index, videos_dir: str): - img = Image.fromarray(img_tensor.numpy()) - path = Path(videos_dir) / f"{key}_episode_{episode_index:06d}" / f"frame_{frame_index:06d}.png" - path.parent.mkdir(parents=True, exist_ok=True) - img.save(str(path), quality=100) - - -def loop_to_save_images_in_threads(image_queue, num_threads): - if num_threads < 1: - raise NotImplementedError(f"Only `num_threads>=1` is supported for now, but {num_threads=} given.") - - with concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) as executor: - futures = [] - while True: - # Blocks until a frame is available - frame_data = image_queue.get() - - # As usually done, exit loop when receiving None to stop the worker - if frame_data is None: - break - - image, key, frame_index, episode_index, videos_dir = frame_data - futures.append(executor.submit(save_image, image, key, frame_index, episode_index, videos_dir)) - - # Before exiting function, wait for all threads to complete - with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: - concurrent.futures.wait(futures) - progress_bar.update(len(futures)) - - -def start_image_writer_processes(image_queue, num_processes, num_threads_per_process): - if num_processes < 1: - raise ValueError(f"Only `num_processes>=1` is supported, but {num_processes=} given.") - - if num_threads_per_process < 1: - raise NotImplementedError( - "Only `num_threads_per_process>=1` is supported for now, but {num_threads_per_process=} given." - ) - - processes = [] - for _ in range(num_processes): - process = multiprocessing.Process( - target=loop_to_save_images_in_threads, - args=(image_queue, num_threads_per_process), - ) - process.start() - processes.append(process) - return processes - - -def stop_processes(processes, queue, timeout): - # Send None to each process to signal them to stop - for _ in processes: - queue.put(None) - - # Wait maximum 20 seconds for all processes to terminate - for process in processes: - process.join(timeout=timeout) - - # If not terminated after 20 seconds, force termination - if process.is_alive(): - process.terminate() - - # Close the queue, no more items can be put in the queue - queue.close() - - # Ensure all background queue threads have finished - queue.join_thread() - - -def start_image_writer(num_processes, num_threads): - """This function abstract away the initialisation of processes or/and threads to - save images on disk asynchrounously, which is critical to control a robot and record data - at a high frame rate. - - When `num_processes=0`, it returns a dictionary containing a threads pool of size `num_threads`. - When `num_processes>0`, it returns a dictionary containing a processes pool of size `num_processes`, - where each subprocess starts their own threads pool of size `num_threads`. - - The optimal number of processes and threads depends on your computer capabilities. - We advise to use 4 threads per camera with 0 processes. If the fps is not stable, try to increase or lower - the number of threads. If it is still not stable, try to use 1 subprocess, or more. - """ - image_writer = {} - - if num_processes == 0: - futures = [] - threads_pool = concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) - image_writer["threads_pool"], image_writer["futures"] = threads_pool, futures - else: - # TODO(rcadene): When using num_processes>1, `multiprocessing.Manager().Queue()` - # might be better than `multiprocessing.Queue()`. Source: https://www.geeksforgeeks.org/python-multiprocessing-queue-vs-multiprocessing-manager-queue - image_queue = multiprocessing.Queue() - processes_pool = start_image_writer_processes( - image_queue, num_processes=num_processes, num_threads_per_process=num_threads - ) - image_writer["processes_pool"], image_writer["image_queue"] = processes_pool, image_queue - - return image_writer - - -def async_save_image(image_writer, image, key, frame_index, episode_index, videos_dir): - """This function abstract away the saving of an image on disk asynchrounously. It uses a dictionary - called image writer which contains either a pool of processes or a pool of threads. - """ - if "threads_pool" in image_writer: - threads_pool, futures = image_writer["threads_pool"], image_writer["futures"] - futures.append(threads_pool.submit(save_image, image, key, frame_index, episode_index, videos_dir)) - else: - image_queue = image_writer["image_queue"] - image_queue.put((image, key, frame_index, episode_index, videos_dir)) - - -def stop_image_writer(image_writer, timeout): - if "threads_pool" in image_writer: - futures = image_writer["futures"] - # Before exiting function, wait for all threads to complete - with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: - concurrent.futures.wait(futures, timeout=timeout) - progress_bar.update(len(futures)) - else: - processes_pool, image_queue = image_writer["processes_pool"], image_writer["image_queue"] - stop_processes(processes_pool, image_queue, timeout=timeout) - - -######################################################################################## -# Functions to initialize, resume and populate a dataset -######################################################################################## - - -def init_dataset( - repo_id, - root, - force_override, - fps, - video, - write_images, - num_image_writer_processes, - num_image_writer_threads, -): - local_dir = Path(root) / repo_id - if local_dir.exists() and force_override: - shutil.rmtree(local_dir) - - episodes_dir = local_dir / "episodes" - episodes_dir.mkdir(parents=True, exist_ok=True) - - videos_dir = local_dir / "videos" - videos_dir.mkdir(parents=True, exist_ok=True) - - # Logic to resume data recording - rec_info_path = episodes_dir / "data_recording_info.json" - if rec_info_path.exists(): - with open(rec_info_path) as f: - rec_info = json.load(f) - num_episodes = rec_info["last_episode_index"] + 1 - else: - num_episodes = 0 - - dataset = { - "repo_id": repo_id, - "local_dir": local_dir, - "videos_dir": videos_dir, - "episodes_dir": episodes_dir, - "fps": fps, - "video": video, - "rec_info_path": rec_info_path, - "num_episodes": num_episodes, - } - - if write_images: - # Initialize processes or/and threads dedicated to save images on disk asynchronously, - # which is critical to control a robot and record data at a high frame rate. - image_writer = start_image_writer( - num_processes=num_image_writer_processes, - num_threads=num_image_writer_threads, - ) - dataset["image_writer"] = image_writer - - return dataset - - -def add_frame(dataset, observation, action): - if "current_episode" not in dataset: - # initialize episode dictionary - ep_dict = {} - for key in observation: - if key not in ep_dict: - ep_dict[key] = [] - for key in action: - if key not in ep_dict: - ep_dict[key] = [] - - ep_dict["episode_index"] = [] - ep_dict["frame_index"] = [] - ep_dict["timestamp"] = [] - ep_dict["next.done"] = [] - - dataset["current_episode"] = ep_dict - dataset["current_frame_index"] = 0 - - ep_dict = dataset["current_episode"] - episode_index = dataset["num_episodes"] - frame_index = dataset["current_frame_index"] - videos_dir = dataset["videos_dir"] - video = dataset["video"] - fps = dataset["fps"] - - ep_dict["episode_index"].append(episode_index) - ep_dict["frame_index"].append(frame_index) - ep_dict["timestamp"].append(frame_index / fps) - ep_dict["next.done"].append(False) - - img_keys = [key for key in observation if "image" in key] - non_img_keys = [key for key in observation if "image" not in key] - - # Save all observed modalities except images - for key in non_img_keys: - ep_dict[key].append(observation[key]) - - # Save actions - for key in action: - ep_dict[key].append(action[key]) - - if "image_writer" not in dataset: - dataset["current_frame_index"] += 1 - return - - # Save images - image_writer = dataset["image_writer"] - for key in img_keys: - imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - async_save_image( - image_writer, - image=observation[key], - key=key, - frame_index=frame_index, - episode_index=episode_index, - videos_dir=str(videos_dir), - ) - - if video: - fname = f"{key}_episode_{episode_index:06d}.mp4" - frame_info = {"path": f"videos/{fname}", "timestamp": frame_index / fps} - else: - frame_info = str(imgs_dir / f"frame_{frame_index:06d}.png") - - ep_dict[key].append(frame_info) - - dataset["current_frame_index"] += 1 - - -def delete_current_episode(dataset): - del dataset["current_episode"] - del dataset["current_frame_index"] - - # delete temporary images - episode_index = dataset["num_episodes"] - videos_dir = dataset["videos_dir"] - for tmp_imgs_dir in videos_dir.glob(f"*_episode_{episode_index:06d}"): - shutil.rmtree(tmp_imgs_dir) - - -def save_current_episode(dataset): - episode_index = dataset["num_episodes"] - ep_dict = dataset["current_episode"] - episodes_dir = dataset["episodes_dir"] - rec_info_path = dataset["rec_info_path"] - - ep_dict["next.done"][-1] = True - - for key in ep_dict: - if "observation" in key and "image" not in key: - ep_dict[key] = torch.stack(ep_dict[key]) - - ep_dict["action"] = torch.stack(ep_dict["action"]) - ep_dict["episode_index"] = torch.tensor(ep_dict["episode_index"]) - ep_dict["frame_index"] = torch.tensor(ep_dict["frame_index"]) - ep_dict["timestamp"] = torch.tensor(ep_dict["timestamp"]) - ep_dict["next.done"] = torch.tensor(ep_dict["next.done"]) - - ep_path = episodes_dir / f"episode_{episode_index}.pth" - torch.save(ep_dict, ep_path) - - rec_info = { - "last_episode_index": episode_index, - } - with open(rec_info_path, "w") as f: - json.dump(rec_info, f) - - # force re-initialization of episode dictionnary during add_frame - del dataset["current_episode"] - - dataset["num_episodes"] += 1 - - -def encode_videos(dataset, image_keys, play_sounds): - log_say("Encoding videos", play_sounds) - - num_episodes = dataset["num_episodes"] - videos_dir = dataset["videos_dir"] - local_dir = dataset["local_dir"] - fps = dataset["fps"] - - # Use ffmpeg to convert frames stored as png into mp4 videos - for episode_index in tqdm.tqdm(range(num_episodes)): - for key in image_keys: - # key = f"observation.images.{name}" - tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - fname = f"{key}_episode_{episode_index:06d}.mp4" - video_path = local_dir / "videos" / fname - if video_path.exists(): - # Skip if video is already encoded. Could be the case when resuming data recording. - continue - # note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, - # since video encoding with ffmpeg is already using multithreading. - encode_video_frames(tmp_imgs_dir, video_path, fps, overwrite=True) - shutil.rmtree(tmp_imgs_dir) - - -def from_dataset_to_lerobot_dataset(dataset, play_sounds): - log_say("Consolidate episodes", play_sounds) - - num_episodes = dataset["num_episodes"] - episodes_dir = dataset["episodes_dir"] - videos_dir = dataset["videos_dir"] - video = dataset["video"] - fps = dataset["fps"] - repo_id = dataset["repo_id"] - - ep_dicts = [] - for episode_index in tqdm.tqdm(range(num_episodes)): - ep_path = episodes_dir / f"episode_{episode_index}.pth" - ep_dict = torch.load(ep_path) - ep_dicts.append(ep_dict) - data_dict = concatenate_episodes(ep_dicts) - - if video: - image_keys = [key for key in data_dict if "image" in key] - encode_videos(dataset, image_keys, play_sounds) - - hf_dataset = to_hf_dataset(data_dict, video) - episode_data_index = calculate_episode_data_index(hf_dataset) - - info = { - "codebase_version": CODEBASE_VERSION, - "fps": fps, - "video": video, - } - if video: - info["encoding"] = get_default_encoding() - - lerobot_dataset = LeRobotDataset.from_preloaded( - repo_id=repo_id, - hf_dataset=hf_dataset, - episode_data_index=episode_data_index, - info=info, - videos_dir=videos_dir, - ) - - return lerobot_dataset - - -def save_lerobot_dataset_on_disk(lerobot_dataset): - hf_dataset = lerobot_dataset.hf_dataset - info = lerobot_dataset.info - stats = lerobot_dataset.stats - episode_data_index = lerobot_dataset.episode_data_index - local_dir = lerobot_dataset.videos_dir.parent - meta_data_dir = local_dir / "meta_data" - - hf_dataset = hf_dataset.with_format(None) # to remove transforms that cant be saved - hf_dataset.save_to_disk(str(local_dir / "train")) - - save_meta_data(info, stats, episode_data_index, meta_data_dir) - - -def push_lerobot_dataset_to_hub(lerobot_dataset, tags): - hf_dataset = lerobot_dataset.hf_dataset - local_dir = lerobot_dataset.videos_dir.parent - videos_dir = lerobot_dataset.videos_dir - repo_id = lerobot_dataset.repo_id - video = lerobot_dataset.video - meta_data_dir = local_dir / "meta_data" - - if not (local_dir / "train").exists(): - raise ValueError( - "You need to run `save_lerobot_dataset_on_disk(lerobot_dataset)` before pushing to the hub." - ) - - hf_dataset.push_to_hub(repo_id, revision="main") - push_meta_data_to_hub(repo_id, meta_data_dir, revision="main") - push_dataset_card_to_hub(repo_id, revision="main", tags=tags) - if video: - push_videos_to_hub(repo_id, videos_dir, revision="main") - create_branch(repo_id, repo_type="dataset", branch=CODEBASE_VERSION) - - -def create_lerobot_dataset(dataset, run_compute_stats, push_to_hub, tags, play_sounds): - if "image_writer" in dataset: - logging.info("Waiting for image writer to terminate...") - image_writer = dataset["image_writer"] - stop_image_writer(image_writer, timeout=20) - - lerobot_dataset = from_dataset_to_lerobot_dataset(dataset, play_sounds) - - if run_compute_stats: - log_say("Computing dataset statistics", play_sounds) - lerobot_dataset.stats = compute_stats(lerobot_dataset) - else: - logging.info("Skipping computation of the dataset statistics") - lerobot_dataset.stats = {} - - save_lerobot_dataset_on_disk(lerobot_dataset) - - if push_to_hub: - push_lerobot_dataset_to_hub(lerobot_dataset, tags) - - return lerobot_dataset diff --git a/lerobot/common/datasets/push_dataset_to_hub/aloha_hdf5_format.py b/lerobot/common/datasets/push_dataset_to_hub/aloha_hdf5_format.py index 52c4bba3d..e2973ef81 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/aloha_hdf5_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/aloha_hdf5_format.py @@ -30,12 +30,12 @@ from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, concatenate_episodes, get_default_encoding, save_images_concurrently, ) from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame, encode_video_frames diff --git a/lerobot/common/datasets/push_dataset_to_hub/cam_png_format.py b/lerobot/common/datasets/push_dataset_to_hub/cam_png_format.py index be20c92cd..264925766 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/cam_png_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/cam_png_format.py @@ -24,8 +24,11 @@ from PIL import Image as PILImage from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION -from lerobot.common.datasets.push_dataset_to_hub.utils import concatenate_episodes -from lerobot.common.datasets.utils import calculate_episode_data_index, hf_transform_to_torch +from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, + concatenate_episodes, +) +from lerobot.common.datasets.utils import hf_transform_to_torch from lerobot.common.datasets.video_utils import VideoFrame diff --git a/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py b/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py index 72be130e3..95f9c0071 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py @@ -26,8 +26,8 @@ from datasets import Dataset, Features, Image, Sequence, Value from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION +from lerobot.common.datasets.push_dataset_to_hub.utils import calculate_episode_data_index from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame diff --git a/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py b/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py index f5744c521..cfe115034 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py @@ -42,12 +42,12 @@ from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION from lerobot.common.datasets.push_dataset_to_hub.openx.transforms import OPENX_STANDARDIZATION_TRANSFORMS from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, concatenate_episodes, get_default_encoding, save_images_concurrently, ) from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame, encode_video_frames diff --git a/lerobot/common/datasets/push_dataset_to_hub/pusht_zarr_format.py b/lerobot/common/datasets/push_dataset_to_hub/pusht_zarr_format.py index 13d6c837e..27b31ba24 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/pusht_zarr_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/pusht_zarr_format.py @@ -27,12 +27,12 @@ from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, concatenate_episodes, get_default_encoding, save_images_concurrently, ) from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame, encode_video_frames diff --git a/lerobot/common/datasets/push_dataset_to_hub/umi_zarr_format.py b/lerobot/common/datasets/push_dataset_to_hub/umi_zarr_format.py index d724cf33e..fec893a7f 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/umi_zarr_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/umi_zarr_format.py @@ -28,12 +28,12 @@ from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION from lerobot.common.datasets.push_dataset_to_hub._umi_imagecodecs_numcodecs import register_codecs from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, concatenate_episodes, get_default_encoding, save_images_concurrently, ) from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame, encode_video_frames diff --git a/lerobot/common/datasets/push_dataset_to_hub/utils.py b/lerobot/common/datasets/push_dataset_to_hub/utils.py index 97b54e45b..ebcf87f77 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/utils.py +++ b/lerobot/common/datasets/push_dataset_to_hub/utils.py @@ -16,7 +16,9 @@ import inspect from concurrent.futures import ThreadPoolExecutor from pathlib import Path +from typing import Dict +import datasets import numpy import PIL import torch @@ -72,3 +74,58 @@ def check_repo_id(repo_id: str) -> None: f"""`repo_id` is expected to contain a community or user id `/` the name of the dataset (e.g. 'lerobot/pusht'), but contains '{repo_id}'.""" ) + + +# TODO(aliberts): remove +def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> Dict[str, torch.Tensor]: + """ + Calculate episode data index for the provided HuggingFace Dataset. Relies on episode_index column of hf_dataset. + + Parameters: + - hf_dataset (datasets.Dataset): A HuggingFace dataset containing the episode index. + + Returns: + - episode_data_index: A dictionary containing the data index for each episode. The dictionary has two keys: + - "from": A tensor containing the starting index of each episode. + - "to": A tensor containing the ending index of each episode. + """ + episode_data_index = {"from": [], "to": []} + + current_episode = None + """ + The episode_index is a list of integers, each representing the episode index of the corresponding example. + For instance, the following is a valid episode_index: + [0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 2] + + Below, we iterate through the episode_index and populate the episode_data_index dictionary with the starting and + ending index of each episode. For the episode_index above, the episode_data_index dictionary will look like this: + { + "from": [0, 3, 7], + "to": [3, 7, 12] + } + """ + if len(hf_dataset) == 0: + episode_data_index = { + "from": torch.tensor([]), + "to": torch.tensor([]), + } + return episode_data_index + for idx, episode_idx in enumerate(hf_dataset["episode_index"]): + if episode_idx != current_episode: + # We encountered a new episode, so we append its starting location to the "from" list + episode_data_index["from"].append(idx) + # If this is not the first episode, we append the ending location of the previous episode to the "to" list + if current_episode is not None: + episode_data_index["to"].append(idx) + # Let's keep track of the current episode index + current_episode = episode_idx + else: + # We are still in the same episode, so there is nothing for us to do here + pass + # We have reached the end of the dataset, so we append the ending location of the last episode to the "to" list + episode_data_index["to"].append(idx + 1) + + for k in ["from", "to"]: + episode_data_index[k] = torch.tensor(episode_data_index[k]) + + return episode_data_index diff --git a/lerobot/common/datasets/push_dataset_to_hub/xarm_pkl_format.py b/lerobot/common/datasets/push_dataset_to_hub/xarm_pkl_format.py index ad1cb560e..0047e48c3 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/xarm_pkl_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/xarm_pkl_format.py @@ -27,12 +27,12 @@ from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION from lerobot.common.datasets.push_dataset_to_hub.utils import ( + calculate_episode_data_index, concatenate_episodes, get_default_encoding, save_images_concurrently, ) from lerobot.common.datasets.utils import ( - calculate_episode_data_index, hf_transform_to_torch, ) from lerobot.common.datasets.video_utils import VideoFrame, encode_video_frames diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index d6aef15f5..5f088b118 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -14,30 +14,56 @@ # See the License for the specific language governing permissions and # limitations under the License. import json -import re -import warnings -from functools import cache +import logging +import textwrap +from itertools import accumulate from pathlib import Path -from typing import Dict +from pprint import pformat +from typing import Any import datasets +import jsonlines +import numpy as np +import pyarrow.compute as pc import torch -from datasets import load_dataset, load_from_disk -from huggingface_hub import DatasetCard, HfApi, hf_hub_download, snapshot_download +from datasets.table import embed_table_storage +from huggingface_hub import DatasetCard, DatasetCardData, HfApi from PIL import Image as PILImage -from safetensors.torch import load_file from torchvision import transforms +from lerobot.common.robot_devices.robots.utils import Robot + +DEFAULT_CHUNK_SIZE = 1000 # Max number of episodes per chunk + +INFO_PATH = "meta/info.json" +EPISODES_PATH = "meta/episodes.jsonl" +STATS_PATH = "meta/stats.json" +TASKS_PATH = "meta/tasks.jsonl" + +DEFAULT_VIDEO_PATH = "videos/chunk-{episode_chunk:03d}/{video_key}/episode_{episode_index:06d}.mp4" +DEFAULT_PARQUET_PATH = "data/chunk-{episode_chunk:03d}/episode_{episode_index:06d}.parquet" +DEFAULT_IMAGE_PATH = "images/{image_key}/episode_{episode_index:06d}/frame_{frame_index:06d}.png" + DATASET_CARD_TEMPLATE = """ --- # Metadata will go there --- This dataset was created using [LeRobot](https://github.com/huggingface/lerobot). +## {} + """ +DEFAULT_FEATURES = { + "timestamp": {"dtype": "float32", "shape": (1,), "names": None}, + "frame_index": {"dtype": "int64", "shape": (1,), "names": None}, + "episode_index": {"dtype": "int64", "shape": (1,), "names": None}, + "index": {"dtype": "int64", "shape": (1,), "names": None}, + "task_index": {"dtype": "int64", "shape": (1,), "names": None}, +} + -def flatten_dict(d, parent_key="", sep="/"): +def flatten_dict(d: dict, parent_key: str = "", sep: str = "/") -> dict: """Flatten a nested dictionary structure by collapsing nested keys into one key with a separator. For example: @@ -56,7 +82,7 @@ def flatten_dict(d, parent_key="", sep="/"): return dict(items) -def unflatten_dict(d, sep="/"): +def unflatten_dict(d: dict, sep: str = "/") -> dict: outdict = {} for key, value in d.items(): parts = key.split(sep) @@ -69,6 +95,82 @@ def unflatten_dict(d, sep="/"): return outdict +def serialize_dict(stats: dict[str, torch.Tensor | np.ndarray | dict]) -> dict: + serialized_dict = {key: value.tolist() for key, value in flatten_dict(stats).items()} + return unflatten_dict(serialized_dict) + + +def write_parquet(dataset: datasets.Dataset, fpath: Path) -> None: + # Embed image bytes into the table before saving to parquet + format = dataset.format + dataset = dataset.with_format("arrow") + dataset = dataset.map(embed_table_storage, batched=False) + dataset = dataset.with_format(**format) + dataset.to_parquet(fpath) + + +def load_json(fpath: Path) -> Any: + with open(fpath) as f: + return json.load(f) + + +def write_json(data: dict, fpath: Path) -> None: + fpath.parent.mkdir(exist_ok=True, parents=True) + with open(fpath, "w") as f: + json.dump(data, f, indent=4, ensure_ascii=False) + + +def load_jsonlines(fpath: Path) -> list[Any]: + with jsonlines.open(fpath, "r") as reader: + return list(reader) + + +def write_jsonlines(data: dict, fpath: Path) -> None: + fpath.parent.mkdir(exist_ok=True, parents=True) + with jsonlines.open(fpath, "w") as writer: + writer.write_all(data) + + +def append_jsonlines(data: dict, fpath: Path) -> None: + fpath.parent.mkdir(exist_ok=True, parents=True) + with jsonlines.open(fpath, "a") as writer: + writer.write(data) + + +def load_info(local_dir: Path) -> dict: + info = load_json(local_dir / INFO_PATH) + for ft in info["features"].values(): + ft["shape"] = tuple(ft["shape"]) + return info + + +def load_stats(local_dir: Path) -> dict: + if not (local_dir / STATS_PATH).exists(): + return None + stats = load_json(local_dir / STATS_PATH) + stats = {key: torch.tensor(value) for key, value in flatten_dict(stats).items()} + return unflatten_dict(stats) + + +def load_tasks(local_dir: Path) -> dict: + tasks = load_jsonlines(local_dir / TASKS_PATH) + return {item["task_index"]: item["task"] for item in sorted(tasks, key=lambda x: x["task_index"])} + + +def load_episodes(local_dir: Path) -> dict: + return load_jsonlines(local_dir / EPISODES_PATH) + + +def load_image_as_numpy(fpath: str | Path, dtype="float32", channel_first: bool = True) -> np.ndarray: + img = PILImage.open(fpath).convert("RGB") + img_array = np.array(img, dtype=dtype) + if channel_first: # (H, W, C) -> (C, H, W) + img_array = np.transpose(img_array, (2, 0, 1)) + if "float" in dtype: + img_array /= 255.0 + return img_array + + def hf_transform_to_torch(items_dict: dict[torch.Tensor | None]): """Get a transform function that convert items from Hugging Face dataset (pyarrow) to torch tensors. Importantly, images are converted from PIL, which corresponds to @@ -80,14 +182,6 @@ def hf_transform_to_torch(items_dict: dict[torch.Tensor | None]): if isinstance(first_item, PILImage.Image): to_tensor = transforms.ToTensor() items_dict[key] = [to_tensor(img) for img in items_dict[key]] - elif isinstance(first_item, str): - # TODO (michel-aractingi): add str2embedding via language tokenizer - # For now we leave this part up to the user to choose how to address - # language conditioned tasks - pass - elif isinstance(first_item, dict) and "path" in first_item and "timestamp" in first_item: - # video frame will be processed downstream - pass elif first_item is None: pass else: @@ -95,19 +189,67 @@ def hf_transform_to_torch(items_dict: dict[torch.Tensor | None]): return items_dict -@cache -def get_hf_dataset_safe_version(repo_id: str, version: str) -> str: +def _get_major_minor(version: str) -> tuple[int]: + split = version.strip("v").split(".") + return int(split[0]), int(split[1]) + + +class BackwardCompatibilityError(Exception): + def __init__(self, repo_id, version): + message = textwrap.dedent(f""" + BackwardCompatibilityError: The dataset you requested ({repo_id}) is in {version} format. + + We introduced a new format since v2.0 which is not backward compatible with v1.x. + Please, use our conversion script. Modify the following command with your own task description: + ``` + python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \\ + --repo-id {repo_id} \\ + --single-task "TASK DESCRIPTION." # <---- /!\\ Replace TASK DESCRIPTION /!\\ + ``` + + A few examples to replace TASK DESCRIPTION: "Pick up the blue cube and place it into the bin.", + "Insert the peg into the socket.", "Slide open the ziploc bag.", "Take the elevator to the 1st floor.", + "Open the top cabinet, store the pot inside it then close the cabinet.", "Push the T-shaped block onto the T-shaped target.", + "Grab the spray paint on the shelf and place it in the bin on top of the robot dog.", "Fold the sweatshirt.", ... + + If you encounter a problem, contact LeRobot maintainers on [Discord](https://discord.com/invite/s3KuuzsPFb) + or open an [issue on GitHub](https://github.com/huggingface/lerobot/issues/new/choose). + """) + super().__init__(message) + + +def check_version_compatibility( + repo_id: str, version_to_check: str, current_version: str, enforce_breaking_major: bool = True +) -> None: + current_major, _ = _get_major_minor(current_version) + major_to_check, _ = _get_major_minor(version_to_check) + if major_to_check < current_major and enforce_breaking_major: + raise BackwardCompatibilityError(repo_id, version_to_check) + elif float(version_to_check.strip("v")) < float(current_version.strip("v")): + logging.warning( + f"""The dataset you requested ({repo_id}) was created with a previous version ({version_to_check}) of the + codebase. The current codebase version is {current_version}. You should be fine since + backward compatibility is maintained. If you encounter a problem, contact LeRobot maintainers on + Discord ('https://discord.com/invite/s3KuuzsPFb') or open an issue on github.""", + ) + + +def get_hub_safe_version(repo_id: str, version: str) -> str: api = HfApi() dataset_info = api.list_repo_refs(repo_id, repo_type="dataset") branches = [b.name for b in dataset_info.branches] if version not in branches: - warnings.warn( + num_version = float(version.strip("v")) + hub_num_versions = [float(v.strip("v")) for v in branches if v.startswith("v")] + if num_version >= 2.0 and all(v < 2.0 for v in hub_num_versions): + raise BackwardCompatibilityError(repo_id, version) + + logging.warning( f"""You are trying to load a dataset from {repo_id} created with a previous version of the codebase. The following versions are available: {branches}. The requested version ('{version}') is not found. You should be fine since backward compatibility is maintained. If you encounter a problem, contact LeRobot maintainers on Discord ('https://discord.com/invite/s3KuuzsPFb') or open an issue on github.""", - stacklevel=1, ) if "main" not in branches: raise ValueError(f"Version 'main' not found on {repo_id}") @@ -116,275 +258,184 @@ def get_hf_dataset_safe_version(repo_id: str, version: str) -> str: return version -def load_hf_dataset(repo_id: str, version: str, root: Path, split: str) -> datasets.Dataset: - """hf_dataset contains all the observations, states, actions, rewards, etc.""" - if root is not None: - hf_dataset = load_from_disk(str(Path(root) / repo_id / "train")) - # TODO(rcadene): clean this which enables getting a subset of dataset - if split != "train": - if "%" in split: - raise NotImplementedError(f"We dont support splitting based on percentage for now ({split}).") - match_from = re.search(r"train\[(\d+):\]", split) - match_to = re.search(r"train\[:(\d+)\]", split) - if match_from: - from_frame_index = int(match_from.group(1)) - hf_dataset = hf_dataset.select(range(from_frame_index, len(hf_dataset))) - elif match_to: - to_frame_index = int(match_to.group(1)) - hf_dataset = hf_dataset.select(range(to_frame_index)) - else: - raise ValueError( - f'`split` ({split}) should either be "train", "train[INT:]", or "train[:INT]"' - ) - else: - safe_version = get_hf_dataset_safe_version(repo_id, version) - hf_dataset = load_dataset(repo_id, revision=safe_version, split=split) - - hf_dataset.set_transform(hf_transform_to_torch) - return hf_dataset - - -def load_episode_data_index(repo_id, version, root) -> dict[str, torch.Tensor]: - """episode_data_index contains the range of indices for each episode - - Example: - ```python - from_id = episode_data_index["from"][episode_id].item() - to_id = episode_data_index["to"][episode_id].item() - episode_frames = [dataset[i] for i in range(from_id, to_id)] - ``` - """ - if root is not None: - path = Path(root) / repo_id / "meta_data" / "episode_data_index.safetensors" - else: - safe_version = get_hf_dataset_safe_version(repo_id, version) - path = hf_hub_download( - repo_id, "meta_data/episode_data_index.safetensors", repo_type="dataset", revision=safe_version - ) - - return load_file(path) - - -def load_stats(repo_id, version, root) -> dict[str, dict[str, torch.Tensor]]: - """stats contains the statistics per modality computed over the full dataset, such as max, min, mean, std - - Example: - ```python - normalized_action = (action - stats["action"]["mean"]) / stats["action"]["std"] - ``` - """ - if root is not None: - path = Path(root) / repo_id / "meta_data" / "stats.safetensors" - else: - safe_version = get_hf_dataset_safe_version(repo_id, version) - path = hf_hub_download( - repo_id, "meta_data/stats.safetensors", repo_type="dataset", revision=safe_version - ) +def get_hf_features_from_features(features: dict) -> datasets.Features: + hf_features = {} + for key, ft in features.items(): + if ft["dtype"] == "video": + continue + elif ft["dtype"] == "image": + hf_features[key] = datasets.Image() + elif ft["shape"] == (1,): + hf_features[key] = datasets.Value(dtype=ft["dtype"]) + else: + assert len(ft["shape"]) == 1 + hf_features[key] = datasets.Sequence( + length=ft["shape"][0], feature=datasets.Value(dtype=ft["dtype"]) + ) - stats = load_file(path) - return unflatten_dict(stats) + return datasets.Features(hf_features) -def load_info(repo_id, version, root) -> dict: - """info contains useful information regarding the dataset that are not stored elsewhere +def get_features_from_robot(robot: Robot, use_videos: bool = True) -> dict: + camera_ft = {} + if robot.cameras: + camera_ft = { + key: {"dtype": "video" if use_videos else "image", **ft} + for key, ft in robot.camera_features.items() + } + return {**robot.motor_features, **camera_ft, **DEFAULT_FEATURES} + + +def create_empty_dataset_info( + codebase_version: str, + fps: int, + robot_type: str, + features: dict, + use_videos: bool, +) -> dict: + return { + "codebase_version": codebase_version, + "robot_type": robot_type, + "total_episodes": 0, + "total_frames": 0, + "total_tasks": 0, + "total_videos": 0, + "total_chunks": 0, + "chunks_size": DEFAULT_CHUNK_SIZE, + "fps": fps, + "splits": {}, + "data_path": DEFAULT_PARQUET_PATH, + "video_path": DEFAULT_VIDEO_PATH if use_videos else None, + "features": features, + } - Example: - ```python - print("frame per second used to collect the video", info["fps"]) - ``` - """ - if root is not None: - path = Path(root) / repo_id / "meta_data" / "info.json" - else: - safe_version = get_hf_dataset_safe_version(repo_id, version) - path = hf_hub_download(repo_id, "meta_data/info.json", repo_type="dataset", revision=safe_version) - with open(path) as f: - info = json.load(f) - return info +def get_episode_data_index( + episode_dicts: list[dict], episodes: list[int] | None = None +) -> dict[str, torch.Tensor]: + episode_lengths = {ep_idx: ep_dict["length"] for ep_idx, ep_dict in enumerate(episode_dicts)} + if episodes is not None: + episode_lengths = {ep_idx: episode_lengths[ep_idx] for ep_idx in episodes} + cumulative_lenghts = list(accumulate(episode_lengths.values())) + return { + "from": torch.LongTensor([0] + cumulative_lenghts[:-1]), + "to": torch.LongTensor(cumulative_lenghts), + } -def load_videos(repo_id, version, root) -> Path: - if root is not None: - path = Path(root) / repo_id / "videos" - else: - # TODO(rcadene): we download the whole repo here. see if we can avoid this - safe_version = get_hf_dataset_safe_version(repo_id, version) - repo_dir = snapshot_download(repo_id, repo_type="dataset", revision=safe_version) - path = Path(repo_dir) / "videos" - return path +def calculate_total_episode( + hf_dataset: datasets.Dataset, raise_if_not_contiguous: bool = True +) -> dict[str, torch.Tensor]: + episode_indices = sorted(hf_dataset.unique("episode_index")) + total_episodes = len(episode_indices) + if raise_if_not_contiguous and episode_indices != list(range(total_episodes)): + raise ValueError("episode_index values are not sorted and contiguous.") + return total_episodes + + +def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> dict[str, torch.Tensor]: + episode_lengths = [] + table = hf_dataset.data.table + total_episodes = calculate_total_episode(hf_dataset) + for ep_idx in range(total_episodes): + ep_table = table.filter(pc.equal(table["episode_index"], ep_idx)) + episode_lengths.insert(ep_idx, len(ep_table)) + + cumulative_lenghts = list(accumulate(episode_lengths)) + return { + "from": torch.LongTensor([0] + cumulative_lenghts[:-1]), + "to": torch.LongTensor(cumulative_lenghts), + } -def load_previous_and_future_frames( - item: dict[str, torch.Tensor], +def check_timestamps_sync( hf_dataset: datasets.Dataset, episode_data_index: dict[str, torch.Tensor], - delta_timestamps: dict[str, list[float]], + fps: int, tolerance_s: float, -) -> dict[torch.Tensor]: + raise_value_error: bool = True, +) -> bool: """ - Given a current item in the dataset containing a timestamp (e.g. 0.6 seconds), and a list of time differences of - some modalities (e.g. delta_timestamps={"observation.image": [-0.8, -0.2, 0, 0.2]}), this function computes for each - given modality (e.g. "observation.image") a list of query timestamps (e.g. [-0.2, 0.4, 0.6, 0.8]) and loads the closest - frames in the dataset. - - Importantly, when no frame can be found around a query timestamp within a specified tolerance window, this function - raises an AssertionError. When a timestamp is queried before the first available timestamp of the episode or after - the last available timestamp, the violation of the tolerance doesnt raise an AssertionError, and the function - populates a boolean array indicating which frames are outside of the episode range. For instance, this boolean array - is useful during batched training to not supervise actions associated to timestamps coming after the end of the - episode, or to pad the observations in a specific way. Note that by default the observation frames before the start - of the episode are the same as the first frame of the episode. - - Parameters: - - item (dict): A dictionary containing all the data related to a frame. It is the result of `dataset[idx]`. Each key - corresponds to a different modality (e.g., "timestamp", "observation.image", "action"). - - hf_dataset (datasets.Dataset): A dictionary containing the full dataset. Each key corresponds to a different - modality (e.g., "timestamp", "observation.image", "action"). - - episode_data_index (dict): A dictionary containing two keys ("from" and "to") associated to dataset indices. - They indicate the start index and end index of each episode in the dataset. - - delta_timestamps (dict): A dictionary containing lists of delta timestamps for each possible modality to be - retrieved. These deltas are added to the item timestamp to form the query timestamps. - - tolerance_s (float, optional): The tolerance level (in seconds) used to determine if a data point is close enough to the query - timestamp by asserting `tol > difference`. It is suggested to set `tol` to a smaller value than the - smallest expected inter-frame period, but large enough to account for jitter. - - Returns: - - The same item with the queried frames for each modality specified in delta_timestamps, with an additional key for - each modality (e.g. "observation.image_is_pad"). - - Raises: - - AssertionError: If any of the frames unexpectedly violate the tolerance level. This could indicate synchronization - issues with timestamps during data collection. + This check is to make sure that each timestamps is separated to the next by 1/fps +/- tolerance to + account for possible numerical error. """ - # get indices of the frames associated to the episode, and their timestamps - ep_id = item["episode_index"].item() - ep_data_id_from = episode_data_index["from"][ep_id].item() - ep_data_id_to = episode_data_index["to"][ep_id].item() - ep_data_ids = torch.arange(ep_data_id_from, ep_data_id_to, 1) - - # load timestamps - ep_timestamps = hf_dataset.select_columns("timestamp")[ep_data_id_from:ep_data_id_to]["timestamp"] - ep_timestamps = torch.stack(ep_timestamps) - - # we make the assumption that the timestamps are sorted - ep_first_ts = ep_timestamps[0] - ep_last_ts = ep_timestamps[-1] - current_ts = item["timestamp"].item() - - for key in delta_timestamps: - # get timestamps used as query to retrieve data of previous/future frames - delta_ts = delta_timestamps[key] - query_ts = current_ts + torch.tensor(delta_ts) - - # compute distances between each query timestamp and all timestamps of all the frames belonging to the episode - dist = torch.cdist(query_ts[:, None], ep_timestamps[:, None], p=1) - min_, argmin_ = dist.min(1) - - # TODO(rcadene): synchronize timestamps + interpolation if needed - - is_pad = min_ > tolerance_s - - # check violated query timestamps are all outside the episode range - assert ((query_ts[is_pad] < ep_first_ts) | (ep_last_ts < query_ts[is_pad])).all(), ( - f"One or several timestamps unexpectedly violate the tolerance ({min_} > {tolerance_s=}) inside episode range." - "This might be due to synchronization issues with timestamps during data collection." - ) - - # get dataset indices corresponding to frames to be loaded - data_ids = ep_data_ids[argmin_] - - # load frames modality - item[key] = hf_dataset.select_columns(key)[data_ids][key] - - if isinstance(item[key][0], dict) and "path" in item[key][0]: - # video mode where frame are expressed as dict of path and timestamp - item[key] = item[key] - else: - item[key] = torch.stack(item[key]) - - item[f"{key}_is_pad"] = is_pad - - return item - - -def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> Dict[str, torch.Tensor]: + timestamps = torch.stack(hf_dataset["timestamp"]) + diffs = torch.diff(timestamps) + within_tolerance = torch.abs(diffs - 1 / fps) <= tolerance_s + + # We mask differences between the timestamp at the end of an episode + # and the one at the start of the next episode since these are expected + # to be outside tolerance. + mask = torch.ones(len(diffs), dtype=torch.bool) + ignored_diffs = episode_data_index["to"][:-1] - 1 + mask[ignored_diffs] = False + filtered_within_tolerance = within_tolerance[mask] + + if not torch.all(filtered_within_tolerance): + # Track original indices before masking + original_indices = torch.arange(len(diffs)) + filtered_indices = original_indices[mask] + outside_tolerance_filtered_indices = torch.nonzero(~filtered_within_tolerance) # .squeeze() + outside_tolerance_indices = filtered_indices[outside_tolerance_filtered_indices] + episode_indices = torch.stack(hf_dataset["episode_index"]) + + outside_tolerances = [] + for idx in outside_tolerance_indices: + entry = { + "timestamps": [timestamps[idx], timestamps[idx + 1]], + "diff": diffs[idx], + "episode_index": episode_indices[idx].item(), + } + outside_tolerances.append(entry) + + if raise_value_error: + raise ValueError( + f"""One or several timestamps unexpectedly violate the tolerance inside episode range. + This might be due to synchronization issues with timestamps during data collection. + \n{pformat(outside_tolerances)}""" + ) + return False + + return True + + +def check_delta_timestamps( + delta_timestamps: dict[str, list[float]], fps: int, tolerance_s: float, raise_value_error: bool = True +) -> bool: + """This will check if all the values in delta_timestamps are multiples of 1/fps +/- tolerance. + This is to ensure that these delta_timestamps added to any timestamp from a dataset will themselves be + actual timestamps from the dataset. """ - Calculate episode data index for the provided HuggingFace Dataset. Relies on episode_index column of hf_dataset. + outside_tolerance = {} + for key, delta_ts in delta_timestamps.items(): + within_tolerance = [abs(ts * fps - round(ts * fps)) / fps <= tolerance_s for ts in delta_ts] + if not all(within_tolerance): + outside_tolerance[key] = [ + ts for ts, is_within in zip(delta_ts, within_tolerance, strict=True) if not is_within + ] - Parameters: - - hf_dataset (datasets.Dataset): A HuggingFace dataset containing the episode index. + if len(outside_tolerance) > 0: + if raise_value_error: + raise ValueError( + f""" + The following delta_timestamps are found outside of tolerance range. + Please make sure they are multiples of 1/{fps} +/- tolerance and adjust + their values accordingly. + \n{pformat(outside_tolerance)} + """ + ) + return False - Returns: - - episode_data_index: A dictionary containing the data index for each episode. The dictionary has two keys: - - "from": A tensor containing the starting index of each episode. - - "to": A tensor containing the ending index of each episode. - """ - episode_data_index = {"from": [], "to": []} + return True - current_episode = None - """ - The episode_index is a list of integers, each representing the episode index of the corresponding example. - For instance, the following is a valid episode_index: - [0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 2] - - Below, we iterate through the episode_index and populate the episode_data_index dictionary with the starting and - ending index of each episode. For the episode_index above, the episode_data_index dictionary will look like this: - { - "from": [0, 3, 7], - "to": [3, 7, 12] - } - """ - if len(hf_dataset) == 0: - episode_data_index = { - "from": torch.tensor([]), - "to": torch.tensor([]), - } - return episode_data_index - for idx, episode_idx in enumerate(hf_dataset["episode_index"]): - if episode_idx != current_episode: - # We encountered a new episode, so we append its starting location to the "from" list - episode_data_index["from"].append(idx) - # If this is not the first episode, we append the ending location of the previous episode to the "to" list - if current_episode is not None: - episode_data_index["to"].append(idx) - # Let's keep track of the current episode index - current_episode = episode_idx - else: - # We are still in the same episode, so there is nothing for us to do here - pass - # We have reached the end of the dataset, so we append the ending location of the last episode to the "to" list - episode_data_index["to"].append(idx + 1) - for k in ["from", "to"]: - episode_data_index[k] = torch.tensor(episode_data_index[k]) +def get_delta_indices(delta_timestamps: dict[str, list[float]], fps: int) -> dict[str, list[int]]: + delta_indices = {} + for key, delta_ts in delta_timestamps.items(): + delta_indices[key] = (torch.tensor(delta_ts) * fps).long().tolist() - return episode_data_index - - -def reset_episode_index(hf_dataset: datasets.Dataset) -> datasets.Dataset: - """Reset the `episode_index` of the provided HuggingFace Dataset. - - `episode_data_index` (and related functionality such as `load_previous_and_future_frames`) requires the - `episode_index` to be sorted, continuous (1,1,1 and not 1,2,1) and start at 0. - - This brings the `episode_index` to the required format. - """ - if len(hf_dataset) == 0: - return hf_dataset - unique_episode_idxs = torch.stack(hf_dataset["episode_index"]).unique().tolist() - episode_idx_to_reset_idx_mapping = { - ep_id: reset_ep_id for reset_ep_id, ep_id in enumerate(unique_episode_idxs) - } - - def modify_ep_idx_func(example): - example["episode_index"] = episode_idx_to_reset_idx_mapping[example["episode_index"].item()] - return example - - hf_dataset = hf_dataset.map(modify_ep_idx_func) - - return hf_dataset + return delta_indices def cycle(iterable): @@ -400,7 +451,7 @@ def cycle(iterable): iterator = iter(iterable) -def create_branch(repo_id, *, branch: str, repo_type: str | None = None): +def create_branch(repo_id, *, branch: str, repo_type: str | None = None) -> None: """Create a branch on a existing Hugging Face repo. Delete the branch if it already exists before creating it. """ @@ -415,12 +466,35 @@ def create_branch(repo_id, *, branch: str, repo_type: str | None = None): api.create_branch(repo_id, repo_type=repo_type, branch=branch) -def create_lerobot_dataset_card(tags: list | None = None, text: str | None = None) -> DatasetCard: - card = DatasetCard(DATASET_CARD_TEMPLATE) - card.data.task_categories = ["robotics"] - card.data.tags = ["LeRobot"] - if tags is not None: - card.data.tags += tags - if text is not None: - card.text += text - return card +def create_lerobot_dataset_card( + tags: list | None = None, + dataset_info: dict | None = None, + **kwargs, +) -> DatasetCard: + """ + Keyword arguments will be used to replace values in ./lerobot/common/datasets/card_template.md. + Note: If specified, license must be one of https://huggingface.co/docs/hub/repositories-licenses. + """ + card_tags = ["LeRobot"] + if tags: + card_tags += tags + if dataset_info: + dataset_structure = "[meta/info.json](meta/info.json):\n" + dataset_structure += f"```json\n{json.dumps(dataset_info, indent=4)}\n```\n" + kwargs = {**kwargs, "dataset_structure": dataset_structure} + card_data = DatasetCardData( + license=kwargs.get("license"), + tags=card_tags, + task_categories=["robotics"], + configs=[ + { + "config_name": "default", + "data_files": "data/*/*.parquet", + } + ], + ) + return DatasetCard.from_template( + card_data=card_data, + template_path="./lerobot/common/datasets/card_template.md", + **kwargs, + ) diff --git a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py new file mode 100644 index 000000000..c8da2fe14 --- /dev/null +++ b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py @@ -0,0 +1,882 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +""" +This script is for internal use to convert all datasets under the 'lerobot' hub user account to v2. + +Note: Since the original Aloha datasets don't use shadow motors, you need to comment those out in +lerobot/configs/robot/aloha.yaml before running this script. +""" + +import traceback +from pathlib import Path +from textwrap import dedent + +from lerobot import available_datasets +from lerobot.common.datasets.v2.convert_dataset_v1_to_v2 import convert_dataset, parse_robot_config + +LOCAL_DIR = Path("data/") + +ALOHA_CONFIG = Path("lerobot/configs/robot/aloha.yaml") +ALOHA_MOBILE_INFO = { + "robot_config": parse_robot_config(ALOHA_CONFIG), + "license": "mit", + "url": "https://mobile-aloha.github.io/", + "paper": "https://arxiv.org/abs/2401.02117", + "citation_bibtex": dedent(r""" + @inproceedings{fu2024mobile, + author = {Fu, Zipeng and Zhao, Tony Z. and Finn, Chelsea}, + title = {Mobile ALOHA: Learning Bimanual Mobile Manipulation with Low-Cost Whole-Body Teleoperation}, + booktitle = {arXiv}, + year = {2024}, + }""").lstrip(), +} +ALOHA_STATIC_INFO = { + "robot_config": parse_robot_config(ALOHA_CONFIG), + "license": "mit", + "url": "https://tonyzhaozh.github.io/aloha/", + "paper": "https://arxiv.org/abs/2304.13705", + "citation_bibtex": dedent(r""" + @article{Zhao2023LearningFB, + title={Learning Fine-Grained Bimanual Manipulation with Low-Cost Hardware}, + author={Tony Zhao and Vikash Kumar and Sergey Levine and Chelsea Finn}, + journal={RSS}, + year={2023}, + volume={abs/2304.13705}, + url={https://arxiv.org/abs/2304.13705} + }""").lstrip(), +} +PUSHT_INFO = { + "license": "mit", + "url": "https://diffusion-policy.cs.columbia.edu/", + "paper": "https://arxiv.org/abs/2303.04137v5", + "citation_bibtex": dedent(r""" + @article{chi2024diffusionpolicy, + author = {Cheng Chi and Zhenjia Xu and Siyuan Feng and Eric Cousineau and Yilun Du and Benjamin Burchfiel and Russ Tedrake and Shuran Song}, + title ={Diffusion Policy: Visuomotor Policy Learning via Action Diffusion}, + journal = {The International Journal of Robotics Research}, + year = {2024}, + }""").lstrip(), +} +XARM_INFO = { + "license": "mit", + "url": "https://www.nicklashansen.com/td-mpc/", + "paper": "https://arxiv.org/abs/2203.04955", + "citation_bibtex": dedent(r""" + @inproceedings{Hansen2022tdmpc, + title={Temporal Difference Learning for Model Predictive Control}, + author={Nicklas Hansen and Xiaolong Wang and Hao Su}, + booktitle={ICML}, + year={2022} + } + """), +} +UNITREEH_INFO = { + "license": "apache-2.0", +} + +DATASETS = { + "aloha_mobile_cabinet": { + "single_task": "Open the top cabinet, store the pot inside it then close the cabinet.", + **ALOHA_MOBILE_INFO, + }, + "aloha_mobile_chair": { + "single_task": "Push the chairs in front of the desk to place them against it.", + **ALOHA_MOBILE_INFO, + }, + "aloha_mobile_elevator": { + "single_task": "Take the elevator to the 1st floor.", + **ALOHA_MOBILE_INFO, + }, + "aloha_mobile_shrimp": { + "single_task": "Sauté the raw shrimp on both sides, then serve it in the bowl.", + **ALOHA_MOBILE_INFO, + }, + "aloha_mobile_wash_pan": { + "single_task": "Pick up the pan, rinse it in the sink and then place it in the drying rack.", + **ALOHA_MOBILE_INFO, + }, + "aloha_mobile_wipe_wine": { + "single_task": "Pick up the wet cloth on the faucet and use it to clean the spilled wine on the table and underneath the glass.", + **ALOHA_MOBILE_INFO, + }, + "aloha_static_battery": { + "single_task": "Place the battery into the slot of the remote controller.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_candy": {"single_task": "Pick up the candy and unwrap it.", **ALOHA_STATIC_INFO}, + "aloha_static_coffee": { + "single_task": "Place the coffee capsule inside the capsule container, then place the cup onto the center of the cup tray, then push the 'Hot Water' and 'Travel Mug' buttons.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_coffee_new": { + "single_task": "Place the coffee capsule inside the capsule container, then place the cup onto the center of the cup tray.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_cups_open": { + "single_task": "Pick up the plastic cup and open its lid.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_fork_pick_up": { + "single_task": "Pick up the fork and place it on the plate.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_pingpong_test": { + "single_task": "Transfer one of the two balls in the right glass into the left glass, then transfer it back to the right glass.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_pro_pencil": { + "single_task": "Pick up the pencil with the right arm, hand it over to the left arm then place it back onto the table.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_screw_driver": { + "single_task": "Pick up the screwdriver with the right arm, hand it over to the left arm then place it into the cup.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_tape": { + "single_task": "Cut a small piece of tape from the tape dispenser then place it on the cardboard box's edge.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_thread_velcro": { + "single_task": "Pick up the velcro cable tie with the left arm, then insert the end of the velcro tie into the other end's loop with the right arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_towel": { + "single_task": "Pick up a piece of paper towel and place it on the spilled liquid.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_vinh_cup": { + "single_task": "Pick up the platic cup with the right arm, then pop its lid open with the left arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_vinh_cup_left": { + "single_task": "Pick up the platic cup with the left arm, then pop its lid open with the right arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_static_ziploc_slide": {"single_task": "Slide open the ziploc bag.", **ALOHA_STATIC_INFO}, + "aloha_sim_insertion_scripted": {"single_task": "Insert the peg into the socket.", **ALOHA_STATIC_INFO}, + "aloha_sim_insertion_scripted_image": { + "single_task": "Insert the peg into the socket.", + **ALOHA_STATIC_INFO, + }, + "aloha_sim_insertion_human": {"single_task": "Insert the peg into the socket.", **ALOHA_STATIC_INFO}, + "aloha_sim_insertion_human_image": { + "single_task": "Insert the peg into the socket.", + **ALOHA_STATIC_INFO, + }, + "aloha_sim_transfer_cube_scripted": { + "single_task": "Pick up the cube with the right arm and transfer it to the left arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_sim_transfer_cube_scripted_image": { + "single_task": "Pick up the cube with the right arm and transfer it to the left arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_sim_transfer_cube_human": { + "single_task": "Pick up the cube with the right arm and transfer it to the left arm.", + **ALOHA_STATIC_INFO, + }, + "aloha_sim_transfer_cube_human_image": { + "single_task": "Pick up the cube with the right arm and transfer it to the left arm.", + **ALOHA_STATIC_INFO, + }, + "pusht": {"single_task": "Push the T-shaped block onto the T-shaped target.", **PUSHT_INFO}, + "pusht_image": {"single_task": "Push the T-shaped block onto the T-shaped target.", **PUSHT_INFO}, + "unitreeh1_fold_clothes": {"single_task": "Fold the sweatshirt.", **UNITREEH_INFO}, + "unitreeh1_rearrange_objects": {"single_task": "Put the object into the bin.", **UNITREEH_INFO}, + "unitreeh1_two_robot_greeting": { + "single_task": "Greet the other robot with a high five.", + **UNITREEH_INFO, + }, + "unitreeh1_warehouse": { + "single_task": "Grab the spray paint on the shelf and place it in the bin on top of the robot dog.", + **UNITREEH_INFO, + }, + "xarm_lift_medium": {"single_task": "Pick up the cube and lift it.", **XARM_INFO}, + "xarm_lift_medium_image": {"single_task": "Pick up the cube and lift it.", **XARM_INFO}, + "xarm_lift_medium_replay": {"single_task": "Pick up the cube and lift it.", **XARM_INFO}, + "xarm_lift_medium_replay_image": {"single_task": "Pick up the cube and lift it.", **XARM_INFO}, + "xarm_push_medium": {"single_task": "Push the cube onto the target.", **XARM_INFO}, + "xarm_push_medium_image": {"single_task": "Push the cube onto the target.", **XARM_INFO}, + "xarm_push_medium_replay": {"single_task": "Push the cube onto the target.", **XARM_INFO}, + "xarm_push_medium_replay_image": {"single_task": "Push the cube onto the target.", **XARM_INFO}, + "umi_cup_in_the_wild": { + "single_task": "Put the cup on the plate.", + "license": "apache-2.0", + }, + "asu_table_top": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://link.springer.com/article/10.1007/s10514-023-10129-1", + "citation_bibtex": dedent(r""" + @inproceedings{zhou2023modularity, + title={Modularity through Attention: Efficient Training and Transfer of Language-Conditioned Policies for Robot Manipulation}, + author={Zhou, Yifan and Sonawani, Shubham and Phielipp, Mariano and Stepputtis, Simon and Amor, Heni}, + booktitle={Conference on Robot Learning}, + pages={1684--1695}, + year={2023}, + organization={PMLR} + } + @article{zhou2023learning, + title={Learning modular language-conditioned robot policies through attention}, + author={Zhou, Yifan and Sonawani, Shubham and Phielipp, Mariano and Ben Amor, Heni and Stepputtis, Simon}, + journal={Autonomous Robots}, + pages={1--21}, + year={2023}, + publisher={Springer} + }""").lstrip(), + }, + "austin_buds_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://ut-austin-rpl.github.io/BUDS-website/", + "paper": "https://arxiv.org/abs/2109.13841", + "citation_bibtex": dedent(r""" + @article{zhu2022bottom, + title={Bottom-Up Skill Discovery From Unsegmented Demonstrations for Long-Horizon Robot Manipulation}, + author={Zhu, Yifeng and Stone, Peter and Zhu, Yuke}, + journal={IEEE Robotics and Automation Letters}, + volume={7}, + number={2}, + pages={4126--4133}, + year={2022}, + publisher={IEEE} + }""").lstrip(), + }, + "austin_sailor_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://ut-austin-rpl.github.io/sailor/", + "paper": "https://arxiv.org/abs/2210.11435", + "citation_bibtex": dedent(r""" + @inproceedings{nasiriany2022sailor, + title={Learning and Retrieval from Prior Data for Skill-based Imitation Learning}, + author={Soroush Nasiriany and Tian Gao and Ajay Mandlekar and Yuke Zhu}, + booktitle={Conference on Robot Learning (CoRL)}, + year={2022} + }""").lstrip(), + }, + "austin_sirius_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://ut-austin-rpl.github.io/sirius/", + "paper": "https://arxiv.org/abs/2211.08416", + "citation_bibtex": dedent(r""" + @inproceedings{liu2022robot, + title = {Robot Learning on the Job: Human-in-the-Loop Autonomy and Learning During Deployment}, + author = {Huihan Liu and Soroush Nasiriany and Lance Zhang and Zhiyao Bao and Yuke Zhu}, + booktitle = {Robotics: Science and Systems (RSS)}, + year = {2023} + }""").lstrip(), + }, + "berkeley_autolab_ur5": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://sites.google.com/view/berkeley-ur5/home", + "citation_bibtex": dedent(r""" + @misc{BerkeleyUR5Website, + title = {Berkeley {UR5} Demonstration Dataset}, + author = {Lawrence Yunliang Chen and Simeon Adebola and Ken Goldberg}, + howpublished = {https://sites.google.com/view/berkeley-ur5/home}, + }""").lstrip(), + }, + "berkeley_cable_routing": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://sites.google.com/view/cablerouting/home", + "paper": "https://arxiv.org/abs/2307.08927", + "citation_bibtex": dedent(r""" + @article{luo2023multistage, + author = {Jianlan Luo and Charles Xu and Xinyang Geng and Gilbert Feng and Kuan Fang and Liam Tan and Stefan Schaal and Sergey Levine}, + title = {Multi-Stage Cable Routing through Hierarchical Imitation Learning}, + journal = {arXiv pre-print}, + year = {2023}, + url = {https://arxiv.org/abs/2307.08927}, + }""").lstrip(), + }, + "berkeley_fanuc_manipulation": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/berkeley.edu/fanuc-manipulation", + "citation_bibtex": dedent(r""" + @article{fanuc_manipulation2023, + title={Fanuc Manipulation: A Dataset for Learning-based Manipulation with FANUC Mate 200iD Robot}, + author={Zhu, Xinghao and Tian, Ran and Xu, Chenfeng and Ding, Mingyu and Zhan, Wei and Tomizuka, Masayoshi}, + year={2023}, + }""").lstrip(), + }, + "berkeley_gnm_cory_hall": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://arxiv.org/abs/1709.10489", + "citation_bibtex": dedent(r""" + @inproceedings{kahn2018self, + title={Self-supervised deep reinforcement learning with generalized computation graphs for robot navigation}, + author={Kahn, Gregory and Villaflor, Adam and Ding, Bosen and Abbeel, Pieter and Levine, Sergey}, + booktitle={2018 IEEE international conference on robotics and automation (ICRA)}, + pages={5129--5136}, + year={2018}, + organization={IEEE} + }""").lstrip(), + }, + "berkeley_gnm_recon": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/view/recon-robot", + "paper": "https://arxiv.org/abs/2104.05859", + "citation_bibtex": dedent(r""" + @inproceedings{shah2021rapid, + title={Rapid Exploration for Open-World Navigation with Latent Goal Models}, + author={Dhruv Shah and Benjamin Eysenbach and Nicholas Rhinehart and Sergey Levine}, + booktitle={5th Annual Conference on Robot Learning }, + year={2021}, + url={https://openreview.net/forum?id=d_SWJhyKfVw} + }""").lstrip(), + }, + "berkeley_gnm_sac_son": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/view/SACSoN-review", + "paper": "https://arxiv.org/abs/2306.01874", + "citation_bibtex": dedent(r""" + @article{hirose2023sacson, + title={SACSoN: Scalable Autonomous Data Collection for Social Navigation}, + author={Hirose, Noriaki and Shah, Dhruv and Sridhar, Ajay and Levine, Sergey}, + journal={arXiv preprint arXiv:2306.01874}, + year={2023} + }""").lstrip(), + }, + "berkeley_mvp": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://arxiv.org/abs/2203.06173", + "citation_bibtex": dedent(r""" + @InProceedings{Radosavovic2022, + title = {Real-World Robot Learning with Masked Visual Pre-training}, + author = {Ilija Radosavovic and Tete Xiao and Stephen James and Pieter Abbeel and Jitendra Malik and Trevor Darrell}, + booktitle = {CoRL}, + year = {2022} + }""").lstrip(), + }, + "berkeley_rpt": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://arxiv.org/abs/2306.10007", + "citation_bibtex": dedent(r""" + @article{Radosavovic2023, + title={Robot Learning with Sensorimotor Pre-training}, + author={Ilija Radosavovic and Baifeng Shi and Letian Fu and Ken Goldberg and Trevor Darrell and Jitendra Malik}, + year={2023}, + journal={arXiv:2306.10007} + }""").lstrip(), + }, + "cmu_franka_exploration_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://human-world-model.github.io/", + "paper": "https://arxiv.org/abs/2308.10901", + "citation_bibtex": dedent(r""" + @inproceedings{mendonca2023structured, + title={Structured World Models from Human Videos}, + author={Mendonca, Russell and Bahl, Shikhar and Pathak, Deepak}, + journal={RSS}, + year={2023} + }""").lstrip(), + }, + "cmu_play_fusion": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://play-fusion.github.io/", + "paper": "https://arxiv.org/abs/2312.04549", + "citation_bibtex": dedent(r""" + @inproceedings{chen2023playfusion, + title={PlayFusion: Skill Acquisition via Diffusion from Language-Annotated Play}, + author={Chen, Lili and Bahl, Shikhar and Pathak, Deepak}, + booktitle={CoRL}, + year={2023} + }""").lstrip(), + }, + "cmu_stretch": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://robo-affordances.github.io/", + "paper": "https://arxiv.org/abs/2304.08488", + "citation_bibtex": dedent(r""" + @inproceedings{bahl2023affordances, + title={Affordances from Human Videos as a Versatile Representation for Robotics}, + author={Bahl, Shikhar and Mendonca, Russell and Chen, Lili and Jain, Unnat and Pathak, Deepak}, + booktitle={CVPR}, + year={2023} + } + @article{mendonca2023structured, + title={Structured World Models from Human Videos}, + author={Mendonca, Russell and Bahl, Shikhar and Pathak, Deepak}, + journal={CoRL}, + year={2023} + }""").lstrip(), + }, + "columbia_cairlab_pusht_real": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://diffusion-policy.cs.columbia.edu/", + "paper": "https://arxiv.org/abs/2303.04137v5", + "citation_bibtex": dedent(r""" + @inproceedings{chi2023diffusionpolicy, + title={Diffusion Policy: Visuomotor Policy Learning via Action Diffusion}, + author={Chi, Cheng and Feng, Siyuan and Du, Yilun and Xu, Zhenjia and Cousineau, Eric and Burchfiel, Benjamin and Song, Shuran}, + booktitle={Proceedings of Robotics: Science and Systems (RSS)}, + year={2023} + }""").lstrip(), + }, + "conq_hose_manipulation": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/view/conq-hose-manipulation-dataset/home", + "citation_bibtex": dedent(r""" + @misc{ConqHoseManipData, + author={Peter Mitrano and Dmitry Berenson}, + title={Conq Hose Manipulation Dataset, v1.15.0}, + year={2024}, + howpublished={https://sites.google.com/view/conq-hose-manipulation-dataset} + }""").lstrip(), + }, + "dlr_edan_shared_control": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://ieeexplore.ieee.org/document/9341156", + "citation_bibtex": dedent(r""" + @inproceedings{vogel_edan_2020, + title = {EDAN - an EMG-Controlled Daily Assistant to Help People with Physical Disabilities}, + language = {en}, + booktitle = {2020 {IEEE}/{RSJ} {International} {Conference} on {Intelligent} {Robots} and {Systems} ({IROS})}, + author = {Vogel, Jörn and Hagengruber, Annette and Iskandar, Maged and Quere, Gabriel and Leipscher, Ulrike and Bustamante, Samuel and Dietrich, Alexander and Hoeppner, Hannes and Leidner, Daniel and Albu-Schäffer, Alin}, + year = {2020} + } + @inproceedings{quere_shared_2020, + address = {Paris, France}, + title = {Shared {Control} {Templates} for {Assistive} {Robotics}}, + language = {en}, + booktitle = {2020 {IEEE} {International} {Conference} on {Robotics} and {Automation} ({ICRA})}, + author = {Quere, Gabriel and Hagengruber, Annette and Iskandar, Maged and Bustamante, Samuel and Leidner, Daniel and Stulp, Freek and Vogel, Joern}, + year = {2020}, + pages = {7}, + }""").lstrip(), + }, + "dlr_sara_grid_clamp": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://www.researchsquare.com/article/rs-3289569/v1", + "citation_bibtex": dedent(r""" + @article{padalkar2023guided, + title={A guided reinforcement learning approach using shared control templates for learning manipulation skills in the real world}, + author={Padalkar, Abhishek and Quere, Gabriel and Raffin, Antonin and Silv{\'e}rio, Jo{\~a}o and Stulp, Freek}, + journal={Research square preprint rs-3289569/v1}, + year={2023} + }""").lstrip(), + }, + "dlr_sara_pour": { + "tasks_col": "language_instruction", + "license": "mit", + "paper": "https://elib.dlr.de/193739/1/padalkar2023rlsct.pdf", + "citation_bibtex": dedent(r""" + @inproceedings{padalkar2023guiding, + title={Guiding Reinforcement Learning with Shared Control Templates}, + author={Padalkar, Abhishek and Quere, Gabriel and Steinmetz, Franz and Raffin, Antonin and Nieuwenhuisen, Matthias and Silv{\'e}rio, Jo{\~a}o and Stulp, Freek}, + booktitle={40th IEEE International Conference on Robotics and Automation, ICRA 2023}, + year={2023}, + organization={IEEE} + }""").lstrip(), + }, + "droid_100": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://droid-dataset.github.io/", + "paper": "https://arxiv.org/abs/2403.12945", + "citation_bibtex": dedent(r""" + @article{khazatsky2024droid, + title = {DROID: A Large-Scale In-The-Wild Robot Manipulation Dataset}, + author = {Alexander Khazatsky and Karl Pertsch and Suraj Nair and Ashwin Balakrishna and Sudeep Dasari and Siddharth Karamcheti and Soroush Nasiriany and Mohan Kumar Srirama and Lawrence Yunliang Chen and Kirsty Ellis and Peter David Fagan and Joey Hejna and Masha Itkina and Marion Lepert and Yecheng Jason Ma and Patrick Tree Miller and Jimmy Wu and Suneel Belkhale and Shivin Dass and Huy Ha and Arhan Jain and Abraham Lee and Youngwoon Lee and Marius Memmel and Sungjae Park and Ilija Radosavovic and Kaiyuan Wang and Albert Zhan and Kevin Black and Cheng Chi and Kyle Beltran Hatch and Shan Lin and Jingpei Lu and Jean Mercat and Abdul Rehman and Pannag R Sanketi and Archit Sharma and Cody Simpson and Quan Vuong and Homer Rich Walke and Blake Wulfe and Ted Xiao and Jonathan Heewon Yang and Arefeh Yavary and Tony Z. Zhao and Christopher Agia and Rohan Baijal and Mateo Guaman Castro and Daphne Chen and Qiuyu Chen and Trinity Chung and Jaimyn Drake and Ethan Paul Foster and Jensen Gao and David Antonio Herrera and Minho Heo and Kyle Hsu and Jiaheng Hu and Donovon Jackson and Charlotte Le and Yunshuang Li and Kevin Lin and Roy Lin and Zehan Ma and Abhiram Maddukuri and Suvir Mirchandani and Daniel Morton and Tony Nguyen and Abigail O'Neill and Rosario Scalise and Derick Seale and Victor Son and Stephen Tian and Emi Tran and Andrew E. Wang and Yilin Wu and Annie Xie and Jingyun Yang and Patrick Yin and Yunchu Zhang and Osbert Bastani and Glen Berseth and Jeannette Bohg and Ken Goldberg and Abhinav Gupta and Abhishek Gupta and Dinesh Jayaraman and Joseph J Lim and Jitendra Malik and Roberto Martín-Martín and Subramanian Ramamoorthy and Dorsa Sadigh and Shuran Song and Jiajun Wu and Michael C. Yip and Yuke Zhu and Thomas Kollar and Sergey Levine and Chelsea Finn}, + year = {2024}, + }""").lstrip(), + }, + "fmb": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://functional-manipulation-benchmark.github.io/", + "paper": "https://arxiv.org/abs/2401.08553", + "citation_bibtex": dedent(r""" + @article{luo2024fmb, + title={FMB: a Functional Manipulation Benchmark for Generalizable Robotic Learning}, + author={Luo, Jianlan and Xu, Charles and Liu, Fangchen and Tan, Liam and Lin, Zipeng and Wu, Jeffrey and Abbeel, Pieter and Levine, Sergey}, + journal={arXiv preprint arXiv:2401.08553}, + year={2024} + }""").lstrip(), + }, + "iamlab_cmu_pickup_insert": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://openreview.net/forum?id=WuBv9-IGDUA", + "paper": "https://arxiv.org/abs/2401.14502", + "citation_bibtex": dedent(r""" + @inproceedings{saxena2023multiresolution, + title={Multi-Resolution Sensing for Real-Time Control with Vision-Language Models}, + author={Saumya Saxena and Mohit Sharma and Oliver Kroemer}, + booktitle={7th Annual Conference on Robot Learning}, + year={2023}, + url={https://openreview.net/forum?id=WuBv9-IGDUA} + }""").lstrip(), + }, + "imperialcollege_sawyer_wrist_cam": { + "tasks_col": "language_instruction", + "license": "mit", + }, + "jaco_play": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://github.com/clvrai/clvr_jaco_play_dataset", + "citation_bibtex": dedent(r""" + @software{dass2023jacoplay, + author = {Dass, Shivin and Yapeter, Jullian and Zhang, Jesse and Zhang, Jiahui + and Pertsch, Karl and Nikolaidis, Stefanos and Lim, Joseph J.}, + title = {CLVR Jaco Play Dataset}, + url = {https://github.com/clvrai/clvr_jaco_play_dataset}, + version = {1.0.0}, + year = {2023} + }""").lstrip(), + }, + "kaist_nonprehensile": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://github.com/JaeHyung-Kim/rlds_dataset_builder", + "citation_bibtex": dedent(r""" + @article{kimpre, + title={Pre-and post-contact policy decomposition for non-prehensile manipulation with zero-shot sim-to-real transfer}, + author={Kim, Minchan and Han, Junhyek and Kim, Jaehyung and Kim, Beomjoon}, + booktitle={2023 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, + year={2023}, + organization={IEEE} + }""").lstrip(), + }, + "nyu_door_opening_surprising_effectiveness": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://jyopari.github.io/VINN/", + "paper": "https://arxiv.org/abs/2112.01511", + "citation_bibtex": dedent(r""" + @misc{pari2021surprising, + title={The Surprising Effectiveness of Representation Learning for Visual Imitation}, + author={Jyothish Pari and Nur Muhammad Shafiullah and Sridhar Pandian Arunachalam and Lerrel Pinto}, + year={2021}, + eprint={2112.01511}, + archivePrefix={arXiv}, + primaryClass={cs.RO} + }""").lstrip(), + }, + "nyu_franka_play_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://play-to-policy.github.io/", + "paper": "https://arxiv.org/abs/2210.10047", + "citation_bibtex": dedent(r""" + @article{cui2022play, + title = {From Play to Policy: Conditional Behavior Generation from Uncurated Robot Data}, + author = {Cui, Zichen Jeff and Wang, Yibin and Shafiullah, Nur Muhammad Mahi and Pinto, Lerrel}, + journal = {arXiv preprint arXiv:2210.10047}, + year = {2022} + }""").lstrip(), + }, + "nyu_rot_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://rot-robot.github.io/", + "paper": "https://arxiv.org/abs/2206.15469", + "citation_bibtex": dedent(r""" + @inproceedings{haldar2023watch, + title={Watch and match: Supercharging imitation with regularized optimal transport}, + author={Haldar, Siddhant and Mathur, Vaibhav and Yarats, Denis and Pinto, Lerrel}, + booktitle={Conference on Robot Learning}, + pages={32--43}, + year={2023}, + organization={PMLR} + }""").lstrip(), + }, + "roboturk": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://roboturk.stanford.edu/dataset_real.html", + "paper": "PAPER", + "citation_bibtex": dedent(r""" + @inproceedings{mandlekar2019scaling, + title={Scaling robot supervision to hundreds of hours with roboturk: Robotic manipulation dataset through human reasoning and dexterity}, + author={Mandlekar, Ajay and Booher, Jonathan and Spero, Max and Tung, Albert and Gupta, Anchit and Zhu, Yuke and Garg, Animesh and Savarese, Silvio and Fei-Fei, Li}, + booktitle={2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, + pages={1048--1055}, + year={2019}, + organization={IEEE} + }""").lstrip(), + }, + "stanford_hydra_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/view/hydra-il-2023", + "paper": "https://arxiv.org/abs/2306.17237", + "citation_bibtex": dedent(r""" + @article{belkhale2023hydra, + title={HYDRA: Hybrid Robot Actions for Imitation Learning}, + author={Belkhale, Suneel and Cui, Yuchen and Sadigh, Dorsa}, + journal={arxiv}, + year={2023} + }""").lstrip(), + }, + "stanford_kuka_multimodal_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://sites.google.com/view/visionandtouch", + "paper": "https://arxiv.org/abs/1810.10191", + "citation_bibtex": dedent(r""" + @inproceedings{lee2019icra, + title={Making sense of vision and touch: Self-supervised learning of multimodal representations for contact-rich tasks}, + author={Lee, Michelle A and Zhu, Yuke and Srinivasan, Krishnan and Shah, Parth and Savarese, Silvio and Fei-Fei, Li and Garg, Animesh and Bohg, Jeannette}, + booktitle={2019 IEEE International Conference on Robotics and Automation (ICRA)}, + year={2019}, + url={https://arxiv.org/abs/1810.10191} + }""").lstrip(), + }, + "stanford_robocook": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://hshi74.github.io/robocook/", + "paper": "https://arxiv.org/abs/2306.14447", + "citation_bibtex": dedent(r""" + @article{shi2023robocook, + title={RoboCook: Long-Horizon Elasto-Plastic Object Manipulation with Diverse Tools}, + author={Shi, Haochen and Xu, Huazhe and Clarke, Samuel and Li, Yunzhu and Wu, Jiajun}, + journal={arXiv preprint arXiv:2306.14447}, + year={2023} + }""").lstrip(), + }, + "taco_play": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "url": "https://www.kaggle.com/datasets/oiermees/taco-robot", + "paper": "https://arxiv.org/abs/2209.08959, https://arxiv.org/abs/2210.01911", + "citation_bibtex": dedent(r""" + @inproceedings{rosete2022tacorl, + author = {Erick Rosete-Beas and Oier Mees and Gabriel Kalweit and Joschka Boedecker and Wolfram Burgard}, + title = {Latent Plans for Task Agnostic Offline Reinforcement Learning}, + journal = {Proceedings of the 6th Conference on Robot Learning (CoRL)}, + year = {2022} + } + @inproceedings{mees23hulc2, + title={Grounding Language with Visual Affordances over Unstructured Data}, + author={Oier Mees and Jessica Borja-Diaz and Wolfram Burgard}, + booktitle = {Proceedings of the IEEE International Conference on Robotics and Automation (ICRA)}, + year={2023}, + address = {London, UK} + }""").lstrip(), + }, + "tokyo_u_lsmo": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "URL", + "paper": "https://arxiv.org/abs/2107.05842", + "citation_bibtex": dedent(r""" + @Article{Osa22, + author = {Takayuki Osa}, + journal = {The International Journal of Robotics Research}, + title = {Motion Planning by Learning the Solution Manifold in Trajectory Optimization}, + year = {2022}, + number = {3}, + pages = {291--311}, + volume = {41}, + }""").lstrip(), + }, + "toto": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://toto-benchmark.org/", + "paper": "https://arxiv.org/abs/2306.00942", + "citation_bibtex": dedent(r""" + @inproceedings{zhou2023train, + author={Zhou, Gaoyue and Dean, Victoria and Srirama, Mohan Kumar and Rajeswaran, Aravind and Pari, Jyothish and Hatch, Kyle and Jain, Aryan and Yu, Tianhe and Abbeel, Pieter and Pinto, Lerrel and Finn, Chelsea and Gupta, Abhinav}, + booktitle={2023 IEEE International Conference on Robotics and Automation (ICRA)}, + title={Train Offline, Test Online: A Real Robot Learning Benchmark}, + year={2023}, + }""").lstrip(), + }, + "ucsd_kitchen_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "citation_bibtex": dedent(r""" + @ARTICLE{ucsd_kitchens, + author = {Ge Yan, Kris Wu, and Xiaolong Wang}, + title = {{ucsd kitchens Dataset}}, + year = {2023}, + month = {August} + }""").lstrip(), + }, + "ucsd_pick_and_place_dataset": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://owmcorl.github.io/#", + "paper": "https://arxiv.org/abs/2310.16029", + "citation_bibtex": dedent(r""" + @preprint{Feng2023Finetuning, + title={Finetuning Offline World Models in the Real World}, + author={Yunhai Feng, Nicklas Hansen, Ziyan Xiong, Chandramouli Rajagopalan, Xiaolong Wang}, + year={2023} + }""").lstrip(), + }, + "uiuc_d3field": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://robopil.github.io/d3fields/", + "paper": "https://arxiv.org/abs/2309.16118", + "citation_bibtex": dedent(r""" + @article{wang2023d3field, + title={D^3Field: Dynamic 3D Descriptor Fields for Generalizable Robotic Manipulation}, + author={Wang, Yixuan and Li, Zhuoran and Zhang, Mingtong and Driggs-Campbell, Katherine and Wu, Jiajun and Fei-Fei, Li and Li, Yunzhu}, + journal={arXiv preprint arXiv:}, + year={2023}, + }""").lstrip(), + }, + "usc_cloth_sim": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://uscresl.github.io/dmfd/", + "paper": "https://arxiv.org/abs/2207.10148", + "citation_bibtex": dedent(r""" + @article{salhotra2022dmfd, + author={Salhotra, Gautam and Liu, I-Chun Arthur and Dominguez-Kuhne, Marcus and Sukhatme, Gaurav S.}, + journal={IEEE Robotics and Automation Letters}, + title={Learning Deformable Object Manipulation From Expert Demonstrations}, + year={2022}, + volume={7}, + number={4}, + pages={8775-8782}, + doi={10.1109/LRA.2022.3187843} + }""").lstrip(), + }, + "utaustin_mutex": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://ut-austin-rpl.github.io/MUTEX/", + "paper": "https://arxiv.org/abs/2309.14320", + "citation_bibtex": dedent(r""" + @inproceedings{shah2023mutex, + title={{MUTEX}: Learning Unified Policies from Multimodal Task Specifications}, + author={Rutav Shah and Roberto Mart{\'\i}n-Mart{\'\i}n and Yuke Zhu}, + booktitle={7th Annual Conference on Robot Learning}, + year={2023}, + url={https://openreview.net/forum?id=PwqiqaaEzJ} + }""").lstrip(), + }, + "utokyo_pr2_opening_fridge": { + "tasks_col": "language_instruction", + "license": "mit", + "citation_bibtex": dedent(r""" + @misc{oh2023pr2utokyodatasets, + author={Jihoon Oh and Naoaki Kanazawa and Kento Kawaharazuka}, + title={X-Embodiment U-Tokyo PR2 Datasets}, + year={2023}, + url={https://github.com/ojh6404/rlds_dataset_builder}, + }""").lstrip(), + }, + "utokyo_pr2_tabletop_manipulation": { + "tasks_col": "language_instruction", + "license": "mit", + "citation_bibtex": dedent(r""" + @misc{oh2023pr2utokyodatasets, + author={Jihoon Oh and Naoaki Kanazawa and Kento Kawaharazuka}, + title={X-Embodiment U-Tokyo PR2 Datasets}, + year={2023}, + url={https://github.com/ojh6404/rlds_dataset_builder}, + }""").lstrip(), + }, + "utokyo_saytap": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://saytap.github.io/", + "paper": "https://arxiv.org/abs/2306.07580", + "citation_bibtex": dedent(r""" + @article{saytap2023, + author = {Yujin Tang and Wenhao Yu and Jie Tan and Heiga Zen and Aleksandra Faust and + Tatsuya Harada}, + title = {SayTap: Language to Quadrupedal Locomotion}, + eprint = {arXiv:2306.07580}, + url = {https://saytap.github.io}, + note = {https://saytap.github.io}, + year = {2023} + }""").lstrip(), + }, + "utokyo_xarm_bimanual": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "citation_bibtex": dedent(r""" + @misc{matsushima2023weblab, + title={Weblab xArm Dataset}, + author={Tatsuya Matsushima and Hiroki Furuta and Yusuke Iwasawa and Yutaka Matsuo}, + year={2023}, + }""").lstrip(), + }, + "utokyo_xarm_pick_and_place": { + "tasks_col": "language_instruction", + "license": "cc-by-4.0", + "citation_bibtex": dedent(r""" + @misc{matsushima2023weblab, + title={Weblab xArm Dataset}, + author={Tatsuya Matsushima and Hiroki Furuta and Yusuke Iwasawa and Yutaka Matsuo}, + year={2023}, + }""").lstrip(), + }, + "viola": { + "tasks_col": "language_instruction", + "license": "mit", + "url": "https://ut-austin-rpl.github.io/VIOLA/", + "paper": "https://arxiv.org/abs/2210.11339", + "citation_bibtex": dedent(r""" + @article{zhu2022viola, + title={VIOLA: Imitation Learning for Vision-Based Manipulation with Object Proposal Priors}, + author={Zhu, Yifeng and Joshi, Abhishek and Stone, Peter and Zhu, Yuke}, + journal={6th Annual Conference on Robot Learning (CoRL)}, + year={2022} + }""").lstrip(), + }, +} + + +def batch_convert(): + status = {} + logfile = LOCAL_DIR / "conversion_log.txt" + assert set(DATASETS) == {id_.split("/")[1] for id_ in available_datasets} + for num, (name, kwargs) in enumerate(DATASETS.items()): + repo_id = f"lerobot/{name}" + print(f"\nConverting {repo_id} ({num}/{len(DATASETS)})") + print("---------------------------------------------------------") + try: + convert_dataset(repo_id, LOCAL_DIR, **kwargs) + status = f"{repo_id}: success." + with open(logfile, "a") as file: + file.write(status + "\n") + except Exception: + status = f"{repo_id}: failed\n {traceback.format_exc()}" + with open(logfile, "a") as file: + file.write(status + "\n") + continue + + +if __name__ == "__main__": + batch_convert() diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py new file mode 100644 index 000000000..bf135043b --- /dev/null +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -0,0 +1,665 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +""" +This script will help you convert any LeRobot dataset already pushed to the hub from codebase version 1.6 to +2.0. You will be required to provide the 'tasks', which is a short but accurate description in plain English +for each of the task performed in the dataset. This will allow to easily train models with task-conditionning. + +We support 3 different scenarios for these tasks (see instructions below): + 1. Single task dataset: all episodes of your dataset have the same single task. + 2. Single task episodes: the episodes of your dataset each contain a single task but they can differ from + one episode to the next. + 3. Multi task episodes: episodes of your dataset may each contain several different tasks. + + +Can you can also provide a robot config .yaml file (not mandatory) to this script via the option +'--robot-config' so that it writes information about the robot (robot type, motors names) this dataset was +recorded with. For now, only Aloha/Koch type robots are supported with this option. + + +# 1. Single task dataset +If your dataset contains a single task, you can simply provide it directly via the CLI with the +'--single-task' option. + +Examples: + +```bash +python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \ + --repo-id lerobot/aloha_sim_insertion_human_image \ + --single-task "Insert the peg into the socket." \ + --robot-config lerobot/configs/robot/aloha.yaml \ + --local-dir data +``` + +```bash +python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \ + --repo-id aliberts/koch_tutorial \ + --single-task "Pick the Lego block and drop it in the box on the right." \ + --robot-config lerobot/configs/robot/koch.yaml \ + --local-dir data +``` + + +# 2. Single task episodes +If your dataset is a multi-task dataset, you have two options to provide the tasks to this script: + +- If your dataset already contains a language instruction column in its parquet file, you can simply provide + this column's name with the '--tasks-col' arg. + + Example: + + ```bash + python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \ + --repo-id lerobot/stanford_kuka_multimodal_dataset \ + --tasks-col "language_instruction" \ + --local-dir data + ``` + +- If your dataset doesn't contain a language instruction, you should provide the path to a .json file with the + '--tasks-path' arg. This file should have the following structure where keys correspond to each + episode_index in the dataset, and values are the language instruction for that episode. + + Example: + + ```json + { + "0": "Do something", + "1": "Do something else", + "2": "Do something", + "3": "Go there", + ... + } + ``` + +# 3. Multi task episodes +If you have multiple tasks per episodes, your dataset should contain a language instruction column in its +parquet file, and you must provide this column's name with the '--tasks-col' arg. + +Example: + +```bash +python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \ + --repo-id lerobot/stanford_kuka_multimodal_dataset \ + --tasks-col "language_instruction" \ + --local-dir data +``` +""" + +import argparse +import contextlib +import filecmp +import json +import logging +import math +import shutil +import subprocess +import tempfile +from pathlib import Path + +import datasets +import pyarrow.compute as pc +import pyarrow.parquet as pq +import torch +from datasets import Dataset +from huggingface_hub import HfApi +from huggingface_hub.errors import EntryNotFoundError, HfHubHTTPError +from safetensors.torch import load_file + +from lerobot.common.datasets.utils import ( + DEFAULT_CHUNK_SIZE, + DEFAULT_PARQUET_PATH, + DEFAULT_VIDEO_PATH, + EPISODES_PATH, + INFO_PATH, + STATS_PATH, + TASKS_PATH, + create_branch, + create_lerobot_dataset_card, + flatten_dict, + get_hub_safe_version, + load_json, + unflatten_dict, + write_json, + write_jsonlines, +) +from lerobot.common.datasets.video_utils import ( + VideoFrame, # noqa: F401 + get_image_pixel_channels, + get_video_info, +) +from lerobot.common.utils.utils import init_hydra_config + +V16 = "v1.6" +V20 = "v2.0" + +GITATTRIBUTES_REF = "aliberts/gitattributes_reference" +V1_VIDEO_FILE = "{video_key}_episode_{episode_index:06d}.mp4" +V1_INFO_PATH = "meta_data/info.json" +V1_STATS_PATH = "meta_data/stats.safetensors" + + +def parse_robot_config(config_path: Path, config_overrides: list[str] | None = None) -> tuple[str, dict]: + robot_cfg = init_hydra_config(config_path, config_overrides) + if robot_cfg["robot_type"] in ["aloha", "koch"]: + state_names = [ + f"{arm}_{motor}" if len(robot_cfg["follower_arms"]) > 1 else motor + for arm in robot_cfg["follower_arms"] + for motor in robot_cfg["follower_arms"][arm]["motors"] + ] + action_names = [ + # f"{arm}_{motor}" for arm in ["left", "right"] for motor in robot_cfg["leader_arms"][arm]["motors"] + f"{arm}_{motor}" if len(robot_cfg["leader_arms"]) > 1 else motor + for arm in robot_cfg["leader_arms"] + for motor in robot_cfg["leader_arms"][arm]["motors"] + ] + # elif robot_cfg["robot_type"] == "stretch3": TODO + else: + raise NotImplementedError( + "Please provide robot_config={'robot_type': ..., 'names': ...} directly to convert_dataset()." + ) + + return { + "robot_type": robot_cfg["robot_type"], + "names": { + "observation.state": state_names, + "observation.effort": state_names, + "action": action_names, + }, + } + + +def convert_stats_to_json(v1_dir: Path, v2_dir: Path) -> None: + safetensor_path = v1_dir / V1_STATS_PATH + stats = load_file(safetensor_path) + serialized_stats = {key: value.tolist() for key, value in stats.items()} + serialized_stats = unflatten_dict(serialized_stats) + + json_path = v2_dir / STATS_PATH + json_path.parent.mkdir(exist_ok=True, parents=True) + with open(json_path, "w") as f: + json.dump(serialized_stats, f, indent=4) + + # Sanity check + with open(json_path) as f: + stats_json = json.load(f) + + stats_json = flatten_dict(stats_json) + stats_json = {key: torch.tensor(value) for key, value in stats_json.items()} + for key in stats: + torch.testing.assert_close(stats_json[key], stats[key]) + + +def get_features_from_hf_dataset(dataset: Dataset, robot_config: dict | None = None) -> dict[str, list]: + features = {} + for key, ft in dataset.features.items(): + if isinstance(ft, datasets.Value): + dtype = ft.dtype + shape = (1,) + names = None + if isinstance(ft, datasets.Sequence): + assert isinstance(ft.feature, datasets.Value) + dtype = ft.feature.dtype + shape = (ft.length,) + motor_names = ( + robot_config["names"][key] if robot_config else [f"motor_{i}" for i in range(ft.length)] + ) + assert len(motor_names) == shape[0] + names = {"motors": motor_names} + elif isinstance(ft, datasets.Image): + dtype = "image" + image = dataset[0][key] # Assuming first row + channels = get_image_pixel_channels(image) + shape = (image.height, image.width, channels) + names = ["height", "width", "channel"] + elif ft._type == "VideoFrame": + dtype = "video" + shape = None # Add shape later + names = ["height", "width", "channel"] + + features[key] = { + "dtype": dtype, + "shape": shape, + "names": names, + } + + return features + + +def add_task_index_by_episodes(dataset: Dataset, tasks_by_episodes: dict) -> tuple[Dataset, list[str]]: + df = dataset.to_pandas() + tasks = list(set(tasks_by_episodes.values())) + tasks_to_task_index = {task: task_idx for task_idx, task in enumerate(tasks)} + episodes_to_task_index = {ep_idx: tasks_to_task_index[task] for ep_idx, task in tasks_by_episodes.items()} + df["task_index"] = df["episode_index"].map(episodes_to_task_index).astype(int) + + features = dataset.features + features["task_index"] = datasets.Value(dtype="int64") + dataset = Dataset.from_pandas(df, features=features, split="train") + return dataset, tasks + + +def add_task_index_from_tasks_col( + dataset: Dataset, tasks_col: str +) -> tuple[Dataset, dict[str, list[str]], list[str]]: + df = dataset.to_pandas() + + # HACK: This is to clean some of the instructions in our version of Open X datasets + prefix_to_clean = "tf.Tensor(b'" + suffix_to_clean = "', shape=(), dtype=string)" + df[tasks_col] = df[tasks_col].str.removeprefix(prefix_to_clean).str.removesuffix(suffix_to_clean) + + # Create task_index col + tasks_by_episode = df.groupby("episode_index")[tasks_col].unique().apply(lambda x: x.tolist()).to_dict() + tasks = df[tasks_col].unique().tolist() + tasks_to_task_index = {task: idx for idx, task in enumerate(tasks)} + df["task_index"] = df[tasks_col].map(tasks_to_task_index).astype(int) + + # Build the dataset back from df + features = dataset.features + features["task_index"] = datasets.Value(dtype="int64") + dataset = Dataset.from_pandas(df, features=features, split="train") + dataset = dataset.remove_columns(tasks_col) + + return dataset, tasks, tasks_by_episode + + +def split_parquet_by_episodes( + dataset: Dataset, + total_episodes: int, + total_chunks: int, + output_dir: Path, +) -> list: + table = dataset.data.table + episode_lengths = [] + for ep_chunk in range(total_chunks): + ep_chunk_start = DEFAULT_CHUNK_SIZE * ep_chunk + ep_chunk_end = min(DEFAULT_CHUNK_SIZE * (ep_chunk + 1), total_episodes) + chunk_dir = "/".join(DEFAULT_PARQUET_PATH.split("/")[:-1]).format(episode_chunk=ep_chunk) + (output_dir / chunk_dir).mkdir(parents=True, exist_ok=True) + for ep_idx in range(ep_chunk_start, ep_chunk_end): + ep_table = table.filter(pc.equal(table["episode_index"], ep_idx)) + episode_lengths.insert(ep_idx, len(ep_table)) + output_file = output_dir / DEFAULT_PARQUET_PATH.format( + episode_chunk=ep_chunk, episode_index=ep_idx + ) + pq.write_table(ep_table, output_file) + + return episode_lengths + + +def move_videos( + repo_id: str, + video_keys: list[str], + total_episodes: int, + total_chunks: int, + work_dir: Path, + clean_gittatributes: Path, + branch: str = "main", +) -> None: + """ + HACK: Since HfApi() doesn't provide a way to move files directly in a repo, this function will run git + commands to fetch git lfs video files references to move them into subdirectories without having to + actually download them. + """ + _lfs_clone(repo_id, work_dir, branch) + + videos_moved = False + video_files = [str(f.relative_to(work_dir)) for f in work_dir.glob("videos*/*.mp4")] + if len(video_files) == 0: + video_files = [str(f.relative_to(work_dir)) for f in work_dir.glob("videos*/*/*/*.mp4")] + videos_moved = True # Videos have already been moved + + assert len(video_files) == total_episodes * len(video_keys) + + lfs_untracked_videos = _get_lfs_untracked_videos(work_dir, video_files) + + current_gittatributes = work_dir / ".gitattributes" + if not filecmp.cmp(current_gittatributes, clean_gittatributes, shallow=False): + fix_gitattributes(work_dir, current_gittatributes, clean_gittatributes) + + if lfs_untracked_videos: + fix_lfs_video_files_tracking(work_dir, video_files) + + if videos_moved: + return + + video_dirs = sorted(work_dir.glob("videos*/")) + for ep_chunk in range(total_chunks): + ep_chunk_start = DEFAULT_CHUNK_SIZE * ep_chunk + ep_chunk_end = min(DEFAULT_CHUNK_SIZE * (ep_chunk + 1), total_episodes) + for vid_key in video_keys: + chunk_dir = "/".join(DEFAULT_VIDEO_PATH.split("/")[:-1]).format( + episode_chunk=ep_chunk, video_key=vid_key + ) + (work_dir / chunk_dir).mkdir(parents=True, exist_ok=True) + + for ep_idx in range(ep_chunk_start, ep_chunk_end): + target_path = DEFAULT_VIDEO_PATH.format( + episode_chunk=ep_chunk, video_key=vid_key, episode_index=ep_idx + ) + video_file = V1_VIDEO_FILE.format(video_key=vid_key, episode_index=ep_idx) + if len(video_dirs) == 1: + video_path = video_dirs[0] / video_file + else: + for dir in video_dirs: + if (dir / video_file).is_file(): + video_path = dir / video_file + break + + video_path.rename(work_dir / target_path) + + commit_message = "Move video files into chunk subdirectories" + subprocess.run(["git", "add", "."], cwd=work_dir, check=True) + subprocess.run(["git", "commit", "-m", commit_message], cwd=work_dir, check=True) + subprocess.run(["git", "push"], cwd=work_dir, check=True) + + +def fix_lfs_video_files_tracking(work_dir: Path, lfs_untracked_videos: list[str]) -> None: + """ + HACK: This function fixes the tracking by git lfs which was not properly set on some repos. In that case, + there's no other option than to download the actual files and reupload them with lfs tracking. + """ + for i in range(0, len(lfs_untracked_videos), 100): + files = lfs_untracked_videos[i : i + 100] + try: + subprocess.run(["git", "rm", "--cached", *files], cwd=work_dir, capture_output=True, check=True) + except subprocess.CalledProcessError as e: + print("git rm --cached ERROR:") + print(e.stderr) + subprocess.run(["git", "add", *files], cwd=work_dir, check=True) + + commit_message = "Track video files with git lfs" + subprocess.run(["git", "commit", "-m", commit_message], cwd=work_dir, check=True) + subprocess.run(["git", "push"], cwd=work_dir, check=True) + + +def fix_gitattributes(work_dir: Path, current_gittatributes: Path, clean_gittatributes: Path) -> None: + shutil.copyfile(clean_gittatributes, current_gittatributes) + subprocess.run(["git", "add", ".gitattributes"], cwd=work_dir, check=True) + subprocess.run(["git", "commit", "-m", "Fix .gitattributes"], cwd=work_dir, check=True) + subprocess.run(["git", "push"], cwd=work_dir, check=True) + + +def _lfs_clone(repo_id: str, work_dir: Path, branch: str) -> None: + subprocess.run(["git", "lfs", "install"], cwd=work_dir, check=True) + repo_url = f"https://huggingface.co/datasets/{repo_id}" + env = {"GIT_LFS_SKIP_SMUDGE": "1"} # Prevent downloading LFS files + subprocess.run( + ["git", "clone", "--branch", branch, "--single-branch", "--depth", "1", repo_url, str(work_dir)], + check=True, + env=env, + ) + + +def _get_lfs_untracked_videos(work_dir: Path, video_files: list[str]) -> list[str]: + lfs_tracked_files = subprocess.run( + ["git", "lfs", "ls-files", "-n"], cwd=work_dir, capture_output=True, text=True, check=True + ) + lfs_tracked_files = set(lfs_tracked_files.stdout.splitlines()) + return [f for f in video_files if f not in lfs_tracked_files] + + +def get_videos_info(repo_id: str, local_dir: Path, video_keys: list[str], branch: str) -> dict: + # Assumes first episode + video_files = [ + DEFAULT_VIDEO_PATH.format(episode_chunk=0, video_key=vid_key, episode_index=0) + for vid_key in video_keys + ] + hub_api = HfApi() + hub_api.snapshot_download( + repo_id=repo_id, repo_type="dataset", local_dir=local_dir, revision=branch, allow_patterns=video_files + ) + videos_info_dict = {} + for vid_key, vid_path in zip(video_keys, video_files, strict=True): + videos_info_dict[vid_key] = get_video_info(local_dir / vid_path) + + return videos_info_dict + + +def convert_dataset( + repo_id: str, + local_dir: Path, + single_task: str | None = None, + tasks_path: Path | None = None, + tasks_col: Path | None = None, + robot_config: dict | None = None, + test_branch: str | None = None, + **card_kwargs, +): + v1 = get_hub_safe_version(repo_id, V16) + v1x_dir = local_dir / V16 / repo_id + v20_dir = local_dir / V20 / repo_id + v1x_dir.mkdir(parents=True, exist_ok=True) + v20_dir.mkdir(parents=True, exist_ok=True) + + hub_api = HfApi() + hub_api.snapshot_download( + repo_id=repo_id, repo_type="dataset", revision=v1, local_dir=v1x_dir, ignore_patterns="videos*/" + ) + branch = "main" + if test_branch: + branch = test_branch + create_branch(repo_id=repo_id, branch=test_branch, repo_type="dataset") + + metadata_v1 = load_json(v1x_dir / V1_INFO_PATH) + dataset = datasets.load_dataset("parquet", data_dir=v1x_dir / "data", split="train") + features = get_features_from_hf_dataset(dataset, robot_config) + video_keys = [key for key, ft in features.items() if ft["dtype"] == "video"] + + if single_task and "language_instruction" in dataset.column_names: + logging.warning( + "'single_task' provided but 'language_instruction' tasks_col found. Using 'language_instruction'.", + ) + single_task = None + tasks_col = "language_instruction" + + # Episodes & chunks + episode_indices = sorted(dataset.unique("episode_index")) + total_episodes = len(episode_indices) + assert episode_indices == list(range(total_episodes)) + total_videos = total_episodes * len(video_keys) + total_chunks = total_episodes // DEFAULT_CHUNK_SIZE + if total_episodes % DEFAULT_CHUNK_SIZE != 0: + total_chunks += 1 + + # Tasks + if single_task: + tasks_by_episodes = {ep_idx: single_task for ep_idx in episode_indices} + dataset, tasks = add_task_index_by_episodes(dataset, tasks_by_episodes) + tasks_by_episodes = {ep_idx: [task] for ep_idx, task in tasks_by_episodes.items()} + elif tasks_path: + tasks_by_episodes = load_json(tasks_path) + tasks_by_episodes = {int(ep_idx): task for ep_idx, task in tasks_by_episodes.items()} + dataset, tasks = add_task_index_by_episodes(dataset, tasks_by_episodes) + tasks_by_episodes = {ep_idx: [task] for ep_idx, task in tasks_by_episodes.items()} + elif tasks_col: + dataset, tasks, tasks_by_episodes = add_task_index_from_tasks_col(dataset, tasks_col) + else: + raise ValueError + + assert set(tasks) == {task for ep_tasks in tasks_by_episodes.values() for task in ep_tasks} + tasks = [{"task_index": task_idx, "task": task} for task_idx, task in enumerate(tasks)] + write_jsonlines(tasks, v20_dir / TASKS_PATH) + features["task_index"] = { + "dtype": "int64", + "shape": (1,), + "names": None, + } + + # Videos + if video_keys: + assert metadata_v1.get("video", False) + dataset = dataset.remove_columns(video_keys) + clean_gitattr = Path( + hub_api.hf_hub_download( + repo_id=GITATTRIBUTES_REF, repo_type="dataset", local_dir=local_dir, filename=".gitattributes" + ) + ).absolute() + with tempfile.TemporaryDirectory() as tmp_video_dir: + move_videos( + repo_id, video_keys, total_episodes, total_chunks, Path(tmp_video_dir), clean_gitattr, branch + ) + videos_info = get_videos_info(repo_id, v1x_dir, video_keys=video_keys, branch=branch) + for key in video_keys: + features[key]["shape"] = ( + videos_info[key].pop("video.height"), + videos_info[key].pop("video.width"), + videos_info[key].pop("video.channels"), + ) + features[key]["video_info"] = videos_info[key] + assert math.isclose(videos_info[key]["video.fps"], metadata_v1["fps"], rel_tol=1e-3) + if "encoding" in metadata_v1: + assert videos_info[key]["video.pix_fmt"] == metadata_v1["encoding"]["pix_fmt"] + else: + assert metadata_v1.get("video", 0) == 0 + videos_info = None + + # Split data into 1 parquet file by episode + episode_lengths = split_parquet_by_episodes(dataset, total_episodes, total_chunks, v20_dir) + + if robot_config is not None: + robot_type = robot_config["robot_type"] + repo_tags = [robot_type] + else: + robot_type = "unknown" + repo_tags = None + + # Episodes + episodes = [ + {"episode_index": ep_idx, "tasks": tasks_by_episodes[ep_idx], "length": episode_lengths[ep_idx]} + for ep_idx in episode_indices + ] + write_jsonlines(episodes, v20_dir / EPISODES_PATH) + + # Assemble metadata v2.0 + metadata_v2_0 = { + "codebase_version": V20, + "robot_type": robot_type, + "total_episodes": total_episodes, + "total_frames": len(dataset), + "total_tasks": len(tasks), + "total_videos": total_videos, + "total_chunks": total_chunks, + "chunks_size": DEFAULT_CHUNK_SIZE, + "fps": metadata_v1["fps"], + "splits": {"train": f"0:{total_episodes}"}, + "data_path": DEFAULT_PARQUET_PATH, + "video_path": DEFAULT_VIDEO_PATH if video_keys else None, + "features": features, + } + write_json(metadata_v2_0, v20_dir / INFO_PATH) + convert_stats_to_json(v1x_dir, v20_dir) + card = create_lerobot_dataset_card(tags=repo_tags, dataset_info=metadata_v2_0, **card_kwargs) + + with contextlib.suppress(EntryNotFoundError, HfHubHTTPError): + hub_api.delete_folder(repo_id=repo_id, path_in_repo="data", repo_type="dataset", revision=branch) + + with contextlib.suppress(EntryNotFoundError, HfHubHTTPError): + hub_api.delete_folder(repo_id=repo_id, path_in_repo="meta_data", repo_type="dataset", revision=branch) + + with contextlib.suppress(EntryNotFoundError, HfHubHTTPError): + hub_api.delete_folder(repo_id=repo_id, path_in_repo="meta", repo_type="dataset", revision=branch) + + hub_api.upload_folder( + repo_id=repo_id, + path_in_repo="data", + folder_path=v20_dir / "data", + repo_type="dataset", + revision=branch, + ) + hub_api.upload_folder( + repo_id=repo_id, + path_in_repo="meta", + folder_path=v20_dir / "meta", + repo_type="dataset", + revision=branch, + ) + + card.push_to_hub(repo_id=repo_id, repo_type="dataset", revision=branch) + + if not test_branch: + create_branch(repo_id=repo_id, branch=V20, repo_type="dataset") + + +def main(): + parser = argparse.ArgumentParser() + task_args = parser.add_mutually_exclusive_group(required=True) + + parser.add_argument( + "--repo-id", + type=str, + required=True, + help="Repository identifier on Hugging Face: a community or a user name `/` the name of the dataset (e.g. `lerobot/pusht`, `cadene/aloha_sim_insertion_human`).", + ) + task_args.add_argument( + "--single-task", + type=str, + help="A short but accurate description of the single task performed in the dataset.", + ) + task_args.add_argument( + "--tasks-col", + type=str, + help="The name of the column containing language instructions", + ) + task_args.add_argument( + "--tasks-path", + type=Path, + help="The path to a .json file containing one language instruction for each episode_index", + ) + parser.add_argument( + "--robot-config", + type=Path, + default=None, + help="Path to the robot's config yaml the dataset during conversion.", + ) + parser.add_argument( + "--robot-overrides", + type=str, + nargs="*", + help="Any key=value arguments to override the robot config values (use dots for.nested=overrides)", + ) + parser.add_argument( + "--local-dir", + type=Path, + default=None, + help="Local directory to store the dataset during conversion. Defaults to /tmp/lerobot_dataset_v2", + ) + parser.add_argument( + "--license", + type=str, + default="apache-2.0", + help="Repo license. Must be one of https://huggingface.co/docs/hub/repositories-licenses. Defaults to mit.", + ) + parser.add_argument( + "--test-branch", + type=str, + default=None, + help="Repo branch to test your conversion first (e.g. 'v2.0.test')", + ) + + args = parser.parse_args() + if not args.local_dir: + args.local_dir = Path("/tmp/lerobot_dataset_v2") + + robot_config = parse_robot_config(args.robot_config, args.robot_overrides) if args.robot_config else None + del args.robot_config, args.robot_overrides + + convert_dataset(**vars(args), robot_config=robot_config) + + +if __name__ == "__main__": + main() diff --git a/lerobot/common/datasets/video_utils.py b/lerobot/common/datasets/video_utils.py index 4d4ac6b0a..8ed3318dd 100644 --- a/lerobot/common/datasets/video_utils.py +++ b/lerobot/common/datasets/video_utils.py @@ -13,6 +13,7 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. +import json import logging import subprocess import warnings @@ -25,47 +26,11 @@ import torch import torchvision from datasets.features.features import register_feature - - -def load_from_videos( - item: dict[str, torch.Tensor], - video_frame_keys: list[str], - videos_dir: Path, - tolerance_s: float, - backend: str = "pyav", -): - """Note: When using data workers (e.g. DataLoader with num_workers>0), do not call this function - in the main process (e.g. by using a second Dataloader with num_workers=0). It will result in a Segmentation Fault. - This probably happens because a memory reference to the video loader is created in the main process and a - subprocess fails to access it. - """ - # since video path already contains "videos" (e.g. videos_dir="data/videos", path="videos/episode_0.mp4") - data_dir = videos_dir.parent - - for key in video_frame_keys: - if isinstance(item[key], list): - # load multiple frames at once (expected when delta_timestamps is not None) - timestamps = [frame["timestamp"] for frame in item[key]] - paths = [frame["path"] for frame in item[key]] - if len(set(paths)) > 1: - raise NotImplementedError("All video paths are expected to be the same for now.") - video_path = data_dir / paths[0] - - frames = decode_video_frames_torchvision(video_path, timestamps, tolerance_s, backend) - item[key] = frames - else: - # load one frame - timestamps = [item[key]["timestamp"]] - video_path = data_dir / item[key]["path"] - - frames = decode_video_frames_torchvision(video_path, timestamps, tolerance_s, backend) - item[key] = frames[0] - - return item +from PIL import Image def decode_video_frames_torchvision( - video_path: str, + video_path: Path | str, timestamps: list[float], tolerance_s: float, backend: str = "pyav", @@ -163,8 +128,8 @@ def decode_video_frames_torchvision( def encode_video_frames( - imgs_dir: Path, - video_path: Path, + imgs_dir: Path | str, + video_path: Path | str, fps: int, vcodec: str = "libsvtav1", pix_fmt: str = "yuv420p", @@ -247,3 +212,104 @@ def __call__(self): ) # to make VideoFrame available in HuggingFace `datasets` register_feature(VideoFrame, "VideoFrame") + + +def get_audio_info(video_path: Path | str) -> dict: + ffprobe_audio_cmd = [ + "ffprobe", + "-v", + "error", + "-select_streams", + "a:0", + "-show_entries", + "stream=channels,codec_name,bit_rate,sample_rate,bit_depth,channel_layout,duration", + "-of", + "json", + str(video_path), + ] + result = subprocess.run(ffprobe_audio_cmd, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True) + if result.returncode != 0: + raise RuntimeError(f"Error running ffprobe: {result.stderr}") + + info = json.loads(result.stdout) + audio_stream_info = info["streams"][0] if info.get("streams") else None + if audio_stream_info is None: + return {"has_audio": False} + + # Return the information, defaulting to None if no audio stream is present + return { + "has_audio": True, + "audio.channels": audio_stream_info.get("channels", None), + "audio.codec": audio_stream_info.get("codec_name", None), + "audio.bit_rate": int(audio_stream_info["bit_rate"]) if audio_stream_info.get("bit_rate") else None, + "audio.sample_rate": int(audio_stream_info["sample_rate"]) + if audio_stream_info.get("sample_rate") + else None, + "audio.bit_depth": audio_stream_info.get("bit_depth", None), + "audio.channel_layout": audio_stream_info.get("channel_layout", None), + } + + +def get_video_info(video_path: Path | str) -> dict: + ffprobe_video_cmd = [ + "ffprobe", + "-v", + "error", + "-select_streams", + "v:0", + "-show_entries", + "stream=r_frame_rate,width,height,codec_name,nb_frames,duration,pix_fmt", + "-of", + "json", + str(video_path), + ] + result = subprocess.run(ffprobe_video_cmd, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True) + if result.returncode != 0: + raise RuntimeError(f"Error running ffprobe: {result.stderr}") + + info = json.loads(result.stdout) + video_stream_info = info["streams"][0] + + # Calculate fps from r_frame_rate + r_frame_rate = video_stream_info["r_frame_rate"] + num, denom = map(int, r_frame_rate.split("/")) + fps = num / denom + + pixel_channels = get_video_pixel_channels(video_stream_info["pix_fmt"]) + + video_info = { + "video.fps": fps, + "video.height": video_stream_info["height"], + "video.width": video_stream_info["width"], + "video.channels": pixel_channels, + "video.codec": video_stream_info["codec_name"], + "video.pix_fmt": video_stream_info["pix_fmt"], + "video.is_depth_map": False, + **get_audio_info(video_path), + } + + return video_info + + +def get_video_pixel_channels(pix_fmt: str) -> int: + if "gray" in pix_fmt or "depth" in pix_fmt or "monochrome" in pix_fmt: + return 1 + elif "rgba" in pix_fmt or "yuva" in pix_fmt: + return 4 + elif "rgb" in pix_fmt or "yuv" in pix_fmt: + return 3 + else: + raise ValueError("Unknown format") + + +def get_image_pixel_channels(image: Image): + if image.mode == "L": + return 1 # Grayscale + elif image.mode == "LA": + return 2 # Grayscale + Alpha + elif image.mode == "RGB": + return 3 # RGB + elif image.mode == "RGBA": + return 4 # RGBA + else: + raise ValueError("Unknown format") diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index 479694277..84ac540f2 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -168,6 +168,7 @@ class IntelRealSenseCameraConfig: width: int | None = None height: int | None = None color_mode: str = "rgb" + channels: int | None = None use_depth: bool = False force_hardware_reset: bool = True rotation: int | None = None @@ -179,6 +180,8 @@ def __post_init__(self): f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." ) + self.channels = 3 + at_least_one_is_not_none = self.fps is not None or self.width is not None or self.height is not None at_least_one_is_none = self.fps is None or self.width is None or self.height is None if at_least_one_is_not_none and at_least_one_is_none: @@ -254,6 +257,7 @@ def __init__( self.fps = config.fps self.width = config.width self.height = config.height + self.channels = config.channels self.color_mode = config.color_mode self.use_depth = config.use_depth self.force_hardware_reset = config.force_hardware_reset diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 2d8b12c91..d284cf55a 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -192,6 +192,7 @@ class OpenCVCameraConfig: width: int | None = None height: int | None = None color_mode: str = "rgb" + channels: int | None = None rotation: int | None = None mock: bool = False @@ -201,6 +202,8 @@ def __post_init__(self): f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." ) + self.channels = 3 + if self.rotation not in [-90, None, 90, 180]: raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") @@ -268,6 +271,7 @@ def __init__(self, camera_index: int | str, config: OpenCVCameraConfig | None = self.fps = config.fps self.width = config.width self.height = config.height + self.channels = config.channels self.color_mode = config.color_mode self.mock = config.mock diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index d2879c960..9b9649dde 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -13,9 +13,12 @@ import cv2 import torch import tqdm +from deepdiff import DeepDiff from termcolor import colored -from lerobot.common.datasets.populate_dataset import add_frame, safe_stop_image_writer +from lerobot.common.datasets.image_writer import safe_stop_image_writer +from lerobot.common.datasets.lerobot_dataset import LeRobotDataset +from lerobot.common.datasets.utils import get_features_from_robot from lerobot.common.policies.factory import make_policy from lerobot.common.robot_devices.robots.utils import Robot from lerobot.common.robot_devices.utils import busy_wait @@ -227,7 +230,7 @@ def control_loop( control_time_s=None, teleoperate=False, display_cameras=False, - dataset=None, + dataset: LeRobotDataset | None = None, events=None, policy=None, device=None, @@ -247,7 +250,7 @@ def control_loop( if teleoperate and policy is not None: raise ValueError("When `teleoperate` is True, `policy` should be None.") - if dataset is not None and fps is not None and dataset["fps"] != fps: + if dataset is not None and fps is not None and dataset.fps != fps: raise ValueError(f"The dataset fps should be equal to requested fps ({dataset['fps']} != {fps}).") timestamp = 0 @@ -268,7 +271,8 @@ def control_loop( action = {"action": action} if dataset is not None: - add_frame(dataset, observation, action) + frame = {**observation, **action} + dataset.add_frame(frame) if display_cameras and not is_headless(): image_keys = [key for key in observation if "image" in key] @@ -336,3 +340,24 @@ def sanity_check_dataset_name(repo_id, policy): raise ValueError( f"Your dataset name does not begin with 'eval_' ({dataset_name}), but a policy is provided ({policy})." ) + + +def sanity_check_dataset_robot_compatibility( + dataset: LeRobotDataset, robot: Robot, fps: int, use_videos: bool +) -> None: + fields = [ + ("robot_type", dataset.meta.robot_type, robot.robot_type), + ("fps", dataset.fps, fps), + ("features", dataset.features, get_features_from_robot(robot, use_videos)), + ] + + mismatches = [] + for field, dataset_value, present_value in fields: + diff = DeepDiff(dataset_value, present_value, exclude_regex_paths=[r".*\['info'\]$"]) + if diff: + mismatches.append(f"{field}: expected {present_value}, got {dataset_value}") + + if mismatches: + raise ValueError( + "Dataset metadata compatibility check failed with mismatches:\n" + "\n".join(mismatches) + ) diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index a20d5aed8..618105064 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -226,6 +226,42 @@ def __init__( self.is_connected = False self.logs = {} + def get_motor_names(self, arm: dict[str, MotorsBus]) -> list: + return [f"{arm}_{motor}" for arm, bus in arm.items() for motor in bus.motors] + + @property + def camera_features(self) -> dict: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + key = f"observation.images.{cam_key}" + cam_ft[key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + @property + def motor_features(self) -> dict: + action_names = self.get_motor_names(self.leader_arms) + state_names = self.get_motor_names(self.leader_arms) + return { + "action": { + "dtype": "float32", + "shape": (len(action_names),), + "names": action_names, + }, + "observation.state": { + "dtype": "float32", + "shape": (len(state_names),), + "names": state_names, + }, + } + + @property + def features(self): + return {**self.motor_features, **self.camera_features} + @property def has_camera(self): return len(self.cameras) > 0 diff --git a/lerobot/common/robot_devices/robots/utils.py b/lerobot/common/robot_devices/robots/utils.py index 5cd5bd100..a40db1312 100644 --- a/lerobot/common/robot_devices/robots/utils.py +++ b/lerobot/common/robot_devices/robots/utils.py @@ -11,6 +11,7 @@ def get_arm_id(name, arm_type): class Robot(Protocol): # TODO(rcadene, aliberts): Add unit test checking the protocol is implemented in the corresponding classes robot_type: str + features: dict def connect(self): ... def run_calibration(self): ... diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 031e608e7..563023f48 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -29,7 +29,6 @@ ```bash python lerobot/scripts/control_robot.py record \ --fps 30 \ - --root tmp/data \ --repo-id $USER/koch_test \ --num-episodes 1 \ --run-compute-stats 0 @@ -38,7 +37,6 @@ - Visualize dataset: ```bash python lerobot/scripts/visualize_dataset.py \ - --root tmp/data \ --repo-id $USER/koch_test \ --episode-index 0 ``` @@ -47,7 +45,6 @@ ```bash python lerobot/scripts/control_robot.py replay \ --fps 30 \ - --root tmp/data \ --repo-id $USER/koch_test \ --episode 0 ``` @@ -57,7 +54,6 @@ ```bash python lerobot/scripts/control_robot.py record \ --fps 30 \ - --root data \ --repo-id $USER/koch_pick_place_lego \ --num-episodes 50 \ --warmup-time-s 2 \ @@ -77,7 +73,7 @@ - Train on this dataset with the ACT policy: ```bash -DATA_DIR=data python lerobot/scripts/train.py \ +python lerobot/scripts/train.py \ policy=act_koch_real \ env=koch_real \ dataset_repo_id=$USER/koch_pick_place_lego \ @@ -88,7 +84,6 @@ ```bash python lerobot/scripts/control_robot.py record \ --fps 30 \ - --root data \ --repo-id $USER/eval_act_koch_real \ --num-episodes 10 \ --warmup-time-s 2 \ @@ -106,12 +101,6 @@ # from safetensors.torch import load_file, save_file from lerobot.common.datasets.lerobot_dataset import LeRobotDataset -from lerobot.common.datasets.populate_dataset import ( - create_lerobot_dataset, - delete_current_episode, - init_dataset, - save_current_episode, -) from lerobot.common.robot_devices.control_utils import ( control_loop, has_method, @@ -121,6 +110,7 @@ record_episode, reset_environment, sanity_check_dataset_name, + sanity_check_dataset_robot_compatibility, stop_recording, warmup_record, ) @@ -196,25 +186,28 @@ def teleoperate( @safe_disconnect def record( robot: Robot, - root: str, + root: Path, repo_id: str, + single_task: str, pretrained_policy_name_or_path: str | None = None, policy_overrides: List[str] | None = None, fps: int | None = None, - warmup_time_s=2, - episode_time_s=10, - reset_time_s=5, - num_episodes=50, - video=True, - run_compute_stats=True, - push_to_hub=True, - tags=None, - num_image_writer_processes=0, - num_image_writer_threads_per_camera=4, - force_override=False, - display_cameras=True, - play_sounds=True, -): + warmup_time_s: int | float = 2, + episode_time_s: int | float = 10, + reset_time_s: int | float = 5, + num_episodes: int = 50, + video: bool = True, + run_compute_stats: bool = True, + push_to_hub: bool = True, + tags: list[str] | None = None, + num_image_writer_processes: int = 0, + num_image_writer_threads_per_camera: int = 4, + display_cameras: bool = True, + play_sounds: bool = True, + resume: bool = False, + # TODO(rcadene, aliberts): remove local_files_only when refactor with dataset as argument + local_files_only: bool = False, +) -> LeRobotDataset: # TODO(rcadene): Add option to record logs listener = None events = None @@ -222,6 +215,11 @@ def record( device = None use_amp = None + if single_task: + task = single_task + else: + raise NotImplementedError("Only single-task recording is supported for now") + # Load pretrained policy if pretrained_policy_name_or_path is not None: policy, policy_fps, device, use_amp = init_policy(pretrained_policy_name_or_path, policy_overrides) @@ -234,18 +232,29 @@ def record( f"There is a mismatch between the provided fps ({fps}) and the one from policy config ({policy_fps})." ) - # Create empty dataset or load existing saved episodes - sanity_check_dataset_name(repo_id, policy) - dataset = init_dataset( - repo_id, - root, - force_override, - fps, - video, - write_images=robot.has_camera, - num_image_writer_processes=num_image_writer_processes, - num_image_writer_threads=num_image_writer_threads_per_camera * robot.num_cameras, - ) + if resume: + dataset = LeRobotDataset( + repo_id, + root=root, + local_files_only=local_files_only, + ) + dataset.start_image_writer( + num_processes=num_image_writer_processes, + num_threads=num_image_writer_threads_per_camera * len(robot.cameras), + ) + sanity_check_dataset_robot_compatibility(dataset, robot, fps, video) + else: + # Create empty dataset or load existing saved episodes + sanity_check_dataset_name(repo_id, policy) + dataset = LeRobotDataset.create( + repo_id, + fps, + root=root, + robot=robot, + use_videos=video, + image_writer_processes=num_image_writer_processes, + image_writer_threads=num_image_writer_threads_per_camera * len(robot.cameras), + ) if not robot.is_connected: robot.connect() @@ -263,12 +272,17 @@ def record( if has_method(robot, "teleop_safety_stop"): robot.teleop_safety_stop() + recorded_episodes = 0 while True: - if dataset["num_episodes"] >= num_episodes: + if recorded_episodes >= num_episodes: break - episode_index = dataset["num_episodes"] - log_say(f"Recording episode {episode_index}", play_sounds) + # TODO(aliberts): add task prompt for multitask here. Might need to temporarily disable event if + # input() messes with them. + # if multi_task: + # task = input("Enter your task description: ") + + log_say(f"Recording episode {dataset.num_episodes}", play_sounds) record_episode( dataset=dataset, robot=robot, @@ -286,7 +300,7 @@ def record( # TODO(rcadene): add an option to enable teleoperation during reset # Skip reset for the last episode to be recorded if not events["stop_recording"] and ( - (episode_index < num_episodes - 1) or events["rerecord_episode"] + (dataset.num_episodes < num_episodes - 1) or events["rerecord_episode"] ): log_say("Reset the environment", play_sounds) reset_environment(robot, events, reset_time_s) @@ -295,11 +309,11 @@ def record( log_say("Re-record episode", play_sounds) events["rerecord_episode"] = False events["exit_early"] = False - delete_current_episode(dataset) + dataset.clear_episode_buffer() continue - # Increment by one dataset["current_episode_index"] - save_current_episode(dataset) + dataset.save_episode(task) + recorded_episodes += 1 if events["stop_recording"]: break @@ -307,35 +321,42 @@ def record( log_say("Stop recording", play_sounds, blocking=True) stop_recording(robot, listener, display_cameras) - lerobot_dataset = create_lerobot_dataset(dataset, run_compute_stats, push_to_hub, tags, play_sounds) + if run_compute_stats: + logging.info("Computing dataset statistics") + + dataset.consolidate(run_compute_stats) + + if push_to_hub: + dataset.push_to_hub(tags=tags) log_say("Exiting", play_sounds) - return lerobot_dataset + return dataset @safe_disconnect def replay( - robot: Robot, episode: int, fps: int | None = None, root="data", repo_id="lerobot/debug", play_sounds=True + robot: Robot, + root: Path, + repo_id: str, + episode: int, + fps: int | None = None, + play_sounds: bool = True, + local_files_only: bool = True, ): # TODO(rcadene, aliberts): refactor with control_loop, once `dataset` is an instance of LeRobotDataset # TODO(rcadene): Add option to record logs - local_dir = Path(root) / repo_id - if not local_dir.exists(): - raise ValueError(local_dir) - dataset = LeRobotDataset(repo_id, root=root) - items = dataset.hf_dataset.select_columns("action") - from_idx = dataset.episode_data_index["from"][episode].item() - to_idx = dataset.episode_data_index["to"][episode].item() + dataset = LeRobotDataset(repo_id, root=root, episodes=[episode], local_files_only=local_files_only) + actions = dataset.hf_dataset.select_columns("action") if not robot.is_connected: robot.connect() log_say("Replaying episode", play_sounds, blocking=True) - for idx in range(from_idx, to_idx): + for idx in range(dataset.num_frames): start_episode_t = time.perf_counter() - action = items[idx]["action"] + action = actions[idx]["action"] robot.send_action(action) dt_s = time.perf_counter() - start_episode_t @@ -384,13 +405,25 @@ def replay( ) parser_record = subparsers.add_parser("record", parents=[base_parser]) + task_args = parser_record.add_mutually_exclusive_group(required=True) parser_record.add_argument( "--fps", type=none_or_int, default=None, help="Frames per second (set to None to disable)" ) + task_args.add_argument( + "--single-task", + type=str, + help="A short but accurate description of the task performed during the recording.", + ) + # TODO(aliberts): add multi-task support + # task_args.add_argument( + # "--multi-task", + # type=int, + # help="You will need to enter the task performed at the start of each episode.", + # ) parser_record.add_argument( "--root", type=Path, - default="data", + default=None, help="Root directory where the dataset will be stored locally at '{root}/{repo_id}' (e.g. 'data/hf_username/dataset_name').", ) parser_record.add_argument( @@ -458,10 +491,10 @@ def replay( ), ) parser_record.add_argument( - "--force-override", + "--resume", type=int, default=0, - help="By default, data recording is resumed. When set to 1, delete the local directory and start data recording from scratch.", + help="Resume recording on an existing dataset.", ) parser_record.add_argument( "-p", @@ -486,7 +519,7 @@ def replay( parser_replay.add_argument( "--root", type=Path, - default="data", + default=None, help="Root directory where the dataset will be stored locally at '{root}/{repo_id}' (e.g. 'data/hf_username/dataset_name').", ) parser_replay.add_argument( diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 0aec84720..040f92d96 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -484,7 +484,7 @@ def main( policy = make_policy(hydra_cfg=hydra_cfg, pretrained_policy_name_or_path=str(pretrained_policy_path)) else: # Note: We need the dataset stats to pass to the policy's normalization modules. - policy = make_policy(hydra_cfg=hydra_cfg, dataset_stats=make_dataset(hydra_cfg).stats) + policy = make_policy(hydra_cfg=hydra_cfg, dataset_stats=make_dataset(hydra_cfg).meta.stats) assert isinstance(policy, nn.Module) policy.eval() diff --git a/lerobot/scripts/push_dataset_to_hub.py b/lerobot/scripts/push_dataset_to_hub.py index adc4c72ad..2bb641a4d 100644 --- a/lerobot/scripts/push_dataset_to_hub.py +++ b/lerobot/scripts/push_dataset_to_hub.py @@ -117,10 +117,14 @@ def push_meta_data_to_hub(repo_id: str, meta_data_dir: str | Path, revision: str def push_dataset_card_to_hub( - repo_id: str, revision: str | None, tags: list | None = None, text: str | None = None + repo_id: str, + revision: str | None, + tags: list | None = None, + license: str = "apache-2.0", + **card_kwargs, ): """Creates and pushes a LeRobotDataset Card with appropriate tags to easily find it on the hub.""" - card = create_lerobot_dataset_card(tags=tags, text=text) + card = create_lerobot_dataset_card(tags=tags, license=license, **card_kwargs) card.push_to_hub(repo_id=repo_id, repo_type="dataset", revision=revision) @@ -260,7 +264,7 @@ def push_dataset_to_hub( episode_index = 0 tests_videos_dir = tests_data_dir / repo_id / "videos" tests_videos_dir.mkdir(parents=True, exist_ok=True) - for key in lerobot_dataset.video_frame_keys: + for key in lerobot_dataset.camera_keys: fname = f"{key}_episode_{episode_index:06d}.mp4" shutil.copy(videos_dir / fname, tests_videos_dir / fname) diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index f60f904eb..9a0b7e4cb 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -171,9 +171,9 @@ def log_train_info(logger: Logger, info, step, cfg, dataset, is_online): # A sample is an (observation,action) pair, where observation and action # can be on multiple timestamps. In a batch, we have `batch_size`` number of samples. num_samples = (step + 1) * cfg.training.batch_size - avg_samples_per_ep = dataset.num_samples / dataset.num_episodes + avg_samples_per_ep = dataset.num_frames / dataset.num_episodes num_episodes = num_samples / avg_samples_per_ep - num_epochs = num_samples / dataset.num_samples + num_epochs = num_samples / dataset.num_frames log_items = [ f"step:{format_big_number(step)}", # number of samples seen during training @@ -208,9 +208,9 @@ def log_eval_info(logger, info, step, cfg, dataset, is_online): # A sample is an (observation,action) pair, where observation and action # can be on multiple timestamps. In a batch, we have `batch_size`` number of samples. num_samples = (step + 1) * cfg.training.batch_size - avg_samples_per_ep = dataset.num_samples / dataset.num_episodes + avg_samples_per_ep = dataset.num_frames / dataset.num_episodes num_episodes = num_samples / avg_samples_per_ep - num_epochs = num_samples / dataset.num_samples + num_epochs = num_samples / dataset.num_frames log_items = [ f"step:{format_big_number(step)}", # number of samples seen during training @@ -328,7 +328,7 @@ def train(cfg: DictConfig, out_dir: str | None = None, job_name: str | None = No logging.info("make_policy") policy = make_policy( hydra_cfg=cfg, - dataset_stats=offline_dataset.stats if not cfg.resume else None, + dataset_stats=offline_dataset.meta.stats if not cfg.resume else None, pretrained_policy_name_or_path=str(logger.last_pretrained_model_dir) if cfg.resume else None, ) assert isinstance(policy, nn.Module) @@ -349,7 +349,7 @@ def train(cfg: DictConfig, out_dir: str | None = None, job_name: str | None = No logging.info(f"{cfg.env.task=}") logging.info(f"{cfg.training.offline_steps=} ({format_big_number(cfg.training.offline_steps)})") logging.info(f"{cfg.training.online_steps=}") - logging.info(f"{offline_dataset.num_samples=} ({format_big_number(offline_dataset.num_samples)})") + logging.info(f"{offline_dataset.num_frames=} ({format_big_number(offline_dataset.num_frames)})") logging.info(f"{offline_dataset.num_episodes=}") logging.info(f"{num_learnable_params=} ({format_big_number(num_learnable_params)})") logging.info(f"{num_total_params=} ({format_big_number(num_total_params)})") @@ -573,7 +573,7 @@ def sample_trajectory_and_update_buffer(): online_drop_n_last_frames=cfg.training.get("drop_n_last_frames", 0) + 1, online_sampling_ratio=cfg.training.online_sampling_ratio, ) - sampler.num_samples = len(concat_dataset) + sampler.num_frames = len(concat_dataset) update_online_buffer_s = time.perf_counter() - start_update_buffer_time diff --git a/lerobot/scripts/visualize_dataset.py b/lerobot/scripts/visualize_dataset.py index 6cff5752a..cdd5ce605 100644 --- a/lerobot/scripts/visualize_dataset.py +++ b/lerobot/scripts/visualize_dataset.py @@ -100,7 +100,7 @@ def to_hwc_uint8_numpy(chw_float32_torch: torch.Tensor) -> np.ndarray: def visualize_dataset( - repo_id: str, + dataset: LeRobotDataset, episode_index: int, batch_size: int = 32, num_workers: int = 0, @@ -108,7 +108,6 @@ def visualize_dataset( web_port: int = 9090, ws_port: int = 9087, save: bool = False, - root: Path | None = None, output_dir: Path | None = None, ) -> Path | None: if save: @@ -116,8 +115,7 @@ def visualize_dataset( output_dir is not None ), "Set an output directory where to write .rrd files with `--output-dir path/to/directory`." - logging.info("Loading dataset") - dataset = LeRobotDataset(repo_id, root=root) + repo_id = dataset.repo_id logging.info("Loading dataloader") episode_sampler = EpisodeSampler(dataset, episode_index) @@ -153,7 +151,7 @@ def visualize_dataset( rr.set_time_seconds("timestamp", batch["timestamp"][i].item()) # display each camera image - for key in dataset.camera_keys: + for key in dataset.meta.camera_keys: # TODO(rcadene): add `.compress()`? is it lossless? rr.log(key, rr.Image(to_hwc_uint8_numpy(batch[key][i]))) @@ -209,11 +207,17 @@ def main(): required=True, help="Episode to visualize.", ) + parser.add_argument( + "--local-files-only", + type=int, + default=0, + help="Use local files only. By default, this script will try to fetch the dataset from the hub if it exists.", + ) parser.add_argument( "--root", type=Path, default=None, - help="Root directory for a dataset stored locally (e.g. `--root data`). By default, the dataset will be loaded from hugging face cache folder, or downloaded from the hub if available.", + help="Root directory for the dataset stored locally (e.g. `--root data`). By default, the dataset will be loaded from hugging face cache folder, or downloaded from the hub if available.", ) parser.add_argument( "--output-dir", @@ -268,7 +272,15 @@ def main(): ) args = parser.parse_args() - visualize_dataset(**vars(args)) + kwargs = vars(args) + repo_id = kwargs.pop("repo_id") + root = kwargs.pop("root") + local_files_only = kwargs.pop("local_files_only") + + logging.info("Loading dataset") + dataset = LeRobotDataset(repo_id, root=root, local_files_only=local_files_only) + + visualize_dataset(dataset, **vars(args)) if __name__ == "__main__": diff --git a/lerobot/scripts/visualize_dataset_html.py b/lerobot/scripts/visualize_dataset_html.py index c035e5626..2c81fbfc5 100644 --- a/lerobot/scripts/visualize_dataset_html.py +++ b/lerobot/scripts/visualize_dataset_html.py @@ -93,18 +93,17 @@ def index(): def show_episode(dataset_namespace, dataset_name, episode_id): dataset_info = { "repo_id": dataset.repo_id, - "num_samples": dataset.num_samples, + "num_samples": dataset.num_frames, "num_episodes": dataset.num_episodes, "fps": dataset.fps, } - video_paths = get_episode_video_paths(dataset, episode_id) - language_instruction = get_episode_language_instruction(dataset, episode_id) + video_paths = [dataset.meta.get_video_file_path(episode_id, key) for key in dataset.meta.video_keys] + tasks = dataset.meta.episodes[episode_id]["tasks"] videos_info = [ - {"url": url_for("static", filename=video_path), "filename": Path(video_path).name} + {"url": url_for("static", filename=video_path), "filename": video_path.name} for video_path in video_paths ] - if language_instruction: - videos_info[0]["language_instruction"] = language_instruction + videos_info[0]["language_instruction"] = tasks ep_csv_url = url_for("static", filename=get_ep_csv_fname(episode_id)) return render_template( @@ -131,16 +130,16 @@ def write_episode_data_csv(output_dir, file_name, episode_index, dataset): from_idx = dataset.episode_data_index["from"][episode_index] to_idx = dataset.episode_data_index["to"][episode_index] - has_state = "observation.state" in dataset.hf_dataset.features - has_action = "action" in dataset.hf_dataset.features + has_state = "observation.state" in dataset.features + has_action = "action" in dataset.features # init header of csv with state and action names header = ["timestamp"] if has_state: - dim_state = len(dataset.hf_dataset["observation.state"][0]) + dim_state = dataset.meta.shapes["observation.state"][0] header += [f"state_{i}" for i in range(dim_state)] if has_action: - dim_action = len(dataset.hf_dataset["action"][0]) + dim_action = dataset.meta.shapes["action"][0] header += [f"action_{i}" for i in range(dim_action)] columns = ["timestamp"] @@ -172,27 +171,12 @@ def get_episode_video_paths(dataset: LeRobotDataset, ep_index: int) -> list[str] first_frame_idx = dataset.episode_data_index["from"][ep_index].item() return [ dataset.hf_dataset.select_columns(key)[first_frame_idx][key]["path"] - for key in dataset.video_frame_keys + for key in dataset.meta.video_keys ] -def get_episode_language_instruction(dataset: LeRobotDataset, ep_index: int) -> list[str]: - # check if the dataset has language instructions - if "language_instruction" not in dataset.hf_dataset.features: - return None - - # get first frame index - first_frame_idx = dataset.episode_data_index["from"][ep_index].item() - - language_instruction = dataset.hf_dataset[first_frame_idx]["language_instruction"] - # TODO (michel-aractingi) hack to get the sentence, some strings in openx are badly stored - # with the tf.tensor appearing in the string - return language_instruction.removeprefix("tf.Tensor(b'").removesuffix("', shape=(), dtype=string)") - - def visualize_dataset_html( - repo_id: str, - root: Path | None = None, + dataset: LeRobotDataset, episodes: list[int] = None, output_dir: Path | None = None, serve: bool = True, @@ -202,13 +186,11 @@ def visualize_dataset_html( ) -> Path | None: init_logging() - dataset = LeRobotDataset(repo_id, root=root) - - if not dataset.video: - raise NotImplementedError(f"Image datasets ({dataset.video=}) are currently not supported.") + if len(dataset.meta.image_keys) > 0: + raise NotImplementedError(f"Image keys ({dataset.meta.image_keys=}) are currently not supported.") if output_dir is None: - output_dir = f"outputs/visualize_dataset_html/{repo_id}" + output_dir = f"outputs/visualize_dataset_html/{dataset.repo_id}" output_dir = Path(output_dir) if output_dir.exists(): @@ -225,7 +207,7 @@ def visualize_dataset_html( static_dir.mkdir(parents=True, exist_ok=True) ln_videos_dir = static_dir / "videos" if not ln_videos_dir.exists(): - ln_videos_dir.symlink_to(dataset.videos_dir.resolve()) + ln_videos_dir.symlink_to((dataset.root / "videos").resolve()) template_dir = Path(__file__).resolve().parent.parent / "templates" @@ -252,6 +234,12 @@ def main(): required=True, help="Name of hugging face repositery containing a LeRobotDataset dataset (e.g. `lerobot/pusht` for https://huggingface.co/datasets/lerobot/pusht).", ) + parser.add_argument( + "--local-files-only", + type=int, + default=0, + help="Use local files only. By default, this script will try to fetch the dataset from the hub if it exists.", + ) parser.add_argument( "--root", type=Path, @@ -297,7 +285,13 @@ def main(): ) args = parser.parse_args() - visualize_dataset_html(**vars(args)) + kwargs = vars(args) + repo_id = kwargs.pop("repo_id") + root = kwargs.pop("root") + local_files_only = kwargs.pop("local_files_only") + + dataset = LeRobotDataset(repo_id, root=root, local_files_only=local_files_only) + visualize_dataset_html(dataset, **kwargs) if __name__ == "__main__": diff --git a/lerobot/scripts/visualize_image_transforms.py b/lerobot/scripts/visualize_image_transforms.py index e7cd35827..f9fb5c08a 100644 --- a/lerobot/scripts/visualize_image_transforms.py +++ b/lerobot/scripts/visualize_image_transforms.py @@ -157,7 +157,7 @@ def visualize_transforms(cfg, output_dir: Path, n_examples: int = 5): output_dir.mkdir(parents=True, exist_ok=True) # Get 1st frame from 1st camera of 1st episode - original_frame = dataset[0][dataset.camera_keys[0]] + original_frame = dataset[0][dataset.meta.camera_keys[0]] to_pil(original_frame).save(output_dir / "original_frame.png", quality=100) print("\nOriginal frame saved to:") print(f" {output_dir / 'original_frame.png'}.") diff --git a/lerobot/templates/visualize_dataset_template.html b/lerobot/templates/visualize_dataset_template.html index 658d6ba6c..0fa1e713e 100644 --- a/lerobot/templates/visualize_dataset_template.html +++ b/lerobot/templates/visualize_dataset_template.html @@ -35,7 +35,7 @@

{{ dataset_info.repo_id }}

-
ACT policy on ALOHA envTDMPC policy on SimXArm envDiffusion policy on PushT envACT policy on ALOHA envTDMPC policy on SimXArm envDiffusion policy on PushT env
ACT policy on ALOHA env3hB8qcV42SSiYej7QN$;@_502TH9gh}I;oYU% zKk)mk57E*uatP+a9a8(O=W3V&wdm~anmG+sK!X0{zdw6PAlr0@H{oHFCOyLP;=LkGB9!d z?CIFt+S6XywSS8g6G+I}2}K-6;W;oyKU>ipYNaS>dnH@@jW8-elFWN3y6&f_bU@Vu z)6|W*^?s?%JRj2_Q}qi+CZ~rrX8C(A;`XNHKFc-iUTX`dkm0%yW$Yxi zBTra9@tK2FBTp(a$Deaaw2X6Hmy*Mgb9d$m4M=PSd-J;zlIy>fZuAYb8d)ROLSrUc z*FLk3FskPX#P%u~%}`a$Kx)5Iqz5&7h9Jm#ocQCK-E-q&^=JCVT01Vd{8?8qj2!K` zpI=v#R^peVnqcVqZw|p8tGRTT*{qf>rotV)0GLH-gzZ zY*ZSly-h$Ad|a1a{PB)9LDgCUZv7SlxUj9nuUKi4s2ZXpB3r|5QY`g9o#Kx=cAx0( zonzK%&1#zo*Bibx{Pl?7No$qfQ1KiQeKE|x#3Uq8fcQslC1;3~2wo*JaXqX@n5D5% zrFm@oN7Y%FrpAv?o@Wxd)JUISeEbj|Y-KcNDRTg||JrH(=RW+iG#;hDTg5c`73oc? z4|x7U&66sLv1%TU)J;yY$ zKXFclz|{nx(yzO2b33KT#Lrr(R}^*#l2|o;%PT%*$CZ(BuWAC*62wGqqp1onIEn|E z_Ag}AC=#UH_DR{tonOK*@MQN_A-3Vd^Asb|9U^;lk6?q_wXCp7dB*+w8KnDD{JHPL z*Im_eoU*MP!mJE6?(4I@O+HIGb*ek=^YOUk<|v{@ z8k52>xcvFNdd8ophQBl=vJ9C($!bN`Rp^HdR<=2gt z)7CKKh5@~@__N3le|nx==NxkyRVn@CH+p?g|*?eLAPn!RSKOSQO{mSYL(T)tb%!^UhA)1R3;u zajCZ;`9fq-Pr}j&|K-TY6Mg0WXmZujh+B}W?otmGppl^xx;MWq&Rp zolGP%sN(x3d)M?UW%}K|t9X+^21_GFg2q*L{WWeE)q|(8o=gJ%;%&B8xkrD!lWCnZ zO$D3+v|rtKyjY*y-}JNhQ9`QW)`&!L>e=f3rWgB7aa@uuT6$!lk8SN;wrQKwzCyyN z(d3wO3;SEb@tKYt5bmaaYmy)w{;zW?n8+6uxd!2JT-F5>#B3W|9K#ku2%nz7e ze=pGgp6f|IGT@YU^}sYOa&UO>j%n4szv{0q4SYW0Z9VEKO3gYsFjS8lf?a0b+&_Nm zVom*iDUaE3=aG?nrlSLA#*8j^!odH3ocuX}b2|ZGBP8wHDu!ur0kwe1w#v~ojJ#v1 zeS4J+jT0vyY-q2xV~A=0e{u2~ASf8l+75Fr(L4JEjrm#o|KjAtLYW<4Y* z+u4!h5Lf$jM!%izYJO4aQDvR-er)Qxd?ZZkjBb49>mKskt7T3-t#1dCXj&%zHIsR= z=D?q#8Z5haqv-Jgqp{PCmLg1raEU zOtR;@|HQp{oVcf*(F!9>&I8Ye;Dha6)7E= zgnh+^6{^5drROw^?XKHJ*h?dVZ~Z^cvn>no>RUgI<#us8k8b4q43(;car4IQh(%r- z{A!Vp>hs7CIf5?jA$(@6-*+7B0(9i*#==n_^MO(+FXL4;Wy5@|W7lJv66iPMY)n3tCMf+b!oM%+j^K&;-CgNmVZ5i9 zlPDbB;2poZK@X~TvE?)qA1p6o2#YG8D~lt(cvOAahWO+j6@Pw`U_L2oQ+unf>5Ide z2axd-PWRd8OTvLV4oiHr)~3x?fihniMqy%aZE%+((v#%mc~O-UC*N!q(Ddv6M7n9? z=*`FHzP!~vP_*}!-=_D4(g|}7*~;!Wbw`u}@)}=$xL;|q{jm{P+5GK+?Fkc`7IE>% zK6z(cBDIIWABt@R8!Sv;VLl!6WsQ2A;IoNNrWS#^-8xX)69y+%$BNq52x_IK@zdK= z$YXUicRRRct0q()W&cMbuzc>uT3F||&zO}f3;R;MHorTVAJ}X;wc1$3mmD>6Df5Yd zXsS7ZrjI~k%!ilPp17WOdE>L?JMqItPKMKUWO^chTsTH`=K7@R=+@4gj+D2u4JF(z z#60g`?0-eC{<=C9zf<5o6Fuep^lnllQKPAJUU3Z{)ogm`p)}$TJ#`;{Bg6Bw@RdIg zcGoK`DkDhG`FR#FcKH15vLcj1&4669cf4S`^p$){TAC~2eGM$m`-4R@4`0W<(bI$v zm)gDJ|AWbJ>Dq|IeHvJcN8LN>eNXt|KzNIcG|S@dQ0qBiw!)k0uKc0;OO`2hQv18F zUzB@&=ofoPAc4BC8Lt%z1o^c5;$27$hnwws-i7}dqJfocD}Dz4-muTkwLv1vnk<*G@TE3!4K zc=r6wJj^YO+e+1p`QZqT4X3+Z??C@Yj~rD4LTF8m>1o&6znb562#bAy%L9r!dOi40P3(YPB(=v=H7XUn9rzrN&&UE_z4r^N zF~m1Trke-wiO%waRk|AsO;~vc?o-nt$HS1A4{AdG zm^snl7<%!n?4()Qq3B|zCf}%EtbeebSn|EAvgi4gRD54%Xk2J*F9B zaZzhOKR6zcsx_I5{abj_8~U49PP)n2l_I|buhRGDQA9bd6kI}w6dTzPDzne5({YKo z;W7pIvHOvP!TaDrRXsSxL)HE}bx3op6@IJ#*4>H5JV|4R+QrKm%4Z)v83B9Ps=BN@ z_gt?{u(3Ff5_EV%-?cgdOo(x7NqKy|f2ma%T+)AG)uztgHvf>=80$-Aa9kaULiI-7 z9kt`vaG1ZviOzE9rV`;bxjDsC{-XZ6Q;z zG9J>`?4EDY;8Vi1)R)21ZCIEBA+j= z4a@IdS70iG!_|7Y^%P3w=cD?$!=VRp6&!i2lj;2co>m#I&tM%VpU z_~K>a+jV2lVj~kBO6pc*Nc$*T-Hwg(Lj6^aClpSaA~lGutW<5|ClBBV&&z8^{!6l4 zjTlfDNXhL;)e;r-`#+T3i$9Zp{5SBinVm3lm}8R;gv_BFN;&70=8#ilPUUP0=^&dO zoifKJ)Cf77Qx2)-m{T>Uq9{tG^XP=s?(6%z@82JA{|9?q*R}0)eLnB!>ory;{}I-Y z8tfz$H&MlxzY8ju8=Ro8vhPy7D$L-QwN z)4dcYa&R)yWmC5=$YF@{u zyUQb9e61S4b>sM0Zci%xLM=-?eNdR~o5Q|4^ruSf)?7M2p#_@pbl7lv=oK5)>vp%$ zZw^kyAzd*|HkhJQ#Y_1(Pe=cq8{J4R~ z!zEAs^b+kjOocIHTMj4Mkl3`)jGc2(as^TGpi1#;v+OjLK84(p==f7hCnD99G%U|V zMF&9UwbCN3o+sZN!{tu;Uzj|>IL&@8Iq_0MWQWYuwOErQ)K|-JIa$!x0=c4?N0NR! zFvu)op3z11>=Upn8tOM3^t z;mYgISfSn@$0*?MAG*0;nlXmYxUAWNthunDlUsycL~tj@FA|I&IgpuN_4~fB`gr$_?!slgl@q3M=!K}XAJE{?nTt;q%YRpBS3Kp29kjGE|Cn7Cfd z4jYxr+cyKEbdslS9U$t{=H&f%m*#s=^AC{sbiBHua%Gd9zT1@=HdcPuKnc);)CPg z1CRgVJHGg)K(ks=t$v@T@o#(h1$&_aq%SG0fNC+iC!3O2@-Hou9j^A+Ngi$TIIxxf z;?=7jYeHr+^+%;%&U*rZpTh19tfMC;=wD&IL#Ks!AE&0Mp79+vz5+01h{(CAX1_P$ zy6>ydPHqs%nG|bjvHM=qqq|Z!I((a4A@71z#@hX~hpbdh&|lph58?bXS7S`}Q^Y5f zgdnn(y{tE7*QMr@Z-1p8m^m=rhrXw;yKl-NZHdr3L@{S8T9Z;OHT@%(64-B3?O}?o zLBYpubkp*~cPr2^wlsJd-KSHg9xN7s-(59xWr}zqSkwdsxvaX_Q-tpif-z} z`12#Hz$)5S3lb!Nrm=oDju9@EqG7yRP^*)bvtn z+Q0S7iLM#_%~v*(PI_CVG|OdkCIa*|lm0Q$+%=h#Ny<_p$~v0o6ZNydv(alm#kArT zV?&rXo3m?HbCM?PC55ZrBWKknh9g}`#}42wU+BFGTh39EmH!=g0 zfw4Ik{8zKE)~(=ZGbk#$hqJ>d<#go9B?@B$8u#Rr5lyeS+`2XMMT9B_3B z0R9C*Cw}EhYF*d1yj~f8{oI{rt zurql;>-4IZtank#NiLL50t(|1jX30lDS~H#YA2O)7ZG&=sa^r<2_6~C3Xv$Zy6$~L zBe0}?cmD3ceLjSepvlNczIYyB6af!SLfqmaMmWe;)=e%K(a1&exTtX!GGWoOCvksu zFvl_{vxA1lpOMMWVQqTvISGQE#lcHRh(;133kPdup#bR4haAHo;dH>g01Q%|%2D=s&36&O+Vgm)RkZ54gw?9;z3M zOc&VtgGwSMP2D%QZP}tdKhm8CY=od|SIm_C9MR!L)#=^UnZoOZo^xUeICv=u(ac4( z7FG4)kS&0RN240?$TkAJkq>vc6XQ=h;@W;&XBF`3h1MeHxl5|h)!SORg_2d`X5EO5 z5qKf!HV@$RxC(%QmM$W0;^2Vhj^b!!G7e5u*7lM2o3=$(!=cm-DFRpA41sJzmlmP{ z4~POVYo!1=&O)`Ik?ACO9RZPmEs!|vp1+IEzbO4uAa$Rh&=#?SUQ{Rzu*^lo!X})J z2K*qhm4vv2hmZ46)gbsS7P5$U8BYX^A0zxS(-7FV~ z1C|(2^fLlf7Y|;JyY`83`-iZ*+5bclQ6Qd$g98{`Xi-{+M!p$^6E~4{7RY97Z6yf# z0wgiSYGQN6|F&NVz(bezmzexH7CCZ*O+YlVZdO`w5BdJ5zk3O&2mGpPJiHquF=m0{ z^J;q#>?%jH5OVpXwine5oj`ySl<&L&Qf9OO7=3dN<_NE5H>DcjNFG*VjD>pqKM4OK_J;4A z7{9!0sJH9ArODC6TLixNEfQif4N=X54|eykv4{r(l*&g0fW_H(WHnY|9xKty?WrWe zy@aG@**SdL%H6(+j@_@pE`)~IMKK^_p%lb@tc57$-cgB^bec+WANFWiRmr(X#5%F~no(yDF2*iTP z9w+2=b^3N(azl?}(PJc;Dh_^#-~W{C9?=f5j#6^~@{9oy;Dz`HOOD7^93oF3evu2^83x{O0e&{@ zatJ5JMN6FblS#_BkCX-@0>{#WQSd<2l!dbT8Q*MLZdstjBMbCI5Bd@Q(bLPQ*~_RN z?xP+S{CdwwFAFum>I8^;DG%O`MHcyuQg8^yUBtXoRVxrHO+dAgdNS`qjqS#wXP)SB zA$VE=0Si^?#}{4T%BdroaVV$s zhu|CuG3g1h9KO2$1Tv>7Xv4c+PW$aimA@eAe*k@6cqZgaU0RURzXyBBg}?Gcyiq|} zA4ByMP>)Fx(^!c)E~;^>m5oD#XvE=TEl-qD4#%eZh3Lm4IMi$%jI`KVKtQ~ipDRYp@U_Ixa>OqJOdAAC=fKJ? zbr1U@+i`p#X=053a754vBoJIWByFC_2TP+CFU~{MC9ah4;a|{Q$$BKB+PH;|$&0km&RiAx`g_n`wMb2g2XjK2-g?{wQM*L`p&nr3zM#m!Z&5$ON$ox$yq5w)D zg=Mvs_=Dh+T#45zx1W$CUj3DNz(Eqs?>3TL|JV?2JD`%cq=vXisfB)m>g2s>#KFDj z4-plO7Dvk+mE%v~Nk!IyS}MBHXuU6!VD(wmmr|QtsSS?Qm19zy#D!VamhrJV5C56l zmmU{@;MKxI@WW%hpZ6kduHT#shXcl>C@pNt48p=oyy8kcC;gW$@Ej-c1S>It?br&3 zXS*iGeaK|bjDanI000yP-;++5DaWEa4#R}3nLHp!RUi%#fyo^zO0 z5vb~zxJ7>02}HVpEjxag!^uv@L;<|TqVJ5t!8;QZNYDHM%0~V%xY_zi9efh z$eZ^*6@Xw-EU{2v)E$p}j+U6VkeI?r6a=V(;+9`M(2azu*|70TR&)u~ z!&J<~7%xpu>Z+n)+#(yNa?g2ZFg^3yVYZHcUw&HN9v5BzvoiZXzPg=KVwUilIT~0E}A0NPhy@ZkeIViUIZlP;!$VSWCJw+w~AKRw23UxS#1G}ug ze%xM9p^RF%{&0RVRXux$JXrfPptB+9L7db>3FVG&o)4qP5(|Be!iS*8M%H2xz1`ru z_4>A%-+1>1{NSED%iLsJK66E#tZ|lN(uQwuw#id*mYRj6@fH> zXh4mcgh)G9FQ=b-?M>}jZ9qu-5fR2J`vyJIANC@NQfdAo9nfZwnEFHK6)D|14-h?3eH!g5ej ztj|p`Qw-ygt2Y?Oqbwjse5qb<(ZU$$sGSgRE4`*;G$EO8b$FZg$+pRC1GD~&Y1}4b zKdx^D=7I0k1fy_0Npa{>kG_h^>weKSdB=&<4!6Bee;9eV?CJA%y9Zt?l%+Y#+NB&( zRa<2cRW<$bpw@#IZezqd6@|}J_*#2ZqM09-v$X6Vy-wF^91ddn{Dbc<0?y8dFafgR z12XnXWQdFtLOV47vgwBH_2{0>RyVS^XH=oJ&>??uqQoK!PCugkdP1deI4F&r?j4lA z@82qZ38H_!I+Ho78JxAR(fdutzHU&kjPqfwL1VADwPWu*PflvxcDYg(T7b=V`g-$} ztG;cHc{xZ!KBjPBw{lcl7s64itL~1l{%oV#`-p}y^-mG!#x0Mk#&hSySXvxX(0v^f z#g%KJxvRU_fnoaLxfj%32SQ!e-hSEc72h1w3_7&ChuAN5$)s$Tj*I3bbrCb zJ2Oj4AztE<_+&}eVc89^q`UIShsuLTy0koJVjt&hbMi~8l6S|8JdZ8QGH{eWPyz~; zkC_~W-uqFaI_y*1(RMNN?X~xtk&Q1l%u0O!=?}v_3e|UG!gJ#WWo!kWJ9)jCP#bAy zGySNl<0SI#z2mPKNB)gtglFI*ku|p0Qb?9CHcnVXRsRKoZX}1Di&_^~eky?4uVjQ3 za&5G*Y(uZCAlY*C;GUq=ZkOeHp(neVW<;0H*#0F#u6_8%j!~cidF%E0IoORUUS0t) zYLDZI;8T*tzuTM2z^WgZN6mW5kk;{mvJZyEa1|n%4mN>eM_0gD&?@x#3Pk3u;o!b7 z*K{{RpWFlHs3F3{&OkoKPiS9awenlaw$njLNEkAZd5v=7O2~xD$|}ot(#=2jqJgqF zqHjlsE4xCb0Pur^IK5{xqcXsHUbmt-(?1_=%H<5=IL(<3^<}U;Z+a4;S|VB}~!GOFbGAy#Y$}VM=os#5DZmPJ)l-apoEO~tGrgPGzwcnxL+3C zcApLPkfa`s@HDi<2(|kao(`iKx+2@aadx;X(wP*UH;Pl5w6pa!*j)9BkX@@UcLq)N zs@xmLL|lOCd#b1VK)_y)>IcSp>@%DjBju`R<<63pGS3_emI)yCX;xV(y8R1Qo*kZ? zZnM$#jA@8$glOp`S4*C6yQMPA98@j=(T)&;TyPuj(Bt~qNdwkut0cz3r>lBrK-QOL zS#+avQx>UVs`{w;`0L3P)}UP3w%84Z%I|aN82)R83TZ{RZMiK+nB|o7I*wW;@LpGo zTNmE0A2q%2dNsxajA>k1JeJ!FK=&Z|IvhXY3Uee~eGNcQ#T(`v>EM-M%1mW&UHR=#HW z`35kgsJ0bM^c`$)RW!ayKQtcL%pb&+^xnMRIik$74~W_JgJw4W>C|DvLCumh`?T7h z`EQ0tk8njY{n&jn<%_4booQ|V z@Gq~HW(X1R=2M}Vew8Wa5H4g1;jtxpyRxC?(9T0k7d$%q%uX=OxH1yuF1PNCis`GB zai?kZ&8Rk(LxAj>#MvG1&Z=LrmrFi}Z%X9L6f8mxjEgihm;lHeTc&lkyeXVtAm6%j zTR%kDYlrJ0OR%a3agNP&jn9D!^Ju4J^7UPH9)mtvp_M7ywcT>6z)`@kklBsi%!GW3 z^5ia-cGD-4SzAUCE<;p)V+c0bn472#fSZnxt2$j-A-g#u!~VmEsb$0VnbUWUj$C)iO& zKjod6wmesPv0rVJMbkp{VO}lTwRGiVg?p!IFH|Egj2h_vOW$}9a_6&DuV*3GvS0BX z-_EFnJbT8*TD4qN_mF+$RLXqU!g;#!-M15x7upJyY(YSKP;RU!P<|u?@uKD4h6u%; zN{KQ48TGbY#N-UVhrRF!mQ^{5@-@0v(zf1j!O}-tphD2XVH@joJmg{cg|aaWR%rL?b2TpypjG zW!th=oJe$ird#L8B$zy?tXfW`g2-ZMtLKJ~mV!9aWp4AtO}p zq2UnuYV>%y!Hh+e>C5}R3A|+06;ETJE%1DzMn%>4;k$_z;^BOnt2YHr1f_16m<*@t zX{IVwleZ^rA9aVBzixYIjf%#=Bs?+|F2V9^R0aUmiZ0T`>OWRysFGykj7ftDbsWa!4Ym-EAT*w&?Dpo+RT%u=*N(t*=QXJ%wRqfWbTm7TmN(q`k zG5Gagt?8Sa3Sl`9az?o`I|lxoV@y1M&^>k+ktc4~CVn|--~zY9k4=^H25c}>1PcS(|8#)FGHDrguL()qxL1#WM{Rna^6PDT@~3 zX@`e57>8M4QO8V8zKXkRrUB8GnuOWoUE?-OInLVKxl&G8K}N06V{2*Q^BI9*)GVJ= zyRv*TR-c)4Pd^oGuSp9KkuQN+_31!Ozn( zYOhAGKt9#Ur9vG^ajH+88MURg;kVJX6S=F})v1U_! zd2|AdewNqYy3P;^4H#`o;!zyvTLSNur}ju^tJXn{<7)$V?dDrA@EAV_7)k4Ne>T;eB)ZKTlmZ5UL7gDpae5fl0ffCv zuE_pQZ}MiUtcxqbM6;LL9tMJQyHW!*E6ZCl#B4K<@WD=mtH2Iv@I311RNDS^S_qEr zQ%!YC%GifN2eJMq^q>SBgrPeUs3|5Ca+oMREVVL10%IuW2B_d_4O;`6OErXm5s#g{ zab~5_7eo&s76apQzKal(B#K+vjmNIo-0<#wnqbpe@b_lwiE3yV|Hfu6G%N{vMzclu z6_ydfg1%RTz4dWR z_}*g(S~i4dh?@r=zof~C@P>NNQq)PHKOQjhi_|Wr=;p-Dr4XPJm`olP@n6PUlEqwY zV2~h+CXSx*JTsu8WF%1e5r>wtI7w6I9G;zt@t}50(2QqA-Es7=b-Ld=(25EU!$E~x z;)W!VJ)G@fhhUm`rmBSg++|7%2y8l>hBXp%t)>!8vd_%Y{0R2`So*OY(B*EZ%!CpBjm(woTzOPCoS7?^8kpoA%&jZIK|OfT zSOPSr7h=(wePx$o9%X)be^=Ed%8qsFD|Ki@l3{dMdx+s&wFS*Li5|tzRYlZf{8i7< zIg)jPab^*^T?uMjU#6qTXmV(^iee<-8985a84Gk_0;gs*er{>7mB#XMIC1;}p&=YV zqO+;%VSK$|QE--sQ7%+79A*mSkD#AdE|ic7;Nhat6pYuoP_4ugP-UY~wY0xG&7qyG;0TKZi_ort-ntCU)CQ@a9rc-X5?fd!}(C<&x!x)25=J!!QQ;fnLHukt64jqY&vKGIy$-fuQt6r`sy&G^yqvXel&3u8 z0z0OrkIH^T_gCI$8MRFdKQdneDQ2X&<%D!2O zvL#Jp41OBceH;UE^@he7+Ln`PuIm(^-AhbXXl@|bxtgvtdN}M)y2#ITqBqonO(P1t z4Yw&zM?ap4erIXK2uPww@LG&A>E}|_cbm%pDt{N|nDJ#wDIRvFu>JMXXr^}K!6c32 zg|^r+MJ5nAvTX%&XrC_~1Lf}WT=xM7Rr@j*E2#p+=VLHa^o#mXH(GpVfGTqnlJZW&a@1gooC&3d3EQz}2G!tF z*n-d}tRQUI+64w}C(=VKrhI|y1{^OS_&J^F2Q>fPIu&755+f>RHqN5O!x%9ur|a%V z)IW~cju3a>vI(}QPrSWvWRp!Ym5-3$TLWVVTe%&H9`vNSxR|*$Rc7rL1I-fC)WXpT zA)Rd6L9>#$N1gLdulm_~QMhP2spUu`?R@3uam}%-8{(#Du>kuW4D_8-s<6KVsImXN zC26mXNPWueN{YRRB%4G_ilZ)qa;m<(_!ok!rkI99uI27+Vd^!w6L-wn4E@x$*%*WF;Xc-(0L?^dvXNf?=Zfgu;pabEoxh|F@$v zlRCpJKIWCNCCu*hvdiz@6d=9BdvFpX%HRpCURp>_50d$@LTa_tho3CF&^SWFEToM`bUzQMohnn?!hH7A7(yKW6Hb3 zFbm(wMA|`L%DH%ym_6@MGrSKUMhFeYty3-)Q5``L^Q0LnTh7Q-(S;&9;KbAeQN1yl zhdJ=cYMS4$*p@5GgAHW$&_b;)2cX3YMu@@#*Kb@@WGen;JXM2vrX*ZH0}IStM}L~M zTw>MLG!BkC`GfZd;{#`s_p}z3}>&w~m zBzifCs)EVfbgkh%ac0UIbhP;Q@kPrEu=n~lOxB_W8NJ8uP!e_M zfr5BP;JIJfv%T5sM`bh)L@hrEEd7^Y`C$!I@%We zE8TCjHqZ-K`BA>Sc$SJX6+SNUX&usiEgVQ!xU19u?pUd1fk}Y@?ZdMJ;g1W=DZ8Ve zx1E_R^btMBZVozdyFJc*EZP@$?qzD3AwzQE!HW-*H79R>H5R=3MBlc3UkPT9g{@U) zu7ci;yNUe^=GlzN%_B))=X>i;B@+(OG?dF-G;i$Kqy*3hh#NYq4*C75Gev9XR>q1V zZq05@ihVqCQe`0jijd?=CkUrSo~cRv6Je@nIlIAkmuAYy7zvYpWE+L)Yh-DaI=iVw z1f^9zHHfejb+Erl9T+~6SQEzzxI$Zg21)LUho+ftGJO>zdz!_u6pM1FqvQED<9fa8 zxlX#bwxpNCk4$>JwO{CL%Q`R8(0mEmuD@$B#H^Rv5lPT0Sug;e{}%a2Z2hC(J@T2`yHsi!^A4C7>{Y#B0h#7_jl zcbDg{N$sr;Nx<*x0)3a(AL;q+X0-Ef|F}UrJ%7islFqPQO>a-MOj?q+z;BM2ZyEMN z6y{CbuI|gy_imc_H40T0Z;)ONPSA97+@-zOV0e4-XIDltj3VPGcWV#9W|=aN0k11Fto;^fHQ!g@3hk+)TT?BKddOt$%Vli%|< z){Nh9FG9L5bn%;~-LZRYl1dxWs3+5GoHY(Vrg|C2{@KWYS0 zj+yrBNQ>;k5#Z*2Fq@U0euo;wU1#pw5ycj*IK`($5Q2AFxR3999+YOxD?hFD`UL%SA}eq1 z^XWFjCB4MoGAwF^d^PsePtr5()~#TVJj}$TY+O&uG)(vMoQ3@`0n?w^lzvJXUdSD2 z*Y7Ad z2swiXF8s{&9`D0UYeLm`tV&`3)5Yr#-KDIkDQI;u8@z~gi_#$HtepO=b(+b;@HSSP zozntH!?=4XD>g~^X8S!qI|H_KRx~GA^(&ik7w8UOcz8dogn)yujx2S5;*b>p%Zn!`F&`LNnl&p zUI_(X>1rX<&Fd0PVkQ}kIn!mWv_eGh+oB+X(EUePmskghmR()RUw__Nk@=u@4)fjA z{t#sq8Sr@rMmXz(!;8RN_^I;!>(JQGW|qnKn^a2HBMEPij44?+UAP3#9veXtK~J(k zz+TKLJ~KR1Lv@w=@Q8rC2X*l)_SP=li!TLvDIRr_o#nb|juVWoEls7nD2MvfFVs=i z9RtGfB6Mi3h+Py>14CJ7a2Ji3N4J3K zrsecdaovodk-$;>=$U-hKxWb4o?k?D?PQYzjn&pmgqp&}b??XmjIHg&1=gJ|lY+@b zfx=a;m>xd%At5>*-~X|&EqOD{eIUr#^;p9`@m~_=u4`&L4buav)3gw48i;3_C}r%Qsd}1 zCUvHGcT=}w`KA0?kH6N;3AX`i&<`o8?E}g@3`BjC*GNIX#y&9{RvhBdQz&NsHHl-g zmr9OB=lU*{{d>4w%4X@I02s}w?%!_WigfSvwSV_|KfBfQl@*i)61NP4;BdhBPq50u zhIne}o5i-zz0ZV9-o~NJUnQ0ti;OmGy?34vpJ~+fY*&GQw%PiALEB7sK(LR&Ih?tt z?DWFdnDb5S)yycWjr8Ha3@wm!W;F4Zc1jraiN+5pUFMQR(C`hXsw6>bvG?@hf48mSERmVhjIi1dn6Ax`hO};^~(DFK+Aqb2D_@MNKlaV zI-H;ROG0yl@)6f_AzvWazB+$T^VH{a;YI&`?0B4r`!WB)+*zYv#{~fwI>)2trVT2Joqz`6%Y!=WLMvS&?c_=-_}wYr z<-UFEP8DH`PTn*<2t}XwcrU20o@cdZ(b0&MqcbbkSZ|e@3Hgym@H%!=`QlU{8#{}i zcxk)crl4pof>u zxJ2!lh&7HUikYPD(8-!`#^St1Z<&`H5&QRrrN264ZRFg)cdK71;)&c~neNLSDo>Z- zFUyl@1EQIwm!=8!B%8}1ioP0E4V2Nwmkl03JCE=UEc%UPZ=M{VwCwaC#JL*B^>HM8 zeaCH0(O})MehK=(@&6R5$ZlSr50$Eq>(|MYd(;NSoE4_-$h6YR@56R(*K@o1`{x^{ zS^xPFRb9~vr!bpj8qa_LPJ8s~h%>=)cKh^S3Q9DmAip>Wr}1cf+Hhz8_!ibTX+Upa zhYm+{H`mfBp5Pmj)742(<@EUw`VL#o+lOeVu(H0wA35yo$ALucqwFJ%`t%6uw65*z zd>dt@oyJZx&?2Xb`C47i_dBLJRKL*kdBH2V#*wGC~;d95^w0R8oyP z5td#sJw6e53hw{HXDI#ru^{QVzMY+gojl7u&ere3?F>MauU!M%hsnV|P6w_z?wcIg z%d@iY$z1!}tCx@0$xNSMIT8QehRN(9?pC`Z&GSxx-Lrgm1oS9m=;84KQEXdq8_>a3 zKR(*SFhuw7gItAP5#0&sa*vmU@&V@_tRu*ZQbBXvXV*S(JN6edqDwUO7ye#XYDC%O zFHrT>uPeHVZ^x6UU+mvmvLT5L={ofT)rW+qX9h)QefrcwETy+B#4SMbWg%&vBR`~f z&r)qJS>3#}+b+Y`K{;Z=a=BV>ywAxy%=m}w_3oR6YnmlPHQC|336T%c-EZ!wLUagy z{1evia+pvZP{x{f(S1lwdx&Ls&B^Xp*LDvX*GM#}>fakSDqUuK zYgDV6{*liH8GC@ohViVbLH%w3jGsD?ADqp8g>A2NTGn*DTnkI>#qPA$7<&AO+4rnc ztTBCWv%Gf17SDS$*NOMk3Dm#WB9)+NaeZPTR&V5cp$eg+Sky;bwL zLFoA~*r+pBC1#YLJvtDzx>0kpYVg3YRq79gkwP7d$K?frs4-|mARYW{*QfD)Lk1RB zh`p5!&@;KJ)F+6B>6XtX_!aL-o#16&n_1|TOT)7(4eqZM{PLgNEEjtg3dY>CgbdgA zq&B>`uWQk0Wm+xyu1oCM-*6=K%(Fh-SHBvvFI>BKWp~i$KB_biQON%N1IFLfeRCkD zd-0km-}BLZ$bm5H11Rv$cu=ru3~cDT_WLU_G4Q>P&R^}lzZ!Y(TuEJgUA6DiRVf4) z>bo9(z`0+?g1mBP-`96BV~rLt*dxo~#uQfarjN=XdysEb`^g*dd+&=M}!DUf|CU2=wZ)>Q@@-$gJ zjB+sNOvgVf>G{U3UroZ7J7hst^pI2gb^0f{i_aRr3isiNR(+b|R$kEF`o0EHL!xk> zuKV-nM?(7bRxHJr8^jn~STRO_AQd?CAIah(DEpvIz=StfZp0F)z3W9E7no&xO2SEg z!%6+Nw*dYBIncpW(7uTI;pSTpv$59y>p&Ht-f(R2=rvsMXo*8>)uUn)x%;ze-$<@kSVh3&FswG5UYN~sZggH)aVr&jnDjJnqJ;b~()|60<@ z0Q~vgr0*XWE=_1X!=CDYhshK$deu*US@R$7Y<^RhaEN|2fcKmK}Mn?$eo_`#;YL{a&cK^q8EQtOB2Wd9Rz9_Xb~~=yr}nu zk5?^Kasp%_FV8HJVY`h6<(wU$g@M9kSsPifJbRIbnS93av?Y4Ep*N+gJ?T3OO^UC$ zZ?#U#WEt8*ukR+1mE1 z;>*9nbBHKAc!B5NgrgPCmIED?H!}|?P2}aq*`6)}7M@d=c6|M?QdJ@&D^_4TzOiVL zDEgDK%|5Yq@6AJ1AEu>D@j@R@Nn6eCj}87+orT*{Rtd8ip@E74RSps9pPGMHCfUj+ zjBL#K(r7esiXAG@;m-dR@a)XDJofj0z-Sh?P6d^;5RQZDGm z9ZaDMAEwu{_RFa>fcN$7iNbG_pT6}DSuQD*?skPvNgdT3)dQ*ps{CVY@Bfz1EW8m< zy)VbmdEw@E_>=CrV%4Q!*)jU_I0w_qTVDruJR85(r&?I^)vm6qYC6>`B*#|vXj0N- zglmX?<0I!!VuOhX&sFHNM?b!JUBr90DBUnUIsfCCcf+;$5t-(L)CMs{9dybeR3W%< z@4=bG2)*NNHd%(0hTq<Ayund9BX}M4yS@n+$)awe7l< z5JqViZ*fk+kNB4nsL$z@TOqMblgx74_*qLvQYcLN7HcvUI+#6+ zLmIhVAJg=HkfK5kO)~UTs2m=m;3rZffOetjHmvB43Z{`v8PH#hS(xMa?{a>j^uper zY!eG3`oTcb+nTko#FXPbsoO$UbVvD)$xwKRx^aUFmtZOA=ZYRTR9dknf$R&16w5nM#)T4Q}a%85DZBzW6@xaZ7_>cdkU) z?|z}fwzA$`*TB7~0hJ5RAxeY$PQrH7?SwnNG(T6|RDW7Ns%CW4G770ptu&5qfsk1^ zvr}hx%7$nP)%Pzo6=Ov-WQXps)~T*HzUMo5KxJI4MfZ3)vGeSDL>ps*T6R8pBX>Yz z?apeBL76Rl=17H@3N=@=d^G3!T@3p`j*cPXtl1pl@sKS`UM$1ZJ?CONufj`-d+F>N zbKJvgAY(Ysa-S3Iy`Q38F@knmOlxm3b;Tl^kX^Zl{9bNHt#ay*)hM@wT36pUdvJZz z@hV09wd!!0h8wvt1uA{AeHW~nWp?fLU2^}`&G5Y8kE_+6OBE1o@3?PFGNalf)jOVh zWjU{4(;h_-t=bRr9O~i(sJfuJPMRjRMdJ|coo}d2o4Mpy{B^P@!uX_puvuAj`2Mg% zdWbx2;pHX73-$W1>8$RfEq7S>ursz-IE56^wua%czNs5>IJd!lL6(1_b?%ZJuX6Sx z{h2z>HeutT>T8AO>AI>5`VKxKP%-LO=HDN zqq!Vy{X*Gge)puKPs9rA=bl-OfSsP{1~vAb+I-MKV^UVJLBTZw<;1IZ(4LTdx*f87`#G^6h@FFCWOcWQWix>qB;&{R_^Rl{_d?P|9UYzLS>iI|JNOr7 zF7l?jQaesHM`H`PpR#(krC~~?y*$)RA=St;1D?V|%#P;rsXiGDI z1b_cAqp%cnJ=nl#^wcF{r2AO>zn(7{_3&Ef=T?bx(68ytKcwADwbu-{jg#Y-kY9dX z>jCQ$^5+k#Tb+iTFY{+T-Z7MZ^C^lc`ZDL@kn#n|CU=L$3xae);u7`@bMlaO&NN1= z4l6v~HR|N$2WYbR<^T6%V+b435Ys&iC^qwf{+#0nF zeSTW#Sp7iy(VlyYM>WA4X$`(E4T-uDqjM4OUL^-K+eL@`K0kIa20ea01W|Ebk)jbL zDngVMzmOGlm_aeLGc?9hNq!wE8^5Lgd7<5pqPM)z0W7f-=R?z*uaF;Vxf>@`^jls$ zpb*=NKi!+~*eFs;U%{G0Qa9Nqpvz;KWb7GFBk_}>apo8F@rRP6(}GBb7-_pR@j|{> z$7$&Wx`MGLnoqy*G%CcuK~v?i7n1~#zUR_uKkbcO^7MWNt=a5p+{o#7W6T4XO{ za1C8zqSg+RJ_!=DB!E-A(mU*Bir2*m#B?EuXkeTOrF05p!uZo4@ z{}U+`pzIR|%L5?+C07k-LmUedjwr#wA{XOxS290LURAfw`qdc%R0I=1*?UBYK(J9B zK(-bU)qqO`T2?Jk4;GPkK|tjlYK(^h0NH&I%!hwwzQA8ssF}0FFl%i%Pq~YnfQOe` zu<8~OkRnts9_hG&91$RK;V6AL+#e5>DxyZeqnoAS4$q-w(_~b%#M6NeI^2I%x@-_~ z0)TlOWUnB1Kmh2zf)PH<%c5W|^f3RSDwSOjW0fU2Q7~ao2E=4g8lnz|AOX}8gzCZ~ zd7!)z09gVZfh<%BHZylP*j-?D`GelcF0`yq4l0gTUriOXi5KD#0FJCAz}i3({T!sI zdeIY7K0p?QXe0%jS+x=C!`q&}Q*LIq=xJ|)y?t`|2kE!&PznKFzKCe!UvI|(MYDkY z%mW0^0}!$iD3?SdSy-!kLI-kh@411lJZsm(QG6I%0B^)18*%Vf3yBdl@+J;BwuqYK zB6pa=DhY^EJTz+ejpdE_cSWA>wQOhBp>#aF6pd`S^6c6*yN3 zKB?mE4)INIaWzxK@sEgdJUqP!)eb7F6u{{YMI(!-ZXUdf08cbcfO;SPw4A!%wKz(6 zQM-Trf5;6A?h(!Xuvlhr!3uGO-c1Ic_THhHG3zOyMOSgHScs zYddzOu`Xtvv^e*C)DagH8uq;5RBGmSbp=~46zC=fL}n{cSc*n|fg@`+OZ82gk#N{8 z3uH(UD&qs96kv@U@hAbb!BxTGdu(b#v|j4|-GRWK778YGQe*9vaRNc3xKJSh4&9Kt z$*BPxAg{Z*6hMj`@hS^sHRnIM$QK|LK9;xPP+T57OCWxh7{9S(>=EPuWL@TqXwxmh zh+dSCb4SUt6}BphS-$gqKs4T|?{{t4KHq7bg4cl10RL;CAmntBy+q6_5c(Cn z+CK>au;3sHS)1_mVt~Nq!!1Y10z8tyqmHK#VC~EnHX0=aG_Kh=^Qn{Q(0in_c-&bK zG=STBg$>ODlA*ZT8rB2J&xk4tx*vyTFkv)YW+@lZ&27lyz=5d*IsrL&Jd@#%l;=sJ zX4L4#q~{(Ffzooh!!-P6FeHo#t0Cfsi22nAa98@}yqfSxK9~oP73H?TVp@QD@9B&6 za3k~>?$jU$eV4<&ONS@okf{_zDk(Q_{{sdW+y5Co%zOe!Vjv3INI)rDqJUs!E(c!8 zM*Aa5sz@()H(<9o&+d~lb6G&X;toJ{hvykB1o%sU08^a2$3w{sAkgL&s!RSje$k%Mta{{sik1R<>RB<2toUR5~ z*hcT;aUxn(=20sMbEB_{e&A&>2}(*b3ed+lvWZP0wH~r=3`brC29SH~BK?}rS__exF9_(WQ_-!KgJE-5yT5uUJ=(Z!+D1$7a zJe1$*9^zEz1lGUgA~gMhzABv8gIEl>&%N=ydJ`Hp-}>VzGzE02pt1mZ%E1MB$vCOn73?_+m@v48QnEhhFC z6T8VB=FNAtd_j~rBZAOb44Et-d|Ma*2Q+gQ2$8T;P!GhwE<7oiXJOQiR+PZsurZTN z%s9Srf{qy{VaB*`fQs!5I*f7~ztVTeLp3#?iEjI1Z2 z3Yl)oz=v(J0oA+oWG&oT!DXCw-+UZX*NCe)~pw5 z#DaCQF{AVa&3{;>qIa(~7Q-LEyO}mKNt~JEVs5|0*lnXnaG2m5y+b(EGhTd*8Td>b z{$A)QbR7q_SFND}q`&dZ(q|qLv5k%R47tc%^$3RL1tV$-+bT4x+x4>DcE{VTUZXT$ zve<EQ8#hmWZ)b@Sr}uz8RslqbNdvL{wX5rU0Bh~%@-K;v?mtU`3E-<3{xx9 zY}aHiD(N3~`0{WA4nhGTzUsdJy8!W^Ji7=~eCJoeM$oI2cIVq4DmAMMgG=1f*IM*y z(Yx3>gUK05)KghVDPYL)nBX+b`&3Ls;U@*RF933%;b3ODm=E)qaV}<114F%nIO4fy zs>%4@Swv%1Nyq%t8Wt3EyS;Mj$j`v@OS@PPF65qDY8ZKblK1)Bcg=>*Tl2r%kPV>w zwME~nh|5*v`yDGtO%3jg^gg!W;#BZV?@O*t^gGN!+!8@>g&=sl1~WuJMAaw#EmPaz;!s+9-)UUtBF}s|^MuP|W6IxS z<~X0;2X8Gg1wU{x(>Szj3gQ;GS*@GawxN@ zkHt*?4x*Q&CGY-Q`enQPAbQ+7*(BfYgH^7E>r1Mn{YUG&+I~4Z&mMoYDLUb*Y3a25 zK11Hva4IJ!-|Kftu^WDM@ItP;`R%jYX9-?U!*2+PUz)7<9SlFD^hm?yRM!3+Ph|~;t0U`M za<(bjnb4M8Bxw*R6)4{CC*6b33asl_?+t9KNjNCycV^oHf-&1h$H_}FaJS9d?8}u-E%UwC16P}K(>Gw1ipv{tg8Oa6$6~Ki z%ZI|Izcymc)jX!sTQ%k)_M?vOUnoEJl(4$b+NRs2E89-*A@zAQ$tXV8{m`R>_nl}? zA0<6O&HN&M=(3M2N$JBJB3R@a*Jx1C^cRnGwa{C6^1^4=*_s~pX8MjZFS?L9A7|WQi7V#{l;^$Pb&Q~y>>l*NP6%33-HlX^vD&Ey_hG3S==+HJRb^>UGY^`Cvx{1Nwt=S;5F(z5F_%p-g#5l2 zRN+)1b;Y4>#4*EMdGbMdi^ZCfN^Wp$c{GC$%E+f^Ta_QNdb$4S2()ck#NpiLKJ})7 z#Y?%sq2jYFt>nFP>}|mJMR!kt|OUGS<2VHw=~7E&Pm%SOyNsT2nJ zQyZmnZf_*$6d1x@Oep5E#VX3vRlVLtXKp5j6UM`IkydD((jU@V@rGX&@=l)449uo@nD{qca>f&8(5%7SAG*DGHDwS**U7CsO2eKtPBox%TATXhFMbS2d zsRX}O`J25$b|3ajZGu(sT1mDHg~Z{-Ozl3Q^pMmtnU4f>od&)dt0pgr=?RFti+qan zn5TGgWyiTbQiArs1ymHAb~O9hu?@?Mmw6nT*bR5I~|voX(Av%Js$~ zoEE9&I())%lLE@&rm4~NU&?awZ_O*1R3)$nyv)8={K|FPJcm_G6h*wj&K_xdEjA)2 z!c6z&dPY#-l5e90O${w1Y!6pWAHthy*jC<>($xpt z1a+_t=8rJzR9aW&OAAfCD9sKwJruiucGysmDj;;qohwPP+!+vS+kj-clq6!tjj}HE ztnEt-+2lz;W`FFBHDg ztm!1D)m4*OB0?V<7yX?=lYc`$nXPK1dZ8&l!O0G)qrE6np*m`qs*^m`t|YazVMZYF zE+xB;#f!A~dTUTnh*RiAEUV2#{gM{SxwBm?OM)u%hnY|q;u&zNz5DRT2hFBlidtio z?qY7$TuXD-VX2b`Uxi46$&v?i0XjG^P=A8|7q6hhmDiz(ftLcWxRK|k?&d76iH z$SIqZ1x&z-pv*D{CU^X@SYwxooaj0#Xw9>0TF2s$_3zX`<`L=9jVm_oDdxP}kKYaP zxBV=f&d{s#+N zQj}ea5Y?z7$3iMwuBOKaUJ5Yo$$P<(l#}dMb>`1`z`9v+{83z006$H=2@I@!XpyyE zztge>uCHpWePjRTOEhZ%TT1MD=i;GOoWw6u+H-Vgxi3l6rd_z3Nz)2lPqJe0iv&*e z?Rm?h9n4O{1XacW7a`Qa3&;q|`c6QHVtlhJMOms4(?nX36U~_oeovs@TNfNKf1(2=j@Yxnrip0=ILOU@Me5JzqJdAu)DwIiD?$NqLC{X~Q&5?D z5Dg-P5nG_2K7i72Vi6$w}o9E!;wB|edexx5H z3jikY7>QbckzqptlB^~deWk47&`l>OZ_@~3!>BpLHu>69`$C}C+n#+&{Xg~NB=KN? zcz`zlbNd(9bd0?NyYp3> zeX3s|^a^gwzp#mcU0ta+*oYA%S4Rh%hwa45Gh<{DW8}!tphN`FSC(?*Pj4vP3zTIE zj}Olzo!v@M<-l!w_)l@;A4*g8nvz_T5&DcI6=tj!PT=upR@DT*DPUaLDBDV~w*>5R zFzwF=nSK2BKSx9NeNRMhF)NW6km4x-fiIMQ5to(>#n zYOL$M=g=mmo!|q9{(S@GNlgx1HGa@oTfB4gg_(Uqw4+Qk{}FF(-IZm;gXh}Timd1f z?Z{wQm;_8j2tkNvg(u^W34*I_&&tt5E zUwy-M+%-mY&BVFmD%`f=Cqm`MFG){23=W=bI^I7x>(Ca;f$}-gzQxM<;Ej$LtN2O` zZMBteXW-0F!szuUrtJH?s0iPE%{l$r**XO4pV<*4<80rSJsWV7)3lEO(ma&UaUDkYBy%CMkBukdNX1-@U1JGIlwqHydOoRA)x3vQ1tgX6<6 z^x24KfxtV}_Zhg3ZxI4Igm@-(MD%{@lNM(1JoF+Xb*8{p>a39p681jOYyiq!9l}9miaz#vyp1|+Ch*q`8Ch(cEiWwBD!Ajwso*1noxmG0m z+zo*oMoG3XLW7!w!X=>{lTZLn1H}M|(P&m|jW6+hz!`dEoFzF!!#Lgw4pn;taqy+S zbfl%ow6<-6In~1X6Y1ZYH0?Je>aVH%?L|wiiUjpQRHWd_vASo*B}ix6sPQy+38<$9 zjpx@><>7F`IIj7b-PyqsS_r&7=aiLm<5@M==AIC%&n|s;7_c0Re%w4bs1MH|#QXe9 zl;Y?eEX@3~lQ^dqeQe3ehehjiGU z0I}OnoOmM`_4vO2{dCK(so9*=JL{)U$BQvOn|f?HBt%VIVnBclt4j~f#D9p~(3a}z zm}Uga&N-V>a#q<3p%T^IvzgfO;zjXBg2YDRS!U77EyRUw_~93-k(o1Ull)&|lcOu+ z>?R=HSCdwC1O@3y*o}nJ6V8uY_offe_mEY1grQe23S{5W zK^yV@beeBZo9XArE0-r$?~jCVp{~HadX9iDJmG6$L05?cOsdkHUo~!j^=}RL&J*s6 z4xYbHzrR~2*szm;pC2o(O3E@uy#BrK-ImQ`y1DEKWV`83Ha%W?J&_m90F9*~#?JBq z;Y_WKgu@ojZ-h%NC7vHR3E?`+`LLbU&t-ZM;-6Zlmr0u%gvw<*rux7cL7V~81Km$E zM@U_5(%uS}nei%UerpSuse)<-NcH2Tf@q5Zc{j5z*TtM8PAWAoHj`>@sVcb2j7E=JAUKN&OFrh87g6_CMH3I5j#kPMC!76Hh{r z&gJ-?(UqVEh{W3xA>t!4KCDI`vT$t@jZ6VoH<^6cXqD@OW)nxc=12Ti1n2HrK5IFw ztk6*R@l$87s46gNK?^1(Sfwy>U58#uc_tcoJ)oMki#4xB;`1qQR;%*Wci_a^ zh)lPn13mmQC!cZTlc*bsg0zN%m0yY;&y)CQdRsG~e)p5x*n}4atUHlx$N+ev zh|fw}sN>4MUnlw=zDTxYh2szi;mIto#Rml|udcjV$wo+>tnCTk`-qr-peZ(+uW;p7 z$+?Wc42JvTIPo`IFk?J58|3dVo>a2;GEiJTAwfknfIS(|q_KGT?}wHos?mgig6$`n zHpTP74~^(TPbELkzYT8q*c3{H@ErqN6Cf#+8bBd?fM~WGv4WKX?p#_3R~vRwMkN_G z_wz(j^VwJFZ&c2G$e#EtdnV~1Zg@{+jQa*WN!{?#ynV!uj5k^MqHoTyk@6B=KVv1+ ztNZ=VZh{E>tM8xC;<@iWe}eSRoeOA3@)R=S%qr`QR^nd#TzLS5kn1ixuhP8O;1d%9 z=K(ty41K5k<{j#a;3u6cEGiVEZ_O^!?2C8CLDphHiFOnuod1;Xr!Y2*OpH0`OLd_b zMLM#6kB6KybIP)J=f3p)DB(Azwbi|#rlbJJ{x3L z`hG`xoziB-jzWOUzAMHjVOJ`_M|=1SE%l~X1TJ147Ib`h@0Kd8lA=i9vv3EAg5sRv z31RF8=)Eh+T44_2?JAE?q(g&vd5&@F!R`fv{7%vNsl~}hAB*^~yfSYMQ3ytfJoek!X=f)me$reECgPxHk5Rukg=Gn-*HVVs2>cVQI~3K1 z>(vQTAQ+L)-hy^TH9_h+Yt?O~^Y;~j?GS}j1al+i0R^mCo%~SRaP{hCq0o*;+lh>k zmTW7nj2>$7KiH8KJ{;>@U{sP2keJ_qhnQ|9zu9*pDoIde5cuVJt1YjG)7Itt@@wfU z=Xv&~B%KLPGrK^G)9>MVuXoO6#Cf;1E?=#_!&GgIRuy0wFTp4v7Uh_#lrJeE_X6wG zbjUYa(zo3qp}p~UZoGU1BnFqo&P>Jk@4{Nr5QiI7eK%6t;WUel1k)(xIx3&B5qx|af^OZIIAsZv0E$%0477ki66 z78WO~^n%>Qj}P!NF_Gesl~p#R8?Eq{n81Dxfl?4ZBCudSO4g3-vyn&yG}2 zRLyGLhxbmp!7zjR9Ur@f=np6A<(f|Yp8fMf>*5yd@rCX{NzD44v;8D|){ekQaqpdr zv>0AN2#x6d+}26rr)A=#l$ifpl8=bsn5mJB@-IlDJH^&aGDy2!UNMLYox_7Vqi0pH`V;>I?u3(t9H5C|)gdOBQVbY#fi3eZ zNn7gX(SAc->+?@a`6z@ck}yM7q#vE#X@74xp1r5X(3Lpi7>6)*R4$fq)_GUVpCiBE zEhu)A6fb7r@OlsSaoataJ9Q<#rZ}hl9_a#VT}!qg2~LbiTu*G;@$tzxv8-=|8}#$M zYh6&$1K_{I{KM4`-yMXEk9=}-q~+rdN4?G69|1KDnP`y!_3Ur#h|% z!d)Z9$uw3AynRT1JmqhsrLKen2Uv=vJqg+TG2GSH9eUu^bKx>nZC-qVm+?Ya`T&l6c?>gudLP^4&cZd4w(hh4EeL;)}%bldaFIj1htB)oUonu##T5Z-p(+)-#oaX!xFde)0 zb>x)ciRq&K%rZWSWfoX@iFq<7PgBZn&u{RE+e>20^4)&JdPXK^e=V!n`X;|qYw7`B zDOx-27CN(auzR;vgZk14ADV_=7&mHOF=unk|&d zYZ77tBbVGlMJeSyDsciv@%;TKQw8lV9wcwTmh=@9>_Em?`o>8-tTZ7S^j)q4P9w&8 zz?-rk#QDm^%R)`*pBnqqf`8fJ4Ara#mJ>nw2s5aB39Q}p$!*uI*V>G>RGzXX=cGGm zpRry&#Ibr&ZU_$bBg?1NLq5kgusRPLjKEH;fb+JE$5fAp*ZA7~JXBQBzv=(({v|k0 zVwgb_sdCbJuAz87>~Od2A3~}Z+(f)Mk+$nEnh|-n6aP+B<(6^MaFoJw%n4!Ktu1a} z_wP_Vum?tVjc#&VcsaKw(R9|=_LY~TC$^=>?3jx@-R_ILT>wSsgyjA=8E=PT2K!Ux z+jSd4XG2NrqH5CM>^vu(T2HwW3=lH0xaGQ5wC|r9NkzND&!VGZPw%*T_GVJRUaoSJ zjHpE9BX&`bhxjXc*B*!+CNNMyyp-967uQuI{?V@VK5-ylotxSi!BZAT=@$@7Rfi1U z)Z88prfHSd3fZsNI8i7keLm(}GzdRs<;m}_nR6U2mMX=MF=^VlZ9~z%aU!fGYTZrG ziNVmLhxO^CJ9_<3naleQUjJNX^oTDhOZgJ3G)lwgmB59}I(hMF33H>SEo>0+A`Voj z5ga!?d>?texK*v|(B0p6TB6WZJT|ovNJy_vg|v)(u{19Hb7#)+Su6VpauZo<_ub~V z+}+1Q7M~WKf7Iorar_Sk??JuaL~21l0JB0q2j1`ecouR}D@b=sdgeE>i5ObvndAyWo4cCe%L1uNlX0i7c#N_AB*&`P$iUKFcu>N0X= zrCijXKGF;Sd(^)YsOx4`r9Be^?av z=sWka&S&>CS>ybg8mxJ&*6-hV>>x40Ppzsp-OphIr|zqqhhmcil6%+mQh z`wAq9_W^Nnb#11%{=u0PEw|@Hqp^#rWfoc88@&w=M<0;NtV|`9lCzY|>#h{E1LZ9> z`;O%Q5f|A`aXTArajz$z1uyj#p8BisR^jB^r?V^NHSb?h1W+Ga!B3o@UWq1NJHUl! zzm8KpRb-uClcjj$_qVj34fhOH`hgVL(=FOID(6$ce$&m1cjQkM5VcOXKK(i^^hCBT zrKzz?vCd}+5El`vWByLtHE{ig^-r9#QP<48->(%;6`({lU$p-HzArw7$9o;c%v!s5 z9Ez|r2_JuL3pGx{zI^#_d(Q)xX1m6osX6(7!6u^i4)N~+ak0V)w7oQ*>&a7p;3j%r z)S@_6!h2%&yo-_1Y&0lW6nvg1QMr($`u6R(;bhF&MX%nkVv81rUtW*Lt9`62Bkwg{ zphg>3A2Uhqd-zKro=5RoOt(I&E1qDfSu2Zup_W&aadJi#mu?fj`oYFvw?ponlgCrH zpu4X5qr&zBuRr7kci#|BI)8SPoM9toJD(f+XVu5T1(Wg4)Do+2SSH>4Vo$`yfo8tM+I_U=bFO=4N z>|4GSU)yz#>i;swD;``^`MLJ^u7xivbRA?Ge;y}VoYHfyYF@N-@G&Z72K_|4rH6I(IrF{N0oOT~B39N9s`p%PJJXqdHztRA@s~Bp8 z=M4YoW`9ssh7UiQ2m3hYz9ah>G)yy%^(ES6&4Q`RLiU+FcxSQV@*tG02gl}ejimI} zm7}(&mu|B)YPj?RhU&dMebownBM-Q`_2PCi<)oy+da6Q_=gA62?Z3c<=u09BR!yq( zn<0ajr-Xa3fyC~Se4#YTj76KwkE8paS{TMjyEhnDcBx;|Kwa2SSStT}bmEd0oiPLd z1;0T|H6229O%=clH(t|qLa%y;w#Ny#=SmGc&dyI&GO26q7U;VSk5J@WVKtaoetJs73cYWXzP~IYk#3HIHUPU+1 zH3)!=ZIpnxC)MJU7Cz{`S{)oTH3}1tA$bmc;8~dOzRCDn>S!#X6W=!SlL_OS#~Eba z*W|1hU+~>?Q?yjYe^8`^v~Z`uY^*jVv#KM^|hT%2f2^*srt{(jA8B%Ll;@!ouC z3xsj&=a}VW!zBshKz5vB!LL%asAT5deO7vA0VS<*Jwo1hkK9wfruf$S%>dzdll;a( z?+55LhrYLY{ZYNe7|(*6+CI37yWs2Dq0_s4YRoMEv+7RGeZ{5s`?__PUBn_QEknCAx@>uuPH+YXY;#n(1&^D=Nc&mv1?yiaI)oeHF8gT?+>%Xe6GUJ z7*zht2ixO@$Fu@;CXM%4QJ*!g)<*RxaxQ0l?j-*Zm;a$4t$6j&(YH31#>urtI8yJd zwVQpNcrTww6x<<0r|z^p28q?`2>d4`PTe36Bdd!~yA9NIa?|6rc;_0RQN_M8W< zo`2%YoFp0mX=BXT07#fTygkr+913o8Tgy>twM;h#N6rYoAAar-nnw4GD;N2^jI28= z8KL!wya#p=CDv-uennjF*HzLJ<}C8)ui~%IAa89R*HhCuGZnWMDy$du2kZirFs}2KCkI>w zB!BsyxcH&cVdYSO-^V3EM+K96TOMtfW|=}+af*>`Z;v*Qn7lae+(kl7JcI6u9h`LD zz2TsKaeL(3xh1Nms$Ny^Z7I=t(~QRIV?H6-Rxvv*xaJf641S~Vr&k-}&7Nt(ccR{i z9sT&tUOu_)v%!Thm#c?u%`Rmhv%MzDUdh$&AY8X))EE`t3kthII5&HHuzB1SN6ESr z3{S5;DbZ1JAhK-=b3X5yV$1jM{{D-5d9~}WG;ZV8=5>b#A7AZ}KGJu0dPlCWHMYq& zNg$Mj?Gs&W9JyMi?g91_-w=S9 zQcxu^kVFa`7-)~c6`0{@5B}Q(tOt$Jk8}RpX>*S<#H)MF*ldYKUE4&s%I z0tPy+b`ioG3DG#Cc%|4wjtmj6XTfSeAVx%ii0ors*_5NUv`>Gr+HfH!kXb;J$i+%| zcl=>d5n433m#9jZA`;sN#J7 zLee6_trB%_pG=a=pu$5Fk6#0mCjtyrX)MPiemhLb)(t5|_e(g@K?!^JzgWD5NsMlaYAf7v;5t z$}?Z@#Y};5?{K--sWKtqvSW}SU>+IBOK}jb^T-wgx{Zr!CZQTZ!1ySt6a+oB5z+~R zo+42{C#u6Labn^(9UMIl=?K4VfJPG#g+OqMj4UQ00XOmTf1m|WWEy6n0Ykth!TK#I z&<%(X?_s*gq>@-KuEHXnzcxcL1M;7{Apd7IYVb%F3;ha@0>p;KWM)4Z-48-Xu^?%V z6uIl+x9?{i@7;G|HOq^L`_&_4@(_snWLA)o1@k}$0|m-QbC{Wcqv!_0GF;gC;N-s1 z9Aljb56g^ji3l%XFcAn&ak0QA8=wi)Mn_cuwBtq|kdy(mLRoNfl119+?*O+WjCs4{ zn-+HmeQ_+`yNHqu*+h!N1T2?}r~=dk6CNyyZsY-J9tnh%C}hf8?K=<& z53--IvD)2IK5BcV$Y>)BzlyA%N7A`i#wuV|Q2oLA-Sfx^o-U$-Mb}!f@OkamSATV= zS<~mCu-EzQ0-!<#1b0Zt0W!Lgg8*Vu-ScQf5+Vx7F_DqUobWW?6!Ws{;-f`>>|u05 zG0=@FAR~wA=tdILe-$to2pShV%qc0uC(E6OdNDJMnjwWtOr!YgUijj-tH=Tp@?bt7 zKbUC%iXkJq377#KDwm9mV?$N8uwD-n_NpFs>nJTlBnFK^fMgScSX@Z~dIjjC`+<_! zeI5%n$}N0FK~!)MZ$4Pqn%))6Ij**0u$(76!9`mqOZPH_Bc4G6$jN~e1Otd_k&u8{ z=>V(^@!mTp1b|~&deNQp52|<|_ysQXCJ-;Z`R zESQ-xA)Ii8Bw!&5&NvKFX)$;b<5O?;DEQC=#Sk&bZ&(4jupW;B;#&(-2)i{j-I58I z8af3@SwnZs{|8@a1UQ|^7{OPzF;N*#sC{YxSU^xXXA?paJ`uRtt__7=dq7#(=)EN;CLa<2pvnA2QwHm-L0WzkZg)HO! z7u>2VU>6s%5vA;61_%*HMylunogGvg@XmM&sB-zW>9`k`wSR^8#Wq5tIEY`8C{PNb zjCEh}IGRI1U(kbxk>R!6syG5_l8x?kLL}*;yXR|bK&V0zB904-;=rOwEJ*7!8VR+; z!2pP4jE;GZKru+LuRpLgq&#p)e(+79PJH9AN3HQwupA8bZ#CCax2y{AH9(Gui|)iD zZw9v{1CR#+~dq8|{Z3|UKLRA4(vHyZwj5s`wPDUuAP$DhJtGCJ;SD!^5her_*y%8091)2L+DvaELjlH=0DGza>s<^zLguj9n|g@NyJdig5dj2I zU}qc);)RC=lKdC}$Zk~k1O>yRV1OCqroc9_=a?ycxBnN+duI167yXigOlCv%UMuq( zmEU3mJtZ~^m!s~7=5VoZf^n}nh-em!$A!&(8RT(blt}4qGHyE`Y@B^t&oJ9fT;-M zn9p0DV1Impn}>Y=YLh-@~hgpI1{LonzFz;ooGv&I4jhuMe?DUR_41o&$$ z56>=FM^%y$w+OCeoO~DyJwe2f3jmvhZmJ#${@Ne#1%v-O@*Xs>L>3%qMMYE6c;uW` z-CB|3=ngWjA$3&uAJ8xAV(#go4;1}wa6OKs4?#^%)s4tm|F#lXDvLD5puXRA93RtiJc6=JB+us$#BVu^C zcg@ddu3mm8tMTTUOLu>O-~thIa1$Hcn%Sy`i`T%-@V2qtr~60oxVZz9{I#QKAxzd@ z$$xm>TFW*O~CBe&CYVwXc{DB*6v11u$z=5a>!SYVJ60 zfHDH89|5gr;27lRH0dAzmViK+LDYL55xa$3HhT##FGK*|fk$`_`qv4ppaG0u79LlB z0+Gf+K>m$2=svq2`E=BMsIl0;cX5V@nVugJcloabSP9@b zCX7O!2kcV|9aT%frE%a3yq*8ViGchNj|n?*TlyVq5+Ek8iMVz=x;zSTvv0MCIBcy^ zVLSzQD*8YtA)cj8^Bdi3z06@TQ8W^)5h$ocJ|CrHE)6Wm6wL(h{SL%HH%Xnn*j zXXf`?e;fIJf=A$#XhiJrGE^Q2AR?USwgFXCO5Slij!Hd%tDQ%+;m`+pFDeE4FdnHG z_sEg?)BWNDZK0UO62m|3*6*&SZB^dcZA%rLW23XU0w0|2|8qpNoj`)xE{m(%@IY$9 zjaCb zJjwcZ>gnSP$FA^FA-BY@PdyEu`BL-s7s$f<(huZ^A0C=j2T&Ql6v;|)j!x~eh^^;3kcY~&go^8`w^a-T4%mg< zt%e!T$mGlq~OW9c=O0=ScC$u2S5^IdQY`RK*+EX6F7A9Cc#BvVlf zWxq?p-ar*9dxd7HA%5!7l8LydLY5ci{G$n1`PAx8 zDV|XA{9Jsw{Jv6tP{rntJSVGlFIzLY``K?Wy2~V4!CBka(%SvyzN1O|7GuuF@9}o5 z@W|aXmx_}XY(y_Uj|kJX_AUfh8-YSj<=H7qE4A zdUr23WOU~{TLHG?y#J<>ME{3)NbcG6%a?Ett~cV+j(`@x;`S6vWeM*`YS+J(3{rg! z({tT!5?jj~pVW9=TZfwZJu-q7UK_LZ`5cyb%)q^N{cCVRaJSPQ=|48$yt~xxZi8EA zqBj#HF0!wg-IC}Bm8EFbNo46}xf;DLI5nd7Kqg40pT;0-B;|;_v2L~!7dGV^uCY+g zu|qFOwrrScKQcnw542Op=u?ZkwT}ZkYr-T;3g3VQG`k|=c)%mfbTVyILKsS>j6>#J z>Vx(Lr6&ROA9?!Xjp-p&oWgoZn<13d0ZJTBFx0n9*XK`-X7eXL-sG2fi-+kvHxhiU zHfSQXfV`Src5rwbdhB^jS~uTG`7)OEvR=u3txU6MMkQET$|K1Rw`5dFhuqBdKxZ`b zYreA2&}Owgcon!W?v}#4uem}gVZbpL9Q#{-2&acOorzaBDO%Umej3qpQ8ur@JYmeX z>oTQH;e@`Ys%gHEyyw2K?v3t))>>BM6b}>`1opFuLpmfHTQ2mP>9z|Q2P-Lxvn9+3 zsYYn`YJQP2;+Tq+7P6;A!MIYw)Q@0$*EZ5Pl)+m8tC-a$yNoG_7dF`_UGh#o^F<+O zd;;2}nrV}=&%*iCh4ZFgVlkdfV{!+ZrunKZw-}*JWh56X%1s)Zb;SkdRF~^ts^nOw zEAFXdn4o3YR>`zb1W%{kRKpnEKva|{!*?Is-zQ~ytyCm;(XTonNIFL@&-Sik)`C+ z=~?Of#pFoQ9>I%j&+Bcf@rP4OfQC-HSU=fcZ4Cs~b@+WTS?9E5qXW{OdvH&8fvI+R z3F;In3>!!3l>GxrH27uIa#K}czo^Q&Z{c}`VhGyYqm0z0y~9y0mj+sH|2b^18lTZF zT}0c+Ie)u%NiKKCT>oPUC%m&mme&Z=Zx_PYv-t#2co0bS5J-SxmrxYXy+RHhIg;3p z>t!WA@{G|e`_Nt>ByPE9myo3B!7pCVfCCqkkp5IfnHC0B$*L3W5VFuY0Hkorj(qVMl+v*p>4ZN6#>f_w;hjwBe!EdOaT4Xy!NBY82ejqO;X~cRx%e z(KD#Js%BL}w(RYQLDaX`CwwyB8ji$pc0T64{Mq&M)qdSOydO7Y=NMi4n4~y}&PE#; z6jFL&i5iVA70F^Io}uu;&xT|x6mOWzi9XIaVok*aZnWdo*T*g!k3Mu<>(uTp!9YFz z#5;lIr+AOl%fyRUvm7D#7UIi&x7#8u!6zjn|3T(i3z!m-S*fS<$WOgtQm-g8_&*@n z39=+^^n)tnRke*_FTeC86RM5w=#S3ssJUQot~d1;YqHX+P^10e@lVa}yK8%j z1yZmPCKvYz1?z>jui@{7ovPBWb+WccZqVVwy&rW4#dhj!Y8 z%a~qijef~l;R;fmEVDy0-;l1$Qo^6KX7}l>V~@HlpbjiVu%e$sJ%UP5dY_sP+#w05 zG?i)wPWB&dFimybDZ$bh`}gmwb9=X$WoyT%DZxf zf38XXVVkWsEs8L35OuTK0x!nWVWwLAVKEP+sKyd04X^9V8-b+fwf****WC>Mu_c%F z9j=?muYv28XpP`?bVX*;)Xtq7y0qb`4#>)e=cih;zgkQ2NSetN@|aEE14F7N=Iif$QR!um43SmrYTC@V)21RxxFBXIZpbS1~YSE_>Q6Mk3iK! z169dRgbEuv#GXyH#M7+v%Y5LpGmLnvV8x4|v@>i;Q|`VWCGe?$6Z6ay?*s%?d-zl; z<7a=Ou5ZyUld^(VTKqY+wGo9u_6Fbjn9&i?oyz})>rZ4B`6j0L(C<8ptqLL>`+5N; z7?Ti}eEeqpvu6RvlP3=RI{vD)qcy4{AulE970r%<&eWjLOGu$&7m4O%=wTcQA%al zX3SyEbE-KL)tt()=9p78MUK@(a_FG*67BnXf3ENKyS~5Q@4CK!g5&Jv_Pjs-b|i_w z`+Yvb?E^@u1pOyT$I`G?8Mz$J^Jr|M+B>hP|qj`@Xpqqm>$Yzd9g_a*Y;1B zP-m2_Ew@t$;Jca%iduS@n6;kBI;gh-EtCz#&Q?h7F5WG9aAkuMx=Bt^q=YE+eUHB7 z?Rft;laf3xbxs}Dea$jG&IbRH+LLs&yGw&S*O0$+jS^Quq^*J$6xh1`gxN4{+84aMU2P5l_GM zVGI(=DVUxZxK2_PEry6DlP`c6pN=2VcPr;zY~tfk=j$lZs|Tse)Rc(fbcPK@kfq*e z)4V+Va63gD1G1U#2q>ijsoOG5@QYrdGgOE>gX9%u?T_7SPE7WVLYx8h0mnOTtNL8* zP$p=^IX+oOh8)SHvO{Gb(51}dq37v#o~+uMD(3sjy%(^QQ-+c@c>AWc;`di2W2_Fv zBKKV~wA|m=l7$`1upj&OH)SWSi=V(g(SChQNUgn7Xe1i-;0PYr1VI233=ZayHaze| zo@B}(`}$ElWFS{{A#6vkV`2J@owiy@OuO}nn5(V)jjJw*` z5Pf9EkZtt;A@I;@(emRZ1t{F^Ap$u2m*y9J${lajo;p@kykD}c` zFT=0phT%%f{3xBmP-9K9j@l_hE#X^dlXbA4KV|BoEx)UQ+SLAZ&3w z*6&g1$RJ@85x|5@3BxXd%$kc}_KVM#!z7R2uvGg*Ro!crikdzNnfmt^&4(lXBj}R0WP|xBJ7AqbGNr>5AuM zFdqhJ?r)Eo#x4V6GQ_0hapwTA4O^&wm0^Js3fY8aB{9VAp1FPlI6xt3#kpDJr5*;c zE7vG7me22vLc?ajs%+9Jo{)j(0dLF!e}w`g7iPq%Q(c_x&=oO!LDpH;7I1rl

nbuaOJl%>Os3V_lhh3b)!GG14;fzm zL=~lCMXQW#c%+Cep*+&in<8qEy<0Gqa*t7Iv6^%;8ErUosxq&Z&uprUYjsdS+i+_5 zUiQ#C9=o@rpugJphD}f+8I+(^goHW-uQ!*x`NDIxrmq*;W1n)PB_&LO5=+nfHdfWr zedKRWms9Mp`fKWO%RXCyQ*H{{9>b*`%s1&99vOAM0~^V=#mUv4d(sdb8@XQlaDmC4`arg7++ZO9(4o;E5448Xbav117lkV7Ev|hLcK-Ge>60-kW4! zOoq4**^w$}$Rvkx0IifL%N2^m!`jAGnyz-KH6Hp}dBj80D;xLrQH5k?-Socz&om4- z>3Cu~cQ%2$kQ4wmlp#4_AnsiG;H|O`XQ5rQMMkdGCd0Eb>e3(7C9L;n^C$X_9rD-k zfK$HnZXG#*43i<5@shIyz$Tlirx*}l;FRPIdDNv^3o8J^E)OC=RtACKD5A8C(0Oc1 z3@?SfW%~VW*SDQT?&Px2{^?Yzm(nkKx;eRX&5XMC*ow$;E@?NZ%M`e?=ZiTxS7Xk! zt~ph1NhZ-^xBKb89LSkEl1#jav!TWrkmL`1SrCYQgsn$mkiCZ?lK)^<2#Sw37=l|q zcY0Z_1UQjL$qzOWw_;mJL4sw$>)U zaaaAG6GlaT2Ki*y{-v;{&Mvs3QF+e0=(iC{ca+5-e-4vpc3Szs0F~A1P(jlkiHl?h z;xR$Irj2u81QZ0ugn@Vh23*nwI_x?t<@mdkj$s}@<`1g9_Vf4{=;R+_I|~o9N24xv zcm096X&YL?hiL6@(>52<v73pqoY2KP$xqIm1GPU+XkST{A<_+&1vtT0_dp0%qB9eEB{=NzJ!;Xt z`|Tw!oPP!4B2%(3>*?Ra;+|<@+=MLgLheKGTQ~gGOvBYh?6l5@H@<4$)w3=ghP;z3 zVHkfT!sT>V9W)ro!4b*6P$ArgV8c#pjnrPwmeKUl4SvF^qRkN8>H(boMls?t2>1qz z2~VL(ei*#h)zS?g$n3heXh@S0`hk+isuUz(vrnAeZ^?io%HZ)sRHR|J9?$-eWa!zw zpNKcb#|(-xi0$`@*{ z8+Mwdo7C;D940?->>gbov{xV<D0Bqpx6^6WB%{^koNL+NLqd>2+jl<%$FX$+sQiC__ry6gADjO`5OpJmqFAor>6*fWK@^{cM5Rs@JMLuwQnVl2;p!J)I zcd90nx`zYNer}jm3^%(4mxMxf%4gEgLT%O7Jqu&?x_|!bI-d*r^~&D4D{owC|Brx( zUuAz&LOx`4+=90oY@T~X)Wix|rls&<_lLio`}{sJSvyW34Mz;biwzu&y=|K{S*;m7 z9O>d}m_dyVh=V?=|2bR%*IO3r+@@YvJt^=1i|#&=`1|K;>aXr+=U^P7PN>i&mc0`{ zMR^A%%j-*9<;6iOY}LqwP!c{Ao~{7xNfok(Cm+NlAIZ8@d!ez@$)NcAl{5=ps$o=@ zPav9+j`Kn{v~| zC9cnnXtpR07qy5w}A$Lhzo*u)mB z?uN>@{o@S1kQa@+qXi%(##g?z0_R8AfQbip*Ox!KJ+E>s)H|=CXWk1+>od9={&Ptd z&kx-Bn>VJQ1qhIxvj*!L!1C7g3zRvCSbbq)=EdEEER?EetJjp^xv*7LPt{N2+7az6 z0iMS~)!s-=dd3Tr8-E>3;-gO0dl2_r`uy?gfl2sC>kZqk75U|)bFN>me;=A`34O`5 zu)>FP9y?ZF`Tp4?yZAywZQ1CbBcVm_DU75;7d~%absKKHDm9&ZP&R6H?%|~`&%8zU z7`C?OFRknx+xoFCe1Ahw+}Dxn;kj^yr6&l{^bk*vE>C;wmcCc8^^qU?^B9G zGTInEK@@c~R3z{6j8mlS4sTaX*?WzrNL5TTR7%}n9H*3~ey3fD27ff6l&(8!sGM1bqXuVxI%VdkEOt(N7sbt%@@+z_&G&-v2d$E61@}RwofqD9h9{UTh5TXAwzwQM3 zAu#!W$G|i&)a(C;fic5qZp@V>0qs5_UgeEgmdx$jlO{C^lYe=I<8RzB{zaiZYm|BZp$ ztL*8if%#G%IhR;VPw2{jP4rZn2Ia5KJH8q3XbCA!IcjiXp4YPWvd+z}3KjjsXNnat zX8LK_-hSN9=lPqbT@PP9V)Jcwiws72XPG6nuQYhHe*rM?^Kqq3`0SE=uJlFmpbyS# z+QEQU*7M{B{`w^>VNr(DOXp`{v>~W{P!C~jS!dK^xoRfL9FVQ z{Z8zMH$;qWyPVJ3;E#T>*A8`yl-jT6iYG=cK3SxyT;65lEE;^6M7@!}`i^F1qgZg- zqPsvT-EgJuMdHbevE>p+*438ja#vx4;&ywaiciNuvQJa2ZPlxt`=(A0ct`HwgnZpD zuLW7Ud5Mwz;&uW&&RDRf-xWqUt1AZ`FZ=U~?BccPT@tr0GbnDQxi;-;W$yRE%wi?1 zj^d)C{=qBkmCj%?@2lCctDG{bIUWPu(7fP=Ia^e8F>UBp z)NgN#y^`hMrdK5=O%6teKa{n-YiFb>z^$C~aVZT7%C!E_xb$kiDE&jN;vV>M1Bj%<`dKkiqh+=g=9r;aq~&j|qt=Z-gDyhqrXs6?u6THrZjK~6 zY;0O@?LV_*mSNL{bMBuiRg}y-9p@2iK4*vNQG>nSbxQJm^?~w6@hx1ddaz4r^j9Cr zy65)D^RZ_p#4~2nKE0}qd5oGZR6EzLL7q;6LM|3OfF$1dIe%>Sv`aBp@P^Bf2kIed zZt5oA{?kqPdv0{RPyczt)Bd9-6PL-ZH^gEcly|AR@==NIH~Gx6jue-;>%0$E-sNp8 zu(c=s;*$cO;w%mvb^lgrSJO6KJLKSWEkiH)Ui?Y_=F)|=yP~be7QI&1Wl!qk(Ha9a z@+9fPF1s(gxT6pO@{`#)Z`TpQ*%9pE1D*Cf^!$|i&L6$qHZ1eW2K1oRE&d1b-;kXy zd9Ki6K6w0V<(J2f8v(cLCSMu7swdq9uk}fCt&I~uUVuZkZwnpQtEB7+@$VCM8%awM z|6CpEG;J~L`eLwGxOh{^EzS|N;osSROx<(w#hYL4zw1l0Gc}8H7KN|y=zd1MR-(FP zDZmVw)bG#+lFCS*R40aP>L;RzX<>+5wYMQp)}E58Kh7?|)Tn1x1-i|Y6m6zpRO6b` zLN%%N*M4Bbr_^Hk=Kl7f?GIbjRZQ&639`RK2PJP-nFwYp+Z(h)u6U=W!-OqgKO26c z@d{%UEwQ`@@~vJ`|4Zhsh(P5djLvtZ4WW_q@n=f?v0nhFBUW+)=dP{sKb!a;Olir({vksqIAh_KPiOL)MtQr{Pi`N2+h^48A zA8+c08|xU!Xe`)XX(tndUCa_IgthNF>;Fv7zrZ6j1`1)v0hkH@7vVBY~ zbIekDpN80uOk04d0IeaqTKk+*Y|>dmxEl>~V6k3O)xqPfXtX7#!Bz+9W`0siM@7wR zy;bEzm84a)=joPpZR81059?!rlSQu%A9%I=(*4j8(n0*xz16?v`eGFilvt{s5e>r2 zGQa43Q1Paao>70BnVH*PNvB@<*$+69J^Xz9;L8itxfj-To|(%m?8|VAA;-Nl`~s=S z{YR6yhL%!8KZS03D99?olyq;tF{t-2zw4vZqWk@;Q1l;9>HsBba%t}11x1P3f=<~= zW9>ly8$C6#_fNaXDg3B5Yfn2L9}TR&3Yna!{~UKa7LrySQikY#CR)LPl!NTktNTSo z(^x>PF#_p^cMVtUvrP3ae{5N=e(p0*)JAHC4R5$G5a%Gq==^zCV^PX#Slj|ti8{5X z0Pf?o?t2tHr7d@;iPQYY)y1-1@uy~J)FoTL-N;Xf{#f|;nqTxi68DpxIYn7!4|}&v zHT|tGdwcT{Ig-tBBhQQL3m$fJDshO%0e@h59!3~tq)^@co+t~2j}CVu{_vkhWww-t zq`iNvIT_Y`Vi$9l-AZbkL{lWFD=YcDuOfzU`|BZ6w8N-wG$0cCZk>3X} zk76p%O+gGUTvmAE5OyXq!fgMU<%uJ2V)6>&RuU5RaEq>&aL0b#KXz1Q>dt|j!->TZ zy4FL*xT5Svva9_i=jDlxf}DabI>ctj_;H0EqU`lIau(Nk*6`XTgxM!-<&fCG;Xi$n z3ujr!eB|b}=f0UK>_nI#F-ezF1s@`tovJHJPE4GlKbl%nob0WB>;n4kRUdyrBz7*& zUn3o}mr@q!17Aq;K*%5-l_y&*BV|&OxLd78Hw2orQC<72SDe0OUspsv;Mef-H2-0O zL!K`A8+aFu!&S77kd`kw+t)t-MA!22cu(>FW63yC7cqM3wt)mOTZ-r2x{)QgFMMBpctq+7X&N-m-q;GQ6u_i0SP5v`3B zJ=H7wuR||NPJ~6UU}-@27YH5W5JNa5V7h<^^9Tzyj!7C}3lFEnKCZpyfek~4s(ntu zTm@^mV3H3^KrVp(BdY*BZBRhmqyHDieoR0Ouuyy!%9equ!$I?EiK-#tI-&9H((&ZL zk|x_bTaKPA#3=TdG8@)s!%1{W?-m17y0<=^7IEEpXiApk^U!aFtr zG>h!QpcGdBqo&Play1T$=Y{?{l-g=}^}`WNew>(0A+58H7LOCY4d77>GFJil42!x) zKy(r)9av-y3+4ldQ}WF*23P!5QkxmdFL~GCE;r=M$)&{qXexkB0jASNOl-y^0V?v( z2Luq|jv!oUeC2!Visv-`;KMrcD{8P3cxD4ZczGtVMFEk9Lp)MI0wv?eTvQzv!N5Y! zf^KeH#!nsa_aBOttC1AR^He{LQNNP)T<;=*o55~JPSBIG@o_(YJi6Pcd&z5YB&hF~zI*S`Z5w$%DFwAzHAAvofdwz%+u=0Y6&BLjsZT4i>op$b;g9fh_qX z9R)DZ#bMwJD4a%QgccQCBP5>xgX-nLI*&N(YzkTwc?()3B^k+)igq=s!r}>V>9`y| z4oHa$10CvK7OD$i!&rdX3g5#aAJa(#1R{{wO*1bA{0#6*k-=vr*5Gc{a8hq?3YQW9 z7z(e(p*ad@{URj11BNp%JZuhL*&i(U6~(8c_6ab1>XqL=gyB;W%^>8vS>b!c;(QG1 zc@%v_7#5CN}ap}!fSr-D{=|&3?@9D2}@wYGt5zd3I(9%OBVVK z8~p|=0_ep>9J-5>0yu1YKJPZ4i*j5qv6{F5s9=|MM3Xr(Uzk)ECM<9NU*bKPp3;Iv zGFULcMhgqWbE9eizTCvF0V@5Rj#~v-_&p%Mk44<(zzZhc z9qB~(Y5*1$^$e5*S7c_7?sf{7_vn^;gvMO4!pN)-_Qp;z-VK&m$Zk#r_3m&3?V zz)(1Mk~w#PBKlZenx;cTlLBJ@dV`B6B8`A}!L9`o(gUMtL<4J{iC*BaM7vm`C1`zP z^aQ9Lbd6#!lZ5m`O|MJO-nnbD2?+vK-&R26;}Gua!u8m)Toyt>2KeH`ZiA3Dd`xjQ z7H)hLo&f^D9RS+z+?lC4Z%oaPx>s=ro`6TrnOE|O=t&Uz$+gA>T-^d4jc!2CTej>X;2;J~hNV3bYNf_Wv-#*Uw3&2Ngjb+s*QilW9?r3af%HK50F z2-9PSkVBoi4V1tgps)m=YQ z#xh4Xvogo1^#+|E1Ca zTV_^LEGQs+X-jlswi_^)n!Azv;KJuXkaIZbSuElusO{umQO~Z9Aq~vgk`8ba>-DCn z_XhgN^+$^sk=I-l;QJeY17?tM6^ZJ_qMlFXan-ii<{^dTm&HUJGdzO_9kUDG`LiN!$`PYHgPBep%$yMAN1>l=iUwmbi2xF1Bf*QpA=kTZ0T%`{%q~x4O;k;2TJI%e zR=sRPgk$S@$A)GMF<}$NW};zd(aiY9LyfFM-A{e~4!_|HXMSvZixqjxM9<>T6XpQW zZ=x5G*v070(jGt#1E@Se10xv$tY~8FWkwr6%KSAKS>6;K1*q(%=<=orVn^g1i!GSg zb!$^N)1w=ZslfZ$TDki_i;+#{#HP6#xA1my7yVsP-_2q)vjMFcftiUIJ~jXJ&7PO^ z>yNzo4QP&e(g2;}8HNf#KG-~leolBk5H*U?ea_dE0Rre-%*ie8D4!*IQVWCVfrBp! z%Y;rbFu4_kT*sprlcVt47?eq9``CC+3%i@KKJ?)#3-@=#tpTmE_mOtQ@XEoLna41O z*W2c!9-TRh9-|{WL8z*aLmJ-b$8>h-Ca~&&@S!5!J79d{ChHePg|bEe5@vUp9B?V{ z*MulwfJ-?k9%VJA=f=NwmQ`<}x;A?`>M!^o5+=@GE74ZtNC^j?-1Us`WnxFuqC}6HB%+~NPa=2QU zr<0Px zPl#6R8lJ!$1j9u=azPhezkY ze!`XP57i2_X;^qO0TtqnD2=Ka_PEnQNPFR#beo6(68(fs^aKI;bFF-g&L#XqG1h>e z)jA!M6}Hw(gY6BUgH3`>+$3X>mz%(^PgHXIt!ScPHC^N_9T2SD<>wJk@Q4u(pn{(! znaTtZF@fgLc;XwuL}C01OfHDjs=%6`h1)G80H;VT%+~0$$kt8d7<1$W_FZpOTmHHC zbC|pBx6qRx8{cwk=Nh?)Hyhmae&mHm6@TaTw^`54QEzeR`qfN2OK^xKvW5};$`V<^ zc8m}{-RuTZ?eC|?dtQsk_+X$u=Bs?Z!gp{JEIaaZ5iwD4vAGO`YGn&Acs#LeN7S$o zY$BBT04Tb!_492a)O>sEMe2kP#A@I*+3Lgo{kS zy3P{*GLQYVnRV=Azw^hI=kxP8+>c_{e25pK4F;`!kVXn>27IB3Udvd|qQ+CG?%7}Xv+_5$$l7#H> z_PAAzd8a%qOeDZTeh!iv9xX8t8YM&S;rTh1-`K0D`GNC%P0!`vrum^rX_ITqGT(fM zXcA#zOTQYWbp6>lv9pCD-kmY)|LV^^6nX6&voW_bp89#-AVQwM>u|CAnrqF8GE=hb zsde`|r|$X;dII~E@&=_&9^Z5{^VGfB*L#akf10BOXRl_0Z>+1_$!j>(;8mWq9X6?fzbz?{q;g#LQ1XjgpOoyK=B&K7hmeD zRrJ21`RBf;)`bOrH2QnD=FFi>Js~fIM7;JsEisxZmz&m-YpZxF-%Q@;y%n=Qb@%Le z^OK4SS3a+={`*PiBJJs?CsmgqnO;tx4i;@yH=Je>ItonUhcst2J?b3qCTZ&SIe839 z_E|TL-E;iB6(ZvudT}tHP@rfl)wgf{ye#d`>`=*tN3*LHWLx+3wrSgi6}jN(qB_aY z_IiqJ*qzHFDw6hW8y*Zxg6I%-P%&wbDFB97w`D3NV`iO8kBTLsYK+t0_lNV zSKh$OJeO^K8@}$DK;e}_TS=DzjJ<~X$6T+Rt2M=#a=otuWY;|_(&ryp*c6vP7zv)d z(AU&-O77zF*C(adN7c&=ACIh-hZi6%oqQ7@2KcPc$wL)^|HR(Q+mnKRRs2}4Tb6gO zDznbJK>889=d{^maB-O6p%_UE$YETb%k_)(SeI9)Q28E7MYIK1T=`&*y&}0a+d;Fa zO8ksSMa^)6@qS)gwv6nD!oUYb=ViTi8)wK}SSGzZwdd*`_1eq-F4hKQ#lCo@80OQi z2Ffk5F$&7B*ITIwsrzFmRkz@2)Oq+759Wk@fUgvHzWMJ-j&t3`@BODbikf7@a(359 z;i0iXxISiPHQ(G!bjO;L5M2b75%LxY-sPeZHh{UVcvy&TfeNe2GQC-3Uzzmbvs&f( zQDKVAg}SR0xyqhws#0X9$Ejzh=eu3(O0RF#U(8xuYcGo(Rj&pMg4o*?0&p2-@N+YM z{(c%YY*s1Y*4of68ZImxiM2ShfyB<#Rf-s`uUdt=m^N86L*C^{7!jNVRti0@XIB^C zmvc_$nJCQC?$v)^Zs|Jd^%dyydtIe4ToiPdMa^gK1&XgK?^U_s%mOm)ok#=665pD| z;G%GjI;_m#Vl2Gk_=^D z$HkhlDSzKgtH1IJlbH6kaOX zPuA?eE1qd3*RndG6D)xGXB{BbCTFAXrHH_PEJryXJ1#vQJ+2d|i1envmYu;qJrd)G zaOMwNYLE7!!-bM1D69Qu|8Ro|$HHkZ;7_=(R@HOVQeGy;$UM?vfvi-YTc_}(+ z@Ap1a6RbSfJ8MP{m3FRsW_}wkt6I=|ClK$CWngXh2TkS=I^{gLsDoCHJ+6LPoVsQ!xi^_l*C-_7j~-wYFk1b&tmz!Gi1QLaOGoPrCtVSL27 z#Pp!+OS=^Z2jykY<(Dj?P_aboq|+8icV6lh#%k4(M`Y&l^=6SaI#YW*CCxEn5$SCh z963fj^m^q%O9Z1213b~H8+E(8w5n(jt(%G;uh4$RgJ`{2o1&*vRrY>^>ZeUD6021*D`rY>%`y!Q4K+LpO3TZsHN#yyivub2I%ahS{30VxO29ZyKY`kt3hXE_Y3;Zz{lC>IUiE{HEm$d#CJ2 zyrC-{U$uUrwTZrEXXTE+%Luiu?0P{T((l{Q3d5?N5^!(GOlmO{>YIN0`4b+jF5gGb?y+BOQQ2`OD&S~D zwy`^MmzeR7U%1{>M~;&7v&~Q~V?a=YDr8^chqO-%q&hQ`&^V!fT`j>t?~PZ=k-G&& z>Bm_656z}5*4e5@C!$mB!BTUf&Bk526-i;U%Fp5`jIR=}=2kVjU!!$ermj`q!u)vp zK}zk$l3#XgOUbj}J%>yuT`~wxNAjL(cazAAz317UKt7i7>9tkq4$_S6DbZIMp z5W6N-l4wyVBb7yY+E#5#4O*Ii^G(}vC_B^Ow%oJJr+#;>T^GBGWj*3EQhYy%iC&3W zk|wYSAeByhwY{?JxJ=x;3~`bv{IztoTbuSW4ly86Da+?s8}fD2yuFr@au@oB@-f$F zh5{v)L!lEUod~nNy4CtnEYsK_?#xsjNuL_%eYgL)(k?|;y~|BV_>F)}YFBnfD@2L1tt=;+ zXm2$4`IqI~;b)XR%h!LJ{WhB4q4PlI*VR&dStJv%4nfxeWzmWO=Vnr5(vq*GGsh; zw>w8st{Cae%ns*Nd$VcYJjf&AdMgXE@r+>AM&p5)zGvYXnBCbxwD-|h?MR-WI}a$o zinSJ(B!p5~eNf*zGGKn);3DZ?#foN9`ENpZ0gd*H%!6AkkB!|Gc4%G3XCInu!(i{a z;@S^g#Wz(MCIK$TgGY&uG9Ltk-Q$ui6et8b!~iR#nN8MIOLmQ`jif`Ycqu0Aj?h0T z65Fts@kt4BN$#X1HAd3G&7?zwWL>I?+BVe~BxJvvq|rxmr5ANFDA5ecbS@cl7LcaU zM-$|Y^4^xXa>aN{)d;kB(Sr-T6z|P@k$B2}yr4I(`D771EctdC55Ulp?oq6z(EbF5 zaOrBchewLMaAtCa)lngpW2HJKll@tBhq_{hu%8(Nb1x-K{*HEF0(Ga&N zp@De{fd{svk`h3IG&K+uix6PJC%0jffy9Zb-lv^KdU46K-N;gFspIyPXqkRzLb693 zG=P)AzgkW{iG`RjfqxXR)(9D4ats2U5{)Heh$L(!rQRPJ%DjE_ooSR)!-Y+X%@)a+ zCm0z8T=Dn69cFm^sT~SCbcH$AIc|1reC$sQGl34f+^_RE264gAX-55ySILQr_~a~w zYHc>jf(J9F3aW7}XxyH#IB3dnm8pWzQ65}~mm)OGNiZjh*bt$iL~uJ?iIA+1#a8ANy!85vFRt#dlO^h5C<&G=iTU9irR zmoGi6iW86o31L5;e7-oLCnMw>DrATkb)Eqmnj^D_Brj54w@kY0DoMAQq)`g(zho8~ zC1=S>f&pQ4UJ8&$&tgwHK?G>SLC);UOL@ zlAd|T@^N)}vT-_(ZoiOh5~u5|rd9kGC=EXg9G3goNO2jd%_P1mheN%Yjx|QFjIm?_ z8~Q!KPB&xhm*>ft7OQx7w@QNBk)G$5Tb>{JNtI#2B{+(+?QZ!+2Mn1OZUo9HHLy|C z1c5`zV$#B^ay0&=U=J4PcEUqJI*}acQzao9k4RgcOkfcCPC;ph6u_bZjWexqEQkbr zzI}%w&YNUK-7f2RDDiI!VFu!jbLm@yNV*Nnx-nn% z%Tc-&DgGBFelNNz>F(o>R|NvMLNmZPgWH)INQhcW#-G!-R~fW8ohS8H(NmAB4X0sg zZbuHM$+lCAODLg?Gg%;=emQmD-IJc6`UEDqa-dh;ygIXuTG0c~*HWd?p)JX6eptxU z7HVox8g&P@8`CP%b=WVT_K%>gbS#me^aa?6b*7eKzsA!t z1d$x=rLu-;4%F#s$@2Rz7ZRe*j-Q3nJ;`RP$wmxt$0l5)9WKHEK~E!|?4%sxvP5%h zj6+F#TGX9FNvCF@;WCs!0tNqR!D%$hlb$?lVZ?AkJ`A-E?NSyK77K$zeP_u3ctXy@ z6Q+KJE0TI61Ajy?8qLiLo_p zm|Sp|eC!cb4+SN_DFOA+01(L(OFG3O0bV(QnwPN+hu_1~;t18m1sZ22SKOP1IX$o{ zR3-;;R+B;)72so`QWE8!1Tgk1R?3<7OpmPbmnxPj;qKu|7$!5zk%NrlwFx7CdyhBh zlrTnC5P^cb3bkQP8$*Ol;FYexH39&m*(-iBl&E2-FB1e}f{fxQfJVNGtMd?38BTrv zxd(pb7xl)nnc<+_jnWS`jV}{0gY{HF+HflkB!S1)n^Al28fAG=bvxO&i?sX>xr6>#XMvdF*e>gZ#C?_9ahFrcm|A(5sS;H}MAz6GeHU zwOr6HnM9*ud}4001zgKoo$Np-2M%RnfYswFhzl{;lOpnhjIM0g&f~r~b+ML@$CAAz zA&zIC!r408yHr>;g}T z8@~USw8tn{heiy!GWMj~DXm9Yg=mbO4MT3S;3gdKIy=YeWk}B5sqa`iya+;m1$mVX zt&BSBP`R9OnUl3?O(SxV1a4Yc6dbztBtKbVJ5Zz{nQ$1W%2`mKGhBhg69U-o4cLT8l52#V|3~$mf#7)p;CAZR zpO${h#=e|7$SUz*9pt?(-e^H=!0&zCOcB~y}HHRrx*%t^l9ez&1$)Sid%`$JW4 zk%U#lf)2IS5~08ibH#P-K&_^wYCwf@2|-QNogJznFd@PPIhBE)c*j%{2)h`BoPCBx zPA=hs$<4!uRlnU0D?T9mF~+x78FUApMtscw3O$c`>?H$n;X#5G_M8DF3qT}HFs~9u zR_Mh!4h02Dgy^S#sAflt1ZE-EO6Jc7P03)8)%Ni5G}c81S&3WpZ0_!X%mO@!Lfa%e z^OBEHi3u{lXmQa`9n8&?FU!sdniDA()xP|7VjApyYj`-V=jbJ(~I7tD#sDXKfo9) zqOJUBIg*Ah%xO<8p**MJZo~7iF!?#M_KaY&YDaa&-lxq-6I{(U1<~IO?|pm3?{+j2 zE^vk;We_xw}t++?|)-prJ;0L`DVYC z0|8HHd#xfh!zL!pB9RZ9BG&Yjk3`M|TLglG7mKqb%pRrkC?|I3?iT>zWfYVqsz5$6 zeM0BUOs;=FFho;3`L6rw*SU_3^;2pyEPt|Pvca!+jR`IOHALM%yBaz{70T0we+?+;xccj3kT?9o;uP8AVf3f1EyHii$aC+DPidUje!o9R z>$n{h!43F>!b zT(rBkm&UBy+S_T`qc(*u>SIpIPtAgDex&Pb8zi}4k!Z`~*tBhl5h=cxpKUzf&>FfM zS)^DLzJ0g7+WOv!s##~gxY2MB{v7D%NnAi=RduwZpCKD0!2ToZ0tT_zVwHw&CypvQ z0&w!cO`8Md;(zQ5b)|M(SFMxPTt_m@{H>m9TK#hyRiimBpRlHD>ZdBwNllpRxfxAE zyOCuAE;8YIcl@0X7q!lrMI3mt`<~Cckc|SHK`C<(bVisc;P%mFRR1f9m&N?Fz0}xp z|DW^;>q*DJPxxos5?tB{Hh`%eojqbJ?WSox-o`%$7FNl1ZyuGOJFW6WPfSdlBIUm- zHx$@-QK+U>{o3*utKD~3!r7xu6S=L{HZhZy(r-L0y;s(xm?q0%Up72_v2 zQGRLa;DmOzqv~gCezbL~Q#LZJBtt(}|6Q1Mg}wWdS-#An6RL&Q-?F6mKWLjz91dmx zb1H7jG3DY=xms5Qi2&DMtjnEpKVGQc>_C{Wqm5doo<)vHRqwj2ob03|rovF!%Fs#P zu7qnn*PIi+?(=u&VUW;L%tS9PVf$byTRey;3_OBR=1P#g?&AFI_KD3&_2&PvxqQ-k zT;Z0l5ZtkPA=YTUzQI|I)v_BSfKUr1_8}Wi26lXseP2P-#;#b7Y2F)nKbCPX&tFWV zuO(gFW<>Kx2CY@bHSK%q%1x7Bv&mD}TtvEAgQ9kt*(RT5@^!=vg!^swYSe8fryY7O zbST3BtD5X6&yV$TPsP2}T&C5IM;m_2A*r8pykA_s)P zT1Y>jlcyYTn)@5<^{(q@oO!*BOa@y?OT8ON*e(~zUG0CVB1n;R43rVvA}fixK@T2;B7{&0a5VIqhU%ZFbGEpz?hk#-Z-tT1{M7Dp38O%_aR0BOXPvbvlc`jsi~6|Vn|bGeVCk%TDp^4B8XZoTDyft#zx}J{L?(h)}k9%^OnL zuLQ%Q$}cMtiGuY0+qd_?l)}Hk3%LsNMPG+KQL#SOmiZH9-y}8Xq%=WuP}jZH$`x}vBY#)f4YeflbrVfv-HD7dN~h!5@F8r{ zSEM(mFAmsJ!QFT<^AzFcR=S_tXY2~a0ufMe?57Yn+NkawsrbE4=j>k0&CRZ0z>zz4 zTcKUXB9F=+cD~Sx0$c%i%lg59iFWkCzW$pBrY~Hehg~l|=smypf}(ku_T`p_xt@Rh zHgh}LaYx3yTVi4qJJ34UUN*e>+5E8Q^9`NrOSIR-(T9(I_2}IE-tczk+r!8Ic65kf zO|F1MI~!_>O_CV*+0tn56}gEeDQhkY%Q1Q-A8mRF3jUur5XXTVi2r*KeJ}x}9sd8l zf!GZNb?E&cHxP7PpY5|Qy0+;h|J^`1w$`~+xcxKoh+eMypCEdfW31mxMYDfj8SPbf zrtcH_(|#h}%fD2@w>f&ftNJ+eKSA`r*=uwKiGQWZMA)xZ+{=Y zGTvlAzrapLUh$A}yvRoGO3;iRaL9WsST1_oxu%yj?SrH%h?ATESnPxa0* zyD4NO{(kiFm!+jK*zHM&?7{snrHkI(O#AT%1XY{6bS5y7A>qs*OZjM{T?jFJVYNll zC6goM5FDy$nxcp9eQV~>V+Y(oxc*#7Rrq(wM(kJ>Y*I|#_RPCWjSd;IN$ zvfo4)>~Kj}4oihqIlcXJ<(;H+;Gi7Nj4k6&vO66XWS8)#Ryo1NFfpHI6$T?;arX&Z zDH7gE2`H4Yo!FIZ6ST`(%mtIWQWhtrQg#KWIk+HZVhXKwvr4ZIyhS}=Y;)U5V6M{K z+|s7DEcJAF(3RIFz_CS~jd4ExOrRs?dO?8(A?LOCMTlha)vYiQ8xmjkUEP=bu=TrB zK^>Ka%@*t7?pC}h`FjJ7Gp}o`77iEWTD2DXH*rRxC=Nk>5qZoSX9G~|-Rjs>|=$RsW<^qFj4I z#u2_T|E2#QBCo#itX89#C@Xy9jg*^YVzI;Ar$TZgrf|<(Q>w+>hK-#6SIC3HH&YcyXElVSr z&%f+~lS50#&z}GN98>&grkMJrh4*#M%)PxkW z*?vZmSNXIK_R?sF{%_TokDWpa88yjjf{OUO73`UiDf$S9^kK(7OiSM?2M%=fp zAhI87p0gRH;5}^VZybV=p5?;PDiu;k1bfuz&Qu}wVxP>-qpOD}QXy-MK};XGn-fWk zT2}gzY1lK;ri(Z`d~5a=FX!nWxS4Rdg#42IFg4~Y4RbLde(Um3&T1pl4JWk=`Au0` z>RS#bd)MU|{2;+WOFf>H+V|i9U74XpV>kuPGzXccu0jq=?eSB#>9blAXihtZ<7%E7 zInE=mn@WjEGXG_F;wn^Palq{%)Y8`dS5BdKx6IH@9O+HaNrfSlLqfN{emBJ8RB`=Uio+_->p|A@I zEyHy4@r$iSnSup;Qj@9%A2`|#eOhIgr4-D#QIFE;^M?ibEx#7^co36j|d(sStE^>O6Tt-}-%9G=c z-(4~1k1@*Q3DmCA{FvhU`=Y~3p0%b+E89LZo~ceLA1ZJZPfvDKe%?939PZi1QyZw_ zQ!!{$N>P2%3fSYb)vQCLgL3*6H}hfMb2sx^5d(?L+buOhmM3PC3tHxg)3={R`(%K< z#5-S_UlLKmexB{c<_k-5*rdDlX~80f_q{WgSQhtkk%r0Q#|EzGw)c&##&}51@~olD z^wx-2c86osDg8dKl`jHG{r!CUp|?~ot=wFUps5#&^jCiZ3q{jj0)tw3eU6Kh>qKLc zhNW$Q)jd!TC{1eSeoL4~k$3WNQ$Nm4U-Q_#Yt6-Jn)I`c(b4=O_gGK4M7GQyulRWx zJy;z(vU>un^w#8SZEe-o76LAUh|PNy$jWUQycD?XbfxE&Itdy)m^&x*{na|_NTTlH z->Y#H$NV7InKWwI-(?TJRcqyS9=$v@byqg;N__y0fLQ?M_**b z2F2xWV~3DhW|EE<`Dx*=l^XYgmnyH%rM&t2@8%{cX3nHtkkrRN542Q?b#+#U62lzHOKP)uS^! z+~-T-W1FZ*#Y2PA#rz4?=-`T@ef4|a8gdA^QjrW+ZcGs+`rl=H)ucd`gPU5%O9w{l zef{DOg_c-&%lUlxYx$6uenYyt^cGj7C|Li;MIbxmpGSJj_Z`|-IjTGMb-T&7)92TH zVYy(K!qW z)2Z~$IiWoCAK?LcJ^T3P{T5LqUiIs3pjlgXBjNF9ne}6T$_sBVEiN}b`VPpq%MQOl z9oR6_MS{MsTx^uC=a}c8{gv6`|N7C3NSnz3f$o~!FAp`q&zf7VX1MEmO@?#K&+CiR zs11Wxk_|MzTZ`_*{WTEqla0P~3VS(EciQv1@VV=4Rtfw&qHvXS*Yjjcx`i)YxcH=l zAC{QxTO2!c%P0U3z3=I&&){D0Ou`bK6zWex7qM}k!mG;s4HM+SamedrD^0|OfLN&M z=H;4SP6~)*fpZtb@??+wBJdBznOC1`luwcBxkx>NeI%;x*Wr_|Y=ySPf|umJQBr+f zqHoU%a|(3O$rmr|kmF&l`@+^7n#)n9bJKUqk!t@o-9#`y)x(M^q)mmmh{Wm#9Z|tD z?_B0zqt<&SBy*_2rPk*oi>`A3UqJY!P&n+?-Ba#}46C(EVTM6t`q)>CF`DoAE5wuy zLQ)fL`H4r;{6Mf!0xS&l@+}cV)ME)sT;l_I51xT8xi{om@r2;&l+J*yB z`6LkhGy|3ve*RrXuFa6j?TZ zt7srg-v&?-Rftel&R;`;gIUoO1pkw@41v6yTQ5s^g+nrplNQKo-kLZL)EyjT_m zh|inJC?JkMibX#HGSGO;D84Y#4g;uKRWl2z{Ln_=5U)#0Ylluo>nVU|6SNrb#G{Y<8@;u%8PBZ;KsT5=9JS$LRuRKk_TVVNxS%#6JGh zAOsZ;Kp02>v*@lW00OCiXT7rz&$0$4z(9trr3Ye>jWfHxtb7_{Q2fEm0B-Nr;RI3xsz0UOv8Qbwq>uVI}Imm`M` z35AzW?3GlBmqar%Rc4`AN&gd~1N09K3!E5TM+SWCnExqef%HEJQO`u4WtJBiVt-z` ztvgf>>$oj%ru@^Zy68i-#85_~Sc<}fD~k3tx6_aS_tFk3VbCyrY`)~9sGyIi1~$9~ zdpnnG_=oNhP?hOpdhEY>vw(=A$* zVqoV<)l$JCj@$h9y#Q`00pk#XV%4H@Yy)T;H3hiD75dZ@KB$NoUkiLwp03ouf5RFj)dxTQu zOe1Rus5({=dGCJ=48W@t&@l6CjCEP@$SSIc4fkS0w8>y?(%s8D=aQ2(W*Vr~@Q=;V23~qIB#r3jg@pLC92e$#X2vIJtvXh2XFd96Yjt(9uS!t)P{r zppoBu|3|_AF7|m@o;fz(ES6`U-3#D1fDju9GtUDxf3kljWdZU)#DVD+Jagfy@b%#lU)lTbTbG#&K+ zh!qOqf8g1DhoMWSTY)-)8Wu8T4+-==JTo2Sm=4PO^2GV_%;N_$)rS+Mcv!57XH|XV zDtO|_`R3ir{FTYFs~4`_JI8$*K(^S(8ri012C90SRZOMPlf;4E(U!qi%`@>W z50_~?Q_&N1>}l4@cnpq5H@f&kV+PMTSGng;TnJN10HyaC*(N*gaRpd_$S#01WVdx= zF@V&(f;Ig(S9aj{XH?+8Gc^rtI|)gm>7FH>Z(w7tmiInC%~Ci%G3Gl#$eoGb=W{h4 z(TW~kU;!A_;K0jCsWrXfb_k9R1AN-FRb&|!RaOO{lE~YnR!t`i-na|^W0(vSULE-4 z1ClfIx1#zX)jcKN@G--=A?CyjpUI2ICkRf%xw$hhWoM^yX0rcb+L&XN0ATa^5iAb_ z+YxN}koc@AXgH8NAQl#G3cG+scbr9UMiv{DfPc9$fnOTpsiKq|-!!-)q-gp7~YGLlSb~kL@Ps=m2;7WQZ-< z=bv)L3#n`)u|+mt>HmEBZ@wABa|oz5CUB=kR+Eq=%(*7=t76$s3LbcXA%E|`(!M+t z_g-G2hs{=DfgJv1)2fVFP&uSQhx|MmGUi>MIjxrrQDTla0PHg{jA)6OIp3 zwpn~%HqY>WplN&n&kimSX1hx0UwpckNFPR7pOIXcq1a-WHfHuVhQ;8SN~`8>-{Ld# ziW*bnZs%57lK98s`xeXhll=8pEZ^T%zJH+i=C_g6ZEpb`e`(S;RUhE_-*xxU{Tdb` ze5Ez;!Ly!yJ_ZRh%X-*=#XM*8QMTE6tusJn%Q#^&clwhU@8=cu4|&qFuExO1e`q4k z^QxccE#dQ1*%uT3*witM;Kmy0=n&Oy8A(C8(h^N|An zR|UVl`T7^I#B<*5gWmr${kiy;@88vLkXhuaH;Nbes~p?cNd|&WRjU8-b(@x5FR!Wx zI;D7iFGOR$8DVCtey4u|@E~+f+0L0~JLmmh^H=cHvXBo}J9V;=@ho_=DxBYFjJv%Z z=(ON4;0ur7i*EzJNq!aL%-(ikmirfqIVIzDV)%2lgaEecBZtpi6Z?XJ7{DT{ZzKO| z^h3^V;2xk@pI)^yFrdTeQyM{apd)Hf2N8{+DPVF@+~TGaGk3?SEP-EMFZfxLQ}ZdF zS5{}1%x_}=C8B+?TIb+%5x339x3qfB{TR<%?hI@&@+$oK*#Pk27r-MfW2Eq5Z9BaHf`<)-A|t3HtxYCpSR_b|UtCoRg8;Zmd&m|v$( z?6}@skQrqhEq)}5z~N->6U!3L6e#-~#30=On>a4uVEz=(vTo$4QQvtFl%r7O){K`- zkA`HIUtdUdP-%rU<}W3=Z?-{(*1e0(h695*#4U?ov$UpwbM?3nMxP$f zT9<~BXG6tlw4Z<-dP1RdrnwyS8S&sbHw2@c)qu{zO@4mn*fuWquJU*{3VTv#oDLCm zG~D4XxQ^LS;LJ9M>@f<>v_D!F`&|y1+%9h;vOWfB<3B) zwJ9DIu@5hM)K(Mup`wh98h_y-nGAQ8<3Bwj(oH( zYku0P>vN`OLnH^sdjCnI_Xcq|Q-A0`xYmE;Ed{SYBfD}reN2S>P}0u+ItB^f;1)y* zZ=^N`ovt1eaW=xwAplh zL18s^Y+*vi=YE1@1a(h&DYE8L*e#EG)emK7i_a{Uhoy%tdd0Djcki?_-`|hCTlqA> z*Kp@=I44WxM(^3oqc48ldy>$-aL+%9BVP6fKL-lVwdZznAFfpU`l2wvH!yC^)f%Z0 z;%x2{TEuePyHjBKZ{tpZYtTz*(V&;G2fr08lDojww?y$)K+ZX935jfUekk1!R$&`- zdoR7jdwi;1A}r=#eOcv*SHk0(bl$&}wbN^x-d@44rK8?nhrdyed!}a4CSOG!Mz;2d z4Y$4PVV%|5Wt5&s?0h=eg!#fzt@Ur61HH{X;(V-75Ls|ZsU(yxPAv&9Kc^%f5LdE6 zawnLHt^MP9_)jL)hJQ@Oe&~_&6}jsjbf~h#TCbUyIe)PjRE?CJa&ntT{Y+zFMXVi;lm-GF9VjR9Q*Ar z0ez-&U&FQH!J@toYwG)%iU=!2ieL?cdk>%u0!Y&W^{h0lt-F}hM98l!+hTBJoqxC^ zA%(R`)$2{Z;@Rk^KX+JBE%#mcbJ=mtkU$jI_ir+AizOUs$HqmdgO>PjLMwv5V@f<) zh(<_-NVc0=nFa|I;h{J~Z472pElxowP{qpD+}l=Oa&B_Wgg80k(KaXfddnIUY1?08 z_DSYhjR?BijVH=cUTty@&Ue61))twklfBG^SYW84ITt2$3F2yKX66m5;l0Y)9g$gO z)#Jmy(La@Bi!OqY*GirVJjdG@4pdu6Cr~72W2u@ox+sW!G?{~4ZDRj10sYn%oyveJ zS)1jM=wQJjaww)18Eee4P*gb7AVNF$3|?Mhg@Md7>a`~(Srp%+ zNEcOwP8TibrMLfeIr24_48j7M&#{k0>I-2dBeP4nu~3aG{FtEqU~#uSxSpXl(∨ z>5BS@=tH_2Gwz2>z*b7OP^k8z%BOf?t|{FNt{m^)b(y=~Y3pD^<|Bq- zPb^qij52B>WMnsC%!|D$Hi|c2GRqNJWN@m+wHSvxWA-7%eS+&8n8jo+@vmdLj_;y< zWxQV8zJ;_+f1qKE4v)}21mr2s1Od^=GS`Lf3HNoAO$8AZp*2){#<)p&;PU|Av^buE z6$K%#3e_I7Z zJDwNw(7mm7RG>}G?zIg=8EJCcv1u)|Y)vmlRL&#L@R*V8m>&Q8VC6Q~Oww+P)Di)w z;V6{jb)}~II@1zI;?Fj*jW-S8ekb`}*3YnIjVHFjqWl*t-I%>p{k!z;#DYHTppUHSug57AUs{Numy&k2*m&A#p<#TpYDt=vJ**<#Y$pd-ia%X7m? zV3d#;2;_cM7>p&+?Ww=$_b+<%JU2v~-nF_>;o_e1HAQTi?V(%~h_Pj^MMZfJ^V1W@ zHpY$A191@96FbNsMdq?~*z)QoU)`}IR-zrmC(3WC;O;nxa8=`oMAzNHBaCDo(*CeW z)t|I*UIZqZae?PNC@p|KB1tUnIE>l3$+6R`5y+x*D-;9LD&1Ym8@hGY`Bz(Ial0M& zqC@MH`ya=y34Ok~($q6F^MN`Eq)Ft~jfr60%SBDx%LsxZFr$!raNb$3j&cx|;A z6Wr6(GOki=mSZ=0_|n+FbiaeORP`%QUXr*+4yj#G5o`rl68F*!yhk!KGi#J%6=53J zxOhB?HJ?dU2G2QM*7rLlbH4gpEHh)%+RDq`l&yPP0#S|UW4qn)}GmX_Tb{!ijzRr>rc+Ish0ZFStN zQRHWETLZ#cgD{I2Ga3;-Z80X>Yj`WZc28}ivgtv0Ppa&G72@uN*Utv3b0e`9BJ6<` zgSlz;h%P;y)ytF9kn3HYcP3W4>afJUx&HILKvMiTfx<*^chlV9iFEj-i1c$rs%tD5 z-HY-#*81FAyFSnlVV2bK$vaBK4 zn|QcjnGq!h3rMU01l^q6H7Z|6!@-D(S4mzJ=>}Q{xy-JU+N&a>;NjJ^PW=Nj^T&}n zrqA-3@#OSGa{AF_m|HCPR&C>aQhTY|ki$S$OcJGA5H0U^$f_arWGvOb0m5!dQ}Lw+ zW}w{3+`(9eD}oxpPSqgP$n3*IOON9J!Y}@V8T;6O_Jyw%zDtdFV`m0hm&+O!-0(#5js&e2ewvM>=HWN=2Bi`?N7+Q^yS z+vrndK7=y4iANxW-}%S<^*=5{B^08ol|Z2s}PZS#H9@CQTXeDPqNR%y?SE-$Y z0?C6A6}51ZlW8o}5yZXo7fPg2W^!8P2q_`Qz#8L^5cD@ z0GE_Dn#>(dm-nubt}YQ->g$aWOD8{nmM3V-;UoLx!kYw0XyOsM1+Oi ziD^a+X%#-y7*m)jo!bI%-;fWp61bf(IE*T4RkzmLOJQLfMVn z4u<6(*up3kcvuGX3kBlF5Q?AyD2u|mqW($+G@hIywS*!z4K(jkKNmEF8>YB2sW~*5 z_%DR_M`0Ja8~oc;Uwp1QixL}qvSwD#X}*P1)Fki;Ka*U@%#)n7^qaAQzNGoVQ;tt2 z*cST|n_9`KMNbM(dSsv2f&je^^@wb3!3<&qYGyb63GGE2LSE4LLBHW`xkQLN8R9^j z1z;d6u_ogNh##Rch6uAja33W?*?Ot=Anrpg9*PLpP>cKO+x2+n;#vF76NyTA7Q~`m z-)TD)*f|X+Lp{ka1Av%08T#v78c;rPVhem_1og|}(NIM<13%r&G9n=sLsU|n@z8)? z*?=GzKrbYOKK2NjkV&4%VsIO(fCZVU2~`z9KX79QXO{FbxF`O^fXgaYExuNa|T#-cubiN)?k6P#VAfI_F};l0}@5Q z0D^44uhgCzp#raEcmB?E@f3slnL-EF=DzzJ!^^D_(&KGm%BG;MkYzbuiMt0!#~w0k6)EKT#q zNjIe_CQ`hyS`9@o;08J0eS=TXl2*Hh_<4MBa4ltKjpXcjfE$fl%@W;B7b8}j6m*Oy z+lAcy5AyoIbnnSD1?z0zhO{TLv&@a#XRO~O{U~joOp$MZI5bfHX{2b-(gHH9>qxxK ztSWbvb=ySpbwl!S3>nA+kH(N8#Au`;2pRhsBFm*pgy^hVDPHbx)=B-Fm1Y&i9nsrS z=2Dry)E7b*B9bZCjo};4*&T5$XX!9Eb{SXD9nosB{WT-E$xkm4OPmZ6>`)WcEF;B! zmlRBVZ>0n?`~-0Xuq&10u>BSvefag%;(hmR|Ag)Oux&}|wv~si_1M?spIIj4?jvFg zEwF5PhS6z$v>}MQUFg%^8kz|3W0={0VG$N&%}RVwSFl#lSZb>LT{H12k5z8df2n1K z)Q#QrGreiYK-|``$*^7W^ ztT)D=@+89CAM(bND?Y6bf2~N%_(3KBHiE) zZu&DyUyQr6EzNEX?P!*Egh&3!zu?a8R0Hf2Um~?iJt%lEizwz%;~f&d)QK76-p%7L z5=#&2h5RT==IPDCu(HsVWPq07-AzY*APdQ+T*p)X=C&t5xXnI3@mhKquuBzf*$Q21 z{ga0p{F`#o=gjY_u1|Mx9^XqsB2pvJVw}7$T(0zP321UnnlA{bm!OiwXkM|oA&KAF zshh^TI`@1^1hy!*V09zD+zOQj^j@&2krB5kxyr+fQADDo-mAAkjhu;$M)Us&A z$~$TZJ@teNGVjRSiI|_EI#I5`NSnx4*8HQSl1BZ34h!znQHMj zwRwx%y~-peK*leCS5yWV;QQ`k|K3kjY*TSK^x&5@4HCT^wA72T=(x9c{!Uj^s!9XI zoBgqQx7(QpF@aoUM#(xhq@7VokKd)LtE)qvLc?}p!Af5K)<5+AEPd6#@U897(8cW* zQ&GVsk-O^I2b0Y*ds#ZG4*<&Z1da0MHN?1q(z+@U=wA5dZ+28Y)Pe{xq_r8bD9JyB z{%SW^@Hf~+6x^-wT@*9=-;PqvkIHZMFy}3Zc>~0p&i$hsjBJQ4uLNz}i)}THue=+u zc%oi2N2#t?X6-XKe_KQt@kaP0B0K|F{HX!q{lB-sZdf^5Ld(sVSYi;h;4Q^O2|tzG zY^Gh6u~*5Z!uU_Cq)1Fw8HV0s@nq`a`W*cF|C7*-HBF(x&KFqzAe<4 zTW^+sV2`>RQj$-<Tto|15dcXU6(rh>h07>ulu1h#sA3{e-6+g z^*JtZb=F_pSz|h!k^E5jYWB=rgT}wq#{3%NB>a>7U-ty>UavcGZn$e&Qaj#p{V{%& zTX4pdx$iO|!=dX>DL3P&FE#t$pRd*$b?ji8K*Ux-C=2FLrtZ5!3)f@Hjq?JI8f|WZ zIr?jb^A5+Vp9_htf9!P^vBIPka-j_wAZ`m+(2!8u6)?Y2vEkC9N$C3}8~Fkioheyj z(R)cLQu)G^GAH`X4xfGJf*#gk)CXbGU5nz8gB=n30Er#>ImXqUKe( zjmK)8&ugaBI!6VjP3k9gY()d&xU9wLSHO1iS(8%;`BS!7$!Pm0RQEG78eZOn>ThbcZQY@&a^gClyI7wYc>)Mz-|-mC z;eMdi>U&+M)snwXWU6#J&O7NfW9Bkc>h`~5v`2~HaTzZ)9h6$Sbdy8y1AqZ}7>@&) zf^4}QL%3D;wWoF8(gh0~)jJB;9klKLcW_%st(g3rBMmVnj#$UH zN(tSCa9nxpoSkaUfA3J*97i_+D;944EAFb^`&HQo2b~`y6&qz=otB#1d=8g+pHQ@L zwSQT%F5kr)HiNU-UKGtQ8me!)rYr26O(5Ng1iQwJ$_;g7Q{Ny_=PwM&&Owz z;Hg8{J~&*GEH*rKKLb{eu3_%$&ZwPs2Qf{!ZjJUcL0AR|=0X(6)_q%*%Im<}zgsgZ zJYrbuEcS0B=WTT1=(yye>r!>UV~18Q%xH7wb*InrT*FDl7v4#4iQ;fg%6gh}x2bX( zs@Cmwgp7Zf=z(`l?vTF8%wVmQ541C#x4_yrEFNp-Q?opna@vZGX{uB%9`J!YS<;tU z@J8wGfl3;GD%<^xCO$d8D=e*6&F+nJw_=bngL;i$M3Ol&DD|C@J`z>VL$NqotFqy> zvNhg$M>{9#_-V;y)_7;tZtnFKGrqI*x35mDp}gJe6pCj>@nJ)mhkv#yKnN(%+~l#h zb=n|aqFH&Ai(K5DcQRjzHb&3$YK)!lNgI^pImw`GTXLb4vWJCy zsls216aaI1w-pPrutyP^%4ArwgFU^5S(8Q_x z@c2T3oa-6uf{Gux6$op+UcJLY)7n;52mJKG-XL*F%g3-v7l9yCbAH;cjXcaH%UN%o zKa1{d*HV>oy_YSMp!)&swtG_?n~X8L^5Lw+pOH(v*;zkR@4mMeIC`}v{QLs;m0m~k z?c^wV$(Iddk}6}`M?p10-Mdzz{TWsH1E9q4IC}|B-s~GcArO$F)fDhgk&Cy}5HLDt?d3$DBrmTu`dIrFMo5 zUQTr#H^u$!HEQYZIPQWf!xU;o|Bi{=HRtz8lJq@#PSe&`S0I}KK6*5ktDm3F+%@|; zlgxO3M@I*K*jpXdJT;89evB>oPE?M9NWM&5H$i3b#LR$sId9zT*SAfTo#|lg`Q6Na zdgJ}Th>eRE!6gP;Lq!(8lli_2xA)xkF@bsZUYpv`pa>3~@JQk5pu=>ZXD!wp*KM8c zJs)?BxB;>kE%m+MR$MTQ3Cek)sw-_Bl!`?ELp(lv=IOj^mVW3R454Jv(f;aZG}3%h zRe&QFP7amd5-rt*@bq$ta!bOreZ_8@DDd*AI}#JaYBTaL1Z}7^^W2fL^2qjiEZOD? z>%nQ-cwM5rdp_v`#+q^oA%;XihqEGcf~CLH;m-bDyooD$K`GHLo@y@VNwqYR3{1+c~UmhaMz6jG<1t*7_LRG84wJ)$#jU#_6at5pK$Q&AN zEmjzjc*Cf#j3Csp*fI@o-k5YLZ>ua|6CK3K5Ls-Bre2EJThsJopS5pZXB$bgp7kgGUt{-cbkxw`bRoxoGEP4s3g3M5^yXmj%$WYwCVNB!Wz!7Pl@(c&5 z+jFj`+#by4CjTzj`G$JVo*gyIorRH)DJ4+@^D6-R&!8 z*)EtGK1bE0;>>Fs^=kd9Pj4i2w_AK|DJ#?N+7eV75ZNWt?thvCOyKqU-Tr>zlC~@3 z8V6<>Cvw0-L0Aj1Q(@FEfKVxnPWkgp_CR}|f}!y2ryYwqIV`C!J`rl)kJ8K8o4+ph zfDC>6v#=K3!%yNM1h`F^eEVj~ILgspi0jJi)=u%E5*uvp@FCxV*s9yEre!W%6JL%( zy=1KxRoyhV(DS|oO+4z6Y*v!7mF5gsO#z}O=Zy>M~n(sAH8E;#g%WS23^O~VOs0Ceh%BnxF|-w}w%Tj=-}eW|L{ z934K?<&+rcW9LXwpR|+DNwG9^Nun(+pYgb=3O*b$BzVP4B6{6~_Es#FYtJQ5B}+!p zxOzmp{IBuY9jL$RGC@thvu;b#4D$>Msp7J5s(bMY_YWYe^F3w1nfT#C3KX22^6!LF9? zU4KF~3Wp^J%%p!#?JJJy<1FeOQ*iq!a=j^vdggX9l&dpnT``Cq#9`FIJg!ArVLwF% zY@rY>_va4Ri7?KFaY}u}4JGTwJn(=ih7LkiG5NN*K<>qe{i8>dk`R}zgID`&Rb^R0Rt222 zo_^u8efcm__*b$j!ylIe(Ft5sm`whs;QoYRC0qE{1&i^uA!HTGrYlHbf(pAh`*cnkC&M9p1L_VZ9u zR(jIndpAR(PhsgTYH53_RMXXDT(odJc0|h(tHey!#%}4iq*S;MA9|kL_2%=qzs91z zHs1yttQBsv6DXj&Sc}JZYpgewDsMIuW3+I#7|7*-w&>ao}QCmI<+nEs~og; z$*`-M`I85B;?WCB4Mo~NBXL#3DycE|wz!UG!NiI4C(Ee=9^OAcxs)7J4(~p0kb_FvX0DUD!jsEmXTAo^0L2e*Nj5HMU*V-SMITG) zO)Sy{nTz7Sxo+M2aRSe6Vuet!^2~p-#G8(b8$J|gKB}K~A&{aUOEK6VF$fvaGku4n z57$j5mteS11g7wI#F!lPU3t@lbflf((!jFdaqt&oBZeFIo&B%)JN!1%EKZ6R&aKmI zM6XbO!_i#zXY!TznuFF1;eZ{t(O5eINH@B4d@>mqN3=`DcV8LN2Y917uo`h#X6e1q zdnWfqCfJ>Qu&D61%KO0TP}7?BpGmDlx?|zsbC8~_1=zWF#hRLmua*-C1`#9qIa&%` z?Xtnzik|1~s+dB;9{Kvv9-z8;-yDZS$}-G&>81#hDR*oJm@egp0Yyj79MZKq?4}** znxA>tO8q}Uebbk^?jr_{5G6vnBFG%))1fV+>xwZmj2nx^S~wrFwR1EVH#CL9LFzr{ zFFSX5+<3Af5yW%jj}=@pHk*6s`_kK7f4GOY=mG zOU9X|8-BB_m60OT>(mV4QAh$kvO!Vr5tO&LkD0y)_icbHwFe!-D=V zx0~IU56Cy%mpv^ZYR^GjwD^&YEw_wrpJ(wNVeaw%@g8R-3@{cVhD?ds_;(T_yl#3V z(S*w)GO>x;`nCl~-_Af2{g7k7{sD%+@20}m`X{E2gq>ZwZz*A_erYFwWPw*nfg0+E zo6y2e|Bk$O|DB`e#hO@|iBi(i6^n(?4slP1vt-4S_@l-;erp|D2Dy zWQZ9&!OGKJ;+%{@+_AHw(PmmVc493O&hgnK*ce~0?c2rRGamT;dEE?i_bq+9vj*2?dOc#6J4h7G zLN4h3krbQW)E8LbNv@7DcR1NgJ=^~w_(s5!Qo@1R%aVc*&UweVHK!Wql?qFB3)K7` zcQwx6m8-QZG1sxps|M$p1BGwR0PJkxJZLWR_-5Ym7NZjLBQ5{8@J+S5&0WQzSW5i- z+>~&W_lN(%&WyE`_^JHRPw#E9$>C0#FTuNvjcK~Bdh0Q(dxFXY2|lF2UdRnOujS?E zGXU)TLilLs;CY3uM>2H|wLg8t?|*yC^piK1sN3G`8w*?mQpkzyCJ)u1PWe;fiqfKKG(O*gGk5T~%$n#!y<(MVf2UdSo*mD^dbO<^g`_Q;Kc6>X5p9K!lG@@|K zuD}Dary)!ODChtuX%+sDmCBC8c-xp&DoZQ!_lJ{&B5ZYL~!s0vf zQ*3W5sleynTZ0b-%ABUv>z1d`m$8;F?!1U82}-WZVO8qKUhT0Rx7L>UTnZEB7V3J{ zwol5kYUwxIO+rIMA6@VIe1{Ni|0i-<^V=Y){?Fi<5|b{e_)l)n_1mwGUHf*;H@kiB z_|H{M+sL}2wz#orXJ6YZIh~g)K|>w%-b=TkaV3>%=u+$m}^Yp2+7wUoTD zYrLw@Q#eX#kA_0=$wrPfjyXqEQrxp}-R7?cnH#ODach~ck0FqXI)@aKW>qOo?w9UN z8ai)~lD>4TiN4q^t6O8pZSt?*Rj3=M5vaKaQR`WB>+#IN%y{e3;F0ozN5USDjifFW zbk*FqGP|L6D#@LnPr5r#$1E^5H!h^+tA)Jqnd*W@d*FrA&i)0q<)-)Ld93M2A<^RR zMVObBf>O5pS5$3}`>9IeF80v?Z9;J-?#&KB<4Ek2=>tL`b@v(E-lyI>?M=OR6u31L zCBl8(CxRsRHf{iS0+?fC?rKS9Jbpbmr8S4SYgEuNv;4WS{Mlc(e{)9*IIV&=3#8_C z=f87AlWud{|G_i}-a6IiectW3-=>PO*R*`Mu@cS2{xQmHJ_!4mnS5p2HB6*-FcYr-tcrRw${N4S#>9WEGt8;u& zXQ%zL6yh5BJ2myR3ST4RJzWZUPR9!TP16dg?rePSzyA2t?7e~Qfrr&X5Z8$mY92Se4$qsYmsT^(B6k{Fo4kGE;H0skU4D zq8}PEzQA~KpPhE{v6h^zpEHq&2ok=?K>L`!s8vHdO`6xaVxKT_(&ygA+~$p`hk{DRPE-eQ<6)obO*&4``zh}2fuq-zd#er{llVzOrY`( zyB<9~U-Il9h0On_F(T|FRC2shX-2I&A+CUjsza`B4JARuB=Y^wnpkNaZ2z(A`XV%U zjcY<;lzm1>H1)rde+orvBND}SzJDIJv|hVb`>5x8NxhVqqKxO{5MRtNWk+_%o^#od ztFh`HK~P}BNzYPt$YXbuZx zO+vNfv@rqigG3lAR?14+2;<%oS>%)FPy1ZEZY!sDa|}~nnhN|Z=#oDCS;M>J#aK{L zoEdKx(^AzwFw503Nc2(Fm`+t*P9T;dJ}qXAx8F&#ThK2HertaLCC5&0Sm_F^v=ilh zL(?R$-RjvnHR3r3H6@t~T?w#K#cAgROs zHua$i4D{&yxt%LFEOI`T4j3!=EkP7;vzac@(t;x(s%n@S=H;`JGgH})Y63;EQl-$a%Jb5a`IXT6ALhYlQ zo|cM$<~$Uxf@;H}D?!Ky0J+LW)>fgX7?@5H0LLK!(&s7x@UmRnww7EOPAze{1X(-1 z2^V%X1dNfFZl@>XcXhmgQYSXjPX$#_g&rrMn>hf^xr!P$MRPz%Di#fN7@cP8{JDQg zv-7Ojnt?`9P=YOgu8V*T1A3Zq_DsdeQ|3@nDn%J%&KeNsil|g7befKo?0SE` zx9gYdm+LRsxXtGF+Ux#&Ts=dp1Yr&%QN8@k|CO%*0f>RFV;^wO0##f;5ImZN2p7nn zFO-Rsa)Ee3j0Ipbfx(;o*&1G|Tj~;yWCQ5g9OIN@Ww*}V|9$$xx;Sds^!+m=fciKD zOeG)LMPLX?7(gWhMZ5|D_7OW_hrCNlhgNzoEasewmP|CQB$J`TO z?BuZkYGV@cbRr6nyRCpH0w5P4so7;0exoXgxj?sSL_ix`EMB;U&LbmY@K9qmm?)(Y zHU#k_V%{LGh)reRfyHR2WgG^>DS~)YISdD&(=?zvhfZv?vuTc!F(+iC zxRxG-wup1R;dg$X+p=$7zK`1Fi+-q!u4bXj1Y*Vf%L5?Hc@X>p5!DI86ccE43hk|Y z6`(JL{{`moeTx{tkqcR;D*?;SN7-dv2Ew$GDpsRV%tg$rXKlmT*ZBXlypQ?U?*9>!R>VnTIFn?&-Nxky zOx!%}dX7Sh+v*YJHRXsJmovJ`*St=IgAkWvQ3XOgx`lMPidK=*jP3{h7cINDh_N0= z@tSMt1biL^SwSlAw8a1HK^K!~cm9YOuT+gGa7OfSkIA?TRyZle?#IM#saDQu_xgqn zvBfLcITlV+5$6__rj{b^41&FWu53qvkXa`v1OyXkk^vf&i)jHgC;@+kjOGe3x4A{Y zRDn?js#vaA_m5aL2@`FFXLEBpD5!E|!+rsb*W4wJ!71(PZkp(#=;JOZbhkuvzHM;8 zB1K~)+#C(}TDvlCkA#Z=);g-9EektAYK~(?_}87aD-0OjNbx^i8yMkLy(fHL{C+ zx7Aa`-%aHT$#5e@rCmRP$ABLvB2JMJMHEyc6J5!^14W{;b1)%jW*xxFWA8#zsxC#g zwzC_p0MSou=miD=h_GaUk;mTqG&lGyvM;3dURWZ>a`m26V%yqSmymyreFz1lD4mg| z@PgY=d&nO}ajpcZbX?g^01KnQ$uR(PMYn-4cev;pJo;tXKXO^h<^_#_l;1{v8+>&f}7yi z!291JeEOX@y2N26FX(3Ut*KxfEEt!?L<(u#Tp;EKKvRO~eb9IT6Lp2w!vq!=1Vezt zZeSsI%NI9)8tNipn#lC>*4}O_Os5OB1dn-4=_4w1TjUPiQ0z~vcp&??OLo3%mWF%G z!Za?T7Z61}W}BoUF53Xl1D3>Bju|>iF$2Y;wDE;^4xRm|_!sc5>`7pGNf?W*iN(Dk zh<>F!+K3gaYin*yLREpXs#oq*Z-`+6P;i?rDi(9g8s9D$;9Fju1WxJ&n3PR1qw{sV z-1|!N_s16=Ogy+oP@WD-ybaXk#HiR8SFqpR+W7{zF`QBCYm7FGdqP+jCn+BJ+FZX- zNk51UpPv%@3s_T<*l)hrzeO?E3o~2fM+L0r63X~+@3`nHYt^c^&=SL09IgZn4y+IK zlQHc~?DNellg#@QtJv#%aJN3Nm0nD#{d*egiF>km&*G05=Pzw{cHMI}ZVrT7JXFrO zMu&)FQ!DY0R}LVa$t%7#8Vz+I{5<3yesKk>=zeTwD|W`^pP1|286g`rS&rKG`3__N z^+X#D#5ifR=a>2C4`i2VHjku6VB1|1cVywt<+hCx>Mr|X9xyScRBZCXl&bPGp3Soh z<29#(I3plT9~Tg?-OssLQb3baRDIVRJ{IG1-8acK5dKTpIGdCrUbAcNM%>($?f8Fy z^t}G^(?7AFcaSyc=PVn%_jLvjg#@pmF6&@=nV2pAv}pG%ybhDgMUBvK0{LoF1#B00 zVFJ{B?h~d9zcB8xAS3$h)IYIV0&a+fJfKiq0c?;E5KWYuQ3(?w0eIcxc1=;{?Tg~v8^JTA7nA=3zB3<_=6-C7efu|a0FwpHM5}I!HRFs?OU8f%L>7cmmN zPU8u%LwuBUYny^%O2YHvkBaY~FmWo|hh#6lC)m7S;Nu>FFg?3~?ril*BD9W$n_y%5 zi0GyBx7N4g&kH_a%qPWaWZlD0kV&^Xg|!)<<8T0Q9VB4WftQ>D$|)aJgU*6JthBL0 z7ND??Nu4)XMZcPmm)RE{=1otyUErgzlDlv+*W2)4`oLbeU4aXyE`02%`q-EM@x-~? zKudO#h|!8dN0T5NvZ#D0$?R?xk8}~T&-D5U(1chnD7f%Rquh{Qj;zfa| z1=kINq>!Xe`DU?SY<#E(z{-0jjA zAsJCXXsP7iS#^J2YKR$#9q6_$YKlN3|BCqrUAo{xm&or0qQXqjyABp+g1gwkop?mT znb@t#>{>W+Z0*d=k0&f~?Lasbj|GCC&m&O1L{Ytd+>1rrE9N(y>Tmi+O{bNAD;)hU zUI1HVh{s64s(vd4$KoA;Cfgz`EEay5iz=h76f?7+p8RSMHsBmPN%mL&^YMXoF^w4X zPS;iM8%Q7)$0uQ3Z8<#VjldrCJz{n6-v=G}ug~^xKKUc|gp4_5lh}I~)5yiXioLG? z3YXKr{z|xrTUf-6ZHc|+<4lb3?@nY~^nyS5Ar@b&`kpGk`^XiDS~5kj5w-|xQF;Pa zYc#XKfKtW}7#?DW)#!ys`RMu}cWF6wjr%lv3uW>ZerCOKI@CbSD(upqZQ4zT>t0P8 zn=$b3y11P#lc&%XWg2;KsBHg-y;T;RxcOfXX1gOh+at@5J~(6=M$+6Q3gkmh3N@`IoKyN|uNm#%o|OJLvW&-tGv!pCOsp1!oH|LxIO zp?>%eL*0|Sv7nJWW#M-dbC0s*q6v?!58EEfx`r5E=;pP3e0uyvPw@A?2Xe-~wR%^t zma^a2Wj6?&UTiHrFXHXJp*whWIMQ3gSzFq^9hx}fPBl-o&G_y-?VD_dM%Js|`c-$X3#ypC1p4&)>Q^-@hT;$_p{pzQMiOue-G} zXbbz0ZE(Yc>#NZ*IWovAjO3#-6i>{22QHJAG!GZ&TTQvv?4$1TlJzT6bS{z++J~0} zpVUp4+#g~;3^-q7UJtNV4Q09o`oW|l*}b|}mF(t5UG1`X?{fbtz&TSoHw^c%Di(H^ z$8_e7-)V00K2ec;@Ac8XCT`tPg?9GbQG3e|^&OM9fn+s$U~B5sqs|{6Ph@E@2tEed z`N$BVu?`n6$ll(!4BpqS+4cCI@pOBeiRT0>7i%<{kS6J6ym75Ca$Nped2GucczHy9 z@W>Tk+l_ijAD&6NfsfNzv3f4gUFS+L*(*z);@%uq=ms}-5_jHO;rKcKkV}(0cGahS zO#9Z0gXMu$bBxl+s22DhHqTME{2JT9XyRLsg7(YUH_8!Dj`PM*ZO586YP^$$u!Kp7 zu&j2U-LpT@H|=wDa`WsBHm+Sxp)`lK*}hy(ZFhsbUspvAtb?)67Ay6V-p0n;UY^*p z?@|bT`B%G?g47$9_NS&CoO@*9hBTkmY0rG-E%W@{m3@2vWVp0fm^I(`szqHITkdJ_ z7Y6BHd)>HjtXo;^MP1d&oqG&=HyDRIRt|iv7QJPOE03h&b3kD5a?kPGU-w4mILiKw zK;4`72WM;b;k9IfE~*_ZO)iy>E-TvNEcuyl`O&9Mw%reyG`hDQaf!Np%(F;R?T~fF z$@Z;nGJctB;iZ0*l!loDQ3Wuj!MHCSXSvFMd&wRE@Dh8@ybp`;M{KC)Smi4&sk&}U zd8(-*EdrIUC``H$b-Y*YXxZ0AtmK^--uTg^V_PD-K7AcA{QIe6BE|0Tslg3xMIu}d z1N!&#(Vb-B%I2WduOV&v^>8C#GvBy=?NT^VLtYrm*s&#^M=b?tGS%tBJ$yRopN0_F zTyjX;+F5NDdt9ti4yJA3h4#%|2JUb1h~pzTe@d!c2g!MRp)tmJ)Lt}^VBEMX>vq)esm~z!n$}0zpB^8fjsg zD}^u{WqV`ctV8nb$)?><99ZIE6!c_NoUK;Pl-u0sbFj39;pxas#gG11{COq!ZLV%-CL18EpndrX ztWc#X)-d7VBB&ii0l^c(473#XjFa{3lTXd0z%xsRJ=En#Vn<9yzU3ravlTU(8HQL6 z;~w>!s*BD8C*|+yHuXz8^zC80t=1ek33NHB*9VAF;M|BiOS0UwVU>1#Gcst0Lq)3I zHMU>b_CPhFOOvxDzrK1RCpI?KtA zH@%|rcjJ-WmY4norwl7TNA&cjLyZ)r$ye#BYngd>a*@Oyp$zY2n!1I3J6!4kUQYrW zVI6Dmh`=zu_ZsWvsv(T(o~q2beeK|T#6R={i;h<1F1?f>G^H_Dl%6KqFJlJ%A zjo@pANjEHex)^w&LP{MKCn*dQOA(BUmWDzv%~_WqOv!c&!?yFE`1-Njd1g*EM_jmN z&)Y(-Mv;c3c#B{5oymOK$i8y-@HpHoOhP8&&Mn>0g0EM)r}D1*G??mt|8Vi=!u@-{ z<{r_smaWD`aQ-@j(98#~>{P61@c!8;G2$-wX>JwfkF zeOrk~%4;LXS}Wu@!hLjYY=oxs=$Q2XkR;OBF&;WD>SS-@4V5G7ydw9>B9@R zTX%!*owf{>y$#yEy{#^<>+^oaV9N=+B$IC3-AgYwyKde4efMj8edyN}LYvi$8Z{=V z2BJfzg~;wH0X_Kq?o#r^yNc_jd3z5UI5Qn}r8vPyl&;7z7NMpN9~<`}6UDMAa8K(R zm{#eZZ|<3?6KY4Yl1D>iI@p%moPMBOdxYvrsx8h2fhk#j*6fb9W+>+=UYE!-H&ovo z#3v9-5xFwl^uH_i64)uaDu>XL^ErSDt%x+-ph~ zdfa{R{l!Mb*}GqZSQkI+0)4ujv;z_E%kbsX@vhdlLD10-F&kHmq(Y8qmK}#_-d9?& zU9Pl~ujxpZ2_dwWrNC4)v?7rRpJm7qij3DdP*zGECZ~30f;VHiNI!akJ@OLE=FmD~ zznnxH1@6xhw;>|G_`*YcVIG-)`T{d+q^Q|BMzN_%>lyy6duUUPb8LFgbA~?%8iPks zGmX~R{cG}=@8xwdI_UWhmN49+vNfUqhi|b}IWRP^LC#G1ev{y_S;%v*9GaR>vStYy+4ydwJ1sB zDo-$74g_G%Z)OW=Ns5-EtI#+D)>0#WfCus1pbBsux>MpgM)4J7$mN?Z-x^4^n zU~@-n>5%Y%@ull*uE{|EMFqs2k2h_l#_X`XLf%g9_nqT=*cdXW7fx};ij zSX+%Ph;cZLabh;zay`RVC*9BDYBG(kEtjj|o7$ZO*78l&77(^)GRJy$BOmWpBBlK;YwvK>CiiwYw) zGTeyJLX%4sX_st3Y3;nSz;zgq)A8@I@vqxEUk;o9`!Lxz-JWTX7-r7N9Of-6I{2j$ znjYx000heLC#Sg+8Gb+xMo=Fi0E$p)_5?bG3ExYDx-#kN)Km^zvpsV{Uyg2!gmBh( z&rR><2u1)6YP+7XFH`)jNjk2#$3C;QRLL#Aq|MaorL(!e^j6x;%-R|;cHB7aS*UydS= zmo-jqAP*%dd+5M^_Dmkf-wN}EM-UlVAhi#t$P(!fqGFYu<*ueL`uGsUeV8zkO<@%O zK@_2XW!+{^57^un8%lf-;me32i`@{wyUVVaSbATAy4m`8$5XuLc@GPI+>X~FbwX>l zFQzDrrYNkZgfC7TUdUBFnI1Hn?uXA={F|}kG^TRLB4XUx+zVhgEr@Yu<4CsNf$zJC zG)U%HO^9Opxn|Ve9&!>O zjy>`v0@$rChosybKPtD~mrSG%YPC-rEvIhNqi^SPljYLfDG-bGRMjTBzrd~PG%V6$ zlsyXH$0YA^rHw0Npnx5vf;fO^1&$6!X*eb=c{b3T2r9*7`4&TX=R%)k1w+ERc+pv~I zROW{Ga#m?ziV{j0R+tSJl#7z_7{^f>wuhEH3hElAq2zKfJs<)X5R>%CB+I=ibl*B@ zFRo?LYq*-B)lq>VGKAs1p4!}gnOIZT<_lkvPn&iYf6;)O!>7MwA`das!^u!>_VoT$ zXU?+oAsWQS;w?c08s(=31P|>YX}Xc2mQ|_|mA7`m+15|rZhIH1{WJ9W3{S!z+>@0e z#LK~sXX^Vi*kf)C)07;2IfhS`XAO0)}nN+jA+^wjZDO z&%aHFzj`FobhJ~X$2i4b!0?j^nH#L=@LlR;whb??gt4+BLH$%3BWgEBXt4+_+V(h* z6?WU=aS#n^)7+vz3MLU@z*|eHg}8q>UH!j!WTVwA%^p6%Eq1<#I zGHg{1iU*0bgWk8i2XPX<{#L<+*wU{v?jS{=moJ2b#HIfRdc>t;J#X^ExKL!-HoX9R z{#M3kq$lvP?A!z)&p=2`Y3|%K_2%Ne32#u+(iOK;b(d4^M`2A`m)7;)sGA@a4qQz5*K# zA0{_X>Zb8SzRNX0Am;3d;|DOAEbrvr7`{v~CXqfG4;7rgIVz8>)$4& z;Hn#d)GqTAz!u8WO~Z3PcJ6J*Ki+eEUg*7?y3==F=h8{n1xBDe)Y}V66)Yylrjd|P zdtrw7dd9EA@$F5kyM>65UxAXxdQLd0?~Sz8JP*8kjcD~LnNw|7f$U(j#&O?b7TeO5 zT4lG`X^3)2*GX3mR}5l8oJZHfT(|M;VdmsX`(^rNF4PAdb;)6ade; z#%7)84(u2Rl=oY#%QasTzQRVGmc~@9o&R8aJBW%hPESA3RH`+eDwin3AwUnSh-@@Q zb*|G^BR1rjVAq@WdT%dA)Sip3z3~O{leQtz!pc5I0d{>(`uM6HA-{@b9lgedA8m;) z1~IO{7?ZB z7H-O!D38al`m{u^v}?IDb;BFm<{BnS)Q#b_ax>ST+l7i{NGQvETINzlQse&I3P(*f zLHak#zr8tiopc z@JsvEOXfY^^B)Mi5DaN#7xaIQX=+;OEkmOWb9}|X==9qCDaeR=@d<_cE{vq z2X@B;Yex@lVKr9MeLKzTRzMi!;kAhn4)5eEJMi|pcXmNrk|CM>Iwms?j>g}_)N&Wi z2cW`0BDtmy_jAB;r)%6uS%JINisPWJY-M~=lvU8q_XQcA=Fc}nD^J%Qb(B)Pp!9o! zYx@@+L3wpF<9 zons`NS#yy;&|Cb*&Wqh}FxTmq$fznr7o4S4?DI`*TeU^jxL*5A;Y89sY^ZM~-}RJ2 z9B7B+6O*FwfN{H$%^g|ljWg}KM?1Nx<2n^dspAnp+90pR4J>u?)uP6gahGU=GN!v{Ou7u!`4S9TwaL) zmWcrUHvRb|z|M51qw#jVX<=-#O*kmi4zN8e=8!^m(Hji$LFwbYR*X6k?>DR1vM%Io8_PC@(v z-((K8l!$X;c7#%OivkiVQ!nU>BDG$Js z+J6xmKEK4|nVsbO)OsPnaZWAbc;wCNoUAyWIZBn^J3@*@1=W}DIv28 zEx(dN<8n_eAsjV}-J=S1VEco~f}^EVHcQMq^Eue8kt_FHho#xf-P&4N*+TnGM{^;W zXBZfabpGTWo)epbEk!uL$1Q;+OXm=_gcL-kJvP*0NMVp&OZ4uz`t0#;^S$AotC^2L zXkQXytJHQ6woc&{$;BG(eK|R4DPKb3sois9w$bLIs{J}xk!Z}sNJRKQnNByPdZAsh z8SY+j_3+!F{~(sj4IZp)3389VAHBO1dj ze0ku@s!5{;5p_t)Os#mW4$P1goZ+$g7Rva8K$=8fZzuT-Q1$O`o#dr`L#E$YIgda4NckFh_Ew%Kj;1o=t+>qQTz9MxmaGa%;y|aGW z`Px4jOVN~3upVAS(jz#!Jz=+{Pka8E_0>wFbE6gtYw(tMj8$fNVBC`b^}tUd2{fX_ zX%jg&%wf?xh0sqFRfqAW7>@=qao5)pt-fPNjb(3?P9JXdLHmn_;FD=i=G{}xpJ{K* zQkcV$PO20>6jPpp4J%ct zA7L|8?W1@MThrP+4O>?YDB5!MdsEiLwesTB?s55OznVAjKa-`+O?F@Wwm>J zVD?lbqmle!R45=MUfGQDy?N{Y<+9elePBM(!)2EJ9{0XLXt871$f?iLG z*c1P4a)-s#HSY(5@~B^oCUybJ8S6l3CJ3E0zX;OwdukS@lt$%81ec6GzN_|mn%?2e zeo2UKDHkq-7RLEm{?>IlLfTs^pYIGE77dKA;r`AKEs_xNn=7FWohdw}aH!gi&i=wW zeD~DVAZ*)P|M6)%($g`D)B}0gPz~o6HT(ELjqQj|@BJR*9D7r+B%2~@ep1B$I9Wro zvwqmzSU}P@bf(w^>7mKiB#_#sU zX+ou~_h0nw!t5tGi1mWTO5uy!@Z<2s#&wmJ zSe6fz_Fb1GPO`^uf^dAU)QHQ=YUW1`6PSPNhKT!tq89jXA!008d+C0Dq+?8xgT^M<*aAYV@c25Qf_z`2a^4q&r8%-da)ATl7Q+g7KN%e^ z*?@81btazbV*rddHVx!F)q!p2dwRzsty7xVjZ*sv3fImx05ISI>YsVZ8z{Bkwo{- zl-U*wrUcIH*c>EqMR=cU%#Vkj7+$o~A>n8uQoLb1c8ZdchzJ%6lH(c`WjEBK{L*kQv~JZJ-W|4w^Dxzb zR`e+otla~SggTnX4;g9Fcd(yVvF~g8suGCvnx)|P%_zMkmoI@;)Mmf!@$&!$*ONna z#MSNnvLrLia+D)I^+*XM!*JYeM>5EG_HCoDgEHa4<2#{+IOi9hqFP@0+s80v3^=82w6783i~qQW4~!3$Vi_hn>D)B6;X⁡HY zh~k2itS?e&*}lbW@Wqmg33N!C#V5r$n#Y3mmQvO0LzHP+U)So79zQy@zC8&RT#`jnmhV) zAjSJW&jxCja%IF5PF~741`RboblC0$iS!VSbbV7J5Yk z1gWODnHPr(;7cC#Yg>?%No51AAz)D`^a9}E2hR;?#h0dPS~;2!YxGMUbYsCo*wlbQ zk>I`e_ls-utY0Y722_>@wXu%dS>PQ|O;gIUK|I~m7d)mr$WRBcb99^qNj%9u%h}05 zpdIO2B<9Hoe9fv1cF>l&pLP`WD4gD+Z?VBPB?7ZD=$eiH-}`g zN9V1b@P4mUJ`LP6jF4CQ;89pj6L2% z1V^Dkm@j}q0Qq?Peso5<$Nt;fj~zDqbgAg4)WOSHySFQ zgtVZEFkc+M6B*#SKk(P#j4G<71n^2ZR_`Gsc&)em^!a?ncIbo0RnT_2vFp%IS4U#D zgBD=Wxz`saza$Q#ak)dL710`7Llmr&G87`IULSoi1+_45cZV|lWhBntaL)cqysu$+ z!eafX;d;;LnXEz6iqCdB?@SV0EUf8+);yI@RX?V0YIkIj%SQ9kZx!d_)l@TO@r4G#bvS3blXDchG z8B=1z!dJ$Yh_L{@GtJSm2$0SYb00@DpChXHmK*~j{1$QM-;$wk#+RxrT~n~8)YrHm zF$|^LJEnZ3P-)BBP zAd7bK+oGq_24r`}$y_l;dUMZFv-N2y1OIg76K74wQY22Tg?(bnzcS9OAz5ObV!ZDg z1rA_#7b_zkD(;bfaz-cc4M+XsQo%Mv;6KNm^&^-&H_dS0%wMq1M82>Sf(hl9jiK z&x_!VgCBL@nwZdMFG9a*xWEDr(2eB4P^`14_V;?F4zq}kjD}D}S(kGpM~y{o>>$M~ zy2G;iyZPaiem7WCtfTp+gRIU7&8v2Y&9e@b8#I*88#0CNef)&kCkJIGuEFhC$1J5<`izv@>?lH{JbJO)km4=QyH?n;Ka0N&QG?EZ~sj zz7r;gZgmAld;Pz(cOO7|r~ZGmw{|#3n7cUvZwMW$?y2|F7#wb(EEA9W%UUHqNvfPrZce8It)PJ=1DZ#m7;fH&7 z+gu0rv5B?S!R!B{y$}7mJ}=x(_`aHFwRGRLH01Yxw3j$s?dSX2)ZdpZDOkP40IrUci zoKmkt#hrhD6LS&+PuAN}zsAQgUeTac(&@2(vZRBKd>yzy?a7q}I>z2=@0Fzf-bMI` zgT0quXV_^mR2ZA~GFRz_cMmxw5W1H`+ znr6iIAfJ_8@-Q!B9uwlP%*K)pf;IAO*YLdjy=TTW&Ok&m7GqVUrw;izDH{(%H#uKq3`(!lw=S>t{D$WkCBRY7 z{W2bd1HHoRlbi%3Ma55R0jInZuixc=W710wD$lIh6>qba$k0zV_#PMrH~!|J^?~($ zOn;=!Wa1mTQ{aPp*X_jFp`9mtX7B7KdCXr_E!644!SlsOgqBKEV%~q-emo05;J@|| zX%=W$9guLBEaM05E#O1_JbsZbkE4IRpau>6l5&0^JjR^cruxG9`5D>zvyR6)49Eed zduzlOVDD%V&k_zDFL@bLx7s{-{XHp$Q=%Sk;gn^hxnW-zJy!d!&GEp>$F1iR=S0ag zl|EP3D=J~0zeR`XxFYG7e*_+PUw(V6C1&jWW{_T=So&VCjfu02b=&-DC;#ZI6aP6m z(fyIIV_2rRY?9tId(FtFq2GPx!smyVi`F-{{^VUd@+#xz)|LUM|IZD6%VC+K`oivq zUk{2ET-{o~Pb#`|Jh2a~Bvv@Mt-Fht8j!HyaFN*}G!xL(YaU70vJK9EcBk4|fRk)H$ru7$D&U8Dp(2|A z%g)~KR_#vhPZ@Qw@Q&9IG8s(c)$2))J_o3KO`+qPb;nBgBNdgW&2=&xFIkf62s?G% z?%LPb><&SCkzl(yfx(!tnYwM#V2;VjZ^h6tupYwoIyqay9~~_wb<}b!TWYOHKF$^W z7O}@(f$jT6Ue;d0N9wnfh=okpnAH0orpAxi&|H zG__|sr#zYLtgA?oJyPS5lZWz+F|U$F6I%v_*D8?4YQE(T;vdJx65+vFvKu~$rsgfh zfv>BPy4eS&-S|IV?7+BV-CAi^T#BSP6&lvyrp<#ze5YWR^ouugx0qgeSFsli>?5Vx zO7UJbCJp|9D|*|fTT}@qS~?A=M4tThGjD#J4~ulwp_6DrSZPvZYd2L z=jp2_O*}J9*RJ`5v&?UC72*m%?I#vQ?d@aRWat>R?Jf!zCxN?y_eyI#PQ7NY9=gA7 zP&(%MgF!L;c*~MktoE(B6|&R2XZ;sFO9BXJPi274LA$gd;g7XdPnzBr{Z`<&jOkdA zCFLzhYdAYy4f=$r>JEC^ap1{&DR=*ZX<_>c=4M{=`VH3X=+D?I>;p$+X8T6dM9-iC zmcce1HcGtz&F6+#1AB{xczcHmjoDl}|G-3`SbNZ5ZXEjZKXw1dKQ6sn zT_U-^3r?6adAZ8Ij=2z^2Xa|SGc4MvnVrSE1}#Q8-9rm24%p#@~79zjmnP^BA&?cD-u(ke<`MjcIZUefa2sol90 zG|(^m&nPNuhmqc;(w%QZ=cNe?O9yp5gb~gcj+>^Wx@TUU(?59cu=`EGp6F^@|-|k6T!TJ$X@nGG#rm6m|Dt{$mwl zzv|tu7qs_SUcoTb^Q}xOcgZ)*z85zaS62TK^H(PJ_QqPnCN4vEbOzO5JSEgviz-;} z*s9r~I7>l}Na(o#`f|klbd4yD=_p^=_Vn+?nkSGA2N{oj=i8R0)iSI1%>El}^?*zN z)OK5t9S6Y|at38Ph%jxvsZ9Ij8m#W4Kf)D+_ZPhED+A+mAx~>=o=>qj`#GrB;c=@!8opYy7LvM>1=yD7kRLkbEIpab0h3a)_V1tOr8WK=QH9i|z{ z_Vp=LwWOJl?b`G}Lk{dT5mgPiTN?VgEQSj(Tmb+`u|xmmYq2~EnnDaTH1~Y(k`ghX zHsBKT&Gh04k+VVy1oKwyGXQ{4CYJZVY%Y-Boxo#Gvd_Jn zIqMv6V!JG}mkr%3fa%^>cL4>)uE8i2H|=k_0S6^sBmOI-meBs|US1|)xB{^*B0X?j z?14aR0*_4;GGU(&?WM%RScQxe#;OOOhQ`@vjG3Qx7Q~=mGXU&FBcrsNE|iioJ85Vx z6KhHZ2G22!SlEp0McofjDm5$2_^^Uc*cln8xPsFZ0nGiU?up?Pb+znp5VC~$A4B$$ z!wdju7KGulv4B2mCtv_vTnB;=$))+Rq4aAxcEMqg0cr^+!I5Mmxx^SnO4$B}(fE0f zT+=)7Sj;R6NY;%IF&qN=0vFZ5MhvYd7Fry0H#6Kkns4J3IuI}4+-1N$#q2l)^g<9N zKu8sE(?GSCi0xWLKfjN<&Bg#04Im{zfp-y^GHkN_t(0!!&!e859ys9&)5{BfROFJb zOGb~gl8hhzhtws}sk7k#fhOm1*cUc@F+w7y0Z1OR(R3Xg4D_;fcAaYhsqFtq?K zCPRS>C#Gb`u8tCO;N}TM>ix9JNlV|yb(igf!|aNrkIN+)&0Rd7aQ=7?JXRp))>|ax z7x`=e`3+1v4PC)X?E>NQsAwP$_yhR*kci<4Fnt6}2?%+fjELr|s)#7>XCvI@F|BNb zodA6NoQWevz3u+_Ju}*esaJN{2cH{NjA0{~{K9PVe>jlMMwb#%Z9Szzerd&GDvv}5 zs-P8st!gg%WXdwuBk6SiG0w5Hsl86jvt6Yyub1u;H41-Lp zU?+(92h8f8IYSB?0dVViB&Mk;wS-ooey;Qe8C3!*4(!1KY!OID(}257{7V3(Zo+4# zu2+H*Dwu?tQapBuP&;UmBg1pl#19PzE=j;BSGw27B*hFM4 zzktoGDFxghnbiowcE*+hW!p(#%rpo$#?32cAsGTOz+B%TU|MN4jrgi!d=*eRy$nKK zCf5W|vHqEj)bn*CtV=h5fqP1{y#NN#E@(mZpRzhb`=q^Vh1*3g?*A`HjBH?|*+BY} z`5zRn5(*j`0ag!WkpVl+MYRf02AOD}=6ivN1REm(stA;gTVre5iN&f`s0(C7EC9cm zm;kv}9tBHX&F=04xH%RGAh+^STo9dl{@S^gYlgu^-mkCei4@i8Ad1Q8$*87kb`vcD z)gTb#lF>zdhzf4ueyf_Q7G(7w)Py{SEf8xIwx7h}=#xOKugY*&=BI zF$U;HHt0slA{wX&FQG9&$9O`3X{DgGEzq<~w1(BqcK6m>{vH0pgqydb>R>fD|Nb$l zEIxlxSE3^2WGV`wh^i@#LRSIYTp)Itz`4DM>1AQ=Eu#1Mp`cU9JOQVHS+DU|4CvT$ zh=q-8w4N)gpGI5zb3<^xb&^8cnSHY_yJL*sp;IINXidicuk5!qv1l?Pkx(Jj2A*^! zZN0KlfO)rp$yEg8K02G#wWxD}5m-`A8= zXZ2U?^k1<#%B>FZeDwkQKuK6Qq4Xr6)A7g@0;__Hsu5K7Z;17=Fufp*`Yucf5gGi4 zvlxXeW;Srx6|z?Nsa^!o_x57L+u3CuRyP-gIUUW>b+I{pa4M~>HFHED1~iUWFt<6J zTT*L~6TRmmx&LwglU!s47ybOVSP34zHvrvEL{|fl8{b~|hg0;o8Q5cZtdD)T6zmWYjm$xd1>&#I50m)` zSxhT)2pql4X1`lSD+_h;8Bx7`<9!uGjK2>3QFH65UAM-_tpV19OF7qqVrU^Tbpwm& zMD8~0l}@v(t;hn%4VUVeK!t}C{KHsmr-A5wg6K1n=(AYdQv&ur9-Rxyq%}2F3B-oZ zJwQM2^bBY~XE$dj)no@2chOp@+32m=0p22(xSS2_T9mYnl_%9Dtd0c*P6lmamkofz zGPX}3)=Q)dfeiuz4#+@1Ce?kj#^eEgdp1YNf24>(imi{AOo_oS@c*#HehWl_2?!v< zy0s_^)uiB6!H+&d4VQ9~e%sy>>7f0%8J>0Qho;bNg&xC2 z6K0`b6Kj~s6@(`lSkw>}m16|20NqvnglyhKpX@?Q+BGTKQ-J_mBl778F+cIu6aAiH z(|vOpPIJIY1&de15EoQ88$Hd$EVg2RELQ%HK*#uE#Hp)x`ElR;18V!{d1nQ{RRX)z zC82CYV(2qTOw}PYYSyj}yo~y!f$AnBsl*4W`_N}jp;a>xY&Lofi;n!0JoLW>6BEDl6gD4D;1u_S7tAp`S~>yWrJ0$i^sNqyk3mv=O%H12ft-_5QtbXu{HQ zP3-Z90{%|3Vv*1K{@yPlB0I6Di5I|!AKlFYj>~jp%pka}sDW2$kk47A4^nhDGvdd4 zj2wD590tr1UP-mQdZ~$-2PAc7wp!PXdNQn!jG3X(`haa66y&VW&ARX$wK@HPM-3O- z1dLk*{;~viSOQ$ulKGUt3iZv-!&&YOg1U+9Y(>i4tZZyW&tPA*QeV`w6ROmv^^urP za{Vk~Zgi`MPfWg09Mdyw9s=kC(GPEl*=HKvFveLg(AvZ3GS}0AW38ng~ai zdGlRl@g)$kyv>ZR-deVz-_LJ9Am}zPQ{&25E%j46ZHW5QBblb2y&p3fZV&zC8%D_a7mnJ|Ag zj2<>2{_JMuvj<*u47yPo+)a0%Xm#hiJFT7*~CVeh`) zz1!Y{4(i=l-~GUDc?BTx;#^ebHtOFt3fPHppEad$d+O=dN1$;};HLro@e+IP+zmSx zH%%mj1Lf6*1#Afzas>ie-;HHp5!fG4Q<@{-*X}W-2iZQ*7!N+K*bZ5j8RWlmD{5K%ec844Q%Ra>r)-GXD#W z-w^gz$^0u^U<*joaTVmp>mT{czqo`=+P84#)%w?s|G3ChF-i578bcr#giwR?b+YF1 zk*v}KjA^OEbo^IY-He%Py8_V&ug<{EuINFf$BP|d`2F_sM$Hm>;qyNJv{I+~yAj;h zf9>f98l11q$L~QT+&0P8R@u^4Wp3|W>z%G0-iKU2DM}=>q>=!~_?cF~-h~~55eIx* zz+|!N)AcFSB4sG_ed8+csODEz5w{>129TzZOsOjsG zX;h#zSw3`XVAt#HhnS7W*GyCQq&^&Ja=o{!UfqtG*0Jfg%)P>B@M^ahtmXM$H*I?4 zIxGzAi=pRjoP^H^X8xt?PRQ(AlbcI+9i@0s;)D`mZ9S9P2vA>a0k|;bonQtc% zwsv4fmv^losM1KYGlUhLX88;lSIPOGyAUi9T5N_ejPOuPH+X%S*Lmbc$82zUWax^v zq;#a*XQgZLp#64=R|D^iU9bNemi{p|AK9Q$JX&pkt(Sz%`cg56)TkQRPIc6I&Roqo z^b5b1pLiHoCv-2ZO}!#u16S1f%wEs^-m@!J*&c;4k{2YT&RB^*_qi}%RPGzL1XB(_vCT&X?P(K0 z*E-j`L$0@bgO!ylx~hddV`dR+iDdtcC#-P*D%MJz3g>3)jW_ZNvDH+e#qO}P`&(nL z?+gjLg^r~ZQz)ft0wlsRB=Tqrh?boQq`28l4_~hQuY=ZXT8t0KlnG7iPxop?zzQsI zkBRMeFmWsWbPtEGZjb9O;2J_4Gn5oxIri!)t(;K1V^e%@r}5{rN6{AsuxcDtDi4@I zp(dWL?>YbG2ICIgFga;MCV0VwsH{{2&F;&%7s z*u5UG6Fmx1Ko?LxLxS7*lEf8D!VFbwa!)2luV1%+z3m)c@p|UPd@l(0$xAalVqpLm zzeQ8o1@BvC!Ze6H2nVw%!L8Dfb=_xekCXVh`V+*`%$s=_kDnWXT~A!z$FKL~#tx=v ztyvo!7UYiv0>>glFeE-z2(%jj>iKX2n*vu-5$3_N@vs95wFQcM0b+F^SP?zunymS7 zIE|MkMZlHVUmg&tBaTvy`_U5C0b)!uE8^aFl<&*{kl_}puL01pZS%q8`{lhe-vsWz zip2Ov4Pf`8>E2oLQmYHF1A9XVtHM))&J|EALUQ+H+>F8#mi6Wx?V7ONL4EaTgoCqZ zj~pT_MdNZ6>fv&BREOY^4L}~Q{)##}Dhnaq690S-z7O={PO3YkemaAgW}pO79!aa# zHVMmeEpfpm1Qt6NW1*iB!w&u2wK0)TzhJli)d*E{=*b)i>L^D+e3drqZ*bu#SS^c>1 zTZE_;nLfixBU*n}paM;DdK031uHUAb4Aq=}8FsjC1UAs@Cs2&HO6u(@iT48}YVlb? zKNld7f{@=-49j$gb>3eN%sn#r!j#RS6VS`>4mQHK#|0B&8z5efpS4i?iV}0F%`fh7 zv6s>@k0e`2SeNB-9VjC9QjbGx>MJ&F0`RV93JYtm|I<)^l#~-g;uVP)<$+%DZ*RPN zuE9cbP0R=l_M2wX-wTs|$n-3|#HXDga0)uAJ{lL^oZ%GWqh$+7K6*Q?tWJa5TKRGEwL z9SoH(z+1?VQS)^7WSdyqmO(lQ=Ly~Narbkg9dDu(?GC=+#IS%g72uea%y{{>hJqoZ zuUtZjD|mtyOq-3!xbS3o_3pN+#aVM4I;mhR%+j3AhD1hwH}Ti?$B;J%g!g9Y%ikbK zmxUZ)A#GN{TFWwqJHxBwD2u8n@pmbFZz&(n)8sdkEP6*}SSyQ%lLHzRW^k0|b~g_- zEq_9qZJXuY&wHLrSrwn4LJw#p<2toh&*D{QH}xM$l9U6)=;KzJmCFl-c`??#D~<1U zGRMXA@f|G@>on6#ww`-~l1r2k!U+%$bPEfTtyFc6{pE1;?$Uho#u(0#+^+b1NyY4M zsynznh=ljQ(H%NOjrfLfq{xXM*yAHU6H8Il;IUsAJ8}HftH6rUBu%a%+0S?x=~?J6 z*a7D=$j70))4+m#cm_Qmmo?7z7kJYzx}Cq$r=_x`{F-fd?V8y{r~>WmWExESq9mG| zc(x@l-RYKYK2N5n$#dZ$m9bkApVTWnMV0a^b#2unUGx2opH_Z~r_1{A=U)xb8d(@b znS*$){UFZw?miL;ymIK;q{#-CODxQvKXm5_<^d#CP_Tkk-WHT*EU zJHt9x`qQl)UkOgeubPf)vnU{cLBcMdQkSq#C7uVl7@&SQ_pb+c-i$vns+@HB&rADl z@VVZ!VU0h;w3I8M;#)%4i+#1{Y99QQaTx7?_;xqp=#7%({Uy(1D&x5lD(i z9uEsxfS%lJ%A1vvH0lFLP-T^rNOJn9x%kt?TBjuyX(Pqw?Hx{;51E6y7T*lJnVA-@ zs=(f@vkQ#Sk`!Zj5|oYLn*j-vDzB53Qpokbtq>y+O@$rc3R{XENq*XQo`^KEqoLO z^|m#oo=wY2>j|VXByju0ZqN^H(iG!)Uj0dRGJYs5H{dELIPXP-ts25>9xBrZmS_WK zK91zk>SEx0XGT->x{_t^;7oRUC_8;cwQ@BY=C1-J&F}(atFj#c!vqf;Y|-q>QPVcA zu|N*Tmza@8>9P5;qd6Z*Df_X|3V>GLPW9ZRb4|BX1KId9aK<4+yyGa;B@JSOuT`Ew z+=6Q0I;d$G80&I90>C3*) zIGZwB+pLt{R@0cGgNIZ^F%nf6iScx!nUpXrH1Lvs)hPJFUp{S;y;!@XMdO$|QO1@f z6tR`E#Matgy60+$?R+9XcX{}hrwR8o#f0*e5wa=af*t=}I^M4WjrpFEy`8t%2t7%F zh2dq7l_aZpIvTO*h#$~^G)6I@O1wW!%1$;s(Bb*22H(+v`?n^3*G?=Hm^=SX{ZyX8 zQUyy#B?oQ8&c=@f*}{NDO%{zb1M;Au3G$h0hDuoq!cro@C>f4nR&7Hquy^W=EiK|9 zkSs=wM1~3zSvQnUBs)PmC5b?TY6kV(hS++_Fyn#uNn106`_81e&PaBCASKQrukOH3 zQ?qW_V;^lpM&p?`d}dEF8Ihx~yb=uuDiAeIxe^Syf?X6mpfNH^WUB;q#DA>ePPt8w zsH^_Ua!}p1E}$LZZWlUKZ0D%ACM9x`#6UFXKYXXLMF04j@3cD__+sz-ISMpn#x9@Q zV7ex6LH*yP>KW)II@metQ5c2Zx{wlX3pH-#)!I&#+~xy1C;)>cD<-+jBNVpzzNT3W zoHQ5Njvo0@u^t=YGT`GfyEp9pcS$1}<7*1V+RrL&mT4?&U)V4n6JG zFp6_OraH$T|BtV%4YDjnJT78*=pUc&mg?~uIn91VB-Z&^+u>SL*%6XtAa>=XV@5%hBzIb;p8h6pbN}M)9Y{X5OM4KJ?_Pg0 z{vOD9e3Nke&QAsCKDsfPZdL->+sus~^YVYZ=uU=|t`2H)=s(|S)@b$}-llN@9i!IQ z*FhyEdFhF7Yt~HFuvdj{Ldzv~Cu? z1~$~S%;$V$C5aJvPHw@jw`x`py}zyJZzByV2v6P3GxS}Hty}3_K&M7yGR#1?5Am-btXb!b%n~K^_H5oye9(H#-#L?qCPiv$5f4}LoFe#c2o1TB_XW0B;Y+l{C zm{J9^YSlNK;U#Sq+Sy9F;Nf;V^pO$>(GaX~HrbSkHPv4FSqd@idiJwb^w}$DSY!H0 z;2bgM`QZg#i&lu@D;T^cQ&dOw*1j7`^nrJ;mQ)zio=r&-Bp&G~?`uTZ>-qF=gFw!N zyyDBqxCuLNDUv}({)7s7{D4+(^72h8q<~<2yAz}+9x+fLKP$v^gDSAicXiNb0?JfPQKpozrRa;GKLWkIMO5`ax0olc= zHy-ee=Ow}0$I@>9tV+T4dfaP!PoV*Uw#{~oSuux>Bqga}BS@QQH_*n;+=#K+Mj-5c zkZ8DyZt7#t2C%w7mqrj>T3-^G;49BO?WJESuZrD2Jbv$v zB=0ke#x88uk=P~fnPsTad#J6U)=&}ut1EjGn_CdH@3?4+j} zg~`w|>`Wws=99sOpx5)w5O1pUix=2aR>W1?+!}DKytbAWJ zfcY)(>W7ZLTXos!l3$g`&`?Qn?()TEC#$kDJTB3aJv^_)pWcioSCqum#<#c=p@ySi zEgqVIidf$+pEUs@wm?0+x5~Xv{BqzC*evJ6b;_67xU=l348{rM>CFPl0?M98UhN(c~yvSMM60%3qVD4#yh@xA>+pBAF*Fl8Mb$ z(N(<;`8A{aN0Wb=x207uSl$`m&UzYlCCf*FM|K5`LXcW^cRpV_=~)8xq!^w&PkJ;J zy($6-PD}#K>?6y5+$ShTWTViFzwe%1`E*~G&%yAvCP}btEXjxXsxGZMkpT0e@Um|l zxwgq~d?rVadH5Pjw02a+gU>JeTw0>x;&qP17O5=pix==vubPzSoFR2u3<>)Zz`yY3 z03VX1^}CTzw2m+u>3TRqFJ(;Qg7UW%z}HH6x$liS@>LR5EDEg8TBY_we77qiNvbhE zU&&%|7UK-z6q+XJv!W;CGz@?Nk~x|6Z#0tfUBAZKhXVFPTeBqbD+x>QgW38hm$hI-`H}&%zfjARSK7$e?_|rpsQmFs@>Jfg51wIhW@ibS7GC;M0ksA2`mV{y_c%CKO>B# zQzwu?0;MHp?ENcXClUH-d^ovX(27iYV(=*OR_Ir`kt_*=n2($P9UYZ3Iz7>~;WSKv zB$VnXyp@3^gFtCgBnrqJ%&$AQ;2JV5V|C4gXCipY$0&BaSZCkcAF6H*jtymJf4)6g zs>1ch&JAKDI}*q6f`7L&S#<{OM0?3}?XnjcJ;k!Mf2XyqUF!Gxy(NFIYTbL{g9+C~ z$k%d{xVJ{P4XRe?DWbTJZN82D8T9+j~$pdTU-#P=_Zu2_| zzjJMvV%gQCh5b$aeD6ujk*n7G4tKsZaHML<$c6?Wl~0R*J^j+EsZh>H?Yb=eMd_uD zwuz5Q>ZZ@|7wJJkIJ(Hh?YEDoYnye3W_sDyf8=o;ca{fD`K*d(0{D1r$zZo#Uhm5o z<81<+zqlWOfgMLnPl@4LsZbT+Jga?Fbak5g82P)C@w<`$pXj66N2iPz(Ef0|?-teq zC-gZ57dQV{CqwoU{=0yWl?OzcJ{vDqY~}aQ{Fv7uRv1l$Tw9;ex<4nEsovNnCTqs+ znA6EWz`X^eu3%OF(f#)U=2-bg;J0Zx_#sF>UM#s=`Fg@CaOK$O2ql2c|IBmdCP#OEklZaz}9^;#V&I z)$A&1#IcfEN>LsCGqe^Tc=Eft$_@(~zt#oA6(XqGr^SOt&CvR#J8}-n zmnd@C`SyZ#LJQtx;ebRaFC%XnNH7we{PQJgW|x-J||ZGg4;Xrj;9sZbZ(n zY%oTRij9Q`L%Nfg;wQ+4jOm2qS9Y$K9IFLE)D3w?WDaEHqqL_zy~7MA=KSDFCp|^a zVU9Y|9_vD6yYuYf*VZ!>FS~!w)$K>UVZEH`QZq2Ooys`(Sxnp^=r+5e&d4G)du3eb zVY9|QGy2egnAthUDl3U~)59&(Cfu4U>vIO4vaHXksGG17J`RbGt8)1(OzNV_z?gDu ze|8Lzc69YaB#SA@a4a3Rz#7qATEVG~4GS|HEndOp9xPuNu@yp{ux5R&y^kI8L@(!j z-Q&UdXQf+9~SWG8-9A-P}M6P+w1_%e+ZsB}QdxGh7ryIOt6t()s1SDSv#A$Ku*UdaK_glA4* z6*~Kfkf!-Wsy|&x8)PAzLrgLFXr|lPmCOSMfhySMw9|R7P5t}R4?D^wn_5U))N5nR ze}$%srE|1m%rgB7gT#7f(heF_YiHeB58!U!Fbz;4%ANy@bZ!sp`uL@pUEY8G>FNo2 z%PM?^IsA&xzwnukE~;#7Kf()(?^D9jeSdMkiJi$}G#Q%rC%V}kyTpMkH;QF*6j#rq z+vLr{`Lw&Xs{@jD!fb-;@_N<_2}kPOU+-yWIJ=qSZtU17Z>KXUbVX4`Ox=Frq`MuF zfn*`5dic@5mS;5ysHik^v1jDe!=PlCZoeI0ao+PhNKNJATQttgN423E77}xfuoy0n zS%H?SM#qeZSuoG5EcAe24RKg4&@7X+Q7GEZ99DC5$#9MJ7oFbJ)UO@P3iR|BxJ0m3 zRGU5ccaBG}JJeG3*^8$KnxW+tEa(;D3VB|zi+%O!im4PRMT0HMPcq{%gKy=^k^{Qs z^78F3w;^pe&BU%iCBCVNVuDLr2e^*}Zw;!MXS(3yuvZ_#|G)=eHsUM9lGdSYp#y1$ zH_iB2xD|!htjsfMP|23jsmRw+rJA>rLcerE6vn^j`r!jELhN8C&INKb&l(lOor%Iq zZj8M+jtmcxZOWO+KFYAPXTz@ybXcEZQ5R?JubF^?p9R*bjJi$hEaloMk;4|VgjlOxVT_GFq>&$xA=o>j{UkwM#*bz9_WQ4jQT@_ATe%v6vq~V&kiln@ z{10jH1w!5p%D;!DKb2?|efUqRJkGTtx5Vb|#D9^1-NL0Gk&=xv)HUxVymrQ`i=`A< zYxT0a5+C5&J|8w3|5qq0gge@0Gz^48hJwEcIO6Y^AV+;2iA8FT5 zAfeGpFZ|J#-|k9x{We5NsR~~GJSi01(v_v!g1c@MTa_?srJTm|I^<(qYDwr2@h%RN zEGW-bO+5H=pKx*+Zb%Pj%g~oAS;+;}*!NMPO7F?8_oRNy1h1a(Ay+FWUtUI0D1!>d z+6ar?q(=*PV+*+Z&&tkd{OEws8fS%dlf!7iB2BDewGsb=VG%W=ZJQ&yhGtom%LhN- z?Mv|4m||ih25+OwS>^Bk2)ssIxF-s9M&c`I4GY%;j9x=Ytv!ZWo1aev=S}jH2jU+x zKYSOJJ>;R*W_uXCe>%BtM8UACqKVV{?=xRIk2#?rae*ME^z6K?S`}YtAT8?5N9$fA z+WyJpr6_Z2LUxGTi+lb3!`&%i2`A|q!ctLl-Qvfu|8qAmvG^1HUj%r`#kTX|b$G8# zne31#o%ZEnhVH)s1_nI%c;JMt`M!lo(@;|NE=|XezcUE7`4xd@laJ%Co)kyv7Y=%s z45&nb&9b=!A^j>V2vsqj7K3=!8aK56qZLkr%7bR>L_)yd>^_;<;;l!26!9n#X}a6) z1}uuM8x4597cdo*VhBB}5>lh?kIH3hTjrJsS!^b&0QhbR$|4XhyX1G-CtuFc!VpV# zW$}(h4(dk@YV7v+66BP6WSlfW=M|n)Wa-9V{j9Kqz^e#_i?YG~^gxM|WW?*q{~?i4 z$%1=4>Nn-ImZV|vG=1T$lb@EQJ%;wzG7xLk_ePWIFi54(x(V|gG8Cj`J4E|HV$c+$vO{$RCeL`S~94t+6@_s|}f*B}s3 zZ&OR{@GqO?yC3vBSOy&ASGeDAttw}!N1>UY8`8IxRi;x<#mbsFD_FU%Y3&RcX4%_> z(iVYUb`mTQKda@gU{_qLTg*8?r&*u2)DPt~h_KMvP2w$4aC)YowL<3wNa)xa>mMrz zE`yOO)c*=z{VIA2Nzde{iJ+x}#OwV&N#wG{Q^Jbw9_ues+{6JebX(30f70BaS3B#a zX&^4bv(Bq>{idI}A;m(kHtU$jpuQtbb&jM~UFZ8cC~1~ds^I&HV&PDR(T}g)|9}VD z1v9m;A+6N;|B{ztTcy-FK1oL6dbJd(~^e}%WE)KC~gkf(7ly>IHxYS zQYk!qO4!rf$c^`Lko>1zFySR7{8@b@?6L5zWTVi*13wf!DdzAQ2Mh$r~C@oJ;Nmd?uO&xM3IRx6ygP+lPMy9WASRKDmx1+0ou z4h<3gXVF~OaCu7E#z!goiSm_=w@$)xPL&~7_LNH?kpI`9bOb`RaS#a31#uBlwymsw z8eB-tXSB6yFcm9rUt!w@glY(0%FEHVnn$_+zfkS}8k7}w?e&k#|DR9|xzAoVgjsF- zKZCNNAkm7kd+^VotbjDEO85U7lmb;6s)F=z_a;w1t(^vu{~45f^p&+yrc8*Yw3qt5 z+i&`)PEQV*>)XC&rwOT_@Od(}a3@ure|e(o&iX{m*vhAPNc-Dq7R?%G=*`KOXIM0y zc)S!@sOm!IX1?sX`{{+r$^BK?_wRjqquH=~Tu!9x>*}bHwb#_{PmvoB3LLIGCs59A z4CZ>gnR@j*ZsX`cDz{Ir!sf^4&8Gpq{6RbKp5B>0zia08@ZVnpo5aKfg-_#BkfQ%W zwfc^irq6w&t%Myy4azUeBRn~DVKp(%sa9m{$qoqn)yjbH>CwqCjsPSMs34vynH9CpHJRo=mc5!7B&Jr z+sW(_6f5LSC3ly6oiI_wmp8*5P*7nWQw5z$s2z0C+!NDwU=n~IDWZ}N^eBFJ-#is_ zizC8Ttr&z@+^pxlT8^on`K6+PskEvBgk6T5;xC#B>Lzb6@#yx5a&k=LCUj z=~y>@hfuEGxfj&iftoM(@%eQowMe_oj~nrQj?vaAh04jCxiUlXdr z4-H>6IFkSFKKN72*Ez}Q&Sb2q+xNgn?@zc2TdwF039q@I>HVow)BNy)g<*fiZ$&2; z`WIMSS>uPdZ;vpa7OXu; zyY>+**94lP=@XGURX+NZaS!r9RpHDj1Rj1Cez4Z>ObS-Km}C;9(bm6Tp-RZZ+)|JJ z&ZR9rJx1cm9ADmJ%Psh4hXA`uCDT9Rfr!C_HE)ONdt^7#4Q#?DhPAeFsJ#Fb=M;Rn z7^{D1V?WC8`!lXevY0h;D9su&#;^qZDW5ZIx$t3~ej7anuV*6jbj(vXFCqVxW#JmaFO{e}4yb;xW^D33C(c8eKBd^SE zoY}uKXF^-jw+*f;v(FSw2)^T*Qc`fk?49J!MVhYTzt{x$`vI}unSu_8pSR~@J8h@c z!!0*+9~5ru$Ui|7nKiDNnoFaABn~k+6_}Z;MM=h?BIR*WF<63TC-2 zzig^HBTfJP=2c;Kq7ol}j4XoMZ6(Ad9P6Ja&JHvOj)8^lW>ktK+$8f5Y5D zNm*S%?tWI6Eq@^euZ>xI+y^n``L5zxIVM>5QtZfg7;o2V9?~m@ZuSA5_&F!Gr*%A*+JlyXeeHZQ@4C(DafEnKqw zNIJ{c_t@=A>M{Wn=67aRYf14)Jx|?ck6^oqk#YqJb&#O;Rlxc3fM6q+Frri9m*uzX zFIpcuB=erL1v(_9>Y9hlJbd`=GP@3Se|g4hYlIe)-J@_4c#>`{i#^5y3$<-SwM%4~ z6s)}X*tV6%FY2mbGJMY9yxm<^>w0VRPtB7m7Gi{rzKhVK1QP)Sevg7ExH=$wodeMf zZbJpYhwy4AM@-Xr(y!UY&-%&O4~ct)PpQ#wMZZbwk=5}?z4cIIqyNmAqfb(dRltJ9 zY`QF{Kiy|7S+s9E^$qX!tRRX%Dw;dM61x2i7{APY&3UkP=up1s{-lQkcb4r+FhE*n zE(||5q;k$B({*x1W+L8NhpL@L+4UEur0wR1eJMD1bZEKf5u97C+&4MVEcU=k+0>@w zA9zKviuge3`10a5}URJN|>k~EUKn837FXeWfp)7Hf{0A@LlSvCqLNmg%}Di znv;Vlf)DQDfW)Ht9P~h-sd6wD+jZsm%oRyI>d13McPk30KVPMX4=)%%yQH{GEwsThkHM7PoPi)mtm}vuh!2o^8VSIm zaD;v1e>qGm1u^ye$`lh_H-k9S3N`TLyTqj;_VXbwfq)g6yj%i9)q+=#sQLU!&^F(HMM4i|6Hxs0s7katj)(jI2BJ%-p(vf55ODM>;ErjA*)O{=pY{qPFMPKytpK=i`a-ufz(&%DOT*hO=L?{%=xzkKrjRD z&vflZYU~J18z8vsLZAz)pUG<^T&=!`b>Bg`dnNZ1(L>l$t+%K;3OsHmBZ!LhRE`H4 zuFA1efw$p#ss2an@p0R@+WIr6NEaJh|Fbz+Oa##O6myb#SaEe*e8;!4faCC;fEY>1 zepZspvf0=z>1=*7qh1uN`OqsBs^}2!-5;5u^DlmVa0?t4+DIJ5ng!34(Bo>dX$~^ zd;uU54leB_W)cfwN#b#jyBZs#Lp&Bf&|CtK6B)zEVF| z$$GVkG{1qJe_PKQuQ4~iX=;2kSG9o|)?iuIun#9&c{d9nOKab=YRYb&lc>7p zRlCT(DJ(1UX+sr1E_7!cd-pxB3)3lV3rH9ExFF_tFiWFrgy*ce;G zSD&<<3C5+N{F+UAYRn}{O(h!mU$pW&pxLcC;91OyG4AsGX+uG1?YT>YQ{qG{EP%|% zi$i31qhP6s5>gC!wlSNGsA|Z)M#M6?QSDrIHs6cvR>IX5)(!C+t@CPaLdQF-Pc=-C z6RO$SzaC)+30Q4r+u9!ineXR#U2-k*TF@@gqa4080yYtg1Y)Qv>@9FV8~{5N&Le;l z(*1qXm?5Hwcu(s%LNcwwN%<=2MJY78dAhq<;C)H$#SXe;X|ut#-c}@ok(i!pY3;1M zN+VP?5j`bd+DmRjsTBgQEA`UNl!E|f*f7b?XM>9RXJP=Sk_*&M#Nr`V9(N0+m5F^; z;=x;zjh{VjLlHa7H8|8<+$~oz#bL*n*>}Pdb!NI(B)LU za3ts;wtuUg)(F3-k_Ob#(}eg5%0rR+Iay=$F$4+_aQlH24-1fg{Xz$?0UN}`9`pyJ z>njMTcJ_aU>;e%3an#LK&-EF^#fY3H*>n!eDn*G&{ACOLVGe>_?jDZ7x_h^qMI-?C zf91t2IDK2-S31NLKkvjfnb;2Sto{K0*%yVHY#4 z7)WAU(F>F~gx$l-O&V>Kdxxqz*|A0e^A;h`TS}G%{*keN38UO7fuIk)*%Cv)`A`ac z7csE(r3i1Uv!9}?k5g^N>m&Lb9c!ma==)e83cgxR zewaZ)&Vw+s)FQsDyonVicZN@VSo|0%yxAN(-GTp0#sX~uCnH3)yILZ6&eL5lGpQ>;0a_z3kls$L}hgY zW+}3pQ?c&>I#)Gb$G2m1a=|EJyiscShy%KwQ&tZ`)U!wAr7*Mq6ME;^`A3>iN}5>t z2yDYc1%vlOK_EFTG>$%d+8G2pgN5e%D}Q<#8NCeSa$sQu?3Jy-u!-64-qY8}?armB zCM>#RrkqQ8Ud={)d3)OT=7AfdSPJwi%-ZHR^(hoDP{@V0^#8t2H&=H3D$_fy*3c9trs~L<6&@4 zJb;89|0UqhdUoc;bCMUTBPy?+fE;}ec!|gw&h2_OVzi-gS`&GlS$Y0g%DI1ub!^1o zW^DG$-l~Qb^%JP`7vc;fpXU5qIQTH;epKA^ouNV}^ivS#kI&qbnKfrE;4_Sw13lyt zF~9b;05ZWbLFnfX4{X0Kp|w@%ZIGfz$1EVw_In}<>ev%lSj6WIE)j-1y)2DKEpssO zQFbbuglXzpI=B_;nhZD5Zc{=;UA~#74pr8 z2Tv<{fr~0?f;C*ZZ>et!{gl1fnDhR~>ya7Iy3679U;hN!oP*v-zG$dA%S3(vIGm8?=K_DpuSW=pj#txo{jRB(o&RBsy#q+m z%u3FoC)qP_E;AXN)Fa}Bs3wh+wLGnm{sOeE6Mq+hy6oCNf%1oIH$Si0@2%bb{Gk1c zB5$8i-LvqMTSP_P4dkr&?e}MGSZBzxBJmxyQ7#{2q?co)-y&VwE6AufTLN!57_j!Y zNir&F8}V}&u^0Y4Bm6l49LI4VZffNs2`aC=!VnDR7O1)Fy7bKy{3Nh`h7X7eH0$3ya={&yDxf4TLST~4c1>A#QJ3)O^ZpSMa*Pr zha;*v+s{8G9r-J;%4K5~wlMdx(^bw1K(5|vl=t0>FK2;|I@2SCS)omBj%uwGv#vL* z7v)ucE}*~@NGMR7#v&;I$|r5o<+yClz+87azJV@l51FYpYsWh+S?7ppo|`jts( zv6&Jh8cclD5c;+0dB^Da?!n^?`6|vu*4^Ij@2@vHmn0|rz4!RojllL$46PG6-`G_W z^Xb!*pvMx#paqR!p`GjsW;f5%xOzPN+69L&Nb+5uLUD4kK4cemxDe5QJR z+6p(LNca#+!)W4Ehmw&*e{H?z9&q7t6)bF(bhOzCDM}>TS(n+p$3i83g^CXim5H8; z%@&-^$m-MUp~}If_r4BSMBn9siMWV5HrKl*UtrkMa~$&xml?<5Wd-#YtjiJ`^I&Bm zYEK&F)$Q(RDHf353)by#pM^w(^ZCAN4>l(U4Z&i+C#;R_tg*bhJ#zF3DYWZ(IyX3AUCz-LYfSQ{Pk-tdLXN-N-$@ zHkzXK;q0S1>+;C1MWyo7BdQHj5tTQBat|m5-;caEeB58)wTI4zjQ`#~hIoXH9iznl zJ=I^)_*Bdasw__M!>8&{AB)^hM>DHANWfTpUCiF%(c(mMUXZXAIXzhX@jQ**HsWD# z(f~T8CYMIY|FckD)KRo?l~TQvQW6?k1(lN*sm6>c?&dp_+ci-#naGT!;+ zw?U$m_o9=9BJK*NHGfVBGD2nlXw7$@1dIOKc~oaTj6O>a5Ld@RHLa^s{U|lu{f!(; zRiA!F%jA1yrQJtjIYc@SWANym<950gLumQ0)?!n5_*U|5{Ul6`TubgE=#Uhh+wKm=t%+Tg+L!`EHa{AM$3o?*ig!$Tis1k|n4V$4hf z;EzPwN?-;=94h3;mqZ)9)X^!!6ip`1B)i>G)%LESgGr;(pvog%1`h4dUde7<@X|Tw zhje853ub9E$rSf?LdC37{MSM!$epaPnE{br!U&UU+mZHTCUu&a_fr zeeF}hxA;7T)#}&XJ^GVsSF$A^SqAHLf6a~o)X1k>!^(HC*5$3!xzD*nN@VG~z<9-6 zt9a9b{_AR%Yhg0}={7_4a30!uv>!oEOBR$WwmJAvEqL)GB3oGDs;3F|sQS*3!etl! z@Q+~8cC6?b0RHoz^cSx79G2!kf5fJ$C6^0->14i>ixICWn%)}LiPg^Zg$!Ql$;(zt z|2-ZlE-!kAm7?m{FBu&A!Jw;lroC|=2V z{4h>!D_8&DAP9m7dGOBE|5$$7#AgByx7CM}){^o4n?ni}3fa-@WZgWV_`!1UlEbghSkr^6((M2F7xr=JTorPg$km@Aw@s74mpoQ( zWVb*>rh%Clff?FqgI4U7I>8zo<}p_(c!(jK~Fuo-(Ku@vFWm~+K4U+d%0$QukjK3 zk?8H82$H2AkAXIoSB=86)s=NyOa%GO?P|f{t+fD~#R1`p!7gv#O(w53H?=^;u?n@TP0&Z|3JA9?W6p$HDnD_^OmveofAW9$y7zyk z|3C2mvy+`L=Q&g(hskNqhsYdrZla9H9HWp9UN0TZPBw>{oaTHMi6#_M%`uW1O6c&K zis_-pXd8>`F?-;TrQvgz-4Uqd_3;A`;{|F08JweC+Kk#X)uqaw35vtf=R)r z3D7BeX{+93T?>&#@L0-;ByQJw*21>(J$*A?cwHCQswRb7Ani%fDl>^GM`~o9(^8Q9 z@FQOe>&`B}(tXl9`5(Io*v9_0{Pni#UogEGP!@9D~E{7U+#&9T>blaNe5{u^K^u@S2humru6!1-Jemt zQDpui(E19xps?Z%FUpPtt#z*-;Oz6aepEpwRbe%zdm*N$aBd{`|653R}6S+7jUB^ z{S2vyJNx#ZC8pVCXXo#$Q0zGgWL3rj;f||U+<$Xo+e>VE>meDGpP)>+gjb|%GPrPV zefln4#v$Z`RL9M3g>4P8;O_o5SXVagv86igb0eWH!5tVIE5fqOdmS;(cQ<^$8D-am zeo`*xjJeczqGG(=Z9%gz!yPweHU10_x16zguTiCZG!0^Cx#`)wsZ&~<g zUTcLXh*cwTh@>>u_FlRvjc&Y3?_GpFc~_{Pvz2=N)~#Dg{cY6-CoGLL&5SJ#-u${D zv@$bMa((sg#;c*SW8-Bm?~x0~*nrUHOl24evWjc_KkUre$GWWVlATVN+qq3#Iiei}SPnB%~q zOEVL}72Y`pg0k%#x*3kq)w^r!Rit+?^wDvcKcBg7g%oKjUGRlZ9fJjCxKwcNUVhKL zMgUL#&i-|an7rQg=hHa;rj-?j2(T)o(YHLOPT`cpB$izYD2o{KB?-kL&`-I~=nZp{+eVTugHV zp5Th-AQb3RViKgkNL~7USWV zHFwBik6LUl?lZT+@?I~cw_L2UsjP9$cqm+`d|1d%oM(7sjoIK`#IB}MG^1D!GTd6X zkXL==t5D(1=)p?M9q5}>rz_EV9e1^yR(^3)XmG=V{4i2Jv(AZQl9RlV9YMXwbJ$%= zDfZdX-9TXE?w}J0fPi=}ObqpxKmvO!W^?JT6!r%no})J_c@?%(BI`t=s|jV4B(h40 zGQ(GqN<@EcF})Z8k@CIn4l&2wV3%5e-iKL%kI3UZ7B6vQ^3cue2i5Uy_%%$v- zQON^b`;n=jL@WSM*?Sim_tFVu=3V=?%+I~fJchKd2)1#oJQG`A(gHUgym7li_p-k) z6>~H8_`{e+%Z9yIY5-G7Wc6!_pXqJgp_k)0&!C6~%BdH_YhkGyNX#JA>KRgV%^|F= z+nna`?@88}1 zxhJE={}^je8Y~s>VHn1KsLk0+tjzX6&wSvXaqFz&z@2#zcd`a~u;;j?S|2r_%njzw z2R{!fG8aORq2OMQZEZpn2?Pxy0`Vg|iP##$U`OU$kbiI^5;J&b`=BtmV^w?1nB^<{ z%0BX#YhDaD=tIU*8eD{i%|9okm7vaYiCqm4hKRJoTVThW_WXxI?N16W`zfpRlMYaq z#PwPApV=lHx{ipk*~)NxPY>f@7ob)7gdza}Qji;YRG4GqCbiDb+MIXOd*;08#$^7#(u@gR;VWq>It+_B;J&d$5o=CMsQ%tI!lxbRp$ZGPd0j-Ruahtq`-=d zg<`&p5siU@?E#H46H>4te7Nxh+ZY-CAPC{dQw-Htz(V#{3S4mS05vbqh0HvvpZDh$ z_nRj4UBlRAaX0>)LhLFtQv#VH-^(PI`L44L6SDVEAy;wGAl$=4LipvJ3z1Iu|K4}s zB(mcu$80Eg(Cp8RJMkUPpOLYG{Z*@>oIJ2Aq_>6w=w`5&NDYBW?!V86o$bpue`agO zvXjJ2$5mAElEATPTcodDfyM<1ftw1XPrqf=@lUD%K#spq-b>qx2mc{WU#nM?ijhMyxZ3&>-hP~)vL5fq*f7Rk_N=a>?k5DNCNF&Wd>4Mfgp&_ zW9}}G;H#ur7ohMHZUcb4$W<|oy#i*+IIv9(7D8Z2gAnX4qdnC`I7!5S-On*z z;U6PqXL`#fbfdNnzH)70266ydao|JijImZkT5QLP=FQ8`51bt>OIt5K^qi|#zHPmm zdoKe^%wX)|G2Ztea~EdI0Z>k?a>4}d)MJ%?HkaB0i!Ni{FUsuz#7$lH0`M?B&OR9o z4dw9SS^%?_xs!BY`;8ZwgqZCsppqWsi(<0hg`)7XfvGPRB$$6p^-IRfDp0Ub zYt+uk+%%FppU6&JS2^}qY^VTNvC8lv!lsTX#quoP48ntIX*fRE8Q(Sqf=a)!5+$0i zl?LCwdFD|a3chfiS`<1os&P^RbNJq<-h!0AiDvhgY1NC0>nMk+Inh;VlxlC@A@Pt2 zg}bF4sh$+97RGht!2B{W+kTD}ZOH3e@0qG+g@tn?dAT+`NGN6d6EM4fntd|as*M7t z;F)7ufZxZ=6wu}HF|i$yab5{}a~G|IhpT$xAc_Iyin#%cE8nx2yUyl#^`ZyX4K17@;7r1Oj8gNFZ|X*4)l+j@X~(4 z%0rw*x+wvoV#L~G@4OpyDJvu^v*ktX3Nrp>WYx37pn^S>JeSYZSCt5tC=!fh-BvTQ zwVG!^B{MhqlT*LFA~`(EVpf-PO(rD^4}##f0AEO)gC(p(h{ChZ%`9M|Qhu!d*UnMf zL|O%u^Qp0zlJ&{yMYZ@tv4pj&lD@@X=g04ykqPi*2X~iSk(>TJ{5jY?$^9FJyQ;tD zc_PPbJoVDplo|GMahjfv%1|bs#e7jp1+l3T7^BmX-;pH4Wv$!jrRlk}bRsp-d;1ct zuHuS)@JFN<+L0Q38sBE6LPFCCT+ub4=SCh)KFyFkBq`a;HuGr>w=$!TVG1$W}_IkyZ z&$kc{wJ-eAV0Bh8zs*!05Bb(0#LiAB-appZc@;(x=tE2_<4f7me5M!Zk}GduMk4Fg z!nEf{e*MnXsO`Sk@%4;U_IDSzqZ4`V9&pplGRVeO2&yVquT*eO!ZayzSI`Rp|cF*aaU+I_>dUxGWethvDfu0OThqb zDV2S?PJwYv+Kt`*bIL1E+#dgfn}{&2O;d^lWdu@qa}wXr-j8}otUZ#aM#6vlL0 zlsoz2zyl5Sjc;bfPj`ErRUarB3ufjNe*RUwMWmD?6KY-|?zZ_O?;^uVl){y?5$$5D zLx>tv?bY}HT&F8ZHQKyQ7OrJBk^6Kh?_=A!y1OqldKx#5Uzo=Eo@^GB=y>up<%&j= zL@wo0#Gl-TSKG3YFo!(oF%nb7Ua!L zvD>ekW1a?DTll)Cz$oVV{b^J6hX-yByj=h5+3$}BdWBi{@?&pYo^F(8Qe{_YUy|^X z0%*2I-05}kNFvxSwj)Ad^(GT6b$uVv-`z=tY|qj2BH}C}Tl~{E?A~wlp3rsKY|!uA z-;vqo)&HU0`|VxV?wCInMUsE&vvzO-E3x0)2jvjqA|1$IQ!y`I-77RddT?Ma3)m<6 z^JewN0#`<-rFW{P)%38y{Z~X&^khSLer_Sa!yD7<2p0w^jyW!yICU@`*fD=gG>a7 zZe7>wxG#_Ve@|b^)7dCKKB3DTu@J$aS?hb?W^uH5SC2*_IYauE>tIk8Uw+CUSZAI% za{k<<{uWG%0QM(;m;6ae9lOrzxJ3sqpXIob@SgyS^10df3Uxy8jlFVl>)Lgc$t+JVAjR4SJZ>(Myvn-*F&!F}^T1jF_pIL* z87dG99hlnQv@Fjpu|+}f@+rsPCf(DQtU*xKjqS4d^v5y?gJzTA0D9IrcU+$oGb@WP zbTSCq609Fi&Xzu&p0F+~M;M)wTuON5a(&zqdlB}+7Cm@FG0(SkMjo1L{Sf=}qP42# zaXrq1jIJrW=Wz}91Eox*7h1=GxQvv#5zF>Cff>0vBsIOY@g?NQz|-WjFpXLel;AJJ z-pjVPo3zFiYCW_+IX!a^&o9y~&_3hMz_Lp(#raZ9bH06>eLXRw=&KC7IccV_tUGBY zc)a(unT_wxT;s{Bd>iW)jFOIFJ+pDjWg)RJ-^j_;WD4I}(P@KrJ+OnYX7lyaTMk6KTF1Et*kE1$>+qJkUHR9$`@P@q zz5J>_WG`uQqM1dBn~I{v;1n3sEFD3&n{|AU;pz`M4d;1GoBWzHY{4*|ke($%a<)s! zRk^wsu=S(Nq^lNQucNKc!(G>s=&}d@NPqeTwj+Vj_VKOrwb?#t^=h-;W7{^V z+`U(0$dDzOA0yj!n&a}Fnsvrm>#F(x1Tgi@PIlv>*wIE^-Kr{R(T-;$?ob|xRGrLUAS$dD@K|Yg+XY0Mm==b8?6YsVGk|C?g>3nMMJN3c3(Hb0m_|4f@NxWWY;PW4B zyT<7AKK`#r4{Lpm#`20g&H|gXEkROc(vqwTZbDK|Rh$kwt-gCw{mO_6KexFi>Y*VihS_+BBLtdpOrf!#=h5j^TJ z={OI4e+#rBzp0^L%+4XmPCf8ATsHCesRerIUS?wmQ1BRLZ_f7wl<|z-I2opb{|fZm z7{;c7hNbvHBrwgb*(0hmsg=pwLy1w>U4+{?)^UQY>(x*?Y~5~fcF-N29EEn&=A9jL z;~GL}6dyP}US~V&NvBk8aDFCRh?s%3qm56DjeI;Wc};F?*VwXG&(uT)(db&Q+)VQ{ ziK`ngxAaWuTL-+wMl`S$N~MH0vK91MA;#>(w%ZK0$^On94S1}Qjt1P~n-S{lt1nEMQO?81~rYR@1R6!UjEPdQf?Y_v`Z~PSuc1p%NJoM>+8uah%nYQCnS2?cm z<2Hq7A8IK#;Ld6C%8=Hn1$e#Da}hnI>t{9r0nVFqxUTeZhqu0F9mh3sPQ7q-#InQ! z^Daq2RrRrXJ;I4Iuw~MV8SO8)R4_jE*# zR)DYeQG?lZX|=|+n;0*bocJgQ*0as?0Z-ZX#-Z)y-Pw+Wczm;fseN2gKIXW) zT7C;->!wV$C9oeZo}!=~qqFZR24bs)^0K|qDwo1}rL3XB)S->T9XQE&^!c=q-(l4+%%0FyuQXT8eT@^zFOkF+jcGp|6t^SrAqykwH!T5WBu{#2mP__f(+e&I1Qhd zU2soMy+U&PFkSUryLnoS8e0-%nb(=)<-ycBu%fU3W1VIBjY95<@2c1mS?qOhajH|B z13oBZo1V>*JCi011Jx=g_+FSdXiv?l)GBxDdW^?wbIwjZsLmp4&dru|dYq2P{$_%H zw*9BnZOcguWH3=rS7F+nL!svfnnT#f#mCz3HLPUJo-vXE(ZFk9<=su~)$7S!UR!$unU9|jr6|a5&0R|F`xtAFaRJ1wTK^mF?6RJ|x>qX3 zTm8VsIX|F#oc{4u;bwPRTb%jtQ!}YwxuRyZ4xVCCb5{Ncz5C0^YL51P1<8xAyLQNn zWtOB_;G?VT^5r<+_kub(o>Ge@*vIR$hd#=CTnFVRah262Vo_(`0(q{67V#jqXu2j#o+9AV`p{G-Ic=;G2&R2^KLvcpJ#-k@A>KLql_7ZDMz74u;$Ta&r z!za9wcLdqsUvfyS^Q>xv9sZws`~WP|tf;i*Lk(4tc`skr!OH4yeUp1bmg=22==g3ffmCci?23`%ebK!Wi z*WOe{uyDyXp>ltpZcpd@>%0cXu>&bs51WD4jzf75wZ=_hos5&*ey7S{OeJ1JuRKH1BTz4;ASi?ivkKYj>DBlvrE&KzMHCfc zN89d0)Prn7cB?|SpO4#TLfKs{>w3M>-*-fl2_e~z!sSPNAL{M--neH|j|`9R8ljQZ znu1(T!+$?_!lUC`c${=bqe4aHc+5@PKA|3Aq(ee!r5 z=OJK+0ZCSOOAr@#alq+*ckAqBa)Ylbg7tRh|Fgs14_)y*dwPrC|Lic61`_v+0&2dH z480zod!ysUt&A+MG9~qRmHtx@^j3e$o0mEc;!RjYZ|CcK7Z==&hNk0q`oWuSFCX+- zE#3}NYH+$#*7uZ``Wi881Iyo`T*MIH3EY=WLaI zSiR*v?91!9K#~>tDe8{v`NXK75Y#{K#KX^|b55+Ag-y>wW8kKDZvP${oQ%p=isO9$ zZIbQLr}XExR2ny0@_g^YbO`hBGMN@JJ$&^0(^IYp=C%M=(UWZqTtds!sFyuzMHEdS z$qJw)-3U$4%x`&>Q-REY?J4dgyw3Y8Ao_I-b(yy{-|72&alWnD(^-wB0{AKrj>L@Dy;u%hCkQA>GZ$Sb~Lm&saZKJ&cebcv^U)&9_N=htPuEN?(>77b55Q)6PsA3GO3)oJ}R9T zkmcMT`+lAFKX-OipexO#9@Wzbz}Cnj11xWQACfDY@wZd?JZ2f7>CqQn`loOz(mgLp ze&+sTOV>kgDc_&lELVJYyFX^~)i*Rx`tv(!^HRVMu|?VLup0?xovi0OPT3!Fb5hAN zUn;sB@~KbzBl>2I6X9U*9lj;=#ByW9Sx>doj;#*Ow@*LZ+vTTq_?=rwY3i-r%L$5K z`E6aB?r*`L+5h>F%q-SEjt>`|iE#QR-~BM?q>l1YRcY16f7^;He=9v4o`ke@_-+|^ zbnA0A|G)XmEUbn?Z&jPlw8@`*ci{~GW z4$TNf9O}h>PjUU*m50A}p2*a-AKZylnNX9~3M^}<*Eukw1+{vr+elUGDOVoOmu^$` zL#H59f6`6e>umus=@8P@IG1{$0W43fuC%jWSq z_;M3q3`|n6{|gp1=Fx1e@MZE24O+A_cg6aq5iiQ}Q(?PazHOgFfUB8>-u)Q`%*9te z$Kg#?v#qge{GcqcGI*lu- zRyu?}usRgtg0yo{t3!u9d6zu27n(5#zxrOK*_8nEJ(W*3yc^sWw0J*sjn;z>#9et> zl&+uYW87|0&~`9v=;@6>!>eSh$=w|=Ul$v|^UxUDt8QFan(@7p`rqa8kWq%F^}l~V z@VOGu_(LJ=_zgmYihRUQqs2k#uAtqES@drqN0eXQ`76B3`C`N)6;BJBYY6(ck4LBY zgQ_oys8kkCAzAEhw}!BK9q|cMvD5A8%VU9~s=-xQKmFj3>zN%;OZOqR`Ll;{O1 z+-v?fIc#*BtCj2Zb(S$LT8fS$Kydw61;7^M_L}2I$4=`X{6h$y+Ul@Q>JYJP{J}~` zs2|thL-CG#+D4;<#1x4C;%wl3K@_Olv$1qgy`xV4G?}RrqnH=gJEX#sWNTA;qj$Uf z8j?;`UZMQ0u?bzWD^r^w-6FG{t?A13I8P%J;7;3VSYra=WtyOq5~RoU$^auMp7?=mH8A~BGe7ozYJNJ^k#4E5G9^*XZN&k`iv^jm&`{z4+ZW> zmUk*0%zxi6pCe6V>YG?_cAbn-pWMnGE_B5tYz*T@$joW{{UrZ)k6!(ils=YKzsx)< zGf8e)`|CIr(sm`T_Glv1z$+_fkH4GBE$Vl(OM{p=Sq5%+9%eweaE$u0Kab>se#Abg zLfqc?`dxd{_~;wQqGW((SY;ahZ;>)JM!gR=YIr#4M3ksrt%o*h*iU>59X^HDoQPYT zx^9&hB_X65db2~%Mib^~-NZAFm4<`d+YR+%X$#BPaS$1zH@x0W_E=jWzV&A8vkM$A z%23|EFyS)#C@s}@Mb<4=b(55MSF6v}_TK`N*m+UYMV67tG%~Vfms%y?!;~(A4k8Vy zG>cA2UvCS~b{6O$%tbeudMCG;Jem8kTVqJc|KVR17?(lo3)bfz++Xpsa?vqOpl*DI z7t@d}M07J5S;<3R*$uEaz@RmH6)txdkK)tf8Bx&V#A~)NUDLQkH$?T5&>cip4HYH8qaOk2m;hBnLrz&=mG>F^okm~hlVT^A?k_9Fd_WT_aXpk z+KVi%{E5B;gls%C=4X08?{t(=J`ibLUMq-ZD~SxYux`NFX%`-sqFTwUzfU2ng|z-! z1OQ((iD@|`ESp$K6CpeCIh{iObpZfypy~nO355K?K>~PPd0$yoUsVtiGu%>k7lauG z5V|okHWtZnpePR3`)6duUqZm+u}Q!vb$l%Xk&Ub*vT8x7(sc#%GV~!rl{}~TS_{I@ z0h>ui)e+DWeSDx(18Tq5`%%S2LR!RtFeP)n5Ialk z@|OZ{4cP;fk+r-gEc!JZ!C1dcdv_eHQw58@KqJda#mNn{x)5o9T}W7QsAF-&{W1j~ z%)ws@Z+|wa1VI}Zdl%wW!n~Tde1@(kI!MYHvyZ}F$OCb`|%`Px?H>EOcS zeYGa`}r5x$mitzl2?5Jfkctsv-+~#IJR1pmj zQ+?~0o?6*3JZf0j@*t@f+O}hR{jyKU8U2CIj>s!fVTf3n9azPmO^1r#)NG6+4)7hKS+ zmU~|{d${T1yVMbKag_)$^t}NVRE;}=HLp`7G;NdOuk0P{Q4NA6t}C3TAvh#t9e_5G zkVQNM)aUZ~x5!F-52Ei9pLgBU0dd;!8rSE7qgIv_du(uBAqx{zrh99T^5l;2}t;_ z%WN|Gmbf3F(Iy>}iB`ayT_DeWLN3i2W^6_>rdYZ<+#lTH$@0!e$!gWO+ZN;QC2a zmASSzW=Ou z@klFmH%7ip?io++X*o-p)(Yt?N2n&@vwDu}Xn%OG0Mu9JABMn73jdzL7--#vXI%hD zrb0mx4UayELZ4bFByhXXKNPTKg<}9TDG?~#NA^v4e=dtr^4?vjO|%0BAeGnLPsJR`Jyzm z33?Fl1#6GX45Thg`+zP8wO6C}(^#2on?T{f=#o!wc;&Kbn=I7A9mjPMZ9xj;D5f<2`ACIANERa4Nxn0k}#Ne zs0v(iGnKvjN@E8Rm8S9VpP$G~z>CBWNU4YGNmFxq-HTciq4xzZ&kim=n;9M-iJxz5 z79wfD=iiJd{oy+1k#MkOJ?ERhNjw=INras7PON!9?7j zGOp@2ofhX2zskv4=k!iP|4^N8ScD}e@F&KfF@1kN7 z0BDPMyHoPw#Yc?gg;~o@j0i6`lXiQCCAnx}D?z=PgAQ65L;5Iwn zL<9fx@z`iAJTeUqKzPtWIqyTp5?CksiXj#lkRO_BwEz8& zbHM4_^N3cjuC4Nws+zZ7Jb!xr(_78t)+{Z#f-Q2RP9-m-RS#dhcwp7>aFRDG!piLo zlmmZ$9X_MJfLAR;;|~I=m3Xaob8XKqY%B_q;`cne-yVq?pi1q0z5Z+YmCS=AWRj`_Uy*?VfQ zIk#6WE_}SSOYZS+g(qaWmC@E+`>^Q$aFL=lgm; zHTL(vSH-uSQ~M-$lRCu1rl~r=6z)4`=aaA}_=nk|EW@d%PqwV8WqvNX!m^YtnOw)@ zPGROdK0>aRzqs(xam(7y)b^58>>}3sQ=>|Xex_6^)Yhy+kRwy!pvZMv4>vYV}E>||8e`ZRm;sEr!RgH?~*+B z14yq=uQwHn4!&tA()}JC1Ga!3AQFuzSf_t+M`$;zYH2a&a?ydQ*EZ!IQBlKW_Gd42 znFFSix1@kUgkc}Y3*egbvYFz`qg*ER?IlPn;s~(clvWgOjs-hl>u;cWS|3%-e;oT4 z^H}^@gv~#d`32nhBk#|Txtdu+^Ow_tKhLG+YdZsPKW>v-B)<8iqGr1f;9X?_lXT=6 zB8`aUgde-+fV+MTQBw78xn-$>gZfm30R`nK8%Fjdesqh!uVmmYJ-lX_zKpKOJTkWt z8@%FIViM^@m+4~5RoET90d0+bjk-du*_0_)`TEZTpUh2|m2DobGuk=*lU{;;ZO+R)YmgYRzP^Xe2 zKxrRej#h;Jd+^S=KbtUZ$~tw3CHJrMD?J20r0b;2_7(K}_4avx4W-f6y2>1@$+LGd zDBo6x<3VBN6KgfbrA-O-U%uz_2~V4)o7~g3{?irC&1d^&_9^<8W!Ac@n?q(Kqc*^7 z%(zSw&@1;D7+HSXGyVM|EzuOczx&X1om+mjY=X(6b<6uE=M#>_JHpxz^qp4SdE>)E z+x~`yP`~oS3CDDqh!5q)w6b@)?XI%hm_#?EoS#XK4mr!X>@w%)ZllBJf8JAiyt#zw zFlv?@LJ5#Z!3}xFEuKMa5P3$V~@Lz@((FpS-xnV zQ;}rjL zamti(o2KH340ZGg(sB7T{IQ%aC^Mx=zqESHjho3RD%82n1%bOOCw5@A><*= z*od_e6-(JHkMg9yel`|76JNUS`|8u;Uk0`}Bsz$ji9fToj&8OZlpi`f2<1n5$r#ut zTso#4Shw0<7#LGB&8|q<1j?wgMY^Bnh7jdos}}XN4M<$ zaV#u@S0o#-6EqKhXkMvtI`k!2w9)VQ1gIX^TGGnNk$Ac}mGw$k}d|n|6Bzt-8LLH`+5J)w%C<^Pb^YasoZP z`HIWzFGH=Yg^D$5=f>BIce9a~$I`g}mEw+hee7V{-U-T&z{H>kWML#OWGCDv zx}Em+QsydCV~;D$YRn>MkN0b-@);U9q69lsHn5y7pC|I3ujOPu7-F^RloNJXc9aD+G3jqX)^Rz@6e_h*NYD6HK^G$^D4!%myvj z?P_{7nR?qbx-y?P>eA1v%#1s7T6JQ`{{~cDun?~y0C}BecVgN|42>R|r|J1YodoOn zvp;ml1PRkVG1jxjzEZ`<;i4wHUW8fDkHR_Wm#1FGFMZ8_^#E?yTbG|igs7z>T$jJt zm&#y4p!B{&(Iqr`FLkCyL7T2iv_K|uz!==G-9{>d4>C7mu!BSx-bn`?;Sa`mZ@f+1 z<*vUnprfa+*dmAn&WcKm?P~}O!f^|9;`oGmA%R8UC_4`&A3=Bi_Om=6j0(9rq&`Ec zv`%=H8@Umq@sO%~=f1l+g#%XY01m<`byNl8_l`19Z(m?;)Oh@Pdp=S7ki%&In4n*A z&*C`z&7~!jp{O?YR1vy4AqI5n9nAAD2fAEhZC0k_^EQI;pqEzn&09qX7MTJ*TCzI(aIIoC&GzY9cMxb`$~$&hperI84}>T^P-Bal?%1C+XkINQI2z?rO=7j4Cngcky5@fKU>$sF zT0tO2b6wBYDbA$9t%Ngm>w8C!O4bfgdJm6zHXXYfb6X4aY4Nf$VZyKBNpntORA2qHD+w*t*jK05x~Nez}}Uf62zE&>euXW;;2S?Tz>aa)bu_t0L`|i3Mdj>pZ3~C3XejI=N@3OwYmQA*q17$mY zb5*3ZKs-Otb>8ZqG-wlw41I>;ct!n>wWc~F!v{(oPu8P{ij*x>3Wh7}OPveXN7Q4o zVj?1#OtWgFQUE$hNP)`pdZ$yQ(e1|(`_!MSO?eAS&i+VqpoA2TP34fvwRN| zuO-c=+UiC1M3!-4G$yInJW{?46YtRpB?5(5Ajre8q;JP%@Aw^z!?>`@>6_9&w62Gr zM!Pisy|KPgyzlB}tlwSm{`~k4F$!&SlQoDT^^WIl(PR$z2Sd#qvDV08AIw9Zn6!} zK3ZJ$3cqO~r}8#lDIYiHf4VF^@V{t64ZrwlzZKW~fi#t)1>5v; zb!*eLuNyt;K+l_`a;hG9$ahiL+TyhCIFRH1JmH9C+;q0@w`laOkxBip$Ki9Ymvt|% zjeInX=FIGaoD1NhGScRGH)NY1_iy}nka#1nmeC*j+ADvb0PXb(8q9%3QQ(Kg>|}4Y z9gt*+5xrOz6#=(wWks&TVkz(&WOe4}oO@a--!1Kr^;8GY=pLL`@DjQIdU(L$v*d*1+Vs zv_L|L9Ln`vZC$t9Jm*LX%aPw?6yzrE((kpW>l5feHDX8}z(&`txaAv(7}4H_A*+m? zL|8H)Wl^BLiCJo5&mjuK4#&Lpo4NG_?Bui2eWy@OJmnCIV!*RpV;OIn_1!!3qogxz zR|>=*laToC5|o`0Q^+ zql^QioxYy?;zqL>mB>ksN^2I*USQq=tXUBJm4_8w87X!Y>gr*Nu9xe@$>;X=->R+B zS*6#Vx#WriyQeh)^o9dR)0m}V^uUIZs_T{URk`kBD;DVAkQ6As|mGgcLu zV%L&j2TuYloLV~DN-APDWOq7ol6*R^TkUfiG7Xx7;QytqvDC_8vpS{H2zxJK3u~}(>+4$1%Usvh1$r_t9AaO9r$7J{sql9;VRedW$qEvB zMnsSzB(fFuS(zl-EqfZAmJ68&^}In7TNpkBp;ts>t*>?uS-qhGS((c-T=VIj_w2>t zNokMlKuo_b=-VKDW3v_X;Z)-s_p_S zZnca1S^1jfD4*%`h*7D|3c@w9k5U63Nx+6JS?ZiDES7cmh@tIst-2X>6b552VNiy2 zW;=72Hqew+vo|L4S>;?iA@kBZIycSPlg}&_i%hGK6ddb=m>Eq*^^UVo3_!djveIvr zT);@efU+>XXe>zP7ErYiA+~sznyZlF;67K-#T0o{Dvi_5zj)U59};qW=mv~TJCMrW)5}vJBS0?RNO4?84*10QWbC`1C1RCmWG6?k|gz;#I=a;#ie5-f?3oi3407Zqj# z-->%FRG=D^$RFb4SZ5YH-yO8c3CH#D!!xSPiBSZxOvmlO1blU(YW{0+ZZhK^qzvP2 zA9`!t{adTdp!q=kbi{NoDO^yJnE|=f0&%B7gIi!09y`6sP;W_N)z1q?zhtA*?wXD= zqiL`h0d&3xZA{t2Tm}u`mTrkbtYQaC3B?vO-uMkuAXviq&unumCMvr|^t zZ)f1So&4vXFb5(u1f+P&8y<`oy&hf46uG~9g?#u+HYKrUF9#HEa?oAa{Xa)-6-rIi za4N$&7y68FC)V?Wq@g^B=Q<}$Lx3a7IM6EN#k?V2-_muo!DQ~$i8kzNt{4$94LGBE zds92nNA*f`aZE}*j0qMuWU-zXvV8ukqomb^ud~X=VWAlhZG^li2`ieoBUZ>ZIOR-9 zgg)B`b*p_@mL{W0h#t>hzR${4yc1!IhiF&)!*&k50N$l_;&#}odUay}?Q`i|Iq?~m zUq;SR?VI04Z7=I31w3R$O0pyHv-5qGSl&D&^%YnZCf}wtvgWj2yvVeQwPtIl@YpV* znX(MxmM0hf7-Ni~P-g-|w?*c%_MO|pMUM(3uZ#<$&=6@f6B=wwXYL2lo;$S&2O@IO zK~Z|Emp+Vs!7uE4`8Wi&B|o)zh26iRa-`04<~pSX7Na8krwI1XZE)F{OM#SlHF~Z+ z50rVEHolyzxb;z)J!C3nzQ;qp{fK}Hn)OYCl@w_8@+vZoSh=@XR&?2sAgJz3#@U8i zlsA*X1l#L6$B@sG@OzE6KjF3eKsbM^&i)@femZ(pN5{ zUl^x5_TGNhmFsh!8cF{ zVYRIM$8onLGB67MHU%WhPj;X&!_#lO3YnDJy#3GNxG8uFP5VU5`{?u|soMgmO6;qn{v7rDPIS&gLw~pb~wmjXZDOFBfFN~wy_2R9)&Fae}2fJ~g zw}fj0wad!A!E4Q*jGvCW zUkALDPvMjap@H+a_Hp#XXIV4P)Y~NJ2y6DKpYK~p`|gtDo(hj4I`c219>!R+;zjl^ zs*w`>&WbAJ+z?a025Iw0Rux1E|BlwBF`|dR#2>9Ox{+(Py)^M8Y+^hv3V&h-0SeFo zNp3udKf?|G!z5?I)8AQ+xEfo@ujBOBWu$CM3*@&M%aY2t^{U}OoNAj1CQ8IQ9?aZB zesK9+K&Y^;p&)N&mPFD)*X5W$ADOyMyJ*>TOd3Vc2`B$II3M_b2)om8DF683`(yT% z!Pv>zN0!E#HfHR5L&_4_*T|AeS`4!oTiK0BgD@i5L#44VsSt%Ww5e3mHVJdj?|RG)3a9j>1Gks@tn|m zYtLE~5n&}~T_eBUA3fdW1+dteCUqRlehx~l;>X`U*%_f0YKx_OpOqBWnKg4q|6YXg!#%?Vr;+yppb>mX zDU)u?r+w_m(h{WOcpniFXUA$@q{uoAT>0DoxcuC>7C03k89)=Nk2aGa#tco^^+x7a zpECS#phV&N$PZg##T9o$Yram3pDqiaAIs0Yza!h(l;IFSa~{_89YOH{g}t0D9yhc3 z+Fe0S^Z50l5)0Lmr^Bd2RAt|{7rMGm-?{x(!;@~y0$Z|ZJi)p5N4}=Wrlw$1IietW z(@mjMwEv0@oJ*B5ODoC>J3s`tmO@|Ztpyd8?F;ui!GhY1F4d+;#LEGRNua!6S$m73lP?;1X5}6b@fi3FY84-J3V7 ze=uFxkNVRkcb(YeKLvnAHc{f$6BeZ8ZIgbwqfckdi=O!B?+@tj_BalR_pw>eA`y>E zFvF78*R1{9%)hj#>s|R*keg$XHAZ=6(T!({J9NNVz7E{Yfo!8~gu0t93~`;cW0+2J z+5Iva^nfHhq=G1(j8?(Q2^v)<Q#?91nOpZuVL9%z(Y?Ur-ij3lE z9)=UfvmUfc(-#3Cgd**{gp(e)&&^Kh5e_PK9`$AYpzgK*!Y08kGDDd>nR`~zxNp>b z(gw)%m`*iDaszC^OEQ@B96}I6v(4FR(zIT7{W9UnjNuCY&`%qzTv*{;)gd4`T&-rH z<@@97MNvNWK&3V6j#Gk}RD^DawGcP!i*C`{*%9(vjBBc>f-x18drO=zX&D@|KxY1( zx%syek+Z8~RbskfhYJ`_?j2pf*^1XVG18r>@`=9oKG#isEvN?_&$l4+MpX8F6PI=1oHAok6(({hqh2 zZEsZ)V?J$i3IT!ZPlOvcr_^FY1(lf4_`4W=hS;>28p-)0+KGIZ4du2nk$ zL@S84-+ZC|f@D71&`}sPiZ{;Eom}?t_7FG;rf1eyt%s@GUv2{mQ9;&fay>T~kFB+e z9_}9szuILfGtMhX*^HHY#D@|S(=tNQZzKiHgYWXMBT0&2*>V(9!?k@^Q{Z6I#5omo zrHs`hK!AwFO20%C1-b_S3~I9_P;qee74+L-u*s1aF8s> zwH@CkXFXW?~SCmpRN-fh&gb@T92~?PBqX1+@UBRF_f%~ zbgOoEJ3oFc;#8h{g|qwwAEJluHxl?|10|SLx`wq#7CeuhqG2#;aVgYDnjiFl}^Q*v@qUC3^6-8b`=|<_XofOf#ITaGkls{?_vM`?ZcJ0wAYPiHM$~ z(hXYOK&gZgk%72{!_>;hDRDt!JLvFt>cROVMXQ;f=y{t_a83w3!o??>q5TPPBlTwl zc4qIGeiS*&n-?U-oy!uWspQ1yzDY^or@MlK5H@H>@f?zhru(1Ep&{>O*euQWEAE-L z!Xww(09zu=M0~ljjccn{2Vw%4y3{47!BJ@6wgEL|h9u8=P^Uv$LDD7EIi96KWSKML zGc5_KeG4|)svanhTtTQ!)>+d4pkvfXn-YR5QP!b!%K!d?|(@V=c9R-f&WU_DeUdr*rdo|Zy{0sQBf zk~gbz{ky8flleBCOwf_+a&3A3S?B~cN`k$ICeNF!)p0h+c=y+-NsBBdl#QTGsY|G* zUo6!E#MPaCiii$AZF&JXY?19Py8EE?~m6^yK-HcsvdawVn^VR-gT8f-tc90;9kb+a-VEVxn;Xdr_+I0 zv#VP|^UycnDb=gCjpMBMl*lSNY^885mth={Z~sredy@Io5x};h?e!J5E~0?zE>k(1 zHq|Oe%14QYTVes=feTK$4IUEN;<}F2jVU`d#w+sBWrsVBX)9LBzd7l9ebb8`^G6@* zie#)z_}q%An97xDWqt%3$=28pJ4uftNPJ6$g~dVLauLf9E{x-S=Ej|E7sNrF0MsjK z0sN%mT2?$GW1KAttqY&ZFfUxbq3K{cUQ5nV>#NaIDPU!%v}7GFOq0AOT#S$V4%@@N zgelzs%Jwuv==&tQbP~Lz)7JE74 z7Nz?Vfb+5?M7MM=yne9U$%WIsc{!03O}X`tv#ott;bRUSa6FYH<5(BsTxx&diNa{C zs2qDq?yp#HmvhbTe7)ERD_j*zzQs=ecS|q>Krs7jQAkUR-L#rH(n41pzM9iL$@sE- zMcW~yPiv=(3QXJo%X7^tMGW=K+54I-B*bbtUw1n%jx}Ui`aL@xu=~mq7pf^B_GLI2 z2bH4!V&<)OZN%Iv!4CCZ!0}QfJCUggDdx*i@HPylj=z@K?jSF#tZTtQCeecCX z0gH%70TFwsM`vDmkU*w{!Hy|>n)S<+t&&r24D<#^e6K_bX5tB2FlcNX7%hjeHgmb@ zVYOR0!fZ|Yt5jKw3q(g%$`ngJ7iOQ0(+)G^ru2bbzT}0&k7dS39a3dxUHoM_Rg{Kv z2Qb#&-3sIgtD6C%7KQz&c4>vDOJb*?G7_q)kL-U<2%#;f2-%Ds5_Gu}1NvYQEsdaT zFf&|ERr7REPMk!jFT#U+*~r-vuFlbtPe111u(LBr&F?YL9t7S7na0gpN6?JX0U|xi z@r_mSimJPyZ#*bG;}u`I>8gO$SNg~|dl1S-=GFXrr2NGKQkQ~h(ukpK+Ux5|#;2=y z2OU+G4K~pq^o_GJUF{bKzuMiTwr^PmdDp?DP|94%!DO|oKk(GF3@~`#*Wk(`@+Xq2 z-VTK1rGC_1%+7T+OU<{a7_yQF=y}bnqdee3%}esm>o&*U-fzr2Gk8Q<)JiK_&6auH z9_TDx*l!j$a4Y)(flU=5E#NPyI}fX;>85IgfJ_`g#F^B;qrxOhJ;Avj;0`sF1*uyX z9o(Veo?siu6*J{niktDAIxEdJH4dN1G~!!o1JV$iG$2X-_+cR*{LVqQ+N-$6JJTO% ztD)lh&bu=-UM)v@EoY{Q|H2*0$BhG(||2G+|he_wy9>^pSB??LCyqjbgH zuBkz%KR>^d^y8DwLd%;%f|dI^q4jq2(g4fm(dL*|~NbpQHXx#!WtFGg_O$jq5wf%3ua=HJ?p8BN>Ux03(N|d(%2) z%`D-a|2!W6g-f4wV-M3V+Px#voxxjLi!|&GnpFc&!&Zb$iSzgGSdvI{niR1PhWEPQOaA+bvCW1 z;9NI@2f`l9*%h71a{2JK*cqxhd2&bms5{nk!niWUC!zj*y6;C=m`wyZPty^$Bkw8w zWK(?|HDu4yJDUcZcdskx(wS4fYC%5-m`u}8Tx-@2g!pCC%}FnpBjz_gp3C{G9cfki zp6Bmy?L^d0YUtj+1?&BDoJEPV7X|H6wRKM&kEM76pdZ99=6D2`bwU;VOX)6!0~vyu zi2OL<)Xvqmks?H?HB7YcSYzPyyP2{{;aev4k=%ZT0u0P@lM&$huC%@CRFLn&eF^_+ z=dJ5~;||~bNLZJ+caOU?G!taO^Vj zo{u|s4+vL!A z#s$j0!lN$*aL2zNj)zVSiC;dX&JQb>64zL1OfMRe_T0?Ki^{$AYU7L7y|46#qT()^ zvt6)*MekZua7uF}$Xj>aZjG2v2V`a3+x)r5#J|zrLeXH?uNQ6Lf9-lX3tN1%d*+Zu z{CDEu@3*&i<*#_I?Z}IY=zd)F^O?!6`(0&v5h>}!O1JZ!YYdIJ&uTCvuyI?ak^>;1 z{NwsX4kT1+s9#P6>;;A-L6oQDuoSx+PjLFIK8c{Wr_g0D#WJyw#nLr~jGOG_be(x~ z-x^b@{+U#{)qsj|Eo!B|5-U(y?~zlDv#9#lk1birRdppEJC%mWW!u}NnHi{upUse5 z^BmIX6*c^KZZsy7H>8ggX9(cIGt+#UcGqOK#|ulDOqj&7uL=t}pSI)AsNDh8+RIe* zbv&%w&g^|C>W~@s_r^0*t0QigzaI*oX+2|NCn}y_N_+A!Y0=Qhd?mSg4ERQO9dsoo z+a&fbVr_3mo^A59CWZ4R{HOh1hgaFw0X|Dghw2?=5_DsPR4{Ih?^xWt%h0YtY(w7e z{)?4$)J64igMFQ)%Gfrxu0vqxrPGE--Rt2_?CCDFC+?X0aU<6*O;d+y$n!qi%Wi}t znlkGxkGi9L4-wQ{vE71+Opk=Cs+9}D);}NV8Eb_~roOOnM(A8v4!MGKQzsp)8vMP+ zqyqs7pC&RS`X&!Yh)gm3MrXw@X*e;XYiuKx#$7Uw-g%g6sfVprOr6Gx)w7Ona0uK{!w|vb!dI&sD;9^u@K$uK7{i`kW4etM$1R6=fR^_2R5`(ZuC#^~ashJ_0{kTl80STYb@AAIqEBA2E zU^@X!js07((0Ieq*9G4Q0%wa?_3`AY@|Uf_B`W?DYb|G$%)Q3Tk~M2*G|b$xe0V{# z->yRRR{n{374}Pb&JEz9sR;kkG|8qphK{-LLcbz{KJIn4yKODOmAx!eMW9JWlW4Ne zh~X<5hGeG7#?2p^@8-W)Vtq~MpD$j2k-!~17a1Sn%np(&=i6zW&O>>=@cGlry=BBw z$#RVYik=f1g0E00FJ8A$mu4_*rZQ3qLD+8i@UE!uDE~oKX<;KFP&{%bUY;kb@`!J@ zQCfL1dXuJ5d&XrP=KfCg{3^1dBE^bFVOj)KeY@}n@gN;37(sO7v9F7RTNY6tKcL$K z&eMq4oXImSYhgtJ@B%#6zBqODml(Mdb!Sc38=!JKFMzvXM~R-h*2FwLu_rXKyZB=B z*pxScQHG2Z&G#PSZjl}^STQA#`5PgSIdjqz)efNg0}xHk$U!W+HZB!Rj)1x$fCj>R z1kS{!G6Mny&8R$RTHbH5`<5Uf5p@>{mP5oLi*EZ*l)P$Z-m6Z3uA{ zfHDt9-ZVYaPC>O15l4kX;X<}6E>6%4gBYZ~795EXaQ*|lB!&^f(k2;z5W-$PfVAGV z3|J*fXjlyp(INKORam<6x+hj8T|iBjXCa#?NMS!#1YiOC5GmLTt!rYmH5f1uzV$S= z`;XW?0=8Lbll=KlP}8D!pU=|W+}twEFQ;nH$v40fMM*^MY5 z!V4CWai-YuI=Fj8HdICU!ceUo*wr7fAnyXdk3|rbf)IFdAfhyEkGeSrWIhRD5@2zY zFnTVcm4p&9VWp%zxk!ZlQ@Er(!^T8x`W*uVy*=+igHsGx#y&zs1|71$O@WAfsF_v zu*PQ#?)@!WiOl`vUHl{%Z7{mmWlgM*c#TE5##)4ht%-$Uk^73%pLoYy#Z!;0Tmdd2 zA3(yJI7Opos9k*2RZ{N#J=m)&Wd(^3!sypVprxq;Q6R-4)=j4vOOTPgI8EZLG4&5%Q;)qhY%mmb7Vr%RgF0H3U_Jq}B;wFEJ->`~m5i(3` zV#6D^HUQ0np2mqNJ$ca29k@`Ai?~SL zcqO_&?q2_z*qjpr{_^#`)T?84Ok9XKKy_B7u`)U-SZ_VWrz7vW2p`(gW zVG$D!fL_2Bb(ho%sh=f0_6ZhE)M0X|y)FvfxmWUlfo;>_^nXV$?AOGCcVchNU)o#y z@aT<)xzNX8m0Q>C|1*99HqgIq>W}K)KI-i6^J3_eXUk(erfGv2%hj@4dSKLrdqcqX z@0HlX$(?PSkk!Km6DN*MLeAlPui@#n&39e}JbaB6eIm4suwyGX?oOpQRWF{C&29n- z46YA1BMYd=b_#M!`o!YXM;`F1mU`?@#a4JX+FKVpiM>6MJLIi6d0TPve0YNZFuZ~8 zlN14%O7wY>l|cqmVs7AgXZecnkU*laf`vxjdm7l>e`@V%N*tmhpzVPt<_%W#HBt24 zn%FF_bsCG#+8x+7*_{<$m{4EDUF&8)A4r&w5jHsmfcu%mR1SK+;J{^7oyRp@^T3w* zikE>Px0Xw`^;2u;`JLF0w{r^Q7mk(>wUyrtP{cIt#LiNN5oC<30lr*)U?g;cmJ-}kO>1`-WnJceK?YyOjV&)RT zG5<&CfV(-ty`O>PzW9BM;A68<`h89h-`^Ll_53H+b^r^&0(M;&x8lHCg#|tdZ7YLb z{ZPZ58|Br-T^SLHOB@xCm$~&&jAq6b{xM3fQ1s%Lz|hpw-f&L zGJ$z%t_F}Eitsaq{<<&K8$K_bXsxBt-y^Pb|F=6iC}NBZGwhR}~lgcppN1#U`8f*L|P8+=YhKH#mMt?ZAH(@T5*xkrxVN>9@~U=wP{6lqKt@XBoP8 z@^a-yLO>(R{C#gM_1KV$ZzZ%|=$E~wVhG9@9uFbx{M(4=CJM?;@abQS|M8UH;(|>L zdCc*<7{TJjSrTSu@rKuf$4vsgw!t0ii@R1e4)W71_#5RN6Ije_E@oD^kO7Z$qlzTz zV@2>ko(vH0I&J~JJ_oBj1-QK(&DR&8cUZG2|M^-<=Jc-IhgZnu+kN?rPs+82oA+*2 zn>gsUZm$AHkV$kTRWU4{;wpvRKK|@YOAg5 zI;&5^DtUXKL`{IpM28^8ND+6aSl6?h*q!ieY`QV-bp-@vikfY7ccN`Q@wy?YNNm@N zMXbmEx*z|dM?-PE{rb9(o!H*3-G{ek0(sOLG0kn|_8w^6Vac*t&Jp^fSLRQ2c(hM# zpPM3jGT)Q#u3cfuM|brNmpJsY0#l#sN5iQiXg-YAFW*PB7Pq5w^K*!SpSs(GJ63c* zZj0N9X=TRsXQULHEwfaaW@*;ST1P?HO9Aok1`h{mLkhg^%7wGl{94|Y^kh4P$s8i4 zLh^Ub5#iY>T_KIxgjU*$@nm^DO4cXh`@6Q3?9?9*>z-PDlkr9;)D*WffosC&Oog@N zDB)ncLKJV|lb|tW5lOiPM)MW*5`96NKjcDWZAJHMiLowB)B_hcg(oottz!G+p4Iy z5yL4iPT~P*HT+?5j2Ew;cFe2a$#k5*j3V+@R97PEG;tbMJ3x!Z=WLA8D=#>nDbhg`KA7vlGmTA63jJqP1v1~s z_RB2stS@Ass3#Y)Z1$n~262F~%j3bd%|YpDlTU82%EC0u?;le6uE^$a} z4ge+kF`cmnU`^`xjJ`^1uc}2lVFi-YVh=LTJX!EQt&(LZ3`^_+Kt%RZ-9x#zC(isR z|M04naHFHfO{8b(A^~EEccrD18s{z|e_f8@UzQtOw3gPLOqIRMQCSuk$h;xC!HB+n z&|QmtQB}Fvk4hn`0XI~YV;K?;ety9SlImKc>A9cfuESFng{Mg(-2v2Hasw2&)^uEN z$cr>gk~8bys4bGmWPoaZzah(d z-&BVC`F>m*aoDTbASYmT*|~2Hgc~#-#^#3xik%ERy7}YUU;bFh&pccz{jXTC{15#h zp$}NOu{TSupni_%O{owLP*4LiQF+5;b|BgV9V8Y_utbZxgL{<*okSA@tZcxl!C#iD zi?lz;|As>I_AWKRy!&zHf$#%>L^&Q_QE!o$6;dvt63w#_XshOBSVUCX!uF&|%xOK_ zhIWWHl?Y$&1=}W zGcPCeK=q|P$#4h9wBkE0Ateb0PDh=!v>6kS8x#!gP@Usp+TE}CHXZNXt!|ApQd*Os zt2{=~mlMHXmb{QOAk7*nSbli9Z6;V;H>lZjs@{BRUcUKXXN-DoK?b^ z`-b~sBN|YuLltCZ0LU+~TJilHbT(fEWwW|OH{p;mQ2>SsRl8Gp_@wpE8=mh^Eg=uF zi=xm#mV0z+Li@@f&e#&oZX^fJLRQp)-@|3CD{ar5Pm`=5*&1Z4pwD)qHO;Gh4tb?X zFC`Ut1$%XPQ?!~?s=j31Z_5c6KHDso9U>$>c;v4i*ZR^Ie5z9GeI=KUr!APHQn8Ju@thIr51t zUc?(D7)yvdSx+Tl<&cVR*I-T@p%LW8G){BN@?W))_h>uq)u0=y?7nB*!>0ANSOVch z;WE<4cR;3f4Md}!lzTb(N&DbOq|IivsCV-pizF<>@yd@`eBHz{vF#h}?iI|@nd2If zl3*gwQY?C9P(BHt8B*AfGqZulA{ei*B?dz+2mjhunKjRVmv=qgB?$O7)5=tu(S(QG9PIi|pf706;Z z@Iianz|OY13!rADX!Lr%8qEx|jS#ousb)=rP5^1U0bml9-cv@WKTtU2#Yp-La;B)) zA{%ae1npyi6|Lde|B@MM3Lup>YU5`N7dkygaR(ei;HJ5t11r`Cnsx3(f$b^zK6AZ3 za}57Ah&Si{eIfQe3N!7)V3q?FL^JAIUx3q-Xs7R*c<>?N z+(Mg3tDA33n{+gr9~kZfk4ABzF_R2eFtK6}OO}{=a1PoFm!VP~A%`xx$3Y$j8tIE0rhAQCHtdrA2Xl&R?Ahoy=hAFR46$SzI)AV3n~@#sBYV)J zdqXr``DtXnoQRV>js>YrV1}|%a`tYYYl&hv#g zrL2H+A`J5KY5ZyUTO$0sJv3&jb-S%3hzcg*!8E`)VsT7tG(%vtI5EV%p0QZ^iC>Ba zYv1b|Zk__|;er}wK=wpd3|mRi09}3q{TsncnWLEl=${nY56|7DkLIV46leq24&#}n z*JU$5jx^H-F8u85YqYYGqnl8{m66sR$*GEb$ZzE3pF~!-GyG@+O+P?+2e)X+m*q&x za9acyTEg@0<~R@--h7B3A>V;YS8fDXq=Ha>&>#S_#SGqqkflY~lGrw{aE^3<>*D@# zI;+YE>k5lGaIZ!AVDfxE~Q`m=(Zc!z3({{^(XgoKi3#^L@ zwkdBK!=l`25hI^A(@)IZUoeDE`mkK*GS-aY&LqaLN4X!sg~sEAC#lln04O$4^)Q`G z8UFl+ei#5%ePNn%{;ElbY~Ns}>4hgJBDx)TH+LNcDwx5|*vx2lC7pDcP941w4~a9KPe|L3!tsMtuR$67hT>p&V``-SXBXvxyCHNNtQ36__B?x zCslp>Q=0v%NtZF}WqTTiKPFo=#Sn&JM3wR?N8*CQ(O2{c zK#+%y%_uVp?j^NPjLFwJGzTJbwcZUDrLlpA$#7HRgUSK8s*ZH=eilTn@-ywo(U0_l zfajCfW%LTNMsx=c^DRFgh1&{EJ)z>#HA~|^q;cFt%|yg}NgO5DQ^zfbDYv323q#ob z^)~Rbyi!IpK!EcCt$92??F;cIW|39&p2a`Y)jLSVWqnXWxu&|$|BzedYSNm)+efbt z!=ZoJc$#Fr9^dWF$&zQG=%w#G8ezJe#2EF(G2--Zs34T~NeOYlg)-h@J|kjaZyVvh zL=?Q##E)j?H`_5w6WU~0nlbey)Koqy5q>CRF$J*W+;fl>_s-?~{u@)MP5jM&Y)?Aj zF%6H~q#jG%gn65lIj+zR13-V1Q)Qb{y@Z5(k|v8VhZ`z!odc0Ln1L-=rj+;(zT|PI z?r=C;O6ul%y?ntZ`et|0lQoXXUzlISM1&Pws|{?!ai!4NOnEEF4bqk7Ky<)gsT@XgM{7b4xVJ2%7rW{8`+-za2*_A-NCnF6OL2&Le$S zxGkJMWdcWx4soL4i*KoZ>i#D0-zkeQ{Rn2_ZU7`HRp{4|BMe9@!scz#58kvX8;Em( zlZTl?>FvO1j$2Z-_TsY?l89CkGlm5PU0{9SL)NE+8Ic|Gi@vzqjWK&B$R~*6+FjVD z@Fz3ll8O8~R!=L16~PKgkDwFH9V^;H8H*17IFY1U5CBnfsy?4U zqJVEJft{$3;9O>ut(%4os~UqMH$qRa83*jU-Vs@ZW=#cd>H$(~1aGgRDZF8x@uZnP zl>B;saP^=!JDqC3aPp0^h&Ns67<{Z@@EJec;h#L{kE~v%tc{gH9-(9%tDULReAsRx z3x8pyM7QkjIB!{1hDyI=LV?yCxbIK0Cs+eOL z=A(?r74yhR=I(ybPJCL5P!wr?sERikM6Qy5^L|J`mB2%S^*sE z@er2Ne&rEU`Gp5ZMdIJ|7|{;|WX44FdvNcVV;PQcP_+@rm`J--0rI~JQv3xpUGoOt zPI!u%}m{N}SLx-t|0f_aw;7ORcE_Y_?v}CH9{Q2%0JE@DSGgnMv$)bV` z@*L&G)Bs}SHj5?r!SKsv9Gs-NQphviKb~U~p9Heh!47#C;T;m|PglWjqP)*2!>h~5 zsrhy66Zj8HgsCgsiVx3C1Y1s~Y1@N#+tZSFvko?_dx{+otjT6R{iFO5px{O8F(MIo z%F&(llFWtOT|gWcFhHdWLfQ2_gzrEXNI{*kM6+)%T3R~bsPX(6c#|lQ|CJ;x0qs_{%4gW}Te$!D)z8;(~T!RFd%r|g3JRIB8pzon~S`J|M_8go_MNvdL_1^+fdgo{WUUL6P5IFLZruBcNVdz!jhQ zjR06aK*)5}uW$Z0X|M|y7M^e?WEc_}RcXI(;WYgou(m#%ehR7<`dazAk?ZQ?g*!c4 zqd%@|Ot1~ZhZTjVg=}sAxmA(E&+}~r>^6o7SbWkM`Q*CIxsRWf_1vhq17)^9YKCgH zOH12#8Z5NcNuE6AZp?M7Nok6BFVFw>?7nw<$jzajVw7tRFt_fsUk4j4y_ivQZN^Sl ztOag4VSX{Id;{T`uGS%DG|;tJJMGJ8^NM~=shF8^*JvB!dEHR(W z-8ni=VF<0_d{9_bc}4QUPt!J2Gj%D#gU^BD)oTWB=Wsq7p7nWEDYRFa=p&zk+9QTp zfzO}TODsP7^sFuR+xEQ)?9uUwSmPTDor*97m;#7a2x_~Do3P*!2FG@c-PGdPqaB4d z)ni>yj;HpPYG#zg$9SxQMvDl{DYkiPgutFL7~kDGk>;Xb;9Qrkcsy|ml74*9ef%_1 zqiw=sSeu?>TAm10&a;s}tDbKJiOWTJliEk{HT!?`TZmxSE+Za!ya{mP$$DMY5zML2 z<6|BZ{v3=}FFm`k>v+zLO1e=?->`f@q6qY$e*cu6QY^t^*y1<=43o`W4PyBZ%bv{D zO;#xuo+GkbSJ*{9$=bC=dU7O~=j5ojw&o^?$Mp<3wB!WtL}cu^AKlHNPB#8M7$f;m z6LUGTSY5}sngqP27@g>5D;EIYtEHgo>Y*E4v(`1C-)j#V-SL>b@tDv|D)6g)nfy<$ zO9MlxfrP?QLQ@BOI8^DCJ?)cI52wmr`BB&VV~3{V&QeS!b=y{mP;=NV`v>Y)6T7I^ zgRfeYGFiIiCoi=RS#Ui{ob|eOKcK<~bZIW8S0@aQcWIQJH_U$nrCLf0+!9;TK}X~v z4rWu>)qHIlAmPXHBjizMV)v>EQY(4uyPfirQ{Ih9$0OG)0{ z2gVvXM%T=?F0*@x1=8b@4flQ@2hkU;afc;r0D!CKjgA^i8@NmpC1%}`_?#CFJM_4$ zX@{vW7p>`j|4F`$a(VO5r5R+X(!Bf;{|ns?*NE?tHQd8(4|Ep-{yjb!-O#)Dvw=7^ z%~e8=vS7iA>^O4mt^&1!7wwpDa_tmBr%hgFpZiGzK7mS)TpMVSB1 zC9aRz-8?5az*m*S_KU;v9La|BEc!otu(T{nD|xi4cS8{U=Anh)bz-oa9@L@pu04R= z$wf@6$0ZHumK&%+eQ`D#JYt~^CcwcJ?J1|(f{qGNlb>B2-hJbHc9bGrcHV7L;yz(yPcIDM z%^zOG9%?8Oj-m;umJ!Yp)cC0>`*Gml$>FJ-1jRvxIe^6OugtaZrw=OQRAGg_?nS+u8V2I1$C}**iM-vTfhBQf_*PP)ReqdN#de}9z`iCmb|$tw+E{CzUSbh+R|I&y zXWAm;Co>~Iq-u0$fQ8zPDNAU8gNOSldF)93M(BXT6wwBQ|1^}-6khcYJY}&7K2$uN zSREa3-Tv`e34BH_#;RVMLfbi`n)gZ7%q7FLRpn8nN4kfO(oT=+ox*8r1fW+Ic7ING zIxo6fzKvyRRJZeKOa3VhKoax_x#w^Ocm1*~jbHzF+^6*1Baf!jp;eGtanZ-@!Ne(9 z2!@mNtWV-}61ZR;#NY&9!tESR1wx zpLFWj`)QeY-NmL#CB5i7-VZ|ygKr8Zp{D0s(w~a{?r7P%x$`~+7Ii*YeV9*2fIoXL z8s6^4ty-$}h>P9|u@Y`%8j_I4Qa&Wyz9VH!H+CM`bvuaavG!9x`N^G5*U>cDrodq> z_no`zH;&x<9kXoOx#SQtQ-#7cANTvF6QE_TCd*}mk3YQqLd2-6&o*r(gD)<83ZZ?0Qn!&CL$*D;g!yt&u_=QkydO~uYK`f z2GOzidT8N2s?fA4H)OrmPC@7#o9Hs=R~B5FJLTNn`tGj9d3}fT|78%zguxP!VYDJN zZ6q0+vG$R(&A|_L$cBzvJXg2bZE`@EL5#aa#Tx&8GZOdWeu2)jf46_%*P$@4D^8ym zW)P8Q!{ZY|;GYY~L8^ig*WSBF2HiNMcz5dnY!S0Ad-uWny>5>v#fcxj-{PNHD|;CJ znhIVnd?o(!*Pm;SK?pBl264rBNXiaZCwWRdj9Y2nL3Xpoq82>pCl!h#f-L*wW?rPL z+%TyktzRWnXB%uEdMo7Os_)LBvz9XzB=d`<+zRs+sg>&$HDf+S7q&J0QWCe`NRZE)58`4Aiyh~2 zFYcv(tj1tuyi;89f-^R_rsVb&dhPphuPe$&GPu^cIU1A6Fq_@jT3je|mL6JM|G6#I zrc%vrC}yKP$E`NJ?23m(;lOPOW1M^Zk>&BP#}4U=ytfhRIXaf1u4FJq?ea9|`|KQ-Qx zyiA~+Gw+xQWd}-W)ejSCCdb8>RTBx6l>GCIG0%{tACFk4JXfsLMxuWn@idDM=P|d6 zjI79_Z%^hLoH~z9k@i3L^Qpb0JW=eeZH!xKP+4Q`z=3ybJL-LJ-^3*v-*H$td2pY) zY4+`V^xwh2cY}=zg z_?GjS9?b9$Hj@~3BKG1!R0Su`tTaC`-k9Ez?s?nJ`}!kn$bQ`S*X+gG8GVAp!1Xn^f6@M>J6h4=A!Nwe17GDc_P+Qq zcaZV@_q6oP(8e73wpz8gORU6pd3FA;#0*l*pO&!dvP zUlLJ_?dMB2g5=ZK7P5%5^1z}PXH8$u5<-T|_x~2PGu$YQMi3GYZVY+~=WE|02O^hR zzIN==a<4hyWM7^9^Q0=RMkfo|_W~-n-c=FvLB-oh?eN>e8iE%_HDP^u%^G-sb=Uc_ zed;pliU-}+G{H*MSlNcey=VFV5cZ!@N&kP~|BozL>dTEI#f=+nI2wX0Eh`-5NDF6b zR%%veLzalVg>Ov4bFQsCiX5h@Yl^idPX={(IHnnM=MzQch^h9QekSLURn>B)TJ*)5|c6piXH4s$!l z%65hv^;h)odA}pnVGwh$yMUlsx3%gKRZWvPmVWtT$;G({YeZWbKVXrHWMn0kxlJ5Z z^FIFS52{9Zd`C{QyyF%T#h5Xxc_76%_xYc2H^OmvjL$-X(|-PzKfk59+7{L2{~5ls zJu%vHd6%5w^8#8DC;qD1T5JYHj=1G|{{)YO;24<}D3h=4J`(0v^Kt^}mK~$GhQCv( zs`q^7uRtClPQFfC<%7x_q|#+?8$kx}-yfQOohc6Oj~c!3-EHF$Ztv+L)mT9mon z^9I}NKVlx}S=T-+`(}dKzv%4BXx4t^=w7$)?PxS~_{GQFu5~+?i?$~{RGA5S+OvPg z<8TNbUWL1+ms?Pia_nEoP5TnkSjZ*&X1{Wx&^AYT;_8D(7rU=7{=Nl~C(%PczPyn% zQ09Cu>)i9Zw6r)%jPu(^r?twTTLv>u8o51*yx?%)zR!$t>x74ja2$_)__-DOU9skX znR2~GropwqujzYzZuvVH=RfN4&#%iYsN3s#LV1p%+(()(4~{dKQq4*`hMqaIO4{=K zEjlTO{#5kiIF?3C+{HQ0MlU6kemsxif!k^$PcTNE(bESvC&D!jYe)?*{2i1#;#F$# zsH@bnof7hQ)+#S@uTko?Zx;_GI<+0(I4cx#Uza^`qT-YsR6zi|tti)cAY<@zS5N<&n;tgC zUBf3_wp74O9+jD7KK$v+KFl+y)6~1O4f{hUE7a{`2XZHQy@mJXxYB5=G1*y;(znuDyJu3G? z>t^;F_PvD`l$diexbULGJNV0dXycu6fi;OgoE_JO6^ly%9 zT!@FADj7HOx$*kf?}-yD&Khd@9Udhs#xZ_%9(}yG7A6tzT=Wtj$ZOw!IhS$OzDTSt zmdN@gL4j1_(80KiJcE=^?-Two&D`z-Z5M|>E2(p5Zr(Tk__L)SU2RXDz_#vj5I1 zl`qSJ`Wf06GK3#nmi>5Q3G43{rf}H9iemQ6Zg}YSrpH!ib~#=J8V>FvB*nz0#zGLU zTq3algLfSDGJU|5r545ckzvD&aAo~hwS1?yopf{Pd7tIQy}eTEu$AIoXPLurnbPn5 zg5!PzA>Ux3Lj>FucL#A$DVu!TdQAq$f`{Wl@Vk;pseHu3yc;jE)e z2SU7&_D^)d9bRvz>55B;K&otUKe`3L*3#JhB&<{d&d>kPTWOV?tryAOF{WE5B>zeT zths52T-6J7U?9qc#_d3#(?v{?PMI7Ab@I%l!{iF*&2QF z{I&smwKl?y@HG0es{3yh79XHN5PMO^VR~l`<^s>r(K#S!BgWhUu;9#n6&2G>!d6V8 zZ;`X&fyksg=o2DE%f*;mNq~(+A)TK|%{vC0LL4RoVbRK0_<%wb@pdbCo9x_6A*kib zo&b3aYL+t*Xa!RN2v$VLxOsqI7H~&V=s<#ODh(y2virpto=El}FT_Ry1+gCOrz+d2 z@Hm1jl?>ZEqlwHr3bbZF@lYChl>AnhN!jSfQcpCTRb&w`Ef8$B097I4)RWMBGPVc6 zCV3Qq{l}P8jFXbEHT~!iQ4YNy{qHFn9J@a;iY_Lh5~;FYrn1K%vh^Sf1HtywFel;> z@J62TPX$#^nB@#GEm3$R${Wv%bd#7r2+z@x0iQTbJBZj&F~uZI;j%(8C~tr*0x2U} zn4-_e4hUsa1gImIuxDa0pf*rGc@`9PW`8SyiVnLwwVR5)CBQaAu;n6I3UiZnyme|a zFhP}zh*?K-HR{-Oa-GeoA{u7Xhx}$BrI=8VPQR1f407t>9s81Hq|&?9^=P?nO+hEK*AqX5P<}vq_(!mfc-K(4-r}4(-cVt=@5r zga+ND1_;(|wDM#ix}Azm2}DOyWjjci4iT0Q@#Gi zd=k|l!S4QBM~$skGpmQqVgLQcs+a*(sXY+#u|CQNsrMVX2mIAB4K-r4*|WN1fmr?@ zg>0Y^k&quB2!P5&y`-V;DXNoHucTS;y+ha*TfIA=8P+O*!w(OK|fLiw6w)` zy!|NZde(uEX%RaDsdumY{UeYFz_KQ)h>B^Y<<|G3asz?3m=cWubTPf$EE9cyyFkL{ zB!6UQ(n?!mTX$XPXgBLoy&yb)u}2I-O}ultr*m0n6#IAJ&(l#-TCbFcI?qEf2`Fhl z3TAVSPq=Zmhch07V*lwZprNcTUfIx%JsyqgkTj$@RtwE@lTGW-?(Au7?g34w^HOZ* zv_G~%fKu6BuHX$j=xM^C-+<~h@gxf6JS+Wg8fk?Xp6LytK0sHb}wE(_vz*yEbif* zW{~@66{S8h1s+OpmrQ^$QEDmyu-j}x*fEq_28;*><7E<@DB0(h6gnF6<_{^a(ttIA z!XJskU$Fwr8#9yvQ1}_}Df9qIFdU64j?V>?6a7)J69C_#xNfmXen0l;OuYBgqWUo@FXetePRC49Whdd$bztjR zb&WZrqFUoT2BB6B?_&Ynp<*yoWzP6pQZPiL;aWwQ4ic^gQtImfdSXmHVb_-(t*h6u z_x~vPWY+6v-BIc7d3AVj&lzC)di^5@%;ax{hdjAih+M&qi&}S^r)~fvfSf`bPA6y# zDl_aoa0|V}^PNNldt_f&u=v}HU!5H0-32Phsl~Lc-coFf01JvY84ehG4W>T7yj+B7 zpA-Qp!e={$V(dis-f6^j*v!`@TT=N-aN&Bl3oV#4g>X6u#W(*f{9uh_@do{$}q=Y6led% zO#;}_3+P(Ocpmlm2wew7=pc$`JkLy*iCO%s1Typ^#xtIv-W$EYL7cH(Y~~TebA57@50@O z)U*>yq=8TO)NqhXFd~bB#;i4n89vm}gw~%VRF7)`^yMw!VNA8|bxH`FV{r1sl zOce=xLHoG@AJ?{u)9t|xi&BROau4bEqyn)Pvs82jxVIV5L93(k6`MK`(^DRtR{a0c zABn%TbzVGWhDH(aQ?^4lX^}JXvWlioC zFL(XN!Db16gB38ly|!x^ed7pQ+3ePfqv(dqsBFlGadgx2?}kSiAC}GyW{)pOpMKci zgL?qTO+w_JN+Q{A;BZkYn-ukG;6H;=hKL?}!1hvLfWwhEM1LcZFG{>x>G=X&qllcBc1xBDPf8 zf3|`;BL(E4it;mFpcR%;FXnf|H;8DjisS2E$SoL2$E}`=Mq|dI6n?=rbT*`Y`u&{^ zRXuy|e*Kj_1NXkyQ~Fk9$!yF?Ss%PCm5e%Gx)|Xo!uW!OO0Ex%# zM2>f_PS|0*HF!t52j5~*r(~P%ANyI*g5n6U7Tdmyo4*Rbe0`?dxk0+}?6^Ji_%g12 z>vQ(8<)-wM)f?ZRmA?i1E{}C`5?#4zlJp@-PNWkkrTr0Bb85Eyf-LP3lbHy)|C>R; zYwZK4C1OQ}6BGXDyi znls!fwUE(L^EyhRo%nRWXtUSV!HB!XHpj1BzWVys{c@Y|D2a$XoV`x#1e+KRaHVLCpdZoGayzq?_6Gg@$Ue9h5~|TEF0xIOLQI+LOAniZyUzzcd+0GG z*lIMp5`J9U{P4Tx@M14hz^lTO|DsHZ*!14XduC1UpIwvhp3k=&Wv17o{@vOe4>xwo zDc@CUZFD_p;GndQtR)oypNBy9(I+BzZ+^y3tKQFLhpp3o1dWuYR(`lE8eWO@a%Kp+ zKUYOpDtb8Ifvoqk9o281Xp2TRxz{ovCzOlpCYCyKq=( zulAzo4%{}OO{FShWcpC7OdTgx8&8BVBC>4v5hG>ZRRu@f?iASe)9(qm!LBF_F(*D! z!zdf{V8Y1}QJP`Ka|>0T$b_o|-Q)K*HY_5cF1e|We-;WJ!ZY0nem!7>5l;OuTzD|* zgWtltIE+^bFs;i=*S%mayN}s+f7PHQ@g1&jJ+DlW!Q&h=&ju;jk%_X zx){4Q+x2kRYW34qv_lrM?2!A5j{Hg6g2 z%wpEv=BM%#Ch=iw4EM6#=l>k3K6|b*K{{U8rX)1Bj{Kvf>>H&Rt$K`atfKn)KF7E; z;Ihl@{3hXxlKW|W_&2&)m>w_9u&xzZe7O6V(X6x9{ZDiC%KA|nvDaqZFUB=7&JtqR zGW^D{(gDB*>wVy~U-AAZchRASfhf&zCdDmR9vA;}Z_~kpqgy|zFyX(Zn^aP+amwj( zfsDd+?@A1%loEWjW9zv?`As)cvhBuaUWT zDw`)F?F}`e&I*~<7u`2P>@&^z{Zg4tXH;bZO13oJ-mZ7JYmnGQ8GH;m9F3V8)s1Cj zuE|Acbk58??RzY%ZX6M75q!@xTIovQ1XS(03&O&ENx}cDf%e4AZR|yO#QR8nAZO zjBMC)4P0@#+YjjQy6d&CG{2}R!mP}FQ(NnGN4N}>+_4THTf(yxK*Rakaw_GJJRKc4 z23*nIYwTU;m9~c`YnWdLEJEvH*e&)O^VqEe;BK~mL1fVJB*1x;jCCea6gz5HFR3ZJ-0|B@4%mDPy55( zUHv=Z74;)S!^2x1pDL8Ws7*Qstg;~RcrwCKq^Y@LfVuCo+gI+JQgg(q4gZ$XoL@oK zzaANJqP&3)Z#ARiKFjZ*I#Y5Wq_g#gIHTfc?!Rg1zM`FkS$;pr8o z;M)&hpP!dCJfU%(J)j**is0A2RV9^u42ExgYP;Q7a@7z#ypdZcN5QmdzTnm9sJ!Sw z@af3zBN#|C`T{LeA+yYK*b@GbSYov`rjnC)dq@Isw zPw@vQgEt!1C}+oBHBDJ~zw+_5^q0+)dhR2q6_1`hYMF9GlrvL0SK5akj)rQC5Pt!C zA1u&NZs5G|ErPGE?XlBMmkO@q-so(aEPs5t+I{!UwlU_Gqo`W$Xq@!&%M)~F zB(SK*@G|hb%SQx?#cYiK@HnY7qb2cCn#{egx`~n>PGL)98Wkx@eIP0R#6@$!x(>Cg z5hdEantRY}FbVA~0_8BT7Ad|CUOD@U8%J4SPza9Y4fXA z5s}Mf+cX7}ikXw`IByfQVuyF2;ZvCNt<0Ow7jL>Y-^^we8nRVliGm{pBw2%N@hAPz zUs*qU!Z8Ul7KQW`sFCncO#wsKe)G9GHBHYRD}ZA5FMaY&pY-cPSnl8S!&=#0_G=-5?6&F6Pp4EJF;Bg*2`HyCsE@86;+E0Mk^$TyM`ptmq@RRA2lE z+bM?cCL#QZY5#o(_6@2G16<%AOa5W$Q3PFlotWfkWcj*t?8x4;bS`ZZeu*(Dv*njD5 z7i4^AI0@wRW7K@D@qEWcs1BErDqt88S?^B^nKQYEZMe-{%#|s{-IEpx?dweJp(gw$ z3xG1yU$}em_6BVf<*zJAnOFlJhBGpTplM?WKn=TO%w|U6+OX)M;k0Df6?Dm-VR!&p z{rrkf6dmsm=m%2N-z<@>KCyO)wcey$FW2V&BqFS}(k#1}2NY4nWLAZE;{Xrq27#w~ zA@2e>$AT=?z%18iCdC=<=#-IY_RZLi5y;(t9iAVZr+ z#*jGXZMvp#n2wO7#qC~|+51y=-dEr|A;Y0Hz)d z7Pttr7qe}bWxk12$;rsQ;8bW+ny)WQiAdLsq-*Y?r+U!Wz4V5AKy>eUTL}uHQ|>V# zFncN-%q@Qs1&73DGiQ(kG~~`@rrhJwV|-+%u$W1}2L$Wy<};6FU9#xj&GpvWw4BN0 zgBchI5s)&QZ8;#l@uLt|Jk>aZy{uPw^S7&WT*P1uUpwa#XYVA8Jd-QbWa2?jCt1ep z!&Y=gD}%hw4K!`yp?g~yU{6!+nPGZSvHC-mZ*wMbQJ$aR@lKq%*IqYh6cJ*tI~A>* zYR=_mD)|3P&!J~n1?c);WZFDq<>Hx^BwK1yT9yNW0qJ$4GN3aM^bGybOFEACB$c-> z1|g$9N|%df=-(W&Th9DJWyc?Z`=Pe_IFydsYlaEenLjSISm|)mKv~%!`aWb_OPR0) zeE9%{tHBvghDH2Kr$n>e`RqeYh&WXGBYV6*o>S0@!=wmQ2e!&I+e=?u4A{1Da5-X- z{1fmNX3SWyEKp2!0Yfza8WUX}O|LT7MEwKz-xF?ViWu4`=p~`zNyLPuFs*e-zAj9D zD^dO4v$Xws*$WrT=1J_`bhv|%wR@4hExEvK9eZAd`>YlI>0j~FHaOG8?1%&*GGM39 z&{O#kMi;$(9ST^M1*rSm5zJ5XPtpXLf4VZoZJA$(;hSpj`H0z$VsfC~1OqbDv{A(( z<+g;3@DQ~TfpOO2(`U1=W3wzL0?HeO94Uo^rcoIL?gAh}NJ>8FtWmrGV&1X!W(*lIjYRAPCmXR4^E05LrH|+><-$!lCuYM}kq1n^J zMpNG2@_XfXY{Ja<>= zF7k*6$D#n?&)sq;K8+&rW7=zj4Nzd2(f!r*Z2{vELQWz|R`db3b&^#kcu~(z3z{*z z)zh_g@5`2~J%1vc8T2&gBk+(_=tPj8CW*0Q2AP`QzD7|3)?`Ea*-F_=?L~#&4^UG4 zz2an63o5`Yj_Wj;wRb0KP&pqx$C36&qC9AiYXMZPXs8%Kl(Di+qk}|xoI?R%_g3aU ziE<#zTi9wAzx*F8lrWD!L@f)GAWVA>vSwbVau-+-s449pjMET3h;bOpY$Es&nqgiN z&M}YhBlwC9YsjpnG)n)S5G~}bKf+W=<~Bj3Mls?(RhEI5jgcUHNApF%i;b&kk?1<| z4nk&U*Sh;NI><-akGp)pn$LbAmEUc>l8z@cJ~MV=4Y^&Cm+gP$1B4aU0X4Z2BzTdI+po@JtiGjt8l$8?4>Aa1yV)?W zzM;mHnCtU!V3rftj~vXuAztBxh^9m1k=_s(`Xy`hC5sYoQ?rp92T}RWm`f$WmG`l| zA;?3t4cYTMA`gT(9SJcW=0w;>cue-+`zOQTGE@a=(qOK6m`VtcMiH_m|1vc3%$#M~ z*}j%ru3S~oP_qm7{I^;*4{=Y-wwhsDqsHa_$qt^8+eAw9Ue+fQpV*(>I~A}uU^$;j z%1m^q0-Dpn4^#)jmd}fFrjF)EX3|7>wvUKS<06PF=`yWMMF3TJfU6<8gGl@Ebb%v{ zC)F}}lTHxi+yZB0HmiJ1)+0IJN0LT%Q}gi1a3X%(;9dJ&6ZL2IKonVqA=1FmnI?)k zVB9BKG%_)N;2~q-Ht!pCV6f%M&0rymLiL&W$TVA%b>9jNpW)c-L%W-n46Wqq0uOr| zqKE-I87TT~Gw#kZsJ}qS^2q4m7qe&X>sM|r)!#zvu3zL4w-U?_uBAIsZ*0_*qxo{H zw_*ggnR^2e2a|mhHMlZQP<_rk(fgm&V^XbcA<5eDgxq zodG;OqNaALFLgD2`MlkFn3=HJz|{r`hR08AxWFjXOcst_P2UQx0rZ1#zD?j7V#++m z+{dfSudY0ddN-534&gwBe`r-USyXr)37cM;?KDQ!Qqs0@b4Koc30WFcr>eSwCnH~q z*7xm=eZ@?tq0X*CcLyLkr?;*D7Z);f;MZpJ#W!#ll0|)Gp8r#A{Mz;TV&L<#s0w_6{>h)g|--%a70z9j^2q*7Cy!?wMJiz^sb0dKj_WIAmgTIRS z2Eq?6VF6ZNlk|Oxau;nF2Ha!yTSAZRy&+|bQm!zg~CDgOMrjoagRPM>)A$&(KGs;vdZk9f`=QoL%RWbQTm zhBiKmEXkGEV8qHQTg5Gt!ldlOJxO`(+w)9!p6E~d+jo$YlH84yd%&V1ePo1u$7@m|oy%j7ZjhXHR$|wt{)6#jlU4JNx?7Z}! zatSj|{>Yfy#(b=eWm;!McUbRA>0?&gp!D#MT&f|{)c9;y{M-=y-!F>fKkIoJ)nMF@ zJ@~kYlLRK(jQ>O{UZsOiK^m*kT}8`-I6wGpSL!Bd*1PGQ&7(FRM)kvkmCDkENjHsD zR~KNzeS6j;Cr`zNo$b6MCOr`ST$Aj-C`n}ItrE`XLx0SZ+ik$T#s^7O|T0YiRme%48K zF@vX*g8!Cbdds!;-lh%J?z?tAi2ugXE5B^Ja}O=pW>U)+G7ZkfICm&gdKc``TAfq_ zx#lZjozy&ceg4ELxqD2tpf(SOMd$T8c11o9KIeOFd@lH@t`kdRAe6mGcW<`^Ob*<3 z3ZB$Ms-I#nJ)xh@T?M;Hsf$zGjLwB`?i#SQ zb~lrkXHAtz_G{rg430tCo0@w%H9t~XeKhX*Q+1LoD86f~;@hum{dxNy(&DIg(zy0r zo0{kjvKG?v(Wz&u{`{p}ji~a35vTZxl?NK(z$43U3U=!cr?vdeu8|zvw>wU`V~KN{ zUPKq%vp5C`Lz{JcX3nbzMzoITMDnM#2M|9uc&r<~ykoLo{`xu9(YB~-6Be2V5wVn8 zpP?@(>t4rX+N|G^{`&8xDdo}6$MT^jVM<2MZFEhV7e_&s& zkJFk$u(aGySx1lMRejrOdh*If6|UUjfFTXTq@F1o5hFd+#e?GxVG{dg@INQ41FcN_8fb%a21-1}n$oC~6}FciViM;iGt%5>Mo6>eZSa`B`4;H>`kI zmvHULk;B2VXALH`!3;t^is5W9M%ln)Z5{`X)mUFXxB!@Eq%}YkOIbDVt@y z!?(#N4c-qw%!jJKiRZ!cFa<^ zGHzQufV*TndF9xMes1C%3!^0I*JyW zxkkp|W(-J;0w zO=Kb&#m92LH2zlr)u2^9$$B_OnkOkd?K6R4soD~K=!fr4BTE%(-lU!FAvK;E3JaUc zXk9e`Z+>v~oxd54gx07{*h{*e?fT46E+-k;Y|`$Na7fkUau|dR)Z_!P4;R&2NM=4a zHy-S&{#M!9pA)@aL(bscAW-{GZ9M%K$BI~@{JP+_^&8LNt&lq*{AKyz-9eIy?^`To zh#9cB$ux6|8?a;xO}ig=Kco^J^*jR`_5X@+v5OfW`AJBdC$cYmX7(vw3Dwj#rr?@} zx%hR8Rm3%KwACt0&Yd;dqx^&8$W!lcrtRJtCKIju{o#p|OxgqR;4#CVfI4u71%m<* z*ak}vuM(6Q@x@SvMZR8lKw5${?o-bb2h=M!a}<9Ln1lT%V~}Y7Qxln#m~gszf4AVa zMa_-uF12Cx0pXD5qLpOed*5$l0z__Y3Y*<6U^SmnfK7q&Ofj_1m*DYLZNkbRv zwg(u#G~_}}Xi&q?j7Ew8^GX-1rY%u)^(2!?TkiLhwl~H+a7BnM&azFZLw{XIK6wo| z@gc|nI*cvM;Q|{!GEx zROYxTtGO$S1EK5V3OB^L*k`dEO1)e=So;?wQgI$#;s4BhROB-de$EP z8-S6zm_~#H&eT!(>KyFKfNq+bee#eK-^F3e+=d%>iGrQ$mNN`<-rV0svF~CZR~?qK zI!IXp}eN$tuwxrDHEY#$47&-`QD4EuEEs2l|*L+fA166}~Igd$R%AZ5; zC9Zq!H)QyTqGHjXyww-k^yt!0Y};NAg+4%ES8I>CDDxR=#~V3K33sNC+m2FjK#-yH z!)3XP+K;5+6v>?ZJA)IJ{kDW4KPuw!J=eO^sPrwn?Y0aNqWd8h2M9HOo3=e{{1Wv1 zbdau(tA|SMwx|Vx*c;&?N1;~L8nR{7;2Zk~6)hmR*g7U{Ve1a~&L%@I9qyaeA&d%} ze3a`<&y3juGqf+Z@8rXGm-J_Z{SJ)q(y6cXL)M&gpSRd;%7+-nM*`&~=7B9HAZg}$)mY_WszA<8N*jw#DBc`x^Uthh8Ux8J!5hZ8A(Gg}$Lt4I? zb-AzT-C`JwYzVS2w29LX;MDJWGN>k4m_j#%Z)?Chv$SpD(U;v3UdjYZ0lQs{(lW@WH#WXFf6qA%`&K8BGCGhN4P zAD>>hldI=Mm7i+r?Mi6!t|9Aby@=%L59jWz(oy;D^p?6|TzmJ;-rp5hawSsH>EXY> zzc23H9cT+T`Se3F&&slWYr6mUySJZSD=c9OpKS*16%~KUAu$8xHW#>u!rMz=0^@dw zsM$`t$~`XjOEk82rTPIymlv{+l(bGpze)JHPOrwhI@0@12B}Q#Ri^63?Nnex;tv+* z&+Wz9s4EUrI@?_^@E~t{j-P9;(aU?x|RRxju?GOSa6OOEjxO3?h+6ny2*dlv^4sfG`*C98BY zIq>ZG$CltoMZ`tr>PsKp3!kM-0za0TF7Ive`Jt^c6tvK+9JmQyL7uW|K0;j^!*~Px zidEc>NgtI_<)smYU#@-rRc9-WP{4BhUI*|9K8S^;v^1!E~DmHg@or;nk6k7&NraZg-JCduiO7&|Y zU)XT80=EjdsZ)K8emd`&e{$?T{KJaP&Y0srbf*v+&rZzJ6n}*<{Ntrtc*mAr8Be~{ zz2|<4;xe3lea~JPcF`%fmZ&fGf9am=@yX`gy9SDD86(&XB+0E)oERgJsem4 zTU_ovmhzSW5Aymn=@@*&Sr@%!`u1(yq&UU~2WQ#HnRZM2Ii}*J$NAD0LDvI|jPwV0 zoxeEObn3T6rF$d=w8VGi88_9PfX?P&YiEY6s0juzXY`raMYd(4cf>Xo&nu!g!x`K| zNo||whqMFWNj8dsCLfsNbiS2?RSV-p#2W?82&F8&c%!`U;k~$I_+}sYLD;3DV}&Jc z)@IWu_6w@r0*r_4&$GFEF3lO8d1rp?h%0xGjlsK-p9*tJ35C7m%#Y4QfoT`Y*izBR zLgtt0V~1~rTZqgHIN^@G6>3Q@d&jwF8Dk&kyaCk$-IZ2F~ z@3n&Pl`Y(E_#-9a(YjD8M?=cpH)A&*tw*6PNBQKT-G#IffpSQM3aM%2-2gkTswTpt z*LiolHm{EGA>g#OW7@c`~gWtLS(__}tZ-RXaGy#_n<^Ct$<5&?FslB(UF zxrUHR^tBBBC)pi8cj2orT9-Z=6-a063^)I}XnvN_-1@;;e-*kfCv=L?`Gz8&NmZ#2 zduyWVW`03ld27bj1=&r@>B@05mI1oR#PPAY&r0l+)!9%?9Qx(fbx_S~#El`R_gX~u z@!SXE8113YB4}U6VMKdXz1u4uLr?ala4_kT<#o%d#d)wqZ)XZwJjb&mF!#-JhBix`FpGApbnI`P2D@L0|w*7#D}% zsEa1#Y`lBbqio^z@cs1}FtnCR_52=Goig@Mnkg~(?InAvG!iid_;5Z0vCh|uboNiH z^-tP;JzIyP}TQjVj`y_~0yRHRq?;5PPOMK?& z<*d?*N14&9fq=;%>rM@4?;75-D%^fTh=)yqSpEGn!fq^R_FbM zk{i!{=h=CMsqAb-)W|x=GcQAxMakgth+gvUtT3fB_+ckk3N~Q)jdCWHZDc={G1mBE z(&5)_D>yXkAhDdl$X@s`cYJ{`+>}Kavyt{HQ~-e!&dZ{B#G?$G3qAqN3DzRZC`u3O zfBDVtOrdLzUS9alfEtB%e{45_F0TlCp00C{iZs{=&scw0RVFeHg07%qq+-m|LqPK+ ziYAinmY~7BDd@Mt|DpwV#)vvrD8@99<1?wUaROO72@O^~Fq>qstAfs9QPr}6BBYRp zlU-g{@5QuQ3Y&t)NO&M_NViOD+d$%<5@>@fmR3d%0U0Lvfy>k!H=3gu@K zZ9~M483XgDSV9`6z8?*SF?;~mE#TOJZ3{7@*dFMkXO!ZJ#|X03LR6j@Ed?i#lViJq ztWGMnUXlO{MGb;xh&WEli@R@(71Gg}5U?Nvf08$hUdSh=d=_GRfvkyN3c~?eyWSW> zmyjpGF%mLbD#?OQfms^%!*!-A7c=M&&;=+VITe~0_i85T+$7>K4^b?^vPw9&7J=^` zxlT+C-`@%+#V9Ec1NKEy8u~O5IJf;w3khSl56A}VGqA)X1FgLCZBi0$n1rS-VtV59 z@TM8YGHmTXiWkF@(pm{%s3_WA&_X&54~<^41Kw>yMHmAP9CU*?yOkej>Vcy^MR6dw z9?^xb%Q<=WO1Eh7cL~5tYT>%pQ0^Q8u9ztzU)X#t9Fdm@%S%6Jhh{%PP57fzK47jc zD~Lpx&i*qGB!#ymIfcY?#l+GWe3sf0c4-+~BS7&*>G7u(mDSbV`(^b#fD96Fx<41n zK%1VX|qEVRy?53IQ^wR~cV8hXm8=zt$H8SAIETTOND#SY4XAKe+Z_!JKh}as5 z>>5-SK8M3n0;)_k#56fE5b4*AsgExLqsBfd89OILm5bwE1YqxqaKnHc_ZQZ%gi}?* zY$auj=tp;XU~@A#4$**C3~*ONFhIr)&{^~8r4OibGj!0piH`GRKK0c2Csz2!Q~1kM zK+KgQ8Tk#gOddUxCC1zWLl_4Pixw^7oloH79*}W6?o{CP})46^C*H6kK_h4%pu`)sD#!PdEXJTX21au5;36Enx zJOAGubo*r8eKF2e8dx~+3!!|;Cw)#~RjdF~K!J{Dufza+8lO+gDJL@~$T;q4j#ne= z(O6+B6*y?nQsXqoxSG%bN?c$0GLD5jZ@N*10m4*f#8xaWu#x;FFv9Zx9=?VTHwff&AusJHKg@>yr3u=Yw zwIqz`vO;?RMumu}ibZn>vK%qyNH^xn2s&F(^z`F}P6_rC2KNmkz%i~eG#iI#j23Ao znk4``G%j>076}$!^!CK$eMv&~aRP2!fRpt;BaKhpY>e3)h0*iJJ{rG@pj?16@;#$3 z)B`E?^fNsoOfhIqQPH*WSJXUeu0D(H#0ViDuigF7oM?W1fQoISm5U(pHxA(-z1I-~ zXAv^Gl|uXkzThQ!#B{>mqfmFJp)Pu-QGC&h~X z@N_I5tXe{ONS7yN4?$OkDnCz>pX-;KrOWNn#6ADp4b{V_N-yxgrsq${7Pa(rmy`M7 z<^V$@IcPJwRnYiYy{;2`z596s2tXl!;~tQjy2-fBJArIRK&JQ15e?kseaExX@F43F z9*>kt@-LcWCJ8q|!REE3_%RRL5PzkYa3*>m=8}14tpNM^N%A7*$}kUmIVC^hIcjV> zP(VdzlF;)g+$MakY-{u5^j;{qnt1%o-G1<|+{m;8hDFgkvM$4`lZR>XV;H>rN|16d z<`I2h`k%r)n2VEfeY|edZcIC#8?e6xI+tEy{{Qgx-d{~@ec*0LBb9_+l~AQ>=tY45 zqI5%(B1k|$KvZl;tb~Mw5I{l^1EPc;s-Y#VzEI&?WWgv?_K~bK+HG@J5A|H zd(QJL9f3+rMvivzr^tP?;w?{;2aP+$8Sr8=_(lAm6yhaY*sh!~K_tJZ{&peK`Jn5}x$D25y7teKt5s zsGblN4O|!jdkZC$o)2BuT{keZ_+FSZ_7PtF--&AsGfKVIQAski!`a%+pWt>~Y4+SG zw-M$2vG{m%q-4^_g<&K7lb-9-n8}PJ%mAt0MPssm=RlTywTRS-lH~cF zEXPih(EGELI;|-ux8c?F6MR8%zyysY5e|^y?wQIIvb3Qc@^L*2(uaL5#C#k=KE2zV zwN@x)m`f#z0Le3nd^+%FCIEW?E_CrPX~6kCLkuCW=CudMOUSpGgp++e!@IokTYdPu zJ*#wI@YqEIyAJex@VJq+(6*y@zW>PVl~0)N-?(Yg!`anIupgwvj7?rqIY5xUKprll zHVY`FQ(;deJT}Daaf+67ayXK?4PRq|4{Rz{7y&%;w0N(UHBY{>C=s!Pc4qlXJLHc^=1-T#D-`I`r6E#f4 zbvu0=hWNbz0~r`Hc8-L#aKHwKcfrjD^l#Kpi!s?pd+HY2-hCRGvwLXKi|L{uMosY` zf@(W;=7h77+GD(zILZ0u0OU&|wEWs}k=l50;d-y zb%v=i?|5vszX8wj8F1f@U!26uBo9u3Xu(u4G#UTdR0Xn*d7gxa-&4f2!SjCNlRWVz z*fXVoU3$s>XOmK_KpK$tmWPfRuZUl-VguMM?F3W-xuB19Owks3aTA}qiKBqDrOPK3 zHM+Z!pVg2sw1t}U5&y0IS>_ykF-pMBb9x^UvG%^$ufF&h{L+V&TiFxy5to^Amt!yQv`r@r$Bt)$825y$v;zou#_RhtXOB);FE9b?) zm;Q|q8?bP>0fg+sV<8`($t>fyN~Yiu;^0LpHY*JKWAx_TRph!IPj&Li-JMk*9II%b z296k2TfF#pW}GL%W3L_=aDDkX@9*dG?f7(!rRnGQkB+|F=XCJ^9-;sggQ7qZ{F}2a z@CYG%(h(0B-g_Nd_Ls}{?e}vdFdGQ3A`bgLL$rIzvb=Kb|QPpC(e z`zW@6#^e+gMHNH05JBLX z_hxn`aWZH+Z8b~6e26ls+xDeV~O`lw@ZbL!${XyWQqi+E85cFX&Rs+NhfH}$e$ zby*Ca1ROY667*qzb3{YYN}*zQaBJ*j+zS_xN3d;!$)|Oj1a3>LOswL>k6hJ0lZclw zz{cfrp5bAv=AI-0rqt$=NvJmKy{6#A%YXXTYinnmCM2g%uHQ+VUNn#B{#&4w)Vd?I zAr9vCbB9_xrA-p^X#I^SBq+K+zIa`ET%jgn^q*}yaT6h)rMn_sTpd1z`rg=u{JG&# z6z>=B-n-4m`jh5u8utp>N=0lW0>Lr5OkCOI_0*2~*57yDKE1v6cM2 z$FcjXzGNo#UetGi)njS}tE1g0DK}JO;f;LY$+Q6r-hM52Z{;?%_#xMQR@tsJ(s#Ym z#QiJuf>;)KPhqH~+~8G*#K7!*$9*fS6{5+iFd#+*xM~r!Oy>23Y^fThutcf2J4*-C zWAJX9Trem0SlB3csWH%SeEy^n-@do!^!A{=_ zlpOsamA58+-+mLhXEaK`Wm@O@`bY;lawxpv|i9G2^TGhHE`0XqNvMqZo0s*ih}zKjnkh-faHX z&D!zUpfbzBvo3ajQMT%k)~PdJ8|~h8UhIiDd{Fx#VR>G|^X0h@9m@Y+9M^T%KgLtN zoojMAM2l&NZ}vPK?fsih*cu&jx4}N&?~~33XqTmngMMbO%*L1jgyX5^H-L95vKhdW z2)`kRtYel?_pNHS#b@f=e&Tq6ZZd#&KXK|7oYUFt{-!JMaA)=Si|r(ui9i9EXk$S6f}U0#RP6(1a8_`N3}Y50 z2n!d6$v@>Cw1JuvCZWtzkI!rwWgt&W+ygL~+Wi(MrcUwmm`PQ6{pWou)#in8t2L`^ zhwQfpTb(PCn9=fKq-fkpmJ4>%dFR%u>dUcGexJpl%*Z8erG~WuU3Kf}tc!RcBW<%lnTMl=hT(7ufiv`TGd2Ja=+gM_|JBZwGh2M4G}LW2K}E;Z(|;=xYm1`>#FgesAQ+4G}b!q z3&UCoDp$aV>hAHw9=~`F(z)Mv6}YP$m#9>PL>|Q>nh*x%!)avfDVp1K`qT> zm_XT?YB_qw$(9DrY+frb{f%-5aku_8*|B|sbOM)4*V=8C6M=uFN$+$Sr+#&0%Ee&5 z1cq(%SFK16-)<10k+akEE%w;*l6+$lg}i4`C$JH$1Q=mk?MJ$48xOU)<%2u8fWk(E z*uf2J_TB5RF*j?gpDIO83vO zTt#xa6Zb*<#Tl=pd&w|wm45OiP`V-CFE5p-jowG1;W=cy*2ZhNd#9BAF)FdDJTNLM zRMEzh>wQB7qR5FTN$!=xde244@iKXi*pp+ajqM7D{(k%wUZv|J^GdUbI!KIjYwKbq zsI8sPJSz@*q+0*0-g55!{@#U0GzvtGzDCz}e3h;;Phz9Yw^fw) zR@8FKjV{h*v^je{yvp(6x;yWE09xjh$_@eHwX+_2*qm%#P9_v zW4=56GEBmy+BExE{n=l#9G0DB{zt+z#<6`_U?rjZp5ChWHx8i~#V`93EnXk#|9$Y3 zTIv*>_#K3Bn;6LlwgFM$X}6DgL(alS8G737Oo&{U5tZ*zrd{|(yj1Pj#Zd}98O63a z9o0w5lU0APUyT^TN9+~#o51~~y$dH5#*^KiAmp+l5H@2_Eihy&i38T95{CAWT4hBb zs6rJiga}cUIhruA>N)wST9EQxFUQH^>H;*=oN$|vk-8BjSFmOb^=k2_g@7^pH%>ZJ zr4#}R%W-=)GPE4SkX}F`Xqqreyep5D)Vl9B+|d%=BWk~qY7#zeRd~Ft#SWWDu2eWf zXs4&SKolrd>ht8cdzn%d4ni#y%uGG+DOD5U+qmyc3f<9kBezFo)VM1k9!RCT9&GJxaq(mCgvzd$8 zfS|vt_P5_ZsPgrtf?Q5)18Wqc#g*>RHxN}GTl=Ns*ghBXAl8j zP?*#2L|YxdAW2lM+`aLw>aan3 zF8LmriGaM~eeC}3mcGrP&%&!tS>qS^aGm`Uy#M}fCU zO1Fh^+fa%u*5UzgzFxJ_nf2P}@%2vY=MXmm)R#K|&!X98N&&J7A)gujfE_7LpYH;1 zHDGDFql=BQZ20sU05P9sJF?(k$@h2$nEPRc(n~001EVM2Bp6}R2CV6Ai&IBvX&i`e zCwiU)b6bOkA*xeJD(fJ*|FjWDsXd({Bp_qNtT7G<8CK_={-6hFVyZI~wb`~?k`-#_ z<=>q(k-bOAl>IGzjF)+oD)2pD7ej@u$5%SAwvhNRlZ}j`1%~f(VXo1g2?IpNit=n$ z&H2&6*=K`}kOqy744`{pY0U62q3^H-FO*Bki=o;vdm8b|q5O0Q5JbOG3cD*C*+;dd zWi>DFB|Jb8MTL%3NYTKZ+|CB_$^X&#WGQA(XHNeJBb=P>d`@A5sOhy@85sierrb;w zb6Th{vlclT4<1L&_FTiq5gCr1^eutVofN3CO4|B$YA$z#g+X~Qxnoq#4rV?O>9RbC zT6z!Ru9+T<1bF-!wAeho<2NF)zSEu$q8IP_ye{oaHoBH*EBO!aQ0CpMh8g>fCD zJG|r`t9e6fD#Yr%eTge3lmrV{t6jEW^|!Jd46^;_8KFEz?C1amll|M09#ZAiSc9 zX{iJdjZgJ7Lu}0K4WnXd77lk;G#)`b4=!12mLQ7}^-9LDU=ZB^=0fA8MJ6lBYiC7q z8J@y2!x1U>z- zthlez?@w~x<@5X=LCzE+$9W#?p}~@B8ATp#vgLsA)pIgGO8xjyd{=4m27(_7Kb^1h z%?yfiZH(mJ86_YxNH7HuRSJQUAK6Y@hD`EQRSKDvc>g1Ev#$sGoW4Cu#KUZXiUtuD z!ZF#Q$5KRqqeTuTrf9uTdQm3LV*|Bhgvief8n#f2xT}&MRoo=x%4i|V?h=8-g8=C5 z;9-AXrN_?@F$sJ3y@vV+l?9EU6A=x$9EOFFF`Ywnr9fQ-O!_Nt`rT;5eBH6aR_mf?W5cja)9vG zJfh+GWW)eysx2Ab>zet{>cur0p;Eh5Z=JR6KeiL}b)!n!;%l+_y^8GTG)egls4ZXC zZq4)Kk6hSVhO)q>>jT|MM0eyu0}#x^941@-sZ&EI`&-Z@EvD*dRPg+wT$_|UFU?>C z9Jbccwx${}(h<44psiCYFbZyHR&LbwZ>d5xTqZv#gz2M?-b-M)0jKqypcY6PI^~T( zzPr^Jp=c|$9Z!F0{`%max>9ab|>$Fv_B=)>RNCq}W?2_afrmY)P;kKQ-6lSK5foCj>;~Jfr(N(O*U; zkq#TBB4@|jt+9DyGjK@TTFVKG^U6E{G3!n=X!N@A^ZS2R%(7 z)eJ?m$%7?WUgx7+u}?J1T<;s7l$>XWNGGvqA1lgI3G`c=h&II!v(}$dlOM^jXprt_ zuumMy+M$!{FuS!a0R)rC&Ufa-Hhy-rq#v+FDfCFbOMhnq<{Z2)?Bf8cu#f2%u^L%8 zmgSFtf1J2><8%Z;3+H;m&Sfp#J3x^}gsht#FkibLe~4aS|LME$XAqT|n*6^u&ff=P zR`YaU0`tsGp9@V0|BH0Js5@JP)j}@Z53|wBUv2gt#n*~2a;rbP9n?VkvzP3x%+U|x!~aB>9o$s zO5!k0SaxiRnH+A2dht|3JsjX|^Q-7cVA<0{hKm8%t_Torq zj1fAL$~d!?QNz3apyv8vKFr+iouWCSH=rVQjWHjg7C_{$4EZmwoh$*sun_n~8iNE{ z*z0l1+UCbY$0!)uE_&(`BfRWmXF@0Ej|pK))C<`1W5Kg}u$U1h|G z7#?J(ce0A)x+%g9Byv`HXG6St9QP}yY*~g+H|Nr}eWd%5YkE6pXe24NaZ)P?9zkSy z%+n)4|9Bexr?G&(ygjS`D=Z)$`Z6%Q-r-3bXC{@<7+^B?(u&3SH!DQE*H6UKDN2gu zG2?AtWw&p=GJIYjL&YOXO%1k&K4p%s(C`9Ou+LCQ&CHU-t3@d$Ck96 zu7dQPk+6Zs?8ouy|MPs8&k~1GFH7@Z#GkB~W;Z*-fYULV;z|3kcPK2Nic zPxt4()o7)DxRkqZo~ieaP2sab@h~If|Be?h174!UOVAK1I+zRHcsfE$f!GN(Pyb1m z3_zM;bGJgP@eX96jXMPqK2{Aah0tNUED?c-2;Tfvs}%ZBkk$LVjSug{KM+)zPTG!T zn!QSTkodMC=TI;Vv`^>x-0`8>59v+2 z=l5YiY)efN>uRKPxMqhW7gwa1*m6BO^QT5(|J&DnR>=R4zR&C~Rgln0KJxa)AB%)X zZQ4)}bgh=awN9{-L@ih(8U_|TEd85RBUj=aQXr#bIUl5Vy$BOwzM<_^*vFFAYSFU( z#H)@N2dx->d%OL*)%hQLK7IJLLoB386E(fW{^nT5%2(4iK%{n7e*=C14t7Y=d?DN5U=^64nj&0bU zEM!WjFN5LP`xM~VoujwEUo&>Ua5?Be;+eSZ1!vTN0S_zx@*IxuHu7G!Kj&fF?)di< z!zjwstzC^7@y%@Q;40FVkOouZl0oC;gkhyv3=R11l4~aqSgw4{)xJb@#riC4wE6ga zeq{ML&7fr_b9=`eEhy-!nJb1>t+JG-u_+}@$+UalsgrAANOe*0rM3u9OO_WWoo=E1Knj%CROF@ww>o~|s+mLxse>Y}X#^nHq5Vo8Vq zLKW4R(5fqI)~*$pWspkA_aU}@G|(wH*@Hsns@h8qkI&*fkN_Wu6 zxOLPhi-JJ-3A~Gq^iFZ=q-P!=30v?9!q%~SvP!z+N#A^|o@WPKv7U=>o3y>Z@hwwt z<;>0yV->rs@B-F7@?kp#jR|9#u9ef5i5bSw`(YmJ4Y_!oNT zbbR!*41}FmGEZ&VEmKYLJ~mG&4_`Q6)d_s-_H+r%gp{8$-TA4b-;#7s;bMQzN?mQC zkM&I8S6u()XP3o`!^ZbFPBY7iGM|kS0&1)~<~g6AO}q=K{`tZ}!gvlZzbSWAO<~31 z>&?phjBJQA_`|Iq}y2{MlzN#e9W2#TwI%9dlES{>7C5Vw=px zOet@xd-19<=f~sIe{bdYVNVjZ43Zyo`r73Gmx54qCggA0^B*WS?~{q;4p?(6@28Uc z?fWSGlOg>6Er~d*YLyJWKG)1w{8YYU=Ee-E7{$A`)YJqf1U?p%(bKSJW1W z;fPn$k+VU5>8Ig!BW_A#s#D2N)Lq0NSWHe{QBTzs{mfCHljeJ+q(EA~p)eRo0x|)C zya4ch?*9*bk9GrrOcMX!;QLM)6{^{xVUXef1HRjyn$4DdJ$PTyz+gz^(f)sf?_tSf zg$CqOlPJ%Q`bP~RZHW<`OCuaDXXs{fO3dh7s_*Qvi1GgwT|&#bKT!J{`?dF$BGMly zH~$ZOM{gQDIx^paOWi>D$7CKfpz8qO`|sn6x0EuL{z`YXzMJN`zB_%g$~}VZ#I*cp zHnjc26TzW?!bE#S^jyi0v6qwGzy52c9Dn`tV|VA5*Ys-&NV)y5Uuieyd6oJ8O?>i3 zL-E~})?b>x-i!OQBu<9GUCB9imr3t7FZKNSwQB4cA(uWpJh(S(_}}UKseSytmS_KU zay6N`nTpUyyi_PX6RYXYQtac=6!yn!(EV)v2I!E@Qv+#AOaow2xqZ|DcNSK5FkR>N zazzYz_X+5^;6}u&EZevIASO6Ja6r)>Zm1jdQFcJf!f(86#K*ZAwWuy0_pbd?}pNF?4NG>M$l{1bNswsp9s(ozRaCkEi zJn^Qh;iiH8iTAfe|LlAbus1u_WcSaUj*!|dX18nZeB3(xQm!*Ut0~b!$xKdR>UP8N z6J%`pk(*zP3SAR;)^FcC35y#(w*IkxemxwX)6I!C+v*pVz0b665zq1{otNEbHuA|y zXJ=CDf#*>+WTEucKe_x5aq&CGF)!d>>kygezfPsiJQv|1y=td(q;5}?cUsx(H=p)a zKHPi^5ygKVrSUbnVH#MwZkux6`RMzT-Yw9m}Eageg z++F#n8O<&gjuOS7Ftd}=mbk44)OX+dXWKo+N*wG<`K^OH3kR1VevYQ&IC$TU=j^lh z6gU?CF+ZwK?+rXuUuHfRw{r8&<$yM_tL1(fYun4oZiO~u;!3dc0ln&G>0E`^NZBdZ zv@@@c;h#!`R>2fpVEO`$$sSJ~hm-3l(m+DNy{l?ze) zO4rzMXBgj*iLBQ6TmqC1-LA9M=PRkE+245YOi zW}OUY$H5`ph<24vUGiWDevMsqQ8JX2H|)9mHIVOJjY_M!7K|EjJoIO2+$h*9Gbt^pz#{L` zKOP*97i8|dE`p=7dx$~UkqbVdwJm2p&xBNd9XjgFFDaf3wDwAu(R%K*`amsNu7#y@ z0{oaQlBoT2Tb>mvdbgWfpdS1tkG0u2VzEzmEPYqT&R-j~J0<0NKO)n4O4r8}MxM$l z|5NVuLsg8_ddkpx6;N?9>9K;R!Ojz*rbm81T~^Xw@QYMzVk3}Q=>w|Xg)eWR2QA~A z+kakFjm7Imq`dVkcq2k<&(xyR;}nu~0)aV`P6ManWMg%mn7}a&xg)Y|qq_0xrC5~Z zBlq2Yv7V*+x-<&*$SO~jSFbcpwYVzw%sK7S5F6Bd>Zp>tGuVjelAfOPM~71BIpZMr zI5Alv6Mg?0*I?JF7Bvh%LN?#-VkXqxygf@1Il$|TetazLv_e$d&$*oC7URGeR{FuX zg@+PrQ_ca_jlBwO={JupmEwNq9Y2b;9(!Z0o9;E4Y}yJlU^SEvo&sAQ@p@k1)7&-E zQKEV6fb8BuB`v1?&C?CWJs*4*iJFGWBfjR0z%3S96-)AGMn4eaebaLBt&?)IYWY8p z@l&D=MRjkzA}{$IySk-C?bP}42)1`T;%idk)i_Tv_`(NaZf}K^dQx7(BNHo&Hv&dx zt6zFxr}>jdpY|Yr>9l>Z(KRbAfB$&rt0un6E<^o~I39rL>niFEKozB2Ltb|fe0LQ< zjI1=>I|-{P=!mrkS)XBxS6_6Dgr&(i*F0BmJsO4D5z(@%`rYf;nksZCl{hQdQ085I zBe~Vxbxi3WZu6Xq`vCle)-|MDb6?9jV%XdG6LIS^-L_O9af zy2mxpzDEZan_XR_%(~mDZnh`f9aa8o@_w`Muza;?p8?*nCNA&6;*PFAjO^a4m<}mHxb@qt5Gv=833Q_02AtK;16a`sSs#5hiDh zYDaw~j-CqcQzuG!z=v|Hc2D-UJeP=>F4*_8-utIki>~R?&RrVmeDPq}I3@E9>|GkR zC%QuedO_>z_R({fE?+ePJ$J><*iqD)_GLQlUV8g}QTA&NhrhRKMmjTIdDH91$nHO; zc}ngc1&OCi+ICH}G4J@WQi}BM+%U!Ae3apuB0ZUx=7Ee4$g8UWln@ky+NjWN&Qp>P?&6&Zmb!f5v@OT%V0PFAcbCJEDL&sU8`F9}iYI#K)g|;{evy7^+lNb=kR# z0~@^~3*=AOA_N_TC?cT&2pGb}K=UvI6yyQo`D+Vx3b5BI2aShaEQ~p$XvTyYpgUG^K-%Ok8C4C!0LVAc z8u(xJWK}wXMBje;;NqM8;ruLHspFASO4)s?$tstFqcWwrfqop8%d+di$MpVqJPd(u zr2>Q<`kokd11OA$Gk^+9H3$KO7(&T#3ZA`k2li9@Wbt=`1RSxPqWA$}d9m=AzGAG9 zrHGw}IV|m&3P`=qDRstesLp`cPJC^N$=u>hw<@qM3X^)8>8 zHDfk#C(k@;N5G7O<(l$?w^7?>U4v*Rpn1m&=eD*|Q3XO|y8tc0=iK;T-~dG>qNnlb zQjs)}o=N6O>yIFhh%~Ht0JpnuQWk1Wf&}Y2ZK*5_@k@;*sKzG4=%=m)>l*18p1t;j z%UHu57f7cPfh&;)dOWB)L?x-9703&a(6Jtv2?3^^j4D`#rGgM_A{rcut`=TOCc9Zt zAP#|$13YQnHtAAlNZUET)?YYl3M2~7-BX_HzR3Oe*QE;S!1BUvCXds^@3@RkZpa$0 z5`=COA~_VcfQsZ$QQi0)frNmsA)`gBxT#f~K!{`$r0FDDpBPm^1+)d!kEh529)d0? zqpsrEJhW9Y8bIvNufidH*QX8}bk1ku%&-IJaJO|o8MDzfMHbpKe5J;bmN4AKHt9fO?Yq-)?WGNL{z$v@ILobA& z+gE`f3tF&>EFefPg+Po2U~AIOGsTbyJbGf4xBCQapPfpq0Ji9_nE}z2dynTDNav97 z)vGw5p;5G2exHP%4@FTpmuiHVegV1$3AAVs7l2+7s37tEjjPEFHaP>ZEvR^Ohk)M> z+{1PP=l&}C9uZw5MABDbUL42{DtHG85{d_a@SKoDdD255L!?Ssh57O#oLb8fe&;Kn zAb{vhLVe}6-?(fl>ORoX0ZB)Ysk(fG`GPcnEl( zArv*z$#Bgv_Jg}+e}3bDR=SnlO(6U<&8aE_T28`C7kEui?(%`;&0TVfgxDhg0T64@ zEdmk9)QRH3G{13(x2_{ z18mgh8g6VIC!K)dlNu5h5T%?paCwX3&W?cbrh8)a3!^Gz7y3RP1D0ylZAdQvrAkST zc(8^ac>+tKFiM3$;|b~Q-c|rY=Z&@87qTk^wM=}wgqo2G7y#njb{?mOh^io?=v0)D zhj#JoxZ>5Z{{uRIp-IEIs$1A{5kY;Yc3Zcl{?Gx{L$mn!0D9OMJP9NXRC4HIL>&(W zpxH%aq_J9EUKo1o5hS1&o#oe3iKwjyD)(OJ06xtnQU+a!ye~j!Uue0~&7V5b^89>P z{#Z-shbEVWj*E!frRs9AU!3W7HD!`=uZ$2pSx5RTr-VyE!A4R!f{IpQWey1W(+)AP zj{A&6q>2#ph86FTXe(88yXcNg28&Jk2Ihs+%FSJ|NKzq z_zY1kYTUE)rt?QsE1p^;g3)%tkYF5HF?zY8z7K|8pUYK&m1Hp;q*2BH4v zwwS0}6QL0tIDB0?4^*+cv67pNZ2f~PSZ%yYD)Y2Q9q3X^pA`1JHVekR0g^vPYs_YpA)6PO?a?DJLZyRJd}OhROmtKEs)I#Lj# z5Dbxmpwq@K;Sp&B{7yD9dli>PDiehviO(uGhEr$PD$iaV(OW}S6VPcpZ@#YU94BF> z$S47|BO6`RP3{Q2(6X@HMAjHB*foloXn{&$+Nh|~WCq|+0rm)F4QDAH1*a+R1P0nH zP8s^a;)T-ROQp{d5OEaf9u724h$sa$fu;Hd;T$dxaRD_fAoAF&H&RjP&7J6b986$H z2`sy#OO(?_sshS0RE-=}^eNbz%4Mo1&AL5a$@SeBwO_- z?Ytlgi!Og?{{n;f(r5{Mo}MF*s8wD%g1RTp#T`KEsGxUyW2VI!qr^MY7pnwBnuLl1 zw_F9fYkUs+h1#svmR?y*k$w|i2*SWh3y@uy4*dW8f_XAFNTvR=JBAX9|7%yTnekB2 zg8L)F{Yl3E72zO#z(37tmo0O|1ISXq#3Cb8dHs!opws~@_4j_j}SP#AuGRUR;2An)uAG42!Gn3Qk1b?#CVpOQ1{jy77u z8LKS$^K<^)MdR}xp;}O>?-WOMx28#s;;Dae%uixi-}v{HNkANI0QznCW{Ds@^e8GJ z5oLi!@?J_`5F)!)F+fvh@dc*<-yD-r^=6WtbZ|D=QT86^aqxAtl~LJcH7cU6OCrSB z9w;dSAklf_=li(*kWf0*jW)HLc@8|SM}RR_{IOLr=w8@KSsnykzi3g*xXHIau4e1 z>i^uIc_Ma{h>?=?ys4xjD}?P!j;P0@NUxM{@oN9sA4mA^L=|y{Vcg-X!uDz+I`JjD zqxWovC z{-U=Je?y%5oFemP6?aa81DZP1M9gR-+N-;=TJ+{%GkUSH@|$nNM14_m68|N(QIh;U z8PoQxw;>P6tsTd6KY!kC+oxzUGfMs;HSz--(ns3tIKLe~KwPa^rFkZl@??J<`TP^+ z3_r380}6v)^OXV-Rzi`H5M|x~JiQR}!4Y^!3tmoDzMU#4a%}kL$}1ClbPg4H#RD1L>-!8C2c~~ea8wGgi6fw1exV*EkQ|c$ zMVHTI*UZ3A3Z({CG;4i}5*hUQPY3Ld&$3Jp?C}cJ^RA9=a`|ycRho-#zo`<>2*SWd*&yYwx%CFO^Yx8CXrG zI^0{uE)|X~S*lyA_2neyTn}juvpp=i>387gXJyl?-6wyatlm3CaO0R{p8qYUSnppZ z@n;)Zp#wC%xF&|Jbph|DoGMvctV$FTA4UpGApyoe%I2a5+T*ZW&Nn=+K3ILedMs#T zEp`SPeZk(xp`-dK{(gq0=KI^J?MwfrPCpsV@7ybv$&5xnKpbhnY{)b=WD{@tdta&6 zH;Yva*pz)!;1Or|?s`)GZ(Y?001Gb)N&H<~6a=*&%il3ZIf1qPzE+v*1d>X(x(OiA zoIUGn(Kr(AdR6`+VG)@hQYvrI6?xIQrS9E)30vhB6RFRAU%x(V@~NFZ#%-$ignNH2 zI`LN3qAU%r_HDB+uFm@0nluRduIf}%nEuA$Li=AA(d_%rU)=&`li63WOvRuo3C_BC zF*25NA)1{mHl`*P+{leEe zO1}4yY7@WF-_vaH8LINjNc~vDmzRpu5#|s5b0=%ze9Opz`478!evUK2{~DC8?hxHw zU#rdcjVrD$Du%v4BKRfJZ#^<{gU+UE? z8?^iitAC0@2#^!KA;;I0?sOfxLG+tfxJK@a$qySt9xf>&rVV=e{iCI?d?-#TQON-l z2G|{u!-0gd`y(z*M^AbLZF5tTO;B0lt&w0kF5 zr`^EKE3PGDKH_8aw(xQFo3F}JQ(OrTc|$uWd6;NXg?xv>ODEnTg_-26l$H(YKds+; z?>M|R5~ZkL7vv43lKL~F)~|Fm2fM|!PMS=F30QErx~Kv5b*8z=iK880le z`|gr=-Uq$cyh}x$?Ua}C17_`=UwGi;j=Z{%_AS@Oi=ZwPWCS9iN?xAwWUa=A9EVI1dHfz8+&a%Rj(Z7 z8LBiOm_fWyQ>Gy-Be44o?vzJ%m@rz&suX5MO9?P+!J0}a(}vYwF#BIw)=ud@Q#_Yg z^sxh5LJ5Og)_lQ)kY1q;h*VOk{kCr%I1H7-ytKKR>mXL#v0j`->TW9(4Y;Vi73GjX zveTWjL8igW;NV{MYkT{ma2({UKdEH=B-yp80hDf#=!`j>Qm0fvj5&)f?2HJVOP4w5 zY15OJbJ!iC)Pfkwpyp-A6Z=(Ae}}hIqpAt{=<0`gQOAhN&y4))?4u36%odqBNt8pX zZ`Y5Wpm)Fi5B7r_QO7=4+J_1CreU=x;~=m^7{~{ft@z||^g#hwfh*ROA%FsFuHVYs z4h{4Qy+Oz54*b3iqedPbmwQZMdjRrL`Q#gekKeMBH!5WRRTnEf7QnV)mJP|ag!C^9 zwjCTi#-^d)^@9#4hI>e@Etye~=$sYKF;s09Kxx#a5V4Rq|K-SQr zB5ERHqitvFVA$g-U9|5!Q@%h1Gjk7r_4K7eSFj=R%BhJ%(de_C3#a0I>Oym5Ae9Qi zLZK7aEm+nT(ba_x7z(!-#8Fj`lX?SkSrrkl@^ zHC$YkuF`o>zdGS?3(O{*K=()UyYmLZOkC3q|3HOgzpT$eI`!?8s~Sg3s`jnzmZfkY zrS$n%2Qz$b>+O%bl6D};^vm4Jdu`mlOBda&JPxV7?HiEuCLBvs;X!r?oR!rczPJ+; zg*JZw0G}fGk)-q6uuJ=Nxb0t@ixM9b%7V?@)Ru0zIqR^`LnnHD>$T%5`oVs-U2GOObpx)IW^I-CM{xw((m1xk|>4#6{Gz!f4&X73endm#ipq zWn14o!}aV5ax~FZxu>44Q2}C6R1UT8wmHAfXgXa}Fu5}PST6Zec#VYv{m2<8+(_RK zB7K^NFhHbP36S+Cv+VKJQtMLc)Boh@41>P==Cj&vs&Fr8L+OF%DApCEmwnzdQ~7eD&mBa7{1B(cBvNo zEkplZg9fiL%qp0Ym^IkplQ0`pkvRvVS*P}toxj2}{T$*{ec*1*vzA{U>csi>nhj3z zB>6j;@P-0rqC0>gG8~d=4xLD9R2F49yGdBH7fDN1Dd~+@0I$<-rlI86-FGOx)dqGq zP6!syvG*c-I@YfC@R^5JAa*HNQ}K2_PiukLa>0edGtaVW5rqQ*gYk)TGR^QUKE8r#WYhEEkuD8-e9<=5@q;cYs?|Q zw%sjpK7IdJ!~L8_r^XPbh2M6aBT#Py(u{Wf*#&k4ug6#*mBy1&kMHr*Rl0jb&_gW^ znk%lJ2fK<;<$R;4Ic6=bl~oD?oixF{)3%5Dt*Gnq&bMO z89YLe?oWi<@zV##n8yTA(rUUhmoY5Q+D4`6;}M-PS$7`}bqKfF@{9tK8GhXKm^FBo z*tX=AVYCPqK_K;WZdDWY&YM&x%)Y^8xiRDK(*{0(4{8U z#n;gcstjp)Jfj5c&C)q8D%iW09#~>SV(mG%fTN$&+%_^)YfHbI&c41_yZk5pDL*|D z*g0R6p%mzZifTQ}hmUfZbz~NDRM&4=SWQCa39x|%kUhUAQq-LDL~P0k><^{U1Xz7N zllkwdS<1P|o9xN?()+wtpDXP%A`S!K&pZua!8$x(_j4A07*x;1{?RZY+OX^*yM_l!pM{Vfg!&Ve1iA%NEB#pkCLX+XaxR~=?m zMujlW6+jF|(o|S!YAo>o;p@KN+4}#$|3{WA#12}G9g4=LEn1DgLTN+MP+HX? zks&eKm<^?kJ*z>rbjGaNq6=N*Ag|C|CuO#IF_W^KoS^)ce~A^@#!qYXxks z2!oQ5GOMzZY*hdhEn|_k@4uUY`Ye#g66|_=`Mzmr?6US|8|9`6^}*<|44f>n)FdS! z$6`!5AdP9dlqtRlfN#AYMy~g$%&jetPIactrQv|~N+3lfulYU|EPUM`T!zjNaKEX}#kYgz;n_V*ggxa> zT0vv2AT!t+WpjlUmi8!Qq9g+ycC$e$GCY-ClYr;O}9?ih~=(5@xmh8RoNU_}cd zVXLy~{p^VF9Pp|vm_W~<(lhJ}*ZF@HJ(lD~=2?+qSRCbiD?>X;5s2P1~H9Q{g}WM*>uQ#SP&O2sudaM|;eVT@2lo1A&$3%QHC<1;G< z^!Y+$I`U>sj?GYwnskxC54bta_Tw524isH9X0BTDjm0yszpLKwWI0b;K~34JdF*ph zoH$_{3Ca1A&B{olcXmlrH~?t}XVY1PF^#XsdKuoh?e-a;yGL@jXs`>>?0ri(y#B54 zis206HCM|UuC7ueXNkv6C2fCH-*7Hka3h0U@#W9LP8rUFH4s#ZD=9g(y<@ViB6~lT zeelQbh=|PHR00H#2Nx7U!nxa&bcNDc6J;1@@ApjwQw}N?n;chxJ=6Q=K?Wxr(S!;} z`faTWR`%&DNP9Xvgb&G|h3q%BqZcEylm;&j13hr;vp(>$w}Y`^*)MzGzDr;?6Sfl_ z71g!Z|30qydro z=&;*yX5S+c6S62ENx#|*FdyKiWS2co4C-#A(Rr;apD&CAk;iX0S4~CyrK03|wX%Il;m&%SVL6NC! zPonQz_?7af%qR1$jb$c*Y0z|*R%IH~jv$bI(aINPYg@TLf9#j>YVij<zzrK{| zNWOjpjb*^H-V`C-V0**yav@~Z+e^P5k z?NE3Th9Kk7V6n4W52q+si30)RhE;AO?eS_x1cp2Yt7PokMQ6pW-U7~p$r!MoPf>UD zJKnD1PJaYG_rom#1(6L&p49Ro z+KRAL`Hhp?+#9E1cg*J;r1oJ-N~upR*0)?S^G#%x!k%vf>|pP5Aw5 zYZgLxHE!GeKi389Kn^=X+#w94+`zNVX`kc~jcDb(+O8AVd%t%Q7=z7P1^G^+Z|W&Z$FmTI zOhkM$KxN|bolv=S1?Zu)i?6<%;snw7zRFgUlb);Of_OprY8~JV1B>A#0AN%JRLPV~ zo4ywbgKPHvcsE*Xd}M=Re2}l}f>+<>X`E&-I+%INRn639qM()ffVlnO`xXQ1z=jRu z-oPVITf!tM1)sf>pLqne(f<7LYOWW%6vECfq*xRb%WW}4uM@uY$)Y9P^@DG|Z=DuJ z-7hdZ^2>BO;o$3a(BlRbvyhv%@_&DxPnZFK4z_5_9N&A{k&Yk#^Yc@wwIp`(lEvBg zEf#MFCk(BQL%#%Xv9$?*GWBlsD*K(B_{8?mEm-yyot5CcawE>Y!uLglQGQ|Gs`jif(oS^j-TX@7tMoQ&yv>nrfHf z_?l{i+FV^9`Yu><08iKc;rVQEZR ztQuC*(p$J~_`|&FDe1^P8Y-C*I6*m^?$roVAGDvD?9 zm0se92A5KX?VbpK?ZZoU2C2AMJ+VO9OcIazMM><_4iRr@d_RBA=|D8<%2h+F+=Pa= z_f1^9{ymBg<^vY8jj#Q)8m57g?i-wpuvu16`?Rv%tnZVAfXW4onph2dYrZ-%GaVfUviQB%Qc`~w!V|TwPZ9O9 zr*Fe__G7?6n8uIw^AF9V=Xwdoq#j85(!Sf)k9I4ww6&7gzk7HD({=7^Mof3T_Rt}$ zu(fqHs$i!5c+h`V6BAnhS>G$_`HE{FqhhE5k4b$hM~fRaV)P`?UX_$BA-xPN1GQF7HJc$3N+FZjk5=d~Dfu2CA`V z)M-cOw7m5s;raeuJqWPN)Z)!O#aDh=XaDO%*$Sd%U^VSa?W5boEw=ejB`KBnt)_i# z)!ssSdc8N7mxtiiB{XHGn(F;DV%J|(hz32funnu z!rj}Isb=*Jg5S=*W!X}RJSFg4@wY-xeC|~(SmO(hXs@r1S(X>J)&7DcLCm?t@Ys*A-OHv=XRyqs@pEb!fUAV z77#P1??_iAedGb2t30&L<9j&EtK9^q zFPn)VigYSshNDlbbfWyf0t0OjaO#WS3gJb`zGEw@1%CiABH*2FyFS;zq(`}v@@9)@ z;!5P zRMXr_w1fHcGK32Xuu=~KYFoe2$Q~v-;+Uh)pA(RzYq1Vj;LvnmQJ<=Kaic}!@!p$g!1`x zU8FXf)d_YX;=xh5&HJ~iACq}T@VS;7;FxWuAqY zrd03P0RRg@!L(kbX;GF-V3itX7c{MKl8v(`FhMI2TbclO@8?o;nPdJoN@Rt<{?D!E z%xUU)R7k*vSxta`d^zury3R96ZyF#Y{{Xiw7< ztrD&<#mzLTUJ(G19O1gEyrS1fkf<8lGyBje$^j5MabNcHKw`}eH*6G8Ueqw1_-hyX z!WY+G^UG7x-1ht)~ew+g$RyZtc*d#s9J(-e8|*L6D`NZY8AUnG1>eQ}73 z_RtwQUFoLHJHyKLf$haV6y9aVj8v~9+HqPxVICc@yYq@g*xZYE@}c1%YxfejrpfH44Qmq z;=AI;Ov5~bI(Ov(@BkHRv%;CVek<_5^KmIUV9?~Q&6?r-4a?_eJQ_WWRV-jzx?A3^ z3?FqN?Lqf9ZZf@s4DK-YC}H_@lhc;W+mWF$OMPKsZK&LnAJvmr z2h=1H?7TLgRe}VN?xJ%3=Vaj}eHj29m`qZ1_*|*nNBmD^ zsFkm}88k3{XQG_1nHj<77g9so2ySO%7mg5(T)%hF&tjh(JWZSia)NVv^*2>})EoM7 z*pzC`LckMkL;rtM9rylGGynj#Io9D!7vuivK_wI#(4jTAabp|tYh_{m&a41()~kHh zONSvDT}VIO<38BUg*UM6bC{(ZaOloRE5Xf@3k+R_*{t&ktnnX{#ec*5iN)BbGIY>7 zK_gy93lL$sE_N2bb~Yv8qx*m+q35n}43>IKsO9A7=jp`*R{DMB?lT@3ARa3T-3!pR zywlS?-fJ@C$}8XNH`c4hD3$%mTB;PPYli{EuYm*?4PV9~S}#@b3`y*BIRkmF=w82` zxs{Nqz3Qr!*x%GOmhRnWO=7k%JY14`rG1%%b(hVXUOD@|F8&9CB=)SSh}?E_!&m>@O4+0XDJ`AI&j5B|0%;9&}ZqM``X?!WOwfi zwyqr~3hE$Mx+dIIq#jFSZoN5wMg@s=-(-8O+LpD?js>#W>4qPY0L@_KV?8~JKZ0db z#K7_a%Y_GU-7r-RP!y^^YMp5@cYb7k!05Q1dq_B7i4BVH(TZlwH0lBfy>`nwM^kcL zhlqX}K%16+6H2fCXBTzU^Jzs^Za%Bmqh@bIupqFPh3Yr|MzquK3teXh4C#}uZvlfD z@%+s*d9HTokr)=6?%{8Q$%Na}fr6LOZ1CW_dWS<&Zda1Yc8yzbO7&zTW(9{oj>=IuP~y=;W381$6`h(rWXrv zrTk!MtH6vd8764II4cCO{Q3;?_g2Bcl>(ophU|Vp@9s5&)F+2dqqOJ8y)xTmt`qc< zJ?k$H^A6Buw)?)2{M2!Ip`$)tW*g|H2X;9bTbnY=eLTdl>W(?tYDAF($dqei1)!D4 zMUUt{wbXpu=|xjsFJfKq)P@m#&mlm+s{@*qC=Wg%-+x9PY!}~$Uw46kmjn&kwWPG(2|jCZr6Ed^0QSxSBC>u)|^ zX*fk{IQI+psB6(VgdtH4=OsoJdd3b2Hp{6{T>v_n*ALo^ z^{U_iPvxRhY8#5qeYhq#WKh(1LU+lt>mWWJ8ChUlJ{W5$Lr5N*^~@z&i(O$$kiwD1 z%Nxd!N&;$HY|Uc!vsu<%KrZS~$~T>7H8rX)yTz zYX+bE|CvEu4}hB0|JMv|mIcF>^9@G+-&l^t!P{w!s>Obc1r4#;=l_~P&0M8{;Q~EU zu}{VSHG|5oo4>u0>SR#Qq0PJgPb^2>$*lKD^K{11&g~lZc31uv%lX*3nnL7b!+Qq9 zF>hZN;7G#H;s1-}bnMCo$gitLo!jDt-gEz)~4pS&Jfk^cAZ>UZT7-R@+sKQ7UAuj$~ki|(OgyWORF z5WjDZiT=eAL?AbeNQ(U)4fC8!E)cg3-A?*-?*Q6Ju2 z@ZUVIFNiLQEfRQ?HNG#~#&`$j#}9Vv1f-~`45(<#7P%<~#TzeP)^u|4P&>J&sIOA% zr5c2P7Wk2R_Uuhee}UX)lN!&RZv_L+c}^c2(^CwOvx2n3XZ;RUoNbCb5#T$i?v=47 zxu4Guiq8Mo)TL$z$p|mjbXSyse@!ZNtDOpKmfbjL;t`R`)@iFADa#LX6UTn;Z0#X~ z6-NDkgv#q)A2DG1^m-V(0i&ADj~si6o9KqGc!f8Y-I1NXHRCY-?&kW}T0!!RnMFgF zM88gu^?O7bAGq=J!=lO=`IIB~RDwJ{6Y;L=4;eKFOrmedL&!k``WasJo$GQsm)n8w z_#d(tH%R?=4W6MkmtXud{F-oYJNv5Jp6JLc1m)-P*Ai)#h!s_NWXgZ8lnT2alYx3{ zBatQi3Q6UeakR)gxkzjk{^Ob)13?;at^?c{f*y(vF+=!@zu;zjhCizgEQ zcr8~ISzkD5=N_SQ(d6u(&)SXgD*T{$3y)VdmOl)?h>u-!XDg~&P`ycAkZUtNcH8pL zF`R$wd#-OWQtakTsOU^H`?Whb~$#joN#+NhL7#^pYy5{mXADse{iO-62Z*6<=1@}8M?Y|HzOu;K#E^d$f zyxo86%iu(vEWJt1p6S~_rD&K2YZ?x*zke>J5_zojalx`Z+x$oVxoe=yD*FmClDxNw zO@Di|6qLZO2y}k^=*+3lxVx=^?FEM3)mcl0ciEei3d;}9E_<%>Td$GyT~tC;&Qd@= zaypr=?goqf_E#>T_|AnjHH35MUEyWs$UUNiyKVPv)ogFanvZI0=FK?t{?khj>~{T@ z=`N`9vx*O6%>@{tKT^qrNQr6p(ocqL|+kl0SQ_cyG`aS@h!9N|pz zmnpDUV?^`-@iKe!TTiPUZ-@!UdvTn8=pKF}vFq1F<_qE>wgP}y`o&Ax84x~c~ zhYf@KgJLq&f`|9hIs*I-e!gC2JaPPZc<55E;_h31lQ)m&CElqa2yqW5BzJ#Z?;8J- zuy<7O=fgYJjsU}>j*$MQ0tk23`YY{fC)*TvLsvDV#kZ<6tRO+BR9i7upQ-kozv=o- z)$e9UwA#xl5FM&b<@|jX@_ch046i&})M8x(sMkoe}iqi&e3 zNA0@z{cm=({LfZxI}?7HB)aZC9hDTj>eRY!snn z;#q@?Oz5~+sq$Xa>WGVTgUopc-2iKax5#}?))(fg7ag@?+XAT9C^w0Rb5zPoC99d6 zUeN`AywxYUYIw`;_6RR#Ba*P;)97^{RNn4~%?W2}hbiWG;4x}LTD zSsWG23NZ=5*ABb9u>QtoK)d%$>MPj0mSLA442cvAy+iNX3F+Iw6Dy>C;=iEbq( z=Nu6|FNEzW0;)>H?#2aexrf)8nEq7{e5Q0%$~Q``w4`;1k?LpKy|sszQes>;$0|Dd z0+q|rY-4+i?CABrSuuudRT7z-5r6CXy~K*1UB8$*g7Ux_iQex@h-sD!s!B0idQ>N= z?P$7IKc;WmO-+oQ+dAxxwqq*TA-4 z&Lu7=w|K@PP$sHv+Y@T#E@SgdxU1StNAOtETO?h~+8Sq(<2|wIxwRzA>Z}g3d9+t4 z0&vRIjY_yswmIn3Y@j+iPut4m{rf*nO3W{(I8mqX^jy~ zokyXoz3M`W=8(y#bH&c}3-RbK?`=BV#@+v%r~dIDfhN&~mj{dt=d&Xo1J!_v1KTKV z*)B9)wd#q!XX?nTkLwUhL0E)H|KzrylF(oKb+sio#3iwZwm!(tTa~?Sv2uRlS+D9% z8pP-j13?hhiGt`}My}YwGepu~ z3lJntqw@zORXX%cfj?6L3G}?s2D1lcykZ zr3Pva*#SVdEh{wB5f6o_-4jwsBYTDdE2f;5LdDA@jug-Eg)k2KBpo1o8IaxqKuN(^ zF-g{o1lqxHs8dvVk*v2YsY5>&vp!llG{u;d0wIl^DfY)>f}lr|>F@?DQfk*OV^35| zlQxvpN-w0;=+#NtARqMrjjE%=PXSg4k9Os$f+~>>3f=mPWM(r#(_ttwonl^X~4K6?P#G4N3hN zqAv*EAwr7q*>n-~ni$?AEj%2SUP8eV2CrH|e7ulQ2#|&#l6!F{M~O&jdPqV^?Gzz3 z7LnZ)1Yj8IM#z(hfG#r7=hJx>J*UzpA#;T!_7n7nE^-k}Rxkm-ECq5TLBENC7sfjs$NNA&1k7D~2mxeJH-UTzpp|rH?{n=NwXuM>Pd2h4z+3uR!QF zkcboMORHW@>S@wqQ9M@m5*;qU!MvQh6~L9jJNfZFlWE zANIEgai#aC9cqks~slR7KL0|=thR#M9#0F)r{(t8TNL^H*Kfs z#ibtzT81VAX!#U`p?x7xCQ|}{b11n?LYa&P|CHctEgxyXJ^fJHEfJxn<`75e@NkW) zec81|WwrB-NI_Gh;AW$g*=$~H{Qg~IH2=!X_9lrCWHAR~>!X<;nx&4=)D5tEH_O0P-5=>TxpihbKyBwK8z_WJOTz#o)%0KgAC}wmjT^MJkye z0_3FN^ZA_IB<0HM9-ssOLgYhoC)%W>tC$Yoq6Gu`!AofE=z6we(!Y|FfN?XBfnh2hd5qb|(r}g3Qf}0-%P9!7qKaDRChuj1 zeSZ~p^JS?MP@f5C0tM_%>+GYpZ#{ypnt=1sdD;*(?1+~pd z<1)3-?TUY|OMiFSwaeM7zZ9M5~VZxO`K1xi1XYkQ+Io&yv3dnhdSCYT~3ncv| zp{qV!-hgMe5|C0=c4p%2J>i9Wcw`<0CJt@be4(sH1GUuMXp1WeTSbZ~r<(~k-Z-Ea zyt{xawY;s0_oOYf<=j>*au6>!Bb0kYIr{rhSwnZyi=jI?es|IHccdAnxvl8?fSate zyPu7&8Vc@gTSSg7i#wLZCuiXu!Va|{>D?o3Ruw>~D{mTeE4-=@zG&xDVvTtu29C^q z4zCdL>i}{R;ia)<(V*z4go0Wf>;YF^!oJYlz@qg(-?=Y7*-u7G3msiY;2Xp29=!NW z5K@zO^VS?{LWG*YBE2*^>O=^3NMnTewT!h|;#j|2n4-F54LO8Nt)e3~mXMD}2R>?) ze;Dqm&>Xz#*BkAN?i+%Y8=)%*-1j_0C%(|G`?m6?bSZkgj6UCoM+tfG3=+JJbh4S0 zBP1jL9AZBBgG8-&0Q38KI~DJuQTx5SqKpyMB6irbq<%E2k5V=`kyPbSI=U6D*fM;1 zQsGUr0&reoZWCg8=p;_-=!FaUqf)vHNTnJVE+0aS<{;D%@a3Dboe1fFob<4DxcGOX zh{Wu`pRj4@7i>oxgeYQ$kKU4|=U&2znxo;lN1xnIebInyqhCLTl}#0o$0VUf(2Bh@ zbUiv@@;b5~k4z8Fjvsd$7ApN7`gE}$ zm_LCqLr-nGFVrZtzJK)N%)pbd$w3injFix}6V*l;nwp#3moIyg0+q}`so1BW9@#{( zY^?CV|L~Rfmvhl_Z9|&Wney&Ql`~1`u=5Abs7nh? zASuqmqp$v(jhKVvEf4k$q280^Pi>Zey(}jIl=kyceWb$daKzP?vpFVLvnx(FPjr=E z$ZDYGN+w_>S73z`Fo$4-r=&bdOGgZ{7!ThxTH`ng)Oiwi`&IC5fwVyNXkzxH#q$nF z=m7vUMoRN15+@JAA4xeDT7Did_j(!COewU=DKR(8y^KYS$0E49)8!Hoodi_t1Z+jx z@PQpWdTPdK2mHEcmkkDW=^uL6sfC5z(gYML?8Gd>~KQI0BETsxE(x6!k7NZ2lYo5DYMZYS2QYo$9ci>Ug#GKUFE&oc9 zCb#c~qSvqxgNDFA8|E%$UQxk_q^| zi!*iDht>R#=XWBd5PhSx{=&Z|VA7Ee{!uSEMI-rsp~I{9XO5~SB%NtZ4cPqVK-lc5 zb4P~(ayEC-(}dk#Gz+^uXmO^^#i=MzQeCtQR6<`uDnjdJrJv~FO{7Pb<0ogZZT)m< z`Rz1@hj7|CQ7d}VLq{B;)dj36oFbvk?OM@czh-mx^xbn-5;Fwdi_F^%-b?%0(L+)de{IK|}T9dR-b+YZItlxH|sspTBtzJU= z50Z4~a9!-X-=HAuF`zdZJ2cw;^*yHrea8viLqKiq8X#TyEIx4M1@)NPodHnWO3Jp$ zeP-VbA6mM0{uiX(1y7Qew4Sw2LgW|cA7ajL3zvI`mFt|#EaamqHc;0@O->Y!C^Jc6yoPC7TKz12U@7U2R-wKOa5JaVwB|qfXl8U`J{I~C1&Aw zSsDTFeambTUiFt+y;m~YlX88XY^-zfe(IAsVfKLm{CW~J=hoBFYu@?F@1V(n|0Y;&gRfx@v~Nv%A(R_ z_r=~wiBr_ynyvGyFFiIkJ4C$@zMLITcwhrNv}=oRU09Dv%!dHetF<@Trw-wt&G=La z9KXjj1=NxSH(S}1-v!8n{+DFS!FkZ(P#0GqXManE5s%i7ox)2hTlW{sk zw|>AW+0ULST&?HoptgVWGzc$Ka3X9^GAJRF)(|Crrorzn9=)XaS=}!#|6PCN@!)sL zd%`|2&G9L{|JBA9xD2RMxV(X);J7sd!7H@Ym=L0&;(HPQ1Yd?u$2S4;8~bY(QW<3)RI`3U>`o1t&E>0>zUjX z+(H^AG?hZsdbvr`P2@O+0X_=#Bfv166ues{kmK!FmB&4~w8c}>_4P?*uRFNyvhDP$Fh9_^Da6!!h=QfZz5!AcDJj_Ybls>a<0(w7&SofP zSS#UfnrTH@jhzZFe;L5mTte2 zWpEs~05^yk62_QHhcj$Q)DQXqAD|Onv*>*qwteNL z={eip;w)kMIe`y;YQ6(8x9^F{_fQGAsc{%X#?SN?L`JU}Xi(3t)u;r1q<_5pNBkwk zsI6OLusFl>!`m%^)U|h|RADgmKyY&Du__hW&mC&MP9MO9j)zL^<_F*JfqAI7mSy`! zM`pVTd6>m~xB&t;h3&`k7^IwmV_RI(F$=PPqh8KuKM@ZUeEm?PrCBz( z%~vPeuc+5o(lugU#mI}Z*OQiG9-FHLU?VU@H31!L_>=~TxR#@PtXXvzVyP5tn8?UI zRSpX6&5gnL=`A+$tXUGjNES6Vl&`s zwGIz2K|_MCybWsW;H}<8=f;o@swI(AuJz%_6iU4&FxJXohsN0aLG*| zX73`GvGsq7>J0A=YQ38Cv>Q=Ge&JTBR7=-C8zcAOsfupcF&M`@$|WabXc*f}?^k-o zhu8~U)p!d*nG35*+YQZiPV^rh&@aOAWQOg|oPNQqQIwN&c(bJf=cayFl!>NSDi-5r zcSKgnzUbCRK!cxz9p4WP-vG%w^gPs@?JsiFch`FVTqD7=zF@C8J4_ey%qR3)bLo#k zw+URMaTOhzIlmweHGY>w;*QSr-$&m`8PJGb$%{JcuABXFB*Ih%+B(VAdcNvuW8%m2 z4=c=u8nbcV4#WM#x|l~|=wG@;ZVb9ly>+@zwN=`Zmd3*+qJC4VMXtBEy8%!|DD!De zbn5;0b0?$A-x~IN9kMRbK>KS+tRFD*+Q0|ZGVm;2O~35mYv&BK+lzIi9o8s?8g7r}>fsGJof@98L( znFco8sLZDPkmiX6y~^Aat14Ts>WKe!oZGU=v<|K3m>g}p!rYLFUX|pf=z#WRW(nb# z)~h8?JjJ4OZ*J7-H-$AWWBM=2;5QnN2qNn^zieE5B*IV7o4|VuUiURqzxx5j+vpUP zh~n>L$u0Q+w@2Lvrd*cLIM%e;tc>zTHTC1e)%aiMBg8H8!I)uZpBqZ-LwTJJk@8-V z0sM@>h1O6)yGx?vd3pBTx+V+12jPx?ays8fDOC}nTBeHlMA*A6=ZHjo`X2?oO+B!~ z8(zw}gqp8|?-e{gxf_r9BN8YFt(4+gTnb%ce5qe-#shhF8y0dW8o{d1tcj}i@Avtw zgVG1-Pzxsuw%JfBGMJz2I$O#Q3-fgy#PKi56TQY$F#RV}Cb*zk^3IN%=f?ztCW&O8 z-{-|>^Pc|=q9`OZ)G12$+48CUH?}vT5#d8$;-}cQk(HJ@Jy;`sC!kesWVKe_V3p6G zWpJ_MJbVv!O0kUexo(Ut$H84ryMLb-AIM}#(&C$_>shPQTrK#AL1j7JyMB1BmW9qk zRUI>MN#HsVrKtVDxn%u3?%Ifj1YfkOq^d(QLL~u?ar+Ks?%j9d#hWYd-!ylA9Qyd; z!&5UEx2BQ&vfk5C4tJ8}x|Q3dS)mXEcSGgmGp-x zXv}gz9-y3vXY*CICVxNDZYh;ZYShH5y1Dy|-r4xNo~~WW!@YWgOr+_VX8=4bHhLh; z7ZRZXkOEi^O6KH;{4`Jap8?1!dO zcb9>yPovO7*Z(@V@?(8A!VH>Y3w3W_g^i!hR9pI9J+Hx8&9S#RMw<*8FihJtT z4c01C3NLKt%w+ybk3+w8gK2MTf8D&xtUC%GL4kXaix)qFyezp^YqH^UC6fChObJiA zy>QRrbf?mHek=}RivjPV)rVtpZ+8*i?}BB1ROSdE+dh?UdQnz4lzZ!<+|D)GkSHuVjRhb}kw+=^ zg6*VJ1DR>IWI^L)8z9`Dtu6SuH$jO2mfh-Y0iF}S%5)M}I8HEKU{@(D zNGvRCuk`--%!0Tfe~S15%pnC#NR76k!l3^HdUU0o8vJJ=UFvC!t4f|&x96T;_f#to#JTF2~KS138;B(e6c_OU82)=;yzKFYP zCswfKkMRq}uBCYI-UVY#LlbebiGnNpU{?j?|2Ygt*hmHjOqd3_2_Uhn9Mv#+TeOeX zAK4EDBaJm9=Q>92XWsZfG>9eHn!^rRX7`ZbxCX|l^(imO=)0(u!BGoxW3 zBz~-9>C)FV&1XQ{Pk{w67SEB&ii63{{DGP;bUr)%;9dyI7gkm<3qoFD`cODWVOdFd z*<*7YH4C<9*M!v%+yyM|uz1{VZ2V=)?Zc~Vrv_<6qWhlJo(hLdb+U}KtCmU47jTV= zVf~6Ja9b|o@WnivSaSi)u^9Ux<1hS49~{qB2&6U_i=na708{d|@9S9(c<}xd84Z$e z@hZJPnx|nuDcOiF5MXqGUs}D1oN@j3!ZKb2h2tqgI?g@Xz62sJ*X~?lho_DsNwAl@$^5zFj7Bc*CqFy{863rl%N)@2<@@F=aG zwbe{L5d*!NRY*N&x5NtL-$<5uQp~ky(wyn>aPlh1me2HCW$*CIb=fhxpTW-Hf{AqS zWE88G&a|A{Yy0KCt=t5_%$9m`ob`ff_159c8=D;oJl99;ZK4Te1*@?V;yTRsW_5*; zIsU7H41RtI#X>Z)OEl_yCb{!`hYyT_CSPQmV!%DO3U%C3EtOX@8f26ST4&a`3h+-P zp($`93>-#)8>|8K&+xYMnNGy<7&GHNu=(j=zy%cZfu5aDh5z7N8^J*^&Xx+ZOa_m_ueqz|B8lTgp!;HkY#-v|A_`m?Ti^_< z%vgSufxZ$V#W1A3JCAXcjV<;CcrjF`V@2TQCUC&S;~sq1hsSLgm`pJG+8NVlfN#xg zE_*quqv+d}yl)zh+r8eTjcUwzm%^Y?e3egrtYuAT0Qg}obz3>rm_qiKQ8xD=atQ+7 zrJpl)%fL#H@C!pbLF_!ARaSwkbU(U1dtH{0FW@8Cy7Mw;}SW5=$)!D zrlJ5XpBUzLJUFeWe?cGh)=ar<@&>}M#mVfq!dxH!)Hv9A9j9+IIvu7^6` zXu)-DdojZusU-bb@Kq0AlCz zD1e<>SdEL*7b32OMc@lb<4h_M9sw~+5&_s(LkmMw}XWY#5T+J_X ziX}p?u90U^e<#amk9EIqi_y6poc3BN`?WvKe&S!&pWR#}(f5)KS7GTjivqO8%mGUl zX35Hj8E`Uyh1igNz<>k9A;n$767s7kI6nsGs-iV5k>B$wR=`pmRD!$+e3+a$HPcq8 z^n{HTX6Mba=(ACU=*&#s;?8{5l1U&2^0U|>5Y0yWgC})a)CBtaKiR1S9!h%p!^A_} zrG?!ka=Tm|m*f-56BTg~(v)jsE6j}`Wbmru9Ut!R_m?5p(^JOB_ zj8jJ4D(6plP?h3X5j*aT{mI&w`!EB*kdVg!%pm}}fvP?PPzT7U<6#zPQ2eX+`R0_D z4a|(CkjK_rRFgPAlO8LyN?)){CwnpYN1sgTMJXqjl3n{HAaB_rZMb@( zN0P&^CGl}?mR_uSi9_)6RE{;bYAwf!$k|~bh$pd!i}l?iSq^xn8TP*tEXXpAIhB}P zhWX)sFCRdrs{@!-%a1(8tQ)1ux!+;ybbxv5Ofl@honvrb84L921rvQJsC(rCReE?& z!4#mt=&@Q|Z`g zpaY)eLSuhuhGt@6B};(X=92~|>)itQ5p+ltG30_YaY^IcSYgNWp#EUy*zKEiyyb8-{r_RrwNeW70|8*mJNBemIyU}=5;p;?ntma zSKxa^{q!3o0KlaibYua?N4=CCLrs6& z!d!t!etMP4z!>I)>lz8WsdzIcS~WRO?)6c4=YMB^$#OG*vPwmUU$)p#ilbxo$XVEa zu9A^|3w1?zFjvzq`Sa3>-Vk4R2NXb=^C&fwKzC;w3Fx{ta1-ZU>K#J9Hy)V`utzsINWa+d$n6MM6({`qNtx zaUKjs6_q;OIdBBmn``%m`hDDaDTO)iT=nFef??je-~A(!;4~dh&J{bhkDlW9$S{!H zlncioQD0Uo{qeUT>qp?hG5kGLHD6mY#PB<5_`g_=ng-o9%hs&$`L+^*t{2$S@0ng9 z?e@x`_L<9lviduQ6LL5Ijb{2g1O9=K zg(1UBCokO)6H)RkIolEy9gU3i16}G>>38<)xEy~Ki>t~1D3G(ASr3q7&I*%f12C_irxS3^%+RS z1xfD9^Z!(n4Kjb~b|{=aq}Qpcm8;kFwey;~)`$E5#d0bmAwuJMH>9jDzuK2mFuJpk z&?}R_CW6o3WruBq9aQ1=i@NHNq_PscWV(0yjGNlzFUX&e_S&M&^+B9(jAre=b^k~A zQ8LkB)T{snUADUF-(xs#eot=Ds+!#Y-Rk)wcra$K+@)X5mx$DKy?KwTZr=Q)z4`-A zhl2HtCjuWkW8wIH+#7xwmvoH;EBfH@e_0PqUgtP)K;u65EYH>ptp05s2z~y*wCexP zwfuk4>jk_27kUi=`KR5j9{u0wb*8>=1Mx)j&8Ou=8h~CWE=Xv&7wBj{ZmD~IlXSyn zS9>@>Q(HlgGTOa4SL?|A>APGDK8fD)Z*@on+vD@vBHll~?t1Uopt61A&TCnNVYX_* zSCoQVJ9qlNwc(DL*dX`)BewE$`5!d>!QJ)+-2DHEUW+#c)|f3ik$JUVx0WnA!?4e9 z9T_bgnqdi=*bdoNSos5K zKtjDf>V4M!11AP0J!lT$knQLWa(Pc(z$oJ?OOFLDXM~&CY`SI>rJJBPXQ!tulwh^ELq`uIR#?dQ_&UWHCp8-9V4Pe z*?cztGrPt%sL8&ne(AhI#>nkQQMUP6zKZtdnT4TgoocZP3BF3qoudTV{}%8B5f-_GB$wr-(ci6gxi zNW$ir*Wor7PwXW<+Wpc(N@C}z1ieIXCiTnV0#U!>`)|Jml|6BK`diWwb7QQMD0}|V zqR*j#!t!QxK&t!`=d-|8{<{u|IySJ#iuserRUduv%V#_&46(SN``6pg%(}wCq_l?A z3ijc54N6Uw1pmeA3C0~2buYF2yWoD{1bqO}ah)Uum2_jjKdU`JE2e0TuYa`maBsH{ zKCdA9ZV$wieoK(?x8za{P4C}MlSI0;Gyk2^`TUUGig9j?^HW7tTMpFH5Y`niK#`j1lg!3< z6h4Wf;_u_(5jGv`!J){soS+ALCHtfdkJB+JiuM{G>7~wk$MnWRZO#nbP)Z~ye$<|K z;#YF@ju+Qm-s@IrU3%{(`j4)1mz)#wYjfulgGIqKuS%(ZN83QhuHbiPz7wuC>;JIT zm;jrRm*`v_&|O+Zk=Cz+iq-8O!?Kl=|CPZ4BH5o-@d%JurQ9JL*{f!lMJQ zccWaSht@KVk77ECrh#?M9#&$bncFeQzRqfxlHWNY@^I@gyYvp)gPa>E1%~|-x>_V? zR}tG#srGTEDPLyewG~{@V*lMQHd6y?Y7Ew>PHP-uamGWzaRI8(^BEr?^Hi*-j_iv^ks9sQp&VNtitI^h>aHcHsyrWca7^m7Wh}&|(F3x%1uPo@&;RHCJFB zm~-C5+4tz?BT=Wv9=u+INV$secheeTe}hFUbPv1}QSPHT7VD}6Ajt0d>-V&snw6iM zgZ1sfPb*?XIbZFDeM_Wro2#GI4TgJqSGzd)wXN0q$InYC_?MoKj;c%A5;Ss@et|tI zfU@qXb=X;^$5Nr$CugG%$=vK!8a}Pu8usb%YgtS7;+_*{V9pmoCS~7*Of(Ej4@k73 z_B7<_G~t~m6(MTuK+6}g{HnMKh0|h>lyp$Rgs+j&p1iL?)-9fvU``;|_aYxfuMFN6 zJnAQR^&R4jsb71&J@Am=-I;Jy+>^jUc$ihmk3VWP290q>h}ZiS1QGyx`8QNhyp6hCOqXKsWUIJFgC*JW4yRz=2 zgy_4&_6dBQhVVI1y?8*H!w$cKNv%+F#kys+Wm(+E9fiALWKsYY=92P5CY z?KALc1ovU%bU<^v`KDI~%?` znQYye-{?{!ZZSJCsoC{D+l?us^jYk#L91`rajC{9UUML1MwBEgCph3!((|e|BVF2& z^1sDR!iALn0k;bOhC@PE=vnE8W^Sm~rRvh}7ZZ$HtP_T1qEKgjuklO7ulMREWJrh4 zVM3L;#>d2j4;;GvUZSI#XeqrMu{EXn#`Rz{>J*zYA6Kcgr~7@@%C;{TAJX*na`TNh zHogO=0|S;Pt@=*Vfag%;X{vPev7D1Qo4 z@z$Q7PZze;f{XqI?bJNk0>_S9Y1vGOEX2J@Uo-u&C5VF_e10ccv83sT@{FL@-%bs= zsN?0rg*Etf7PM*MkVgM*vlJw8B~&PYWR|J>ZbN_ev(Egve@oX+o_!h%v*^4s<)Cf& zZZB?O_f-mAvuF)-1bRcNb{(qn0`#Nf_1hco-aH6u1N||~vz|S@X3l4e4V69FgqdZ6t6cXo%|JY)v3=)HNV;`!Mly$)V@*+q4& zHw%shDTlJ4f>(hC2pI*itsQtF050lZMFSYh??TK734K-&4n3hg;Oh=|lA=JoXaZ&r zy`Yw!_BzUbmFgY=2Fe+Nl>O@>aUcYfhhPJ3lQ}eycNtq10Z2hUo36Bsj$^~FswW61 z;{+vCiEMArms7zEJV3DD0kvH$GN znPg-w0S!P(1FLA>BV;R)+5~h}Rs{i0`_gjiM=v1bhLQ&X3 zLnUlmq@m?9jf{Y&6ElZc$lle9O#mj22VM!fW>v5ni@pvLoP7z4hG z5TL7a-Wl@TCf}lm-J5$(Ph5exkmV4K?P7{~ZipBBO%_X|9wM72=be6@dl@ucR8)+; zi$GKo(YFA~o`U4!QA~hn=B8B_p>Gk;69DzzgK5U2fZz#@g8*=DfHpB))7~7I zq*wXUMXbLr;M`iYpV@*WagTEpP0MtxI4VnSJG%JYji~$6R+Eu{-0-~b_S&dCj zUlnOZBE~e(Ts)f3EBkJa%mQ}r;{_=RX{|(T@TN#72Y`}qg~}vf!V7xzR2X9+MkII> zNa)VFp3WyD8cAr5ESe8^8ocrXGOCeqtpHFMc-6NyMGil{^RML2y$*B>2wlTN zrmw<*ywBYpOz&sRIKH7@>s;Fs?y7Y0qN!_~>5Ukli;`x@asrx9Kyi@B>V%SBY+=i4 zQz-~Y?^L-0O>|1G1`^FDp^x&BnCt&lCxA~i8gLNS)3F_^^<8t#A)Ad4LDhEwfRl*n zMKys>B#W45Xqbt~+JrDus1BzkPd>tWySB#U!=p(zI2%p3<^b~pcws2DegdAa|<~Rnd*F>G}`+zoO`L^Pom6 zf3-x^)!I8Ho8BvB3_XZSly%NkdGCET4vWktAd1?o z#iOE?d?}cbGw$4m$gXs}Y0<-CX`OwvbRd;;7H};|9KOiJ~MA&FXdCZCD%o=2)R?T$u|BRHmIwHP@}>B)U{_Hx_|D! zn%Av4bnxDmb?KI^y)E9ecOWT)6;ar%eOQH+7MFDZeir&=imhwFP97RUq}XXRK=gAV zItkcTH!NXQqyqyvg+A{Q>(4}+r+nen>>37`S2C?bbz|4W?a*rXRkGrtIJs(-QT80h9G?rpnr}|EKv@R_} z*j_L`56+*3gSJJecr4^PqJrI4;amz%L6#i#g$e5$bkw3U|i zS7lcF(1XL(T$e%ciE-fn$&Z;WS^u8F6uB;ef*1HCLGH)Yx2C02F_jRHn_z2*pa%q^ zIQedUpDX9)!IY+$CA|2ISCwQJyHiW!6(1V#E2uZ6<7j_|H%Y|Nndqp;h!V6dwG9KxD`&GRz z3LlF|UKOk)=gJA8CEHO8D0DBjVGJ+;=9;^B)ev;@UNq+M@QcRamc*`FA zE_QK5?#COEomG*=RpEw5ue{^w?kIHns-RFkdSn&Noomzys0Q4x#1hPU8j4ttX2;G} zl-}8>M~9&*njX(Lex99^7rhtI#q&qqSVaOsn%ygdqm;)}ppkxF%K?p>v-?>5COG#j zp;+|rU6$-xJT{fDhpo|_suwB&hhFhHhKf!DBnK4eb#*84Swkvn1TQrI07W5lUS`#D z6RzF+ga!^~+e1s5@x9#6`342iz6<^6B`u*dE@z_&1c2D{#RM=8n>H(U=Y_x)_0=2=#+! zsXn4Gjb$?%)k9vK$;1lGBRuvoL9}mGirjQ^c`DEHjAwihc)+TCT)93ei?o*|xcrBF@O*K+1zM@U#e zObA^S>F$R2>ccPM+p^h6p?K6QlJEyS7BC>@Ny4wOm~+Fq8T@5){+GHZD?dK$ywHD_ z+|T-wQhJfUnk^Dv=Pt6Do-y$30oGssfe-&ngVmL~?oHqFj|1fQp!wJrIsvtAmkga& z-q|pPcI~I*JQnQ!L$3#lJl;EG@3K6v^W)C27(t{WPIJTKgG>IAoh&3oe5sod`i$Z+ z`DwShTXjpm+{XjU_Y$5*$=F4ZBx;hcn_b#eca>7FcQ@bGhGpWk+=_G#ltAky`W)E! z?bxbXQG8%;;`VFFv(mO9-Iqgu*~cn!$^A^xJ%5h-6Z(K$i$WXsyA`AR%#;`_U8XGt z-PANt8u0Vz_;t&(7C)YjNTs?~CT^4lR*q&I32Huys~IaXI>}eNw3*l{agX!1Z@bY! zr?@$|djDygsMYeinsT>%v50)Ho1Pspzg22nb1Ivo2-t#cqRHo6v?-mkrK!W)`gnX)+2r!(g zhiB=kym&7(DK<3L%Fx@MRwUgUrV2R`ItIl3!emsPU3X?`0V{u+VI8Jr89z=sB2p$P6VAuFY86AjFrp^f9_*d^_apX1ca3yW zXj$k`am1{fo1)1(pXWv4ndZ`myT2)~d^2ZsiOWXs+*Z4mTq{#_q+jIVbXrCMXyCI4 zDMz)?U`8n8s*7yh`*P#AWXRfN56C#fkW~u38dxVjn0v4t`KZXhs98lO(8c*^p%tj^ zgS5v*14fp<-UEqgV<#1Z=qgv)G9k+s?F%g3ov5nM$vt8buNyzv9B)kiy!b~to*#X@ zB7CRJp(K*C5n0?Z6@K+?+s_D{x95aL?_B=3?RiS(C;xg4oN6gZ21zeM2c79Q?*4re zF-@4(c}?88lgtgX35175tXRo~{^u-{YvV`~UzMz3E2C$EboZx*+(U-W5m`7Ne8Z@6?OqItDf>ZL`OPHa&NgBw>*Fu<5!_t|v$}Yx zQc6Eci459*`B~ZDIM%{LECcw9DdF}~6)qddNAk3BCo+djIP>X|>tL~1GaFI-BwG_C zUM}tY>W)?@%5PXns%Q>+#UGb_y!LiQY0^jaQeYx8RwQNaz5R#B2I@(*6t#^Sbn?EPS&16MqF5JnY z)K;o!8HS9vDuqyJd{vStI$-ODwnaTuXJ{fTGD$?6TQq3s?~-{o3@nulqCGDdYDp)2 z6^byEuzhTu_X^f8UF*-#o7;nn&x%!in6I{e-xs~`qS9^cabZ-ss8G*=8y9&AaKGmr z<#(t)hfmzNmOUHcT9@vd8bC;ad|PI>yF(k%1{AOqFGbqy#e>~xRK~ZMT(^@pQa4D5 z(#-kHfW-y5*OUQkbpfUm!_J2B&ru>NYT~a+6^6|2chHVaA8qVQe7_DC4>mx%ag<6& zaBv-+iauA%+XMWBK!;9jE@M(jV?K!)f7bp^$gg|)y-t3A8_(K5{7k)}BR7~So%^nv zb+BdUvzkdMKW8_CSk;+8EA*c~-FRxdUnVUNrZ$a*AXb``J_fVES`@G?m>MYLu*YFb zQ&e5P0#iAMQkgxP8OiGt>z#(1x`1yt`e zsSD_Ugm#hhp(;mw4buFL7X0wqf$5r_EzZtSP3SaHqcftJ!N2k|`GjM7B{K@~Gw6$s z+YC+js2R^mN2|7@h&P1OkKpGn9bY`TKsQdBs=ZEk1+T?^G zJh;|@UYUIoO=hn*n2M5t%YWQbqeViaCi2C=R0D>23{R%AT(S9hC-&U)yVoB4ij0)L zY##W@YAg~HLI$I7{vb=41(3ulQTP&QU?48am0oyBQ84naEw+f^p`p~$OrWbC-H!<5 zManK|z*KT8SgtBZGOFjx#^m#R7W42mqeB+B%je&3=Zb6z^G+_7#mM;3CRneuLol&7_wC{e+Ihs|HsDHb# z_q2|G6f|s@897&2tO*MsR_}MxefpZEOEySdX2uOOfI?nDsOU|9H8SwUwTKzMe#O6t z5lp!fECcsOFeC6x0Xe$6(}SKO%QMb5cest=w)<guKjUJb`2iZ0^Kr_=6qfp!bmQ zqr)(#TDj;|CV3g+p8zGU@AtvdG>X`&Nz~*du&NnHXB})vDEX_^gWZIXEQ|2v$~iOBkor1VTYuJ9Gb!_^{xn4O;yGF}u-F^g zvhhsCgDWH#o*CHw!04G&)H*zD8gdW^HR)jl^f36IWSXrvSTzZZ0t^*1DgZxW1=MaT z8vg~;EdB2fjY|3!!^fH(>Zq;BJjRvShJ3sbYngexmgzwhUMA-<$YM8H1qWFSvQzJm zP|Wvpcz=S`#5xeO$qEEDg_=o+?{lciKo}d^XzuBYhK_RS^}m{~&TB9Xxw2kGur~`* zX&ks(9zqr?v>5oWS$xBGk_IXnUieZY0+>Xk%(ERJ)m_gcIt7b~Aa9ueV?ihOY;*7=dYwS6w7O3Pb44V4z2u zK4O@s(T+)@?gnM(PQ#99Wb1QaQ3$3Ld0$up94800#X~}B;rTc@6#w)jBc{ZPgHmo9*U!~bwQ~=2gP(7rhj_4$;p>j!QsWXP+=B)Syat(O z+1`l^A2y8ta5HtUSvzBxs?$!@EgI7V#?+h&e;$n7V-dXmu<6;A9`?1{W75%fegC#x zw!OV=h2UoEH0Ncy4+jiuNf`_tBZy#n zD%OC>Lo+#24@y}hbg(*$s_73Vo}hZvLI^A+ZxY?ImhrW&O1}phxlVL68zT?HZ`1?9 z2bx?|irl(jY`lQ{@C&IZ0nwziLSD}Wm$JR>1$`DQ7jDhB^UTxL^^wzEPXe$N>#4`4 zoq-NTv_IUBll^gZ#M>f!WdP+(kUPqOsV8}v89&ucknk_MR-LHnS4(&N3Vk2e&0h)J zEuX^LU^%Etly5{0*#}Q9xx(FewDw!XfRviw6xzc~Fn>hgNk?Wnz?uRb0<6k7!Y@O^ z_URlQarz2b!}l*4v4DCoMkv$cJlA6#P)LIKC4h-67||c>ZAb?i9z+~Nn@b;^hP#5G z``EBU(@;E{Dz-{V#Zr=;4hdjEaNs>88hp&tE}=qfd!U8?QayU;5p(d5oobSq%&1kl zFdTg;?slooEU>ou*c|*g#}Bvw1Be+nIl{{c={3AGA2W?eBI8FK!kqD(!Jf^&#B^T< zn^7Qj0(1w~q(6`iq&g&A+?yG!zT)D|mUOK(1VU8>K1B?Epqa?AHPw*fTImG0bP!F6 zBhayxq78y{Sl&Amm!6zpnV=ZxH^>SiFp}?&hI}p^jzfrFDA7QqxpQE|BKqFpl>MMg z)aj0B9^=3iGk%qBw+Fwm>0(-P@b+^n^&rH@bnk( z4-NHR0@Q4^!x97~avw2pj8?lT**KMKFozkpT*DwS_W48i;Zj6FDQNCuay!Lk2dKzUl9w0V z%NC*gTdqRO7@+IpDKv6%(UA%jGYvQNj=a&GF!!q{w(EZuQ+dVncx~@$B^7B9aBjduh>GhHR zFcadtt5b~5xdQERHf}vtmM9P~9gqfMj&HZCa#NC%0&T0EHz@}nUCzL-5%@ImMYj> zYewlI*7yvLZ!K_S8LnT$0_JDA`7~YZdv{$b&BxZmFe2N@HjU$zieR!%vGz2uI9cgq zNs!6y)L?nWoeTL9Jh#=>+39g4x3+#(|g-pXiZzlbC7vagEf_Wrz(3icR>$ zSYPD37a*{6V7+z0J)BQWP(jyW)|kT^Z{Y&+Ml>x=HcV#9m;l}Q02fuOi=NAO*_?Ed zfzrY<2Q=K6hY;MWvhKXflNy4Cp(qoQRel4JT=Z<)`^$OpTW#>sotEkd5Y&WXsx!uz zyKQ{Glv)_fQYwNU1L4&7NI&zWUy-8%Hxz|h0h>j{!Slz`hN-4SOUbMmCSsROCfI}v zz`o22U!#t;i?dd%P7l4!PFj=M5i}=T?8{-+5vwf`S-tMM_1@~39VXdK%B`JT2Ncnk zq4v1wH%ky`Q3CSzqQ1Yo*?Uo?!NI)qWo!F+G{HBJHF5d4;b#7^$4pM{ z_$?u-ZV&YIh<@ZU-F2kYapq%oE$w9>t%c@B9s%1Xji#DC zO-{Oa%`{8Q_%p>wJVtCJkJdG3Y4nO2 zYKHdb7RMw(E!hxD9GyXiVuwNRmf};fXY<|3dk7GKxHl<^espqtV5+oqQ`vqQVvdz! z_S2*0;N3f;@kJ3%-)Vw4S41{L_4RB(K|yz;i8( zX@*ZQqu~Wj=+u=!-tFHBjIpK?OMm#R7utbLFBk{0H2$ViqJhiJc<#xW@>^#eXES~< zQDu`_$q8yaV?n$OwvQxseeFav%so?Xe91qAx3eD1}%BB{NNH)j=eXP%YL3 zD>g*GhqBO!@`ra!Oy4z{WEDBs{k^q+^}BlljPLSMN;inrH}lct8!H&gu);q@MJyn+o8%;4v1??i`(2kf(F+sZs>yqD-y}Wp|^>lFPIJG!NmUx->S_Yba zWXW$=a5i@(eH|9|w~5#J%=zYTqgH5$08206;Z{E#$*xGw+z}0141=a7i}F3Th->A8 z8GIsX{v^|_$TV&|N+im<`s%irklz^WH zMYa5zqoyi<>%W{D>}5rNOMmQrqrqQuDYrPc)7kaiDQK-FeC#3^jhlVDMiv-vI$4E@3-ij)${G< zsWiR?JWX5}M4ZUbkeLI)jj?d2-O)lyD4h-!WxtT|<$OQq%iGP;dq$lgqteN4O6fWs zD|d^|^hP;MNSNPW6%o>3?#nXbk6^DpBlwj_j9FDDhRWKCA@+vUYFd< zx1NwaIT`wFHw9zJQeyj4M-F*)D513;I{m~{Nm!oB*)z8F9%DaV#jZcznVuDg;~a)6O7`O_K^ z+Eg{HB7GvaHgP$i^-U3f#KQL0ZG%VhLQf_v#Ip>#$>%577Juc#tog*gw9|{uU5`&! zj(aL;xjc;fVwF>XN>iHmpr<MC7#KV8}3QAwZdNj#6CD0s?=FRK0#&>O-%<5PC za3yqW_|~Vla()Ox4Fo8S4j>I;FUoZ|N5Y#zHbm);m>r4Dz5F%ydv$@B*CU1WM5SQe z*IEwu@?*L4YC_fgpANhpvs-Ie%naQz_X?bZiQ&Sf+>v|#Zjn>FwmB-lgWkZ&t?}e$fWR$LV z8XAbJ#kuTuA_2RGk}fty&TjwXC%>LGLb$hA9-5`vt1ix!3UBoXEg6b{@VpdUc&G@a zovf^5fC?D+uzRd_(l9r%&Q14-tlLRXO@AMBaOvmW961M>W2fl20Sa7$V0Xa8HYe0S zP4%WBEb4NKc$9TLOSRbBd2`UhIpQ;oAN9s%zg^DZ!M+RpX5a`DYh9d3S87X#UqIOB zIAEw!Un&sFed1}iJ?N01URam?s}wXlwBP>$9EMrqE9YczH`TzwkYpMulbr@u00PwlBzUY*W za&9KSk+`OE=X1W|8528wUqqV5TD3#EMyspk4Nvh43!iJx=4uBBMyqZLo=*SsK*t50 z(LsS})vvYdy+FxMaE5d!t=jfbWogcaqq1xh%W0URgl~6(J0x&KEvm}+%e_`ht0E?g zO;>idK3a{gGELhZ!V@T7Ej(B|e0&&s2t-r(!xJRBfhC*q%+V@Em7`8HTtaRCRh{$s zPvalqtoDvb`{wl5dJK3L7JqQ2C*{PZFNmbiEiu}WW6IyWi$;&UeL$Gnn;~G!dKaT; zUlpJf$Z^crxsb12qu5;A+aTM7y}=tc$GBn%IG|##R7HR&VHIJPY#WgxJWR8e?<3@& zpe?oB12dzCVz!|ghkt&yda>1Su4Jwfvz4kRmh=-) zzexwB+`k?%QI~vG;?pmgzUzh}Ra8jz^bxsY7CprzMQ}K&7aiIDO=bWuXfPX!QJGQa z|I&K9=9yu)?eJ31pnHM_(EOgpD~}R#a#r*2JM2Hn;AOm>Ts=_%!c)NV zWUAu*UbqILPim8t=I)<(IK4^C;pg*LdnZG&KhlQMf**_B2#b)!_{PvxXLH5*w4+)T z35=gBnCQKy8TY1M)KMmGf0-7tzqt4&|Jc#pfzGxP67f)#y*Zd;m=C*O*E*=khay7U zXyWE3w&Hh5Z<5!64n4lV?&+NTiy-Nd#>>X8kMXeq+UMf=J(R=JL;>*z4m<)hP;ek6 zpmY0WRhWshaGBU^=dTfZvd&zOL;gs!VWYrEy^)wBa;+BVQ*Lj>_?1V}zs6k!(P&5N z|G1s1IEKAi-ya_a!7u%=j+~8@eX22NPf|pUVPSHGei`tmV2c_t!}kSr^vW>;F_K6QQE;9IX^2S?*ueu%d`xO7@Qpc_QejJaq)AX z0&k!*LgTz#XYH#r9Z{vX(Y8Z{2~b6fL6(OKRM@Zmo1Aa3*spB8_p;?Lf_?f-y53z^ z+O_*+$jG5an0&8UEElhSaxH^@2L8!3!`%KY_E353qU~(4f<6DJ0g66nKR$db;0e=J zyJV!{m&UvrE-Ur^R9~iyYXh*e>^^GG`r#E)H@SYx~8FQ)~uz zc=JSWF0XD&=7L>DXVW8;>X3SProu(4rW-?Vi>gPkH48_ptbq3{_Nn;Wytjaux^F~f*t``K)JY_Y4!_z|x zyYNC_Fdnp7e%*c=WYa&&zLGFid@*Q1I%eP!Vj^|y8X=3l$En|N7_2+ir-z}fB)Fb# zPe;cO#vcF_plP_8kLTKa-MWo#9tNK%fEyOb$nVn{1HU}c*XU+5PPEZgu??a)@6M!7 zo68N|7m%OaC0bCa851Pv)+=>i0N(&!v!Jb6*e)i#us5S@XOWzLmANTq$!Fp|49={T z(s@E}a63UVHDwNQinj*@T@Y8ENO)bSea$JR2I8UWnH+8I<9i=Uoymfp`S|5^8@eO|_^`Z<614W2?`Q@?tj!{7r|(Zl`+o2$Yv9SxZ$N zu0RWrh!PFGcRKnmx&$vrh+S^e$C7OvA?P1vx2!|dbBo6H%-8gW7>M0Cf z0)|SMz73-%I->oC?O=5sTVo4|0ioYSr+@eIlifI*ieCbn!WGtKs)21;qEd>mtsbdi zfg>GmWPg?55~z^3?UP`qb4FnNuQCGsh&v@mI=9U9bXDo~`A@C%Ni*6?57@qes>Ghz z|3EGxJ=;x7iWfy!{PjqoJ>%3cKP51{S3L^ya92dS`3I{+YZA9$!MJXFC($^4b%hp-^?P`YsdAd1`jC!h@{zAW@PpimA9S7FD3w?LGpsZm@ z&M8-;b2K?q$?B`~8|32t2iCj7dsS2x^b?tT7QqI*K3OQlqtf|3?I! z!_`r>2HyRKiTy=p{aU}QcVX=kn6;(jpIq64VhsZFM6eDPl40{$(k#~>MAVH#F#X~D z3VL?-Q@aIdm~6CkTBIqm#%NN|xJuY$%hp&&+CU;-e+<0;nap*`t7|V9 zlIvuzltiYc4n%9f=Cd_K-KbCBj%EUds95ytfWX#kUO5wWTw!gumJjm>z&dU;leBqJ zBeuU;ZtIFz^#D|DC52XJS9zFzkrjG7ZhoBvxrEW&1MR=x9s|WaS7a0*D zdvFlKB;Q77T}9m=tb*xN;M$+UYPe1A%I_Q~xJ#EO!gP!J2=}#aH`E$I`_*+Irdw21 zyM7({$>mka9=J}^u?DUKNrJnC9|K<^RtZJXAy`|J7IinbJ_T>a_I2E+4bRV8{nc=o z3ETgA8c)BcPmj~5o?xSHL{-9o54p+P);IuB)#!#^ISrf6&naD7KA1Pmfx6u;Q4I|8 zS7$C8Pt6A@N20oQP8XxSl^<&Y?D?2%G~Nl zYs9+U&ptX^_B{wL`J!0H6KXQKVwFV8WQ-8Vj=Fg^ni^nv`Cifc6u3@LMj{b7|Libn z?lDfK8U+Ib=a%a`oJCyTF2kSov?1p_Mu~OxF15!lpLlZ{`?O21|2D{;P=y=WvX1S$ zy(+BViJ`#c1;PUQbnd$idkjQ#7Q5b-Iwy`c+R<9WZA}trrU|xYakRLpd8z?-}ax5`ttCY%fR>WPP?I)c-JJ29WnLS53Tjc{Z(O~pFDnK)Ke58 z0ae)=2_Mqi7QO?KRtIT>%S>9U0_zS)bma{}JE?;XZS?2+`^PU+RawV{i--s^2o}Tz zLwg|kPysICf+b1Ni0d}@-D)DiIcZt0!3N|?Gf9M)PNR&Y`b~>$MrQfi_+jgYMkLw2r5(f}LQ1m@%0hT?d@wqq7xURE{0CIr6$()!9eZcQ)95-N za=5N5b77*yLHd_r>`s6A;t5@mX6rv|sJ!0jAUZOt|4B@2+uZ@3VQXol<9q@aa#Qb1 zcDC21&&uT=>LGL)@n$oxptYTT@HFLo+Mrk-H$+XRH$#kwzVeeX z{Eh8g_Oi_V%bD8!B1YDCUxLlt{I_Td9GdI!9v7~(^*y1K`fs1^UnBS>+C>^+8ws5t zka`i#;a#voNTO5WFHPZoGhVs#9V6F!EiPDMrYzC;ey;1wmIKW#0%o32-me4yo;zK$ zGyB^@;sYc((QJ$6vhNqETgX|z)k|(hg4^V2W$fekd#J#zC9u`^_-PgsgevMG6xsT| zPV_p}8Xz6{@H|2t75$zfVUG?-nAMnI&X904RRSsO;2)yg8BI^fldpXenKtN%vu%-&gi1cAgm|7~=qSFI=bw_5NV6^cs z(dBPHzq~uRx_LO~cUpl$GE{0@?-g&^lpQ>IVJxG%PwBk5d zs6eT+m3&hueRoZ5SlH1IL>d)u+`f=$BxN!vX1hv;WbTH|RJ}Nkn;E=Zk80|LCNf<>|hiN;j~w-XV78 zneF5#kMK2->VksLq2*xviF|wWE&C5P{!{!7k;}x1lA&68 zU`on0EZNncRo$^JoT}}!=J3nbuhQNi`jGvcakae_qATB za_C)&(Al8*@RXX?TX~K_)_T?pS!&hcWeS<>aFl7{-A6_*Pv5b7)mlxG$h%tBFjgrS6;ql&)W*(F&Wo7;hDAxpIv2CG<-tu8Z*qG@~0G8ufp9_QX{>^kVR zxP0!C`TPCPq`cUU)hvsI!hhe!-X$)56g(mQ>_e=r;yat)Gn~^uXaD9g#Cf}anK_@_ zqZ0S#&CPD{_u}!#J+pOpt3-$fknZekYo%#z+ReMR3`#zH??JX}w%C&4DF={C?1#_f zZrWFzLIv0eh&c785krq-nszmLd)^=3dN0^s$3a;4b)@5BAI659+%}uBp24}cg-Mkj;>TTDtSWhrfKCWN8b>a z+PLye6PZ_3H8*n~0j&BP&Z)&9@q9rmCJT-Vo(AKO6ubOp#0UHBmD9J%9Sy1zb>Mdf z>j@f;9X9-qIy;l+`#<=)uc#&-@Ik{Nq)&jMNhnHa(lJy4MMCcwiqb>^(m?^c2ohR= zPz)UuC4fLEYG?{b300aBii#ZzialaO6tnaD?_TWQ>^+BbNSPUCzUO;6Crd#mnq<@gH<<&dkr5*AlLTRGWQOHRziHy$%th)D8Eeg$EKkm&YZcngY zc0Q_-rsrvJLL$=RmimInqfX_UUaK||rX^YHtBqb^m%V+$wx!04un``m`;Tn7zqr-v z^7o-{XgT z=t;--*V>_D`DJ|{*g4j8FI~>KiyIW%3{lNZtWSCi6*;pL7Zfzp) zb;#^n=v_J#e(sdPh0Vl>0ec+QNACDY8cjyk(`_nhGItvJE42N2!WCuls^yd`-}=6| zUCX?)rJBjUKcXrN&wgBt6pRzBHP6L4Gk(Z3@i9H5@SJqCMBrlf={}-RK}l77aM|~} zyYr%sGX0bvzl(j5>bS*e?KpgbczofQ*UKShqe5MJ>y*yTGx1xLU5gZ{M+iCB93oZ}%hfg5KdJmJ*9K41c=I5NtxyNe=#dgorhR$_iiKf83RO z$&@tZJjoUfdmI@icUwoAv2jQV|d*mJAg zM-Y0a?fwoMT2h#eyzNxuWTyjTts-ahjCzjf4Y#~xkW^8s^!1a-wXN;pU3^e!!env_ zTlZ7x>M>$5G7@g{WS5)d>mCb}9qbX^BdJMBnxFM<+LdW4Ts6k9p3c>C!x-M@IbZyQ z8+M{^Uj0&hpwi%)?6J;chViMh%?*40If%D6#b+NES`65FV#H(KJDu(DI$V&v|F(Xy z%TE&rq9@Lp=Cp>45xfGvZm!=3(vFcvWo=YuCn>Eb+f;U|@6m{xmL^}m5POo}EGq7= z`657^|31k(WX4*C3!_6!m-ujI``v|;<*W~(IDVV|{p{MGS1c1uU{xJvJAVkvPwajy zHQ7)TkEWY1*5HFUF?u&i-%_%-hCS%0eHdXLXl6DL?Id<}rQ!%U^yK;$FV+e*?l zO24vCcHGvVux#g#X@rjWF?Fe$Z1cWT?@Gnw*GvXapBL=Va43{~tT;dG@$OAk%03rP zU(6Ze&p`1i&`y)&!HC$cA}5GP=|>6yetB@o^!465B9_`}^8-Ic=gtV=nYDj%zaD&5 zTsizR$mTxOLQ?v2(^-oD`K~chAjyu;RHG<~9MTyfK*<}pkjOL{KR`kIz);_PWCPcd zm$MGPjM)0B?W}~p+&3Q(St@&9ML9rRyX!?H`k3^-anJ_>yDSW3$I7Tsg9#5W{Lkr) zQz0*mA1C9JS?9i%9us&WMAvCA%I%I=9RZY7+`%A)5aaTj$HsO#+3@!MHBiR2OQ(1! z1M46Jgp*kqDCz_iYC0g=x(sQ2{3Ks&nvy=s!eFzH?VdQmKxYIGd1TcbJ9!!uq)VxH zY3?80tL3f!0WI#gj)n+l7Yrx{fe{LDZ5iMR_;_Sw`T!FsqZ~U_?gEoOaCAaKJHph~ zSMKYIV*np{)BY4voZtfAW5yJwz)+Wb!JhAE$UJtDpga`-)fCty9G8oqA^)cm89Zzq z>13+9*2ACj32gg|t5Shsaz2=oP;Kut4oH@g zfpN-z9G1C^tEZs-Fzy8zr}jkJ*?dpG!&dYm1O+}w9ymtw^Ki7iVH)zFcCb;t91kJAV?h^TM4^#|Miz}@A zDkScJx)(zKp3Kk}wygMx;(qW>! zl!M$20XjJ0iEWvj9oVvNb<_u3AZAgh$9K+^xegWWR@bsEmR9RHW@QQn!7$a-l6E4l zjDxGEVyZ~^AuReW>@2R8t9jffz`!G?Q)Sy`x~lvd12tDs;ZdQanF2Ux%xOkO?)5Z6M- zQ4X0=h0Snf<{M(>7o^+Bv`D`*U1cX%-);*!EAg}h`PN1HYdx?}c%B$+~ zMIEI8&woSQ7F!&DIgy5aLjXEJ$ns@EB_Re3qhX4He0-y*M0f`usXKw!o50&JzyfEYi3}lC$qLP2!SyjVIatmzt`3T^@i6t|^g;0a zXg6f4FjsbhG-iRY5YV;^FbTj+W8yx)#ud}n9+1<+0=QEJ5UUpOYulG`7qA!_4L3tg zkMg~WdK2GRc*W`a8Qcpx^%pW0tkPs)+d$xf4|dfVs%Ymf`(e+LFf`(IHW~PDV*m{3 zfWCg~8^DcqvA{?UY8MEX=P;Z&Tbx>N#kZbf{cNNub9xjBmMa3a`3-?oq&lgCt)W}r7u+CM=812%)xXHnn?m8w7~G_k`K5N zCKZ#v+R>*43d?iS|A;x9?Sy{?UT1gb$wNO+FS2{I+FhJax)qj2NDoz|>4zr74p_572|J)t7qc|Qb;5MX?FwiCg=5kZXyLM=Wg05WQ z=Ja5x8MHe=WFDg3#7044pS=^uF#w#>1|2>C2%%PZ>Zl{W2g>u@eVcT?g3Ws%!iyL> zKG&o4LU<2MT!$|fG(&(OuK>h^?nXz>V6>WRi+SU$3rWRP43pa+pkTY@3I(JNBW*At zx~H9l?Tqi6KHDc8&?4+2ekO5LSWwtdM!B4yhsD@*5q}h7izUI&8!Qxho4}WBq+LvZJ<@o=G^R;18(t37<}w4euqOY=c8k5v122u zrjOeTpi>*M7aNDn3*)$`7!HEUZ=;tZ@1u&)`a^K5>gJp=Mrs>o4v!GJ3ku!6&6?W2 z8?4}BFHvyN+6Rc(LkFf&R!WCy`)uWH0U$C;!VMk(a?WsW#p0@|P#i38Dwi|n3XbP> zkLQiLxPop9_%k!LXF2Gj{2{1T){bq{2B#T}@fIWEtgjgw*BqEw)Z^7^b0hb}+*$Dz1UT*oWVUkvB z2Mt$G!vVXlwNPl8P4WLC@C%UGrHIUt=G|Scx@&`r zT0QrgLqa?j#9xRR_Agj$E(pJv>H>k!ebCYPW*dm_SuUvOR&)~6XFz-vn0NGjRXYba z;fK2g;<=p07Bawd>2$_R405J>DOJ$o2TfnVvHw1gDe{;vc8?_D6FU!AqTRB&xL*m??3!9t6Ez)eH4o;I=}Q&HxG-~I`RxC%504i`=Xb$#!j z4#N6@z)@mw>oXC2k~yvxHvBBPf_V!+M-jQl6qzUCW1n_LOyE`Au0E+!EaP_Up2jw1 zVYN4!SyzD$YHJJcQ5_SQhKcaF_)9#@CFoQlH<6?L42T^ClDUnW;vWgng%fmg!A(6V zA0*NTX^TS?IushC@iObEr2_#SE#UIg8nKOd`~y}cV$bqHQ`{_ZQSu>nDgxTC(DF+M z2d!=CxQHKQVG?2316zmLWFF#At@RAg_Rl>ft5&)W06uz@Z_&@?yonL*8Dy2z@iUVt z=pYWt<2Sl{7x+52%nl`Un-5MA@xnrPYhaTntCCg(m3KQii$k2GQ4O$`gsUgLEB=SQ z+CPvC>-OFQxXA-rrjI(vtv}`RngUxHw|GjQdE!Ie_6i(m?Mc1{IOqmS=z>EaKJNqc z1xBAG;aWgI*h)kIUd)L;8AsfHE?n-+f4CM*VxsO`Lrxc9a%oe%NjzwlbB#4v`s`5^ z|I+K+eauLf&tT;*lq7H$mUMA&{yR;T*J5$ZYwTgsb753j$wv7@L@s^~LspqHu9hMZwn@>h-P- zu{vJnB`!AlJm-ZLSPfl`b>n0|H6Ab>ggS^!ZelTSipd0?GCPJ zu;1|=7WZ9wLyQ;kd`N&wfY%t;MRqL~y6H~;yokdNQbeCYQ8bF^Q?TtWA3x5SX7jL# z9|yE2uyq^(M$V<-MEnkaJpTUP)u7ww zEItgX_?$Vg)zkJ}8Iw9ho4kCPU0xT)%W5^$lpOL)K<>wx9C@tga>=zOEvzhX|BDQL z#{<8!2(H)G;a9(L{a=ZgzF(?4Z}FYlT43;+Fv_&hYP%v~NBpC1;1xNiW*p=>9XZB4 zD32pNIG1y$;&ss(r|#mDHaXp8=cWsH)`rM6s8v@bpfpzh4cV*0VU!)tnvGZ5d({da z6)4+Cy@2jmMmE{0*UI6eL^`KTTbwnY*Ja<)etGeAk!Pq!X0Zoq>ih*?+joc}|Lhm4 zgpdu`tKyVBnqh)+ivd`!h{=;b%JYu5Se<~uLl_jH+1~mpUrhbse9^w6P6>8f_PTvi zB-ksLnL;ukF3n zoUL=t&)xstKM#@!3KfEedqCHe1h^D_H>4W;CUS{vAj}*l`jrO`? zB+xIeHMq|{l&^LaQ=8{(svm0LeQvT|McOcWPK6M0CA%TGsL;MQde60RxhU3|H}?;u zdu!Gs4*${head{<<@ow?&YMadJOKvNuz7SQpgIL*enqXdcGdX`-PdL%^r(kylWr|7 zMD=>wWl=%D(cB+pz=EV-FXc;Vvwe1~STo{cBuzZ5=%MYy5$UM19AvR`c%>@f>abDH z{sz-Kl%p8yo3`c1aZO~gM|O^{v3Jnl#(Q}=uT3AOG}nY*h+_X|LIzCrMuc}@G=?#(ZM~ZTFH3Iybz@1cG$q=q zz9_-0E#qT!S;CugC)b1(F|R94=SrPSYwXVN*cNywzhiA%QqLwfj6cQJCK)I zwisSDw;1SK$KH2)pM=y8rmgmSi}diVBlZ*a;o1j!Y)xxprs5diE*_A5rFfU(q-)=n zMIe&}Le~waK2*%NGBsduC6?7!Z-S8qZ7kAJ6MmUQzyo^qm=}IZC!cko-Md4iJ0rJ+ zo9ko4OAaNDlTca*QY|8N4$0oq$W*2TGrm^Nx<*<{dQPbq{X)EOex>0c5vHH(-=}S| z{%4FqZofD_*07K5I8Iz8%DkdUO}aZNxT z)01$h`+K!50hZ+VD*Oe*w>3nnW1^G=%a)MeRMn{Xv-BpfP@ZUEmu8^pxe$9y;Sk9N zQrAe;DLx#N&CF22((bxOrfIL%h;LSoH6JjW(~!Md;-m>zaDKta{#!?P{+jxwiZoTj z$*DEa405(n&a&9;ZBV*8suLfDKjwI7%a0g@`f+i5_}@dagEYjzeZEF`c%gqjl znWBW#Bl6SiF;Z1U9(A!+HQZZzd?TxPtB{RM17}5pR0xE0I=k*pbt)_o7MZp4n5uLKamR|+;xeJwW zuL2&@3l<_X$s8k+tnz$S$7J265NBA#KH**UNq;wPE8+{Kcc)7- zsrJTYBYCGk!OvE$?k}i^KT3(OlP@mTuQu0@@mdTqJBz35QD5MKI(4kZc}QK)cEHEC zR;r7ya=q`bLw>5BPB{HWWntt{XjSDHeCDVQ@hg3gBT70fNhF^wyk(z@`L0gpl-xjk zCZbrvo55kV+pXm@T@kVZ7D{8De_l<)O4W_u>N-p$3HG2}Z%W+#u4C$98}%{dlv2Vt z$+l*<52#i4u;$dxkgr&e?2vImh0ARZ{k$k|8@ZYFOdV?5lX!=n0bQ#jTV8s72x|3F z-zob=F-Il5*Z%R_&zF97T0D|4QWwrSvDIE(BlM&1s&&hOZIcE`C>J(m)4U;UMxCgS zVHi#5($~>M*j!Cv#r;l?=24H)(7Zi(gy;ZmOn3JjF(vCYHh)XbJu!TlqtNhD2MP1A zB+RNQ2qauvvQwXm|M~8CaMQHNl&vyI^}iz@LYLb@4T{8jli~ODY+opP zEe*^3q~@I2`X=F)glMItclgh#EB%&1alG^Ht#Z!>y4R^X-V5~Tzj-| zxN=rAo^aW*By6jxkuu>=@z`y_9JDy(g;>h+fa5=!ejN7cYpE>ZZBt^x4CNq5C`i>5N|!sWm)$FjI57BhQ0W;;~#jxt_I; zhde~p{;WjzpU4a_E76@u(}fM`RHW&wr|l#mJlL6e7*ySeG;F?oTV;Q#60W*~RrgK$ z$t#PeF+_9gg4d=6L9mRnBAGu4`CqJY2NR9|+$tD#-o*v5(2Y)Cwu~P$)0Z{O^v&GI zF0cNLiiBn4tRthTnJLr^L&7yhZq5D>YeDUD@5}{#*9zp3NagAcG)tqhY$DU#)Jj;# zvXE@qxJHMNTLkS^!3V@NWmM^6?xd-D#X7Rs7p0(&SYuz}ZDeU{)a%5TKZxutWs2)` znCVaUTTEMR`&cD&Kz8eEt8EH69}TE1gt+cERIsY(S&K@Hv3bu0(`nYni?N~ywoRxo z3g*kKcw`Pc;L(}<5d$^Qb`KwhN_KdC70zJp9^C*R`|Z5`FNwM{t*SY3HPn036j4a(QM-&4(;< zut{4{Do4iFPNvUd>yx4V#~lUdov-ZW7+x#P^dD8!i@BNNo2t8nvV7HX*ip=MJ>viY zORCW*!ME9UXQnVSpf*Pel~xGSsuXZ~8o+i$x;YJz#=^L3WX6)rqFD4vSy=`Rr_f2s6uuhqGOF`(~h_duNd_hAAW(-3ljYg{JA%ot9?cEvqHHd0OU$U8qe$PSGg`q8HyPTQ(^*S7m>^xRC%uoJeb#0**aUZWe)voV%m zK7ck<3$sTRile1bD&`}uV+x}dx%l3!1DAKeGMosR8p1Kxd?&cQPy9VROF(Xdw45uaGo9la< z$;G}rXUjkOuXj5f;X~W|5T+G~fzgbq_eI&w^utT2NS?3;4Zb*i0oI>JHWMvxhpi$!zGnV#F4*^-&2s4&ioL!s!{nEgIfE-5!K$@d-zC~tZBn#TP&hG+ zSHpRmUMqyT)lzpec$q0M`-ks@ZPqiwvQd@Y!q%(lVniIaJ{z|cX8_Z80vu>qf|)vx~wg1qps2;meS2RonHzw11XI))ALcq6E)c;q<+WqiFA8kVY}6gmo1r| z@7im!g(S1{&7RJHQo4nNtQ6Yh#39Cte~+{TGHU5kG=EY0mauhww%9T((GF+3iMBhj zP_uy^FHY~v7)YU|!}BBz{e*p1>3QG0_ikpH9Y&b)gnzdP+ng2_*s#OY>_4OlqIvY2zwbNOXX_x`-GBQyV0{Zu zvppPd6%ro5BW^o%g<%iH_-M#z3gQkPVZWZ$IrgB58?aZ|p;lw3Cibo;to@b$@T3|} zOgzV8HKUK=by(xUKcRH#i$jH&!M@lG_X+DVd=BdbQrNVH$nCXYw|bC~>ff++k8>_t zbS!=9e|?(%MuoDy7Zgfl5oJaS;z>1kEoq`&6>S{%STzncwI@iwd@xQ<5Ymzyz zdd!`YdL1Z;R{>uTMtDcQN+DU0*hZu6;G!oYNCN}CMoSY5AG;S^4hp+)5bkBz?R1>&7QEkA~~ri z88-4*`}kCmb+jn;F_YtS#=;wVdQokZu1|WSEsBkk&W&YZN}ix%InSvud5=pO?$iTT zhEk-5iax)$=Qwif$!~GKsRqnJt8OFr?99OI{ODJ2Z4;@r<5ZSLdw*s@E0w`x@^bo{g-9;0a~>CIAtpiIu!5H&)i2;_b270 zOlUJscMBythHGSAzgI?Vz;rM(-cRpdYKAvW(DjdWdHM>QF2P;S zTF2)`@AF$ok7fvP>!}Ve@OG^Gz8F+&r7f()yyI@ab|%7PS>nmqY+#dirEe;c8`E|1 z{R2KG5VrfXN|^mZq_YQ(qk_}Q*d5}UGpr&j91^{Is&cAq+5JU_sh#f^zRi7Z@pujTmR9%o~LDu%bB@=@rHv8cJ=u^16SA| z3zt>a3+O+#VBtq=HBQtPl6!(GYzx_6SX;3jNbSS2jhEBn>Y-gJgzUoAFDbr{>rLHM z*U`GZe1TyjCdz)&|FrP)_O_a(YA3ev;H3g22PTC{GhP>d^j*v!gX;I~NOGTz@XgdE zdBybae|j~4V@rB*KiHN!Z3Pw(qPV7wwAu0$58#uu465{_t;- z-t`2F*@p8%piWf{AJ$ZNkHcmD$*Rdf*!dzVneX5ZIDLYtk<3X3k!v`qY+l{A6PEtf z={&4E9(OubV--Hmf%qh>yoz;(bo>ZBOCm zSwT@kEcWL)MxU~5VPst5ATjPrwukx&&j)})W&cz8D}>N%Jy#?`6d3!s^eh*KJG55o zxFLcg@62#a1xj=91RJ4Q*t(9)+j< zPIp?rv1P{Z@HV=Tk%-1j^)WBc>H{;W{j6Da=`O zZhDGox<2M-VG!Tkg5mr@Cc=Z3!lt?QLM1g}JIZT6qINV7X-Z3X<`><3Lp`~c<2}2} zMW1(tazk3^7qcQGk}dmYLc2-qXyfTGO|!p}zWnmo`NQLv#)zXzAR&1-GEY#$w4RVS z5<-2D!bcshz%Wk#Nm+*Ll8zOgeyP4k_$MKK)iV7)>aXGKqLvU1w)`oD27_{A&d-Ww zC8 z5jYuxfYpzc`raLpO17pSLdFAJE{rXAXjW{=eK#Liz<7-9)qqvmM*6fzD>nZt_p8sT8 zlpix0Qk%Q-M3inuW&9J_u>0g?za!wt{=PHcW-Kq4Ml4)A{Kw?;6MGvLyY0=as(V9p zGEzRTqAhd=Z-4CK+&D9@(q`CB!>9dP-mQk;`E@_?xgVc^xxmMCXV{$L{+uq1Jp){tZfTWC;5|rqpG9$R*H8N74Zz_ew zo?cbTQu4fkvfh)UApsK{Cyhx2t_opP>t2Uc`A+I~957l~y$7w?{J6eA8sZ{d?Y?XZ zqt87{7%g{j4!JK*ePwlQ$qHF{YTH@NJs)vHS>xAuL&4nW+Zi3%uv5y`Jx1$D$`In0 z*mn8NSC01ee+``++k zmE4*!xwEmJiW@nx_COzRY)c$hX{uSEdMNM8j~)i|m~76lL>OCS<@G7GLaq5Gw%nW7 zI)~hF66aWHB`$hO@7DnJE1#64ws(#Ci*HxB%v2<^~)Isn=dEXn$lVLZfb@IQr-QMD|X@tFw z`SeGhX9XN?h3_a4x~*7+FwD2Q=3kYNv`v?EQCmpB-bTS1%agPR@g_9 z*BTto)47ikQQh`ZHaXB!(=uI%o)J%6%vP(&OPfmBItRQq;IWFtRhc@z5^Xb~k9L0U z`EYJ=7^cC2OT}r_cD^(VaTZy#+@CQVEAmf#=2K6he922c^<(=3BEKTteyBCAEXXSj zc{nJhFUv|1eM*Yl1}3xTvlQZ6+r}(2=teUJf@#9bpPy5{R~Xf&kVbS5E*$(t4;iffE2hNKc2a!Cq0e68E5@A; zUN`V;;CR~}6zWqFjazNiA#kL|dAU}wS68GqRf1eobGuCzyA$?Zk@I*pk(ef7qnT)X zoQ!=g^)~ZDDAZyfGW8K1ftH}XzXRL81eZs7Fm~vrdq4Se8}?6}W-5_uFgm=?m{EG0 zL3t%RNf_U8vIg*ljd(4LTws$!lr!!nNVhL3$l7@iJ9-*upfE#Hj+s)yuo*q0LF zhN=b2cYGT_^FW_+S2kWh_UvCE-F9ydJTCZs=9q4>zEbw zOQjQ;7L(bX>-#k#j7W*wtgw4*wC1N~JgWU1>ogyASBZv(;>c%STJpaY?jfhkW3)@m z$9&PI6GJj*GE^PRho%c9y4Z>jgSY-;&L39FfC-?gWO%w&#Os$8-E-s}`Eo^k@mx9b zildq*`(9hoJrx{zNUE2I_T4Q|VF==z)rLJ}J@7BlI3i7G%D;7I>kf^0cH==|`FS&g z83ctoq8cjXg`B9BcleGGmqyVhaAhVJ{-Td=(JGSJf1@KkSsQo2D0@+96h3PTdYJ}e zOl*m1mo4Uk9`YZEAKAjW-hY@N(?BEg;y_vKPz0m4zidCTp!=z0giFzrR|e&Ins71# znp4g~DXC0J;!JcBGT!`iy76T5v!j=7sv=DZ_GS}3^ph>)x~bZ|Y6+TVud>kxP7PRf)TRjMjhLN$EwciW(j;4#YpTk*XKWmee|9fpy-bJPC$oi%UM}K} zb&n*v6=HYmycC~)pqXaLjImeNk!Ylpjq06CP%}HU!0474HyQY9;ReE$?{v!MMh6}_p{=c=i z5L*~bC;G`mTiyT7GIohh`08_MLYjxBs+>ChH_OQTI{Y%1pnn{yy>+tZ>Ku#Z@gjkp%i3vgHf;7E%kbFiey6u9 zW}H$>PJJ2b_%7eBinRIbl1g=IHi8wKu661#H^xo^h3dnwaNz zHx(Zd&)Vq;W}o%pCvQ-x9`s{)`E)qJE?)qKV`YIVm&t}N;O}^sy%=}S!*u<+s$L*?tOlyWW!pnZU=1QT@#2e+)hMOE) zDVY8G-VCa{=9}DoiS_%7)pQdw$!Z1fwljQM{YHnico>^1T-bHA`>YCVA?cLP+6a|ww zrPU$mTv9G)9Sqhw5pdO4Tujy8>{Ac3^nLABv+x%e&%5g+*fzW3diQ0-)wINgiI4BH zJt&=wEG>_?8gPkh`F-Vq*rKs*WM{1C;)emLi~9o7wuql$mc#D4FoSfr)ocrB6}62V zU|IiI9F@KqEA6EhlFJLx0YX<(++Tm(Qt|tmkHN4_cjnPMdNP6cny#)fGi%UcR+K6~ z+kPYVvxnPjt*u^{Db3lR3M^?dI9B>DMP%&vY)V4I=JVq(l~tD{bZkEUcw%R@VtY;U zaA}?G;Rb=o^?O+3Uf=!4We(n}4UU`nVWrl*^;6c1Z5hPjXoJJ+D-KrB6>8q&)}PV= z2NDoWjGG=s{8R9?-ta1CsqePhJI{T5hzjZ9iJAQ6EWhu2D`odVb8Oq63kmi^5zH8o z_oIvbJ9jKd!xmKgopNqucXnJAAjwblV+T$zO%==U)Vww;}L&Buth`evD@fTWg%j>T)QQddQVyp zm@X$0iZqkn?%jCx9OviLYZ z&B)bpU2u6zQN5KC#&VbA2BN)RahMk%+BzX(brjk7B23#!bs|9S?I-~rndOvl;Yz_o zxy}amNZ{WW7oI#Yp?6ZY`>j8-Ja=D4{_i0S*7cR-3Ev&r_+X$YQArvZLfls5c%D=> zoTcHJp=tD0)o%21){mGmFKyuC?s zG#oolzb%ymlv6S^obRICm*7TqlNMOz^U8PAE~<=SC6N2)ypOqJf>5OnM}L07QLjww zM;Hn+o+!jrDfksjYIqrNSI?jR8T$Nqv*t`HWgg2JeSw$1QD%cPs44%p<&x1$4QKOW z=+B@S|G2p`&-{xg{&03Ci-)8|BO;ouC4+uG@GM@_i}qsII}97zodqZ~Z^b=r8==g?lV=%2g7cn@JC+ujub<4!ou4m}j?Ge#9UcKWPP) zq4(eWF{6@hbI2(#OYK8N!PUdY3Q{&jU48}jjgEI(rs=->1WEUlW2%BllAimAE>8!} zeJCLxM7LnlqB9G^syCbEDmM4+uicXv9o{2jJbd!CsgH4v*B#SG!(qWd!&AqG0!{{7 zVEnV5;W`-{&{Fq6^t+1L1VhDZ-t$

cu{{qBvm}Wcc-18XCfxkEvP z+{{p^nj8|JatXO;FB292N$X6&$CtW-ecQuClXwe6-k&P2y=}FeCo=p}=ahbL;I;>Y;9|9L=25}) zOX=&C=V!up99tBD{Za&)%uu+%WHHVCwocX;15 zA867cF5#f%An&nx2cD;NwCeZr-3O9AKjv@1vfT5AK{|UxY5+!G8jb41h=1xCTZ`Fa zXYEg)W2!6lcez-Q}LMzhvXK# z-OT(d%HB6u>{bf$T^z1#E$8DI!GFrK+l7L$uFxjrVzQla#aFQ#>aRXcgA)cQA!H-k ze8i{N+_wORBqask4vRX|a*I~}-slW*GHPw+&!{kWXXwMTgbXFQU<`RCO?KRoZdjrJ zJ%XIRI?Wj!0Q5de7$*FtVYTDnmW~x_qgHD-uy={Ec1V7%eN%Cg0 ze*wK+r@Lk7NPls()62>A=<-P60!wvv+DZz+x_bClMXNsguY=&M_#u z#bg1qEC6aJRd8@nN{&Opwm<`%Ff95s4U34O@`BPq9c+Db>Uh_Q z=}}=9FmO}Nylf;H@iij*K9a&gm+`Tk5bWRplhDw<07_kPvCvq1H51Uw##M9BF%W3r zpnrO$zWRZ@G8AtXe%dYE99Kj0M`S(G53iYsj(O>J^XBgPuvqc+p&?rx+u=bh6 zs$k&&Vu}DfWg4Yu))jxOWS7nlFl>7X6!ubwf?RyDEx!QF@9caS8sZcUR6GyFYp~JK zL}3p%uY-pzd4O@kVin9V3=-g03D`9OkZOojN7p(EhmD5gY?4j*$oA#DbHB@fCLjwu z3oMrrmVV&EPqCvEY(!RJ1z5(QV27yqTO@$VL&h-kxD(jO-(tQ|IQO2yj%C~>0Sn{Y zgrUKpw+OrTE8ETq=;Z)V7|R}=Q%k`n)AkyX%iV4i35X&WZ>9|VmhZU@`Z0B!e|U%& zBE5*vXGyG-ife;rscBdS70V~!Yk9|uVbIV&_9zjOCK%;tY=H&<*?@K!ew2gzk%Ln* z$3RUvhHPCYrPR$2fQog4ETD54w`V6Nh($2rz`aPoUEawV?nzwD6`>2V!c*X8gVvqS zfbsEj5bu%rRSF@O4k|RI3pKx>tl&v555p$n>Y+3ou@)N97jWx4{x>;T2JXT{I=EPf zpM>4MfGh-P<{-nbgn?z>;sDd@*vKf{q=1`{e*upeI_cb-;Pzg2ufI*`A%#uVbFvch z2igsuoTx8kVwqH2C$pgxY=9sY)K9F)f*=LvELfXD%GX>^+3wu97J=`eHB`aUd${H3 znu>I1_UHw`SEG6dyY^~tg6jtU@Gtx|xl@zeE2TKu@@CM&FGDOiiY1X8OT|LYgH6R% zQnBGV*p^2prN#W+EP_bA|VEab4!6S?$8gt*2Jse#(YR<{j0{QQN5jKF+ zuCBb9aIObG&V(><+k5Cq6JKZJzwk?r{_N-L`qS3$U+LtuuK-_ zSxg7Z54^?)cw~H(Oe^ARhn+k-wn^IsQhg9zS^#|tM6Jqf^8P~)nI*BMkyI|*MGpTH&#&k*oc zG9nymhp9hsCbt!8Ue-d(((vre-eI`M$j?7wTtUmo0B-^!3qvdj*kP>?pihu6wJcx; zCi3Y$UgsA69!=ySQDg(%CSaYx9ssdVF8V!@{VxPY9?ydf9Qwc-L<2PdrXHMRo^G!P z8*P8*UB+W~zAvd~Hnj7**zq&fti12Jb;7|TCb67cg}wq;aC9f|A4Q6v8JABPXLV-( z5gR9oJYxMvD0nay<*(SMk9XI816nikYp+{ z1qS&i@A8giZ&Vf#pg?9$3k*NV2Ov1r&>p{og4^}@;!r6yzkycDgjM!%{^Jp6 z%zLjf&*W%Bb{Z;K0b**$He+r%Ljjvh$gI zoFTVN#T$t|qQNETxx%m2RWVNMUR4tF-~@n38me^EwvR^}66 z{{C)ZWObEeER~Du=tZmUS}Lu<5A*QDQ1gq76&}I_nJ)^s*cl>3BY-mQeF&E*nCDy* zaB##d?1k8=6Ev)a3~;tN&j{L>l=R3y8Em@rs5KeP&uhJ|3kbc#aXHVo=+6F0p8KN< z4lY9mGVd%aUp622&jEz?!eterju62}GV%-=TSJ=8BjKvJxZo&k8yUDP%Z#-sgTPd0 z@=VmO#lxw!6iyXcT3$Y`k3!5P`NxkHGkc=T?`~vuAM7q=x;@Ty zD;wWcQ_LJs)d2>1*gI8FAQMBQVyI_kB5vZ^DL`-F2x{)t9=&daAeH0r`1RV~w1wYd zL(JFC+m<);AIn(aTSyq|-Pk%JSQkIzpat%nT*=f&`94BN%)DD6iNf_oS3uDfn&=W4 zzefuf`mmyk8rMRsxfAvB(m`A`Shf{E5#EFu-*ZF#Ag(Q*{poP0h2A_?Y4z*m^UbTB zg$Li=bo=yBba{YUviu3x21{Dm5X;kE5P(xx+-0aRbEpM*Xc|+?7is+`@|*}hU&bH3 z0I=h;%a|W}K3BGrZuE#wyg!rjGaQq`>(8eq06__G@wdXyJ~CogTMpk(@oyyPF6ZMX zoweV&>;V_=J||on9s1J&l|t+Jz}mW4z~vRa>d(PKs9@-f>g$L7{0vh^5{38%1QMRI zM2su($N?OLo2n1uEV8~ob}g%7eqg%et7+IS4vtP95Kw;L<32)M6`tR!dg&3o=CQQc z>+|?~UA$F+#i#rKp8w4U7ynHZ?U{uKAMa)2=RlD+c_LOj-`5p@0pc)HoD^{?x19GK zj>XnN3IY_>2@)9sq1r2+lr+bo;&Nm!+v{ z6T?T3|115L@*~0zm%n>Cz2&jx-3i#&y~|{35A_|~K5vOb9i(k;81ofL)FD-8e3{1~ z5@V}{J9M6TF&H{sWp{D^RXOA6d;i@2yj^>KK1EpX*=VKLTldQr$^Q^?-m8>ayZrxH zM$_Dmz<+KJ4`GWM_jTI_zcgy{?vCT?By5ao%If+}hP3_O8FkOrC-4Ra@y+hDB`Iua zqVU@rk*b}7URv~tNW-v zdty~GC+%8q^q3U{)XALu4%ZHoq`V%>*ZHO1J6YTyk- z9-8!{M{>7<-n*&z_$tPi1hju=X&fY1M61LeUwc;&+KPm4@*x(+C=fpc{CCmjN9e(P zV2~lpQTse7tC&(W*Q_feHRj%>nBs$s^|Y)%+tCmTG0uLRg6&z+<)Ih z>qx^|9528wGN2%!AtbikenDoY7>&&N6cNN9$t>yJ^)%`bw zV3@3E!w3Z4Sh4*>SFHmvO*cetDuG9JV=IvBu{Y2Da*a{IcKFsWDSP@B!jye`)MYCv z&<7}snuR>>x`JvIvD7X4ZLuW|ecT!0q6qDh3t!e#y~YkROCK)GCV5CLOW!}*hF4Y$ z$U8s6;|gP6_JY2%tg_Q~CPa_f4y$rQ3>I-TQqxgLUM&ykYA zpsa@?)KRLdI=&uzu94`6+w->R}|c*GI6`0 zUY_4nFS3K8-L#S-8?oII zRkxDsHxuR174LSM{h&Gb@&XEMKjJhryeWYP-r7iGZY%T8PY5eg&99$AjMWYTJe_psON2SkW98m5ZIw0METq5ZTrG6 zcQwy0?NM2vvNL!Ms*M7u?TBJci~!moYaJ&weJKcRnwe^_PZ=>C@;{$Sy|w895=|i& za+S^As6Bk@ZgzCVnLanN3Cv*ambs79fqU=ixXz{I{!6}EQ%b0n`4XyjbRuJ}LH;P& z%?PEoFVn#~ss#4wmWwgg7vv)EiFDojrO%cK8<1&FP8Gk_`)QfM)Aas2z0L#gZ{JVfo5v>Fy)mhPx>uXIde>L)0L9XYxOg4zz z(*7;XOGrAXG43fe_w7WRd`UqCQot%bAh@`pK~=vc&^fpFK)_MnEp2)46dAcNjQVT2 z90AlMdV$ya&s!I3mUZd|08&rcJqWdAL^=Ss+B;n}J0m?THzF6w@-10(>$_^_rLOf^qPC=6O*S%#jqeNs*5EZZ|TR z6EE!1Sh-s3G<%>1@$}iI(7X6mBGSL_HTOxBGEIBE%+yV{bw{q3ow?)J+LVL%6I@RN z^W+2$U*>+P0JtWQK}sXyA;}cXlTG_<-odv&U-0+H0lppb$!-wblk58ocC2tVJi77% zLt(_k6?D>63Qh&=s=6vE%V-VTP3{Amm|Evv`>UtQO>s9@>f$cNJbO3(tS4mPbF#DS zE%htZTli0>hr^-|9k`UbeB#L)s0IQGOQJrv6Yc)$2e^64v7XyDI@#JF`p3VA9|Ujc zHhKNsrk>*N#Ryu%#8O5Ei1)m1ak@}vg4MY|>Dq?vj}D5idQ&)e^qlNyxKCZfZY>RrfjO(NBSk z*Sws~@71GlQZ(iOSLAe*24<}2P4gW_G!(Lu0C5>0tq8%6$$a%E+`FY5&r}gtm*o*Hb zFaMzF^O;UcY#fPsgmzOS1mAsO*GmNaP7%UEj{)Fw9FPpXk4Bd`(2gR@f{eDfeol^J{#WIcYpa#2WGSIy}!x<|0NW z4DIH#b}eVoDcIoe4s>3dA0cZi59~S*%f(*f4l|5}XglJ>f#2B?DVziW{K!oI>>^Z~ z3o&+Uy3%R(^3C?$bKVDWEL$q1gVK#Z#UN1?0X<;pxRp_FkI@Fbn9k;sRF$h0hr9%nujb)3C-qzC=H{&Kq8W6#=)BO_c zj`&W-Xs5ZPaZ%;G7O`g=*@n}KmOb5D$yNMN(d#II%$zxY0nhmSSN6*%j?N<3%Fbm- zWqLVJ@h4j$i8fqCo=TPg%pBC6HkGlQ6+xLUQ9&djvi%7Vs|uL^t39%A0Md|v zU6-NB-*)zW!zdy<=MNyT$K>Lcvn)yE-$+Zx8whlC!B&wBz12ZP$C*;Tk@~kEuS$97}0+O%utR_O%#Qs@xjoX7z@mlPS zN%)z8U@1oejy9A)c3@=5<-4*G6(n z!kL(F`{mk7Yp0M2qWVU%{o5oS)XHthOHd`zsmH>qKorfN99tK>R2Vz zW-}r$B-i~3mHh@5$9NpYXsj_<)eO}Qeo-u-AP2E6PiNQ6b*ps*87M9E7w(JK{7O)h$ z4UzFJAy0I9cl`yl^$c0Fc^|Mnv7SmrML+fD29QM&uqMHyb<~`3H zqsv7-h2H)&9AAbolcju%v9E7*=SFi}8kRZ4(P2-~CCe8C)3Ohd5kd`wVsv%i@{rem zHNu%DdHD-D)GOhrqJuEH=X^$MT>JKf`qrnHw&!3)jb=gx_Y|0rig-!S$GMazw#IO9 z;L1E!^%qiYE2QQIo2`oIKgoN04dY!(eZv-cJs4}ku@Z?)QY+Mo*kjul_x0|F21-(g zc8&~@PUy?D6f}oOihB>`clA`33E;`V#>oYeegSl<8XbG>?t!hf+K4g7#A<9}0x4R* zI9WE8XAc|86*Hgty~O#ON&hP6c*mD6?c1bO0dtfby2G+=OHNuB!=qMfDIGIXTr(x&Oz)l__Dn*8n{QpEybLgK| z)Vfs{3(S)_^MiXwIQ#ly>L_2YpTs>)W2vaI!2X0cn0O|*3B*E_F%RhG>=m@j zoLaF^D2|?G6z!$NS@!wbYRJI3D-OSvmci%Qra!LFbG$vPqH&$C z^(G^;fB7LnC<2%`pXJ}@yk5qR@2kw926?Y#|G2Wca;~)s!AX}}t(_OIzMo7z=d;(C zD-EH^h10&J^`>diK}J9ZQ3RzTY^YJI3A9W)5)_W#XP}?<*DX}<1Ec#Ma@VjkZ*N-E zZ_#TC%zu98uA7qTaz$B*OtKl1Dt_{#K@PD-kKd4m;o*ro!d&uN6fjgWA6$ zBNU88*CTE6r(QHsLLhJZ1HBiKKf!)p8NV%{a?h_($O3>tHV1jJ2G{s^M5U_U9RIK6L!Gq zh2NwhXGcOuJ+krGTvTE)&CgqO8Bl(9ncK-g+qzlH8Yw9{vpL#Zku59eu z`1`wF)sQNx1q9xba{{RUCoo_#Q#ei@5$eJ?(dtGud)g?PDlP<;@DiP=vdrzopb5`C5|t7 zHQL#C1-{!`3qG|dyr0snOrXrRhfnq-KP33%eEK^csP{x~cU9ku$=?57-Q2t&pIT`l zkotTyb5<~sr6*lKpCCGQ|t@3c*>_MZN3_j}q|`0f8AjvwvLJpMP5 z_wnPizGHu`IsUm*aLfNVTE}l^oAPz-v(g<}{e9ox%^Wa)|NKt`chJAZ?bW>-1Ma0= z?qKOJzoEgkEYWVbz2^Ujd+&Pa8@pOk8)iJbA^2+{MC~ca}(k_c{2=HN?sP`NRaxhb5 zvWRb6-*|=oY?}4D`Qq0!Ylmt=w0ofN->|*r>u^}%ZV%%nE*Vu~pdwml7ai%|w|%KR z0@Yfr?BlC8TL4(zVZ0=7PJ{{>x7`gJI<#nT?odx#-1&nOEmf{zN1L7>kw$mEt2a-y z9ouBJJxGnBW1s3?!`}a4LFMSfC)}_u&XS^nD>?CfD>QK*!>`h0bXF;lWbq<%v!m4O z!{x7r#;-1&jEQe0>7HJFa-|#otUCRQeBlQd`*r?klk{?ho~P4tX%m0WCC;Q8n|}hQ z(l9b!cfzZP^11H{6Fs(nK6WxtRj|vg+|AW`_m{zz@aqq&?rgCxlZ$R!tLrngcy_t< zhbm^C=guhK=JF?$kWgy)f@d@g5B~I6#ivPAF{DPdbIeyIFlj|d8UJ^51ie&OCFk7z zEI{$Oo&j;(I@s`NkApFVQQy;G@T|*5_O9AdWjT#wzRqdJKOQ914|0$0COr>0=^GsW zP-V{9?eSi9?>!F+T%qr}9!4uLf4Uv`&eh%HAh&ShNy?;~wHsYEQvcbeU7EjM+T=?& z-;dinBxfKx~q-+d*qxCZ}kIKq5b{2jX#7K;DRN%L_xZ) zqh3iYR#1=a?MO7?tc!bhxH>PK+}n5;`^lrlMUG3umLOEPkQ;Q&1X0QkRrz3h196(D z?{BvcrT|RLB@xk+e}K?<5$r~tx!xyqrW6}^ebZAuS+@k!KGL8u{z9CMvMBbD4n|c^ zhv_m&z73>IE0+#u8IJegg>Q4ciq|$<m|5@6;J6>PRL;vmOY;iQcZ0bhOaSc;2@EX5iTJ^bTqG(Pt#A~OD zD&2JR{hG?|crN+D(Gz6AIbAkWVsbh!e9)AwT0ZU@u~Bp^JYGRxVI<4?!~!}z<*n6) zUgkD(d?jMoXW4CRDtZ65%D<5DJCzBWw3qKz8IHeo0#u4S>9hEqE3>+hnNkwxQ(ldD z6exUB@4V&~y}rErn_g2!bda^i8&5yGoFcQqqxw6Fjmc8~E%f=@hhaDFs#eXA zv-6nvjfG)JbQhCQ)s1JUd}u*fGKMeD*@O#CoQ0OET@sej-^xT^@6-D_`WLHvBMm}y ze{Lf0d*7mUJ=5n!e+9$3{h!&Yj|xeG=9M2^Rr+f#svhHyE5vi$|K7h@q#=5nbAS*WVKT0M-(_Xm<+waA$I5;ga#{wec7qr_IW<=E7OMM9sV- zNBPiG^1=8|CGRx;$I+(!i~lyYMP;n=MLTVHTj#oqk8zic&J$55#tRsUF`ioO>cxD% z@!!9l2OUmauDEux6VUZUB40P1RDS!{vp_VdFNUzujJpt;F!e=u1!Sc3yjX zYrIoCSNY3U#o*XTxkG8Ln*kkCNS%vH4v3-mL%d*yxH@XY8kgxDrJOHOBS!R%P;yWS(l-* z3*$I?t&39naT~sF((z^xcTob^+`##1#P7u&cIdUDm$~DKRGvZyF%~k zx=?yKDvSYAv6+RUlFMfAvX9GPXz@@3VkFYtG)trKpWBwa;X|wf$K34@hbA=U1>{gK9gEh|?b;m0E-_6JjAIPN=6g&SP0Y zyU^4bVBOGuIepu~9Saq9{bczk-9M)FRAkt`Rf_WII_@&B)2*SmxFgN@xIf?lKA>8~ z8?)5#Lx=o@DD9FG9j~6+Lww%bJRo;nh*Wx}I`Qq4NrrB6!%3gg{#|7DzYS>2ap;tcB4dOj-&xp! zY-}2~m@wvK8p-ke_*#uGU~C;dj0|!+y{S0O1~)&z?A5I9x2VZ2pdI*EUcGm2EWZW8 z5$-d(d<+%cALTj(${s_Fs&vLfjr78EGk^&_q^-MI)e7cd$%xWf?k#OQI?8=;xU}c> z>yWXLV%(^pi!>aQu}wu~;sF(vv&~U@s==Q3&(c-j&jHGhU;%Ja%4_8;(5RD2$Diuy zDAg`;su@c+-&+}?OykR*C8I|9|MS8&l95?>S*n0=G7uWh)X5@4Ey%$;3y5KK$>F@f{ z4_(ui{HcK6TXd|eF0Gl2V$C4ONtn)=Go>H|06Px}Fc0~dQUKK=BCpMy>7D^(+{uZ% z50!zCEaIt~0AI@o&|p5Qg@`&UfbS+l_DK|MsE``rHh3WXh<$m@FGC!|qoDvm z3Xo-&*&%g%uOy@ zCInSVmTmd&V2_2czG1ZE&-c>L%XL!rMB=_8jsc)dxmY1z!~(4ESpb|iNyUs(kug-p z72y4r^Q1GfWn45MYVYEq0bUva8yf*oX9jVC2iU$#u2Tzd7-6rI^7{dSeM)+Mo$LVt z{F3OfS!h4*_b?krJ-LX8if4V~LEQ#Bhdk%>e%0-AeaTb6o)9Q+) ze9R~y`K2NOiF$8ZE)9f`t;i@M{LiL;jKTl}&W%JivJl;1TsahsO@MO%LU|Zy2Z#@W zhs(e+<(#$3)F-%OZP<%Z0GVJ+FYyAW!baXAzT2X!iAX><-O0t=qMlTiMRNh(IfZ>@ z20?A(O0noWc7Ponl|=^h?}%N&iVaf0UM>c(tjwDr%w$Cwq!9CEyylv5x$*+1=~obX z0Rpav9_fVv7~;R!Y_LC))mA)-m%B&8>I9M_%aenUgP~k#!vGf%j+B zL$QsV!hR9sy*g%;gy~pQxcRmwQN6b3y}Kg4cDo2tSq2B}+caQ~&$!Mm1U)T2Q%$W0 zBiZ+_$G0U^gHtQ`b?AF!)De6-s<2e!G*+#mLdT(baZN#hZ|HbZ@?i^hhMa)#&oOCN z?M+C8)I)5DSW_aF$j2UfD*G=MQ7DdS2F2DBk$IwO77?)`%P8i{7OPjEz_V=#9QV`J zU1GFyHsD}y0!vftLqgDb4nQ8XeqU%?pab^p8i0EK4{xt&SG?kNI`X$tZ7}xW2ZB;P z6cFrQ{veyqmCYof*jSX4?f+=ifBr3~s=Ekqo~KX<v{{V5w&tD>WbCu~$!DTu1~W4|U*n zKxvQs;edRJL{k&6U3~NmA7gKXrP#MAc~?q_ZPO;r2;Gi3NtOVf)J%$A41^!~KXCC8 z(M1vkJu0Xip8*`d%q`%1$FB3cehUQfbd$Z@RTSwBf=cRU4UDpDy*Q5KdJ&;>^k;pcMh-nu>mY@$^fI#PXwrG}F?MahIn>2cIsZvpm_7;B4G`^i4j0pF_<) zjgBuq&0@`)+KDv-WJV(ql|x2psQ16OAGi--zC<}-3?cVoytg{~ieMBSS%7}7ddf%P zCqQ%x5Resabwd4B!KG#*u*A@SfE*Y@VIC-e{l;{Yi`$Iz{k`**5=(1$-12j{1*Kn; ziihUBJNmikmOpp+L=@m@23j7Ec{Tf`Ic);cm1_dzcN8K?0Eg6%g6m}i2XP~Hm=Pkj z`maKW@1gG1V>d|{2}M{9x@KH85^aj=5@2RUCuYafOP5h?Uf1e4cV-gX8guV7J-cJ8 zb#vl(YbOm=#b;F{_Li(FK($5__Sf`-FxSMgXZY|w6Kt_;OU0lXpvF!YD=%-J!*6Y$(1dX;u*wvlv^L_5)oBKMgcs2zF77W7ZZWRbPCc&vQI7==hOby|5I`2 z#-~Yv))dsg|6CG~4@oVF?UmIXoD8dx;s>wtVW)|Gf@~C!^O)w!ft?>bt5S_5VHfh? zHXl!vk*J`2FiuNyci}W8+)UdM2n7Alc21*yjHk!2z4J zoKzHV^g=a>2%ot=I8Ky*g_VCLl6x-rAKE!bW;fs&4Ji{YX;Y12q+{N!@8`BvjWXx$ z2*;1rN0O&!as5GehafAHA&yVanm!U7Y8G&xVx1F)x#&w|6c3d5YihKM-*fVF{PDAo zgX_QdCm6x9c>UR%+dysh0pr)Rg%bXor6g5 z3S#l8T-FP@SA01ssbLt8ZXmv@=8GEfDEvCo;l?b$souoPG50 zI$v~^C0a;0e~FbcY({vflT(NuxYKa9-}qcjQ(NJ?kpA$^Zw}s=%Dhs@I9wCn@lr+F zQD~0Ae0o$ejhDNQUi@*Rr!#LceUkbQxh~jIO~h-3XrFp*Gnv10mC>T zD}eDQ;)in=&~HR?!=TcBJj%%vb7;S83>nD>p-29NJP!rv1h|zqckZ$*)P8RaNH%Oc zf|+nhW&+tM9x=0fHwxg!IS*Cas)s~1w}}a}@{ee{-aI(>ZM^E~!(ERc^-t%e=W29w z>ZY-Bvt&7kBaatkK;|-_T?)3xeXz<#-8-Mfz3(Yu#>uMy>+anYre;wcd- zCJuF)h#IJSev^p&97RQMU&Ur*{us?VBf9irJL1WON`reVCz57vznqC$$IN2omQH@( zGG6>7ewpTnHQV?$?)&Ke;WsoL%qI=&2Z8AV%Qm`I;b#avTkpS_wes% zWNE9%)!V6m%99=$1dT>JyDWWDH}fy0mVWrAFm==B&_=aeg;LD8Wz0tDso5n&f!-0f z>l&~_kGDk(oO})chly6m zx9EvdvxwVOA>U)~6_r<88{RE%uypsU{8ANqB90g_bo_nPa9I( z8wVQ0kKU%5k zR`HZe`~DbxeiD4}*6WtB>HW=N8^@%DKfl&?X4adiA3UxYqo6Hu_*5$}4;08K*R{G9 zdU=l<;-ZQ|I$RZ;pcZb5(#W^9p?v|P6%iV#O0OfF0{)UFM>DQF9QN%L@n z#cf_j)Od5*4^~KwlJ5rnmcgXQ(Jn*dfs`mVzO1#mGAyhxro3hFd%}+JJa2E~i1U?( zdqSey3~{y`MIuhdHhQl{VrxaL##-jMg44$8pYH~?vZcj1`@NaprL}U!x-3;s0fi2R z1X+rlOEypfy8KaUqhe5>f!Inu#^72|;NE7_`xFmd)`cWr0}n+aOEPRt*surh3pa)w z#QKK4mn+r^AHRR$2w>qT+Z#Qecq8WI@n&V>M9PD%M4!+sxe97t1JFZy;;tGVzh+ck z%l`eYoOsi<{Y7;;XG|q1+JdPZ%8K;4=X%%0xT5{}t=qg^vnD=Wna}jBd66oHNtdPU zQ*SG%iOw*tp$i#AgUjGaBX~jUn|xajiy7YZqphjIrNOalmOg%`A@?(=!=q~Ux89Gc zyqQmfa5G$7KG)VAP`z)MTI6-Ks#z(pe`Sl5XKpVOy+__jnOPk2Pr$vW ziC&h-Jj0Fa-)d7^)c-4si03dTKTUb(_%_Wuwv`2Vgt(V@os=mz{rg<+>&-~j6FxUL znAg0wL96!vv7I+?%3J0!HKUVnR4zM&P-Jw@3prV!V?vnF@9x*F=a6gNS1PtH{I)M zr#~2inmu2)R393((tNZxkmpw4N8+-{5cLG)>-77+umU9*ks4;b(6W;s}A zDqj-18<7>qD872QhujG(cKsA39VPD}ot*j=`mJE=Uz)5>ox9y&ryTTbrm~OAm?_&? zF2VF5t{dQ8a{{zO>Y{Md6nG=e86CbjvU4>d=iF^q(lyibsf@@)JzZn_0aKMs@afiu zm)1EpKkAia3*)>=YdVo9gDg*YdOc}5p;Rk3g1xhYlN5D)JHfOb-AcLhrI?r5mY-?|QRXeXh1w5uGI*J)L(~GRyoD_hQ&EJk0}U(!;$ld2y?hpN%=DZE z{+oEWQ!N(B zg>c)J1&q8G(_}^n+x&~FM66UYR9ItK@9*r*NRLvHQa*;5-A8^5ch|TD^6n3-&#kH% zjc%s6s8n&8+dvIU$u_hcJvlCednkeG`&lY$^C*VI_z{&W z+{n8n!#B%>9AgJ5J-_WQq;`r8w{BG`3?bfOSpN2~ZCAtq3hk=eWd>pD31@E=RJj3r z*_!V!m+(nXby9FUn3r1P{oDi{E_6|85C@Ttk8Jv#s=V9q;(vEGf1ttTt=(jy*P*UQ zhsTLCri-Fi0aKZ(Mh=|KcMhuQ9oes{KGIDlhMNbv(?@+k5R(#*yii^g_JqXGY=h4- zOOH~2$z$niS+JO;BOEDd#48jJjg-EDOXFp_q`EANDn^_3=PTYXL7a@ismEoWw=Y!{ zTE>&I+{URM6}7isG`b(K3V92+?bg)_E&)%)sJajCjtumnWGY_~!YoWT%e^=8W}WUE zQSIU~r5Q=XBD1?!4Mm4`+xq+R3(?&}*tRquSK{Bc6o(mi@~5u+EjVzZ zvc$>pe(P>)rE!c)dp?b+bw#Y`o|K@}A_1E;9LV4HS-W zVc!bqcg~`ch%o%53nn%wQ*Pr$)aL19HJoi-uMwktnQDW1y9C3$OLeg8g!Cv&q(S|P=nHBjiSO(5Xzy>beyk^tyLoV{78#vn!ETKQDd@y)2fs|FHELoL{z+$d zqJ#O@rs50!t=Lnan;h+`dHN{a2yu>iUH=`*^}NgGs3U5=@|jC#05$fE_CS#`TT|tH zgB{kA zDb6E8r$Pysz|M4DhMw^$ZlPKx&#(@Q89OM9+DQFGG>0?r zn;ii!Fpi=1fe}!b?=#RH%2#g-l@EFkFG1Wo{%0sd$Vx!KeaX;cN-$~HWNx?wo=CMk zEP%TUH(?T;uj|{n+g+xLu&u608BoXckjRo~Fbbig)}G@`YAcS{ zE1_X1e`SwcV8u(ak9ab54Ms{Nv}oVk8GRt#onsRu-J@?Dh|8Iem%+reEQgsa$N8+n z0~JJH&S44sNDAvsC&Rms5X?3GbZEyFyOO{WyaFS$JP}QyK&HQWyrD6pXW$_?s6P%C z3No~lA-JAt+Kp-Uoa+O|EVdIF2cwFSJ5c>%x0XX_sY=@IyLQb&YFCNabk>yOoW7I z@(jH7O32>LrpOwL20&DPgv;_sgM?jXcmTF<9wQ;8G=qO*1aCLuS)%&mw(SfvLBLA2 zLxvDwK53qzVk7qiyjKu@G|;oulNE`B-nr$bTqVrx+&R)J(>;!A8pK5GJ2bf5|`1Eyrc#7VwDP88bn2-UV1#Rw>TcE0ygIUmUZXCH=W*;96w$xfhr`SbrqRg z#U6G5;Vovqw;J33jky<>=`4Zw(qL)aEnSQ?LBe?RL!?h5I7yLg0R&tZd(!H7(_S zqOfOX@9WkfO!9qcPYTl!XIVnaS4~0_)6{{TN13A-Ov@V)+@o-bugEzW6qw_(x*v`a zjfIiOzMKEh^fBHBO?QR!j?Yve4-N#D2=*G88Xio@bpo(r9&hp6x8EE47U9-%wE!(9y?EZZ zuLMEgx6JyIzFAfxi{N5PU+3xDX%p?53A9XOUMEl8ey$R_i!;z8}{ot3UmH2`n6BXk-yK^9|=mK5za!|I7D)$-FRecb|~KKhiy0^E2`giMiaH? zkAmEAQ?y{Zgh&rrhJQM?zk!pv)zdjQDVHGn@18I-2;Av(?Q)N3N6_-r@ddY?`Gx*= z7mMp)6TcN47f@HIS1*#7yNJ-@07gc-R|ysBfpwX81q$$+&oUKP>?JWj*`aqR8Q8yvpaGS1TVBy-u*4ch z;aBuCLfT$Dh@mizm$SUEFwOg;4&QXVE#Vn5mk50N)a-P`JgZ8h^pRqp)OhBqW#*Jc z6lBqt6P%Bscq%LAc#Y%XaRfwow{;0+OnzbXl={pdkeukNDPi-fidYdm#_M<}CEd3K z!SKX0GVnt^0MgB#D^8(HUO3+POeiM8k~|wT>?qoXc{fkYZ-)6K5P z7sgmlK5%BYZIz$bim1Qr!}$@9_TzOFa~H72ui3<^AWWbI&d!ur2g*$3;RQ=j%^75*eD2Ol> zZzTVIafH?);^6F$Elf)Gj#F7m>V}c+FH14_`yW*fe=^f*<#@ z@ChX6M(;((oL?a&KhttP240ydQw%2r27sryJ2@S=uwO;2__V1v77TAm-Y-dZA|C1v zf|7)c+N`X6-zz0{km;!VRyfG^H2HWvHjlLA63gew zGx6>S#>@C;8N{soAWrOo`=wNQsLq#H7-UsVo|Z=mRSXLvi|-0!)QuBhT&gB5>(1@b z|73E0jf;NveUk1RHykIg5X%tPgE;H1I4Vx9)c)%o-NLav1tY7VeM*8Kw1VvLS21-g zVR{qXmg6 zP9v1e;6k|StGru5>ZgJ^|CAeywEh?01w3j`N8r5z6mK{=dfF{;_9@?a*M$Ya=A|qzVQ``-Pk4CZ7hl_c@NC zxN0zAKy$C0BaxX%JuxLZ6HxzGp3 zd!*He@}d5950xSZeI?nxpokD|);8hp&bYI57+F>%a~lVH%IfCRx}Q2Jq~zkHK~5M* z3Vh3=+PNIx{cHI`*r>Ll>=sPZ^aW+-N8dN>KJP~rjvnEH zA$EB7-Zhwb)m=4EC6Ppyk=*I68-y=-vIV_jg(Ag3}*l?o8pMQ@PwOx2nwyq@n^s3ztTyE%UxchZwMbw=l zvqP(QzYu{=}Oz&a;qa>{@VXo)?7f%VcqZ5{6B=f_g7PG;BOg15>n;Rs~CF6P^GAZ zUd13tM+4G9j3|PD5(tFQBveC_CJ3S!iV9c=y@(nR6~z)16|4~(Ad)%n_ug4+?))(G z2LLB4Sz)c`*?WKXPbNzQjul+%j(qcd3v8Esm5G~`(RI8Rw>mWOMtkd{$)_zpGjYS? zLt)V+$|DZmV=~7+dydPr{QKcXVA=m1l?g0sc%cwJvHDPL3?|_oKd6ZIGr_ESnbGvASB7tEjlbRhK(w!jQ&laI&(>lZm+4Dj z^*YK_(8u-iq>O@qzNu6-V@X!Ae=a8U*gh@ z#^(=qzOTY~YH@uf{Bt#~9HVy94FbfDOnXQef~a%FZd#dQ_-_lXPVkBKoTY+19Zzx8 z9+fq{DKwdfK!s>mj#SJ0lpiUy8JjiQhbpTqKSO_~S;Fp6c9Kqx`LjPl{L7Fyq10R$ zb7Qokdgs9C0rrSIz07vn_>H*91sqL(q#>ly`;m`H?d2sOBkZ*UXw8bvCg(QjQA4q+ z;Vo3GTmpM$JiD7B?r$#`DO2GZG!vT+4wx>aoygy=hhb=2YYaa%=Gt%C+Hcoux)As@ zRHyicRQM0TzCNJrQ)pDlvr!r7${(pZ=uB=$AUQRwIZqI#Jaur40sCkSggh$TnO7D% z*=D|QX4k7oI3XHlP3#=gy0^RAJ(+t^(o=E);wu(^WY29BGK{6X6rWYG795q=vZt|8VfVA2| zSJ^ok@>m$1n{8P(WJR=mXbt6ebpz(b(>7NTFqmslQGhpBljk1D@T=f= zx4zRIT4IzTST!}(XNnjyZd(i9^R4uoJB6G`jrU>&YDaw#gp(oYFa1N(H>j$PIyu=5 zY3h12P^tiOyB_JeCajY=W1n$_r%?3Q*`;-S-0yen{$u1BRhc%s(96g3r-SZ6ZR;oY z^k&+-d=|IVT6MeVV6X5pP2<5UNY0T9+WYDQhm8g&9U?Dx>%ovVSPlf`3s4~xxhxBf zH+$k8VG7SC-kP;4qdy3B)sBd7hs@YNfXMe$;vO$pBe)sbvW@3DwQ|h5Y^39%Lr~Gt zC${Cej=pCllRxXNoFukEq7P^&3b5#a#Rc* zCbYmGGb3LXV|i>djm00@fBdp@t-;S?&o3dQRM%SheU}NRe=;1~4GS#EoEBewpMy@W zv)ym_`t5P>cbK3Jv2>4zk`{zdfxnucn7lVljt$p6wC*n!GnZ)w)s8wW(LO)g->kT! zp+U=%>Nj@aMpwlzQGJ2F%V@ zTs=H7gum?~76%^HTHuvX`c@0i#s9Q~_YP_5h}4X)zrl?tK!m#dUaTD0b@@2qxM&kuBx)(Yhe&>>Z8Sun|FC>)x?&J+#N{A{`{jC z&j@dFqp=?QWeG&s5nUeKm_?OhUZW`Jg@nc@_CqcZ=uc&V|EC1;|C?QJw1LPP$H2({ zXLjA|a**6{DkwpSz}V)c&G)O#Pkeka*?nn$wP7ZDyZqbHymSqw&b}$h#XK47|D9cL z_qi1Ha>{h7M8$3>Z@bmSi9vObMlvWtTwSsTCSNa*f$@9jJ?lqC4hQ)YGzQZEbrGh z-f+HPXX`1KS49g)9w|M%d*|=-cMqG!gVyf+`@6QVP4FRXGJ$y)cYGvnT`G!~vD>C| z1OOLzE)Y4Vb9h;jK3WH&?}T64p5NM`st-$i+k`0O|bN)VC;tT)cP zVM3!)pajvBaeGp8Hq6Prp(5u$2_iAT!ShYJ`qkw{CMZFuANNpfXmGYU`DcH=*Qu4} z$gLUjaJkaD7L+l?hVJ80x_S|FMYugpB7HN)|oR1U;Mbj6}5Bkg!iwxo*oq!H`OBLt=g8o zv-V$#B^21&E`GE7Y1J5rh<)w4XFaHi!kO~D@p;2jHS*5>xufi>b384AVPce+=`#>@F zbC1oRUKWN{4l&k}X*LzdD(~1l5O&o6wG@~*`bW}bfV(2_wt}ysW~}@}KAt}&*!TBT z)~SE3)mHFH)M#mDKSx7PE?1tyU z`MfNnQ=YlmmPNQ+m+xMEYT@uqah>Sdc7!j=3|iL=Xob`d0HSz)?~-5Yq#yp6jd z%iqjwvrDd=%ZZEcx_jJKMm*NP&+~JRl(w6nOSQyp$&j96UH#=76i$f%JJ_bCCE0X56ddUlyf@-FY0H>tQ4=Z&cVW~)Q^cZmsKQI(*j19_cQN1xxQ;J#qa8D~(c zS`xpTW`8ylCD=tZ*`Td})v1G7^%nK55!bf=owJY0yP^E-*bQKKk>er)rfb; zI^7G~Y5hl%mzJoE!5QteO(0~oiJ!O(lhAdBeJcKH=BF;N^w8TFBQE;j7lzq>WV_n| zcW_}=b?YCY{stG`Yimz@SsC<4GN?E-!lw3ZsA5w1w8Z<-WJ_tsqxO1U75LLEH8M}ZBBCPvlKOy__o(XrG#viWz0DOo4664GRR0DeW$ihjRnXIuNF^K-{ zJa2zZ59$wL)jOrHeJoARdtAT#^vaTpYm4cd=jXm%)-BGw#wXZuyy??rJ2=H~= zzdFx!-NXX+RK;A|K)=^N1G_P-s zSE_g{H|~zb6GsI&N?k$r%SP?wJi|jkl#MRN!Q4#FE;E!t6c<4494i@ROg$7Pi41N&DLDk8o57mHmmUAkR+K0pHH+& zz_5I!l*zp4efj2J4)2B-+sEX-*;y8X3nvd-b2uMLcLd|T(+RSTdMB^a-XBU+x?lM% zs5qtQyNCskKi{_DfDN3TW<33KT_kiEzHQ;_bwkS0s26+B(Tebgt`Z(^PuS@u{u%A> zH>{@jJ!kLd{}EuiG9xGMzs3ylGdGW~Uifa1Wm#;fhZK#2WZyq=ft3h>;Snuz^F47 z1lDo094uH&mSth@v9SUUwt}0QzYAbKf=}BW-xAS^j5z(OG1ZPq_4p&2KmZ%sVD%RX zx(pB583G>m0g!I7CfZ0myP=s0JAOv9Rrl_}q<&vhHxV)B4+NEj5|GhM0%n$g{rLwg zwI(`ANFU^(kC9FxJx@ACY3H5V`SXTMN|;>o;%>8wV*)mUP6dqt%tyj( zLW~+Y8ND{Iw-6F{EYl$&&Msh~ANMpx8}#FFzTSNFDbrdkusJ($8~9R2M{fRbkL zwV7g&$Au1JAMlE;GM#YZA*Y3MZv4KvTP2&i%@s)mbd#G~)GAsb1UQWOR(r-J=>G5|NDR0;$nVKdSNAZu6AY^50+ zzS{z5bOELbRlhTmF(DCNBwyUB1~td?o?85(4}wNOTghRbM4=ykz)XWS5D~+IAi5_} zKX+kSe33~xOdkPr9l+G$X`mlNBO?nTNIDO_+rP0#n+aB>OYtH%l8jT7gBQkRydyId zwd(M;sffWUKTTO~m!g=rtJrrqsPME<(b@qZi;rT0#tf;noR0`5q5G*Q7Kb?`f-L1# zce9&&fV{%`i>39*R1Ru)U;TAbqkxII1=<{x29OVCvPFm=4jyQum{KBUh)t&Qbt0Zk zW*bW8DZq_n8Ek^Q1z))FF%W^+Ef5fL9?D_biOt65*q|sh8SM1q>zM?A%57*RwRGVz z*C`ntTvQz!(?LeoW{+x#_X6HU>MV1q>K}c*39@9>~%zV~H<%^t5E;Y+- z82f`Q4nWVWRGXbHjjn3xV`3sxt_h2^-{rQPmTT!C)=WaKAQrLTT&|1;;2-}MURrPL zjRb~&TLprNdjJLMOJIwdPDYJTGE7sLg=~=;G_r+U+QV*^eSUF_isn8;wzDx`CV@UY z@Jk2y(uXk<{KasHSox?7STS}CxU$C$n5VG6WrViffTRD2zK_1JmnV$wl-WxO^7xNS#bk)5P2ja$vp@|bi8!q6GhPZIl`a_vtQC@+9A z4pyF#@huvgq6=8N_541bFhK87dRh$HFtyJBOU{nLUW9-o0(PnExHaGmKm||-dP&#$ zm=OZ{Ex2n;Y>95ap&naW3K6LTx_1TwC#1zf?-?==^u8d-GXlQo+SC8W z6ks7;P(#cBA3F&?hy1OM)Rya3z*@kqU-I2uDFedaF~k4U-0vWxR(1g=)Q6}|H1(C*;8Op;0Mg_I-&a~^0^cFU{k6fzZ+J4flouW9t8i@Im zI=*{%`^i2`AOB7)pWKP+1O1}}l1K_+?EPQSK>@L?eqHo?B(`h{+sAGbF}!gAtMr#E z3hfjXa7Al2xBUb_84U@wnS|Ojzi7Y6k_K8bU`ARH(8Q%=K#Q@r|BB85x8a6Y9&Z9krzd+G zCTsP8bs_*J_~!qj94*p7Lu-)GT*^UpaGF7dfm@#~A9HP&1qR_#4GvKN<_{zCYGMEG zoy1HJ?gl_VCaJByj#pyT``^R~s9IRu%YM2hdNvPdmydfyypI{Y=$-<+KtFh*oNdCm zQ;N@PCUv~C!qx_2K+mW{KnA1Y>4*Zf0ocLULOWEIf`VTQ2h~itdE<7e$iAC{ySt&C z7-;l3b`OT0i*DklF{vo9)Xb@$h|8Pda%Tj*8SB8=JAcdPrtgb1+}GHr_@7@y!9H=G z(hf#B97WT(4YhxBhB@_gKB|+1QTU7Pqk^J9`z0$(2M^uMM*rOa{m9&Y=3GheO}DGu zq&CbID@V#kJnLDXF=+*J7@fzUcG*PAfrC{?w?%LSsRNJc`iRNggG}KdDgcbG67Fe`w#QZP zXufDDUo?$5T7c&WID<7DY|nqAB&dKbQ7|2!TU!7Mkt=&Jg8-I=7pZ}?wF7g_kY{N% zEv$X*8edQ`t|};3*qBc#rMr@Oe6CwYfJQI^yNn`wf)+SrFhIe z>g9VpY%6y(f6qfXoy(5h8Qywqb{2?}XO6jF>m#I>LM*7D z*t&=wcGGU(3%uNNso4?@!2^*TMADwACK7IegL_8A%~Bpdq~fOQyKaI;XEh5r)K|EL z^3uZ00<+vgz6-};+!2%aR&m68VdJ)j+K8MD!Tme!p7zF z@8KT6@xU$t8LMu+vS0wH6y3j_`ZszO?zv0lPLU$v_21Jn2+?%}XyiUYqAKeD3i!Cr zhgXNe_wRWcxS!O@UvA_sH}Rfr3JgB>6V`{Hp^jWZD#ak*A44v^M!negCUN&oV}%d? zJAVKAIK1ob_+OphYv~*9uRn9QK0_8`&v&E`pwU0Wna{do=2{Q_m6=%_hyj!xM_8V3 z9nWpwa~39dV9B{erMt|&^1wUSl325@^-CXK%T$;ieYGj_{;4~8w*sT9y>UT010tFt>JVx{r{l?NQ2i=>6e%k(ngn#W))8%dH$Mo*& z#G~CScg6AMo;?y_Dmz!`9gGP>mDKD?fP7hh>O7O;Kr?^$TfKjZtUaCmn|; z3*;~e7DN@Q(KWuAa)l_Y+f<-Bju&p(IgtsrvLhQSTjb-|ixVc#OpK_RqE2d^_7YYH zE{aupgo!onybBS=KJPb=X1e0nohky(wU3BLO*J5-Jj^{|<>Bsa>Xk12yrmr;uIrIN zRgjLIrrf1R(fR2&=HHC&oLaUOB|<#I#GMhHBjx@}Q~7sWkyE;jcQz~uJ5dd}W0heg z>yedV3^@%JM4>dU6Yi2QEx=Dndb4eJH&@b!qZ8I5sdE88096ogR7U>{fSG!G`p+hK zi{G2j9+SD%`v&cxXDCtOPp=6piPQ=J9j4fI5h+jiXK+>+*%Rh!9%L*1xFB?TrOt?) zCswd)>TlDY>lgCB)vbLULV6q(6jKaQwD0Pb^a~+lauFAcHL9X6%sc{ZS$A(Edx@r9 zHZW9J!BBX8NCXmsc%Vgv7>q_gQtW6wBJN&qVj7yO*|KJ*d+^;#Ua95ch`84|2GB_DF{3F~=h%VJ%J3)YKFTFaF(n}ym7euiM#@g*u*BT|io5u>q;!apvmDzE~_{!@!+XV#EpY`wp8 z)EI)bG$K&9;|+?|2ZSi0m%L^&{z+27})=|Yf4*PxEF>JnoGwlYPixH^1 zsUN)rbG>85FODJY7?~1z^~I&^Vl~0v9A#HeOu%%b);&*{;ZSE`*xVaJ>%4=P*%82j z6AA>jde~FUN`@a7Xo!J)2^gsO^|;X>IV0qTii&aphbwdMxPzXnXP*3)EeWQ>C7T>k z#@dX?jo_P~@<+8C2TRW1xpIhbbyw?Q@8umM%uy}KV%9c5Po>3^iU?)GE#@+CQ~?Dp z-|kc(*c?Cix<*!yG(@-AU83sb2Q{}y=svdzCN;F+Cp5$`z9vxFw-aMKM^-EX=H8rn zfJA7zH{|c4Hk{P8P-LCs7b$NNr60kgXaX%P6QW~*Dy-1b3> zSwk(W=c+VsEdT2|Zvby0gnzUet}zV0Crj5Obmqv|Qz4Lg4yJ~iW6hid_XL47nB;Uw z>!Y^%4VpofYe`s?syvf1q*&KqB0DLBO{ChZhl=Gper{A$e6A)7-jsT;y^(v!cTf-d zp6gZ-RwA!$Cn>*?9pK$mRCe!>LD-;qu&h1)L<#9@Oa|JGJR}ZPa~C{vw-i?~TR!iY z)ka1bdxhv|5#98f=3+wf49geMRLZzLh(=maGxesF3;n@# z$i7AcLX9CV0%j-E6u@&K94q|TMfI?88x=R_HZ8x#sr~Xf_KYFw z_Hn3GS1YFG_W|I(xTESfw=n`sOlRBW;|?mGZuST<1;8mxa++K4+IIGQ;QZQ-m9$Lp zfK5@^*u@|iWrjP=C+_wP0aRbYUnuznH>wMUQOd*RqEx_gW?fl=VI)Kee2e;wCo2vJ9kG*kM%N*>4wa#<#D-( zJgWO*C)KUN1;a53cU1y0zzy z+xQ)SZ0ypC`#}{#g(up)e&ykH&Y56NIB-=)5Ug76ajPv^y;_@4X0Oj+Anp00@*?T_ zVq(jhuAar&r z09A!&^J5b#p#^(tvfSjV!Dx7+0lXS62-a$PpNqX8Ug=;AH(x3gFaR6Te1;UKP{Lbt&k{ph z7ApRXie)fhQ4j-gfYjN_yA39zm+i@hg>n#>b?n2n!pm*&7nwN1GAw>ggtRHL`WNg> z)5E!%zw#NsCE#UE1|DnK$L4|fD47U~weECg&@@9Ek~P394O`2$tUm`|#mjdlDaTn4VZ~|A@8Gt9@(A`mY<-IBl#SHnBZ25kRE1nnbGw27Cg-?&52wHH`PsDHeXGiqEJJ9_CeJ!c7V)DPhf zCcwPr^SjxBxEd}OaI(?5Ky>|#1Q zBi+wcRzj*=vG~pKgVR5X&>`E(SPhS5wJ!T-GpMY`_$RDoMTl(@e1}|*6HFkpK?6Rkw+~jjidv#MH3sH?>(eN#PSj&DcC7@?m;>$%W=ZsXKVIR z_Wg77yKXZWeq3=2s_;+QY?X!l*+wvX+&8gtnJ>o2}5}sUvfE zUKq=yOoRFrkbnE5o_C?TdNKnfX-L(%4cgD(D#uK@1Sf+xuOT{z3rYFYXvl! zmhZVUS4j3L0EUY3I9TX)R}RdgKGzY*#_Fp#%h3fv^E5QFu7C(a)KoaphA5jIKv9oK zyP8manJgQNx}>Ue+E4wOsa)0Q6k|R;INUJeWX#XQ)8zBr59Ig|5+dG3-nm z?9An4OzzlF!f2L9&t2Z_v%WsVa1M*)Fyy~7!YK&ffLzqk!o3G?rxV^h0qgX#8R;x) zu`@N@+1tpux8Z7NUdZ*Qi8vNdu6TLs@w|!z+t;6{6Bv5|t+yD^O0#awLT>GU-pQ_b zA@QdVC@{|)aL91v(=QjuI#%GEx2hKxUR3>hoem+NTU$CurZOfn8-oYEDp-Vyd(5bp z^HkyP;6isHst^Mr!K58PI>#T-9&$!_Ok^GouX*vP0@K92>(6kKtKC7&kma`T*BZE# z5K-W~TvY#j3U}9;DI~>33S{PyGRzDyW(I>L408H&LLV4|yOe5Krfe!U0=K%JQ~pl` zf`_2l8GDwqOhYc*=fQ9zS=N{*{eIZuFAC0gfwzOmr;3WCEILE`<2s-VrhyvuDRhpyCsih_Z;o=rJ~yuK zoRj)Ar~WDTJDZ{v>AHv4qY4off*^@PS`*M4vAduL7PFQ=$c&YyCnF1q&yDjKrwpZr zl!^t4xq>!A+@-1>8)i1b0O8?{TUuE7NG6 zWniBv9`=hm+{-VR;9vU9={To}Co4?M(DkG3l!X!dX8m+j z1yf?H(e;QpE7*Wup`r>sa~x=vo#JEwz5C`e}ZX#?qvbP_W{x?9)z+I%(|%hkgN|pjS!ut?q{Wk3lIz>w7f%d zz(%P;w#Sl~UGf&0RLpAJ8x}2^yI}JT%-|WpWg=p&_E3Tfsb0o%s2u}04<-FEZG?p6 zWW{Zi8kIyEKObnM)yYgCMJV5@LHE-S9@m=4iT<`F$53ooy77r|UZEm586hZc%RQX_ zCr`9IV})wKat}zZllv(eXr;=m8`?#U6$Ka3*ODrLN=o?-k*?dvVzO?08ZM-S<=jgM6H?e^bPQGyG!yj3No< ze+u!7)qge?RqE={5J@eXC3O@%hfNa=i=@!?sVC?+bAy7L&VOS#^QH1PqPbY)YJDt7R-nquGnTb_RK zk<>qJ=XbolnOyrV)0zkKudnf!my0|_-!#MtYyGThmGH?foKE_)hXu#0olT0=d}Dv6 zi1NW^O%bnS`7I(ff^wfhrEV;qEnzfYEu#fM5~|7XK~tO!XQV?#{wKR$Z6qSIEo_*t zJd(am)gbN1x6tSz&nM zeSsW0)9kV*trx4pPH%;Y>wa8qv&k0LuiErIh*!*4YmlCk@5ENKB~laqZwVqH8-=%* zB$S>KlVHU~?ngrqXT_FHK>H9 zZE)W1)=&SZ5)t>o8V<#6D*QZJ<#dFm`oOil;j_ZEYTQS9t7(#62D|(C!qH9h)ukx` zydHueH6I>Gt2`vF&lzBW^QjURpUIcfO)F?M&i`fCqwcpK+s{35eosY=7{*br(j;@+ zDJdD&;b!<(l;4viVfkcyW)++pBz=awdM{Y8smVl0Y)KT_l&beG`X3G(RAwmWvBXaa z>NyB}>GZ0XDXf8wGgAsNS1DA!BP5b)`mwj^9HyR4S1w;Rx^D)>@%KxiVHtrKb^eu-)L z;rxGp`Qt!hr^Aj3c^FPJRQPJZsbUYqvIe`%;`V{T>kJo-nBSZ~a&e`YTZ zj_pahcIXi(L8u`9kM_Jf*q)z-{C~9PRYo8Xy)A|M|2KC1c`Y=1Ojh@Qwdel_yOvxY z2`$sMqW$moyh9OoeUSEsdBORAVb=#6UDHX^hH6vRt-ix~+ud%&`D;4m!DglioTI2)P?)x=lM_#6_~7uIhHd-9qb4(e4W#sGz=X z5WBWo#aV=*=DDq2?LPN!u8iXyYKVvS-MVq~cFj&&neN}$pBFeZjMK-9&XcM&Il6}* z+-0|V)EPFKQbMcw#+US}Ys5u<>`JVYi1I*Q27K>2_Nat?ex*~NNf>=lSzM@dPp z;utjyt(N3Dal?O<#yrB9-=iZ7%@+>>9&s9P&+Wb-3D4L4$Cu3BBOR^gaH-8?yW|d~ zm8DY5QN%@eo87;*m-$7kKa}#^ocG=5BE|+gg3puP5K+TPZfic!f|MHnVq^E<)3LDB6v-%uhnGK+;sUqYDTh2^%VO6gPOm(-wQcF+kA^yU zUUp1Bb+PFzZu_Fvm|9cBCnsNK|FKTs{O46qFTKuHyWN`+o-)33z1)83fzRC}d&i%& z`%*94UIrLn3%5)1!fyU}l=Pj@^JshYO+!0t81B~--+zRk&bV7{B(IQ!qc`^1Ki#kc z0(_V3JN)cAN82Nxo|&D-9E{dL;ujZx6Kt351t*)N_pJ*PEiO8{%AQFD@4m3{84-Ls@{NdC>uk}4 z(bCgbJt7aeK#lR7q^LvC%EuL@9fNk?QRJyWJyL{?!DEl^y~4? zZfR^64^Ngj%s86}74JFv z&|J2}tbvzKfwS*N-x9s$Px$*Ru_RzGqa(AIfl)>(%2nYm2{V?6>uYJz{NBZ=MeJ3i|0Ba7YhR zj?TnsB}{p_-gmtQLoFH{bU(6@pBm`AWMo>x(wV%fHWN4T@ybfK)tN=K-TZr}vrL-G z^ggwhCz^?ro73o$6CwWKA^6^Bf`L;B2h@a5;H-sCJgmF=VMibzZEcm~WYK@$`?p@} z?f36*mu&vX=uMe;r?#;(uq4a{>45rfzFZ!YAn7ByPu=;6PgYCAQVu%go;Zg*Tk85T zl@i#NqA1@c&2KVhe%5L2S^9I*f`Ze(;l{$=V%=N=WA zuazVD_p>sMZPv)j7!<1Ps;l460g!!B+N7EMG z#i#sx3?KAZN?yD3^|=aK+;>~z-RT7NfbAu(wYx@7D4Dp(++})09%8UP2OIk@zL#%_ zLiU(V+9qzVxwKQwTzPHZJ3_HmS5;XEX89fE%9GUB!K?L+3#+71)5e!MCmSMl=;eo! z+By^!ZL)o;IvuC}GJm|6^$vDUC=qxL8(d^@tRag;*8Q1SHb z`>_}9*;Xm9)@oBjfJDBr;@$eFYiY9FyHyK_Xz8ibuKQ-h7GEiRB#D5nD%s)IY`uie zyaQ>CV&EZ}LPbHejedZ#mVt>4W1ObDxvm_$W~XjGgK|F^DnBbbVN_yR5Ds}O)7MIC zirv%tO$GMwSn4Zj&0ANa6BnOi*KK#`eJ}Dr!lVR@F(X7MHbc!0pT}yu-d6iU;am3| zugz6L-G^AlXB)9nHmon*5Qx~M$sy9|gMy6Q?T@ORdK@QW6E%8H%deqt`Z#Y#d>8cu zhlXLAjz%@#MWc{ea?=70y7ts2KSsB25*8h<($sVmN=rBzn`=8J0TprBY?8jUCSus) zneS(QL|#Ba5W*Jo(|c8<6a6Un;J;SSj|X}7zPRLfK6&cs9y#S>d<*@c8RU`OZ)L#S zIz#6Rn1IbDF{t6lZH&tMw)WPKubWS_Y^?4Aw2WH;h!;ZUCfIlypk*@ zp;F0d&GpDcp4KrFpsG>XluPZqC>1L~e31imETTW1N?7`!2z~CM_D%7?5L@amIE)z?l%_b-w7jCZ?H$qOt$u;1VDR(;kFBTcnYVrtqOA zJp7*)WeGoEH}8zd%{ch+47s%(Dn9aF`~W3K?WxdA)Kg%YeeBffW-_{lfC3>iHaDi7iRoaAct{KH1cY%>!XE|RCq7=( zDp@{N@F(6kO4+T{L(fzr#q7+s5XRDP@aM4)C^WE497|xdFtL+73>fiFx{gDOWouq8ahn&(M!q}clbkCxBx%8S+9xFY?qCYa5DC&e z-2eupfdyn_1v}nm90dlC*+fh^8Qp=WDn3Q6X#(rM=)!vB&sJnQh;QT5x=EO!Bw8OE zbGIJjkOL-nk+DP_Y?QE@WOhnL+`;97txotzw{*dx#e#7XdIp}yL9zHKODzhWgZdPK zUGkwlpEyp1AfX{?)=6pI>>NrF97?X}h!lfffL=>iwriCQFoHl)^Cu+W+KiS-?O znX+>%L@J1gLr~3p5c$k+=A}Pk*WLrLuhvAi}$C4yxoSYUXqi zcm(_{3b;CnouQ)ZxaW5~uTGsjuVM)t3;^_&D~36FpAZ;ZOP~f1uz(hQWtm>VjbbStq*5={}be`J$;1R1FoqGqPEftk%=y@zYno&4_OCK z#YZW$b);HgM)=rSCbkB&^_NRF%`uH!I-B3V%NbK_*|;IdyJjPEvY(iKj4h%l5)H!0 z_lVd*Hfw}%7FgH;0;GvCmk_Q%Gk~c8Y72RoF>YmeYsD?XDR6;c7Qkc%U}BIMu(aI@ zKAAkGm4vS4p$B7{O+S_H(rpuflM|4-J|d-qithZM;`tM8bT^+qOr#)+ar1o9TwUCg zs-7O@PQ=XBmzKaA*A4*{eVvN>!$7r}VXj7@6yz}7Y|JEpo8+ObbJLH4eQF}(7Wt-? z73Ns=wG)ADiTA3nLon7d7%)`M;v(w+3`_*O&leab;1;ML;wO5H9CI#J;e`(HuU-^o z2%`K{4<`(j`=4M@cBwF15SWivz-nNyHAGA&=|Yn3jiO7XrOz9H1FT^2a?3$f$BcM;#AS1AfPRKqpO{zYE^35DHp> zoO|FB2m#epf6LIVF*&y3xbDsWi?91&YH9%=G#=7O0}cohz!Hi`CxCQNx->CVsSyW!%{drQ?4Do4GAse;h7=#dt{0#`%%0}+n*?3R9xb4WgH<1|c3Q+9 z337PeSdY3o2Yu_L4jJ3&Ib@x|4E^m(#NbBqmR;9m4j44LJmt$3rNY0(I135%r{_${1{Qq(|H8O2xwh zD;GrZj%{h6*6dRFpwg#vV%|6ej+^^)PDttKEJA&>sL;w62UBf!v zbb36ziJ^OM{MdTVsf321KfV149la~%L)yS`JRAN#JBb6HN72_n(q8;>z_*DiXUj0) z2^5^#)6FoMFXHj;!O|qb#`HC>a$WmBab7`WeWTT8?6K9;!I?*OeDs1p=nDd3G3YDQ zPRPT4q;i+-nTg)fba>`~`6of|+)0webkB-lpE;ImQv&W}IJ}*^{Xp%h5{u(}Uk3X@Fk$qk|ID-0AN3`hbzhG)~sPuCc1WA%IW~cK!W+*4A_o6o(B@`{Pg(P?yk=M zuTA6N#7JP}UEIrlpQF<#>uI#Xv{Xp1kHuA3zQmLBz!Xa*LU-FtEM6xDh=YI!!nrr~ zs5-vH>jepD-+xv+<}PkPnDaLnb72i#rt|c4<>dATYzt{>l!s}ZZ)K1!X9ERdd9##l z)%!B<=2;7Fo1Z_no*=d|^<4D1xa6e(rTnTF%_@8O(pEfklGRaVEiugkYAOl$d=(n3 z0r8Dy5oP|$YD_3W{G33X!NHu0<6PrOyaoeWqQoquuyX;sZ?69qiE}y!^Y8|$m^E2j zF%)4jw#O2^{oD*M9>wNij>a|jXOI64yjhq6M)|WMA!G0(*6nYCr|vW?ZD8>;z$hOG z>cUNO7N%_^vfO~Lf2C}9gs8Ma9yb9wr+44{E!9E9mXJ9WEQuxlh~1fXo)FvUhoMqy zBiV=}e58na^@U}X6b5~TgiaA6DL_>!xs!hX^6~SxG!Net3%U8=E;!S0d*at3)nf^s zzeLKL!zxc8M7B#1^m6T*)Dz$z$HNlSM2Q3W(wYX~YbJ>D0=#bC?4g9Bar8y4IaCR? z>DzA1JW=v72@{rp=CiOhHn?s`>KYUMhxw0aAtp!tVEB)~5Z>7&;s;GG>KeaSgg+_N ze2{y;NAt_#FhSxmhwZXI>G$XW?r)dWg;$x!=1h0+_Z*vZk56*yxhP^uixFjtcR(b` zP&Xcu1`NAB0$Sj*6miO*5eiFye!d_v8jS&?e{i)>k1jUo(X-~xq$mm>wt6JxT};$z zzRv!4rywZqy42tftmWCeqsQJS>$QvJEjvL;Ki3> zbCLVfqV>heO(-()OYueN_lE&VD%6vYOr@fK7%m z;(Cdga}exPA`Tw+kzxw`yZ~VI0qIb12ri#W?B6g0ly2VqdgNutHg;_jWt5ED-+j!$ zRpKc`LSz5!7kQs`F9Xb1K=EIJD4q-MZBkxQX8I<4eQBAfPx$5{mzB zF8-+?+}{hFM55{`RVn^0SNN|e%;wuXOx#Y1=UL!i1)fll(Wn1lq<=}KM(>S;d6LlF z=fk?qtJ`j_>Q0nU6$k}>!ZuPEF9`?g49Q&Jj-n^zYw*lw3Ux}kT4g|_SC6j^K*W# z&vqYrTHrH8$(IS4ZgSbW_^?U^vwT@Po`Hi^1ys=%;>$)pUuXfQhtS{ z9Zh|FA=bBKv_iV+?U)Q(9x#FOA$08p&_&-D=`xHDzo?vzkC-sjHl9$g<=J8N2Z{C) z#_$LuH*#W>oHL=v_si=pVa;Y{K^#BU zmQIXInnPSM3{Rpf#Q2rf7Ta#7MeH9+dBM$5-9(3D4&}~8l|~ha)ffAd^XX5GOM<-2 z-$Y7-F24Hf3Cpj<{_Gm!qB`RAdtZ?X}XZ8_>xA&OI9osX_cC515*0)my*75yC&>u@HU`6UlnCW>*)otybl zirx;TjwNInwc(Pqs4B-@OBK0aZuv)N?Rwe-`5Pr)vWebO^OG~Z+;pQ0dL;1IqZem& z8mS6n>}TiKYc9E%NnhI4bTaI_b`9_};&8+DdJ9p_uC~C%tVZK|%dY}s*JGwKWEB`? z!eWEELb6{L;)?DJc{+??KBj`&QOw;{K5fw#Ip&{^PA(-ULp!&!&qz;|ypC@@MGQaf zS)lQmd}*$!dB!p!pc0gpPF$OG|IYPV01Ig^vZoh`ZKN_T$a8pUaeD5qML&9X8_`kn znSlj9D7GJs1l-N$J<)j;YwyuZF%N)$QZ1B+E25kNh8wus?1qX`qdjZwahKWj^3X`- zye%HY-|*tl!u~tO0nwAsgrRS6(NpkB19d!k%5JD$uW8=v;jm9j+-P&mReSP#!}MaZ z`yv($eKaGhwiR(}cbNno^5dlE#}FTjXhDDac5F%`4&l`CbyNqxeq~w5iZIo~vl!fF z7<`2JhPF3-L1$ArJNP_JvHt8+ZebhFf7xy;{_McNmzHyU*^6873XZ!UWuiS!+HD;M z7T=t&!WQm|P|}de4I`~K8iLyk>zVYJ`hxm_&cSH*xr2xJ4mQwZYL^bXkas-%v4@PK z;b|;;RSVBbHfkL$4uHcTn5aeG9>~G43(3Nptv7swdJ5H|>@~oDWjw=psO<>>^ zp9u4dCuu4gzofiBr7JxJ0=+7v^DdY#$q(X(_7$*|0}3M)yIJA8uQH{dFjYz_IFh>Q z(s^+Xs`4!(j(a**$4sLJj|PdDP}yoC-O#UJ_7*-z58U0kwx$ze1bf=%|G?b(U8~Ml z7lz)fAk&2jJ;kuU#6G>>GXDHhp~&4wmY8JeJ!LC7z~g*b{3+$OF>o!L6crvQysSia zfNvRc#zVT;^uIMS_}30Px0Ul^Y?cTjyp&UJ7|t;vtP1}dY1*zV0ixrwz8epS`&YAG zhe5a0IoIe1zs4rSMwEq(kL)xoK;*jHat^VtYfouv*lhoxecWMp%2ZaqrC(De`uuy{ z1NroQ>=ufCT$U5{my|8X(eN|{4nqN<55-XLV3XXZ|9n;c1XhpHxz=rJ7F(mmD#do&&npEEMVn(@Z3y;{(@ zc&tp?lL=K_N@r^Qot%b^;JH4hwF?!HM!}Pw zW>a^iXl8-BC@!|mr!J~Tg>xred(miREAbW?97r(8_7|wAkA!7y54k5No1s5)xd+ho z{(vXMM8a846aBM%By>7Vl{!12_i}pVSnyq?S@y8LYZ}^f_O^81GHqAw>YJxJHCq^K z;@c&XEd^c97yjjlTjP%7C)xCn(YjvA?nKLd5#Xwpe;-Aj567HhF6c<+Eze3K z4Ad9Y>W4n#Lu!d7%ubs+Iaqows}Hy2lyFb4T-x*T5hagb4Aa`MENfh+l**L7y)pEe z=$M)6)+^+JCdu!)uI^Q;+iwggZnAK(398#(qL5FcUt{v(cFXU3N;y>b^1YteQ9N}y zT?Jfd`PPd#85+>!SIwg33dvT^j5CkSlR|AOi$%@4~9& zwV0KH_U)Oku{1l-&F3IyuMX<4ghX*|?UOhS)tMgas6^|%LbyBs}#2TWT6&!(ST zdd1}qsv#%E4|W@>8oqMgMP4QBKMFp^<}|$9OLwE3_?0O{SS2nZ{gG5=_U*Tx~?K z!vsRh0gQuTH&emjl6-fBQUwN=+kf;luI?VB_Qr90Q~4PID2AkB@6!=*@!U-Ws4X(h z;GguwzTqsI5H=JlgwKR5^ye*8RUmiXg*V-XD(z~(`XSHQsM4o^X-8xZ@#yO z5gC2{NFw!KYO>g?Qtf9cx%s4B7y3}VFvT0rNV`bc?Ow7wX}JFRKB9lyPODvO1I&p) zt2*l5JWid*GRy>$!3d-oYG@A_RsU5}_iP{Zuxg#UF)V!x|h3;9^TK51aKGSh6 z)6FvXn2%}hLi(9z!EbZg$i%IQOUB}K zsiSubb1hI}IE6981^A1kime|Dyk=o$W{SnyYN0y!$jx;HUQW5(v{XF&*a&h~xObM? zlI!1aR;=8?v(AwscIO4E-2sQ7jX#dWNz4K;4mDK(^C9g-#JPgF1aa2!kf0qmMNcv? z7tgOtjg{bbv=Y|D6)EXE0lG+C75CMCY=~*zoxbPF6zcR-_fD|`iBFOHF;p?sSSkbp z^XUxk==V$pOYaO%Dt*>Laz6Kdb0l)$1t*WI@3YLfF?EmXsW!ZZwu>B8$jQiC7E@mn z*I_|7BV8HYhWiduoTp#QpOF|#OdGqQibVwIl+Ea{nC?aP~M|?r7;~Y&56mm zqN!%GqWb)e{3;nET~U6=g80=4S$x9D*-iP-2uGcd!W+WmAEM-wJWV*0iU;(oDD>Th z+7Jl!e=z5C(LNsBY|mbaT7hLQCS&B`6F%d>AnIir=HDr+7~o#sh?C{-qUp1H;?zb{ zc~3yQyBSZ@Lp2VB%snx8B$yM&8xB^bxqQku6?i#E<(B-IM)&2YcBJdGU_U4EEc?Rmk@Y(p z^`O&C#SXo_A-MoTqia0da};&dIwyuhzv8MNRmcbq&oCwP@|LH`r*LH7L*png7*5k= z(F`ecQ)L6BbT*~iyyi(BV-hFnm0K;ib|=0#Po{bhqWGAKJQ7vnxty*e*n5Mi!D`G9 zky(tR%N$qA;OQgJFn#wf<>9t~#{74Bq#4F84q%*Ye!74>J`2rUveWyaUs&yTLuk{K ztl)m`y5&YkAbHkFOexI`=g8x@E@uRD>tjfbitxF5YXP94>cOI$n#;CZVDrvzK?ER& zQzn%;Iah!12Q_4M1EvY*7zKgZsm!d+Qh8g0o7QX3^4LhCp+1k?6u-!bS*H1(n0H#A z?U~M&Or~A@GgDMHVdH;tvCbs|0M3}j^4q4iPDIYNUV}9&G5+ekX4=%Ogc%rv| z$WYuTxD{igZlw@Uf# z##FiGN1kRmK{AR#twq!o!m5OrUPg`_HMjLXrxt_!n0EVXC1H!NERhLz@EHdd;dOSo z;}XN-tGPaO;Cm7I3>wk}fgm_y#97!K^BnpM`Pr=DRLH(uNXBvkF5$xE5=}(#mVfqN z$L?@6deD=JTwBV z-i+MJ%SPUMuo7Gs@bHFbS+#L{Zs}inUMVAv#W+ZUhj2UEl95t~H~VJ*sEwEz3GRbu z#Q19tbdaKx^P1K(Kb*(uvWK5`6K$A6f|RWDl8I92?9gaCnX-)ahIUL<+(b#e>~Il1v> zCVgfQ<#t2k-C3vHC*#@fnh0B`=%fL2!VSNvqMKBQ(G7a0m`~V4=YV(9?K=k ztrU3ViY1F#FVh~4Tq2*;Uw-Q820R*1R#76Zln<}qJR!3FFdGdzy|&}vGzvj^GY(m< zaQaZ&f`cZfS>WN`5M)pq@~BxXHkm>5`_McSzh4X@ZU((R3=dC6#%pAjZe{`~Bhh`_ z_Lm>pPk+o~dx-m|?TdwbC;zunaSfZEG-9FWlslxla(8P&A0r2V(7F!SQ-@IpuLRwB zg-XZon`&g7Q2I1>`iTA@3PJqj1&)()JoIkEPppY2P(BT6y>XEje$x_$YDCBh`B3>t;sMBTRTQ?9!{xZ$0Amf4EHS4bK%` z9uYuD(O*9Hth|tnJ+~)KXrH?{{6*N3a1NKAxVAi?!6Ps4U5!3o*PfBcWjvWd9c3dg z*b06Pe=Q#l4M+9gU^4=j)9`v3Oo8$q*5W_nk26s9ZGyk`@DlWNQW-!6N37!f!uQqAExw`OxrRv5A!Y4Z3cg(gco%k>O+pA5R_-eU-;)gRXi()d?1`KB{-9xZB>k9&JX>7>|0B_S%?tNuw8?c#FIinW}%=D5!x zaVQz<7aMkLQDQp8Wgo%uH5mS_&B>BJ{UYyo%#bf+>a?TgWNhD%VF_yH|2_uxUszte zWYvanl-~EoX353u()EbT&guVdD%hRTdYkCB z$eQqTDq1USmtDS#`$+RAGcvL~K4{j3BHxoFMU**~U$xfnl}2kr1#)QVRuO!cRBc%q zP-ttGKeX>`+lM1f^AeM!<~tWNW}=U5Ha6$%lbjVC?k|hdwm0A4G+i8zKKELV_}fG$ zSrlvbxq-jh*x0^2T=GKBar$S%#csx*GMh&d>o244*Ei{(kHT1f%B%Pgzz$j3@n&1q zAN7Q*O+_eL7rT3jV8Qv;Y;^iusH{%)*s*f4vI5BU-N+m0IP8 z_&N&X^GT=lB5Tr;zkg2l|6`o1>EJgvecEBy)c|1H? zB%MrP`iknt&*j_aex7mkI&}NQ)}Ub9nETn^S)t2!4tqS;^PpDep5=e_OmaE>``=f7vlFa9H&5>917P0B=s&0Il1xHWio%l8!&Mv)R8n1vSChPcF8|5^}Ug177Yw z{j*a!;j3Sc5eMmQv`^Yx*)Og90LrCbuNo~#C=XOl3`|zmsL)kO|1KjXvQM{q_7dZr z{Ny!-(Lp%YM~ra;lwEXA!5=CNn%fe{UkjN^>RK9@&FUB8l{`8WGngZjRleojF4mTJ z2&476{!bkvihIgpmLIPtAa}>tvK=*)*Kj-H`NHRIhlz? zCtBK(10UTYRqp%SXAk0NGWp>h>1wrGqNMZ7ez@J+;1bjs%`_==e=;d9-_XM_3e(!R z&&y%lr#;HxVq}yy8hTgL$5Z8;=j;7eB?ya`yGrl>cpLac1qf4*y{K~Xu&Uf4_>rr% zrOy*0?%XaYG<4lUv|oF5Y4N9>)H_bO)|{Pu7lppR=U7tw?@ZIjE}{q1A$^%P8w4G1 zFMhwqn~Zal?`^6_AAgh+dP$FF-`PNoNvJ&bqdoDpzkqI&`Adv3p+K#*=kt@5rD8CN z9(M{mJ>kV)YGP{?6|x#+*w&vN>^JGBPLq_D_{rpp$W}GalY^_1E6* z(hw+I+qbl93~n;f5Pbq?U*g)0o-=C5u5yiL1Wr{y5petus2|#bt{u?Hh~KSNbhuX4 zcfB$)B6=Xcqn-Eo&dhPEBJe#m$r$mtD6vT*ETpnSZM^6Abd_ktE(wa2zR%Oq_2f40 z4@3!CM!#LYY)zJLBf8u_?0FRadRMs8lWyZnV{TQ`3tIzC%_Bq)8FgJjs(w42p3Hv9 zJ0HSM4|C|JCB3|(@AA^^_yuhf_JvD%%K5L>2(#8-iegbaBadlSy3NlkesmhB(Q_{N zX7_Z_uiO2~KPPS-(V3-Q=Sc^v->eVUdVL|RbNM0OQ!F;{Hd-%hRU&Kub^1RW(FyI7 zP?z~g7rV{8LAD+Anw@YF54(Jc3-P7QQwn9?l;#os4Y*4GIb_L_@HtzzEj@aF0Ybw} zyg_c=PI-T>fw^mY?^NRqr-c|nS3iC2`;`bv=TeAb(Brbr4XrP(rA2>*as@#Hh0MHr zd#bOpRcx(`Q?_?cq#alvAl4}VHtRW3+L_1 zF14{vyLoPVy7Xbhd(?kZ!YgHBh3W8`UA37*I=zxn`>AoN-~5zwbN}`pfVlh6C1Vg; z9p@T$nSE2!ONcg7`g`LI>f+YZ2QyA(VB{TBB;E6_qWhmgcSky>XnwIeo*o~Uvnv;> zncfxFbhM}I&&$yn-e~iw*d*HgizBvYq;EqjQx{SUg^V*>cib?$pAh|A)4c!w>gS>_ zinWxfgfsk~of&lOFPd){rF_3v7~|&KJ*5VyE^E~Z>bQ}nh6tuYTJhDAGfG)f?(EO8 zepK8qQD`!tsfKSM-PkYHkhJr*Ezm|uD5ff7-`1NSvO5eg#kUHw-d^>fL zx<8X4w4Fw}z>UXSaG|pkBkv_kHr~9$dfsK~nMM>X{(k-dTYCLnq6B07%;q=vbJcd;8~N{baq#6exbM9fz)kaU6GUK;2P&F40TrVnM>A?i z)a|EL7axn4-WNYAHfDt!G$lFL~=TXM%v- zVixua0W(d+ZDyiD!?u@%Z6b-c5WyS?bx3&DsQyI0W8fl}3=2>`E}rru(k}i=j?6Eg zxCq;EB;vg2Z4T#OV=%+~D~_%s<%5+`E0~EbU|TsT5m7>@fkAT5b)AX*^dKcv;Qq=` zHTkvEzqY36R*d#p<)vZ-%nLSc5>}L%=${|Wjsd>;AP)iO39+cpvH2nr_`fJ&L-GVd zYy}@p1A$#ChDr?l{^r;{)nIb~wnr#s!g0GT<8xa@dbcb+G)@`B$!;0jnyrM25H@y( zaAq-(z(JMIil17>Pz9F;iCCBzwj02Cj^KL0{*))q1@%@U7R-gR1>(oS*kR$ENO*w^ z)}}5w2r8-Y6FBO@HAct%T2ct!Puzv50Fi$Lx zjH)1G&haqd>-=W(|02j+LhK`IW*0>K6cNq;AK8^n#MBWvH9|DVdeR7B%f-26gDn;y zJV8~92Ly?u$PF^ur=Q{~$XB>|@M0%^9tbB0F=LEd#3~)p!1$KkoHdvYf zWMIWx2oik&_70(j%EDIL;F2}4=lIA<2+ls>KVuh+3>oDAaAJ2wtb_&FWtFr+u-Axa z8Xqa#pYhz@c(S2NVcu?Ty=qgrNJdP}=n0!MYH4o-PfP}Wtx08*(Zxb>Q$^ez@WC(< z1-1fU%5;(|P96$Ud09Ai5g#SIY6w=uV$i9t@A|{vQeN2&w?H$P(vYKd4Xl2tLge|FD!KWy0)Rfw zY83UQ-3SEiCh5M)O=lMIBg)&Ol5R%H?4SvyGKA<(kjh=C?GxfA0Ne#uSp^mSUsWg& zzaW%iXaUUu*fD2`9wBR+vPj~!rieSFba-pa zCySj1qP3QPepN*62Y6S)M_a|SIjA}zwn12u2jF%s<3?GyTYPk$kVmpaH@mb!tGK;H zdZiFeC1MO*TZ;l4pki&RZotfMP(se@1h6%f@(CV}grXad?`$r+RsOwlB29iT2WBUS z2oZ{du`h>;t>d6*MDzeB^AWG*2@i8l2*yMmAe-Asz{2`&JPgE~B8V4(Zm+O46x;r= zv7tH$u(W9Fq_*?PIG<%4#|$V`xcjE+ij?vx%Ok*EB5-{Q0a${`UpmVIJxofUw#k0V z=Se>A*bKlHx`B!bwhKg_iI^yrU%Kma#R#&p+el)pdzs)U*V z5tmJC#Ai2V#vY^*Es4ZFbpwZ>s~zgW7#{!rAVGRhMV5#<8j4QL zeqGhjDg}0`zd2G+uq-74g{-k$A?mUgP$cBC1gI+zP7~+;!{?nMAr^TA-NLyqG2eL` zg0;Ym)M>W^VS|slu{C5=icJg|BJQ*%Rr*JqLBRC#aKn`BEv>hqwzsqcWW8J6KD4WU z99P_=j9uT5TIWbTV2u?DQB79k)j$iCjOt&zcfH|$T{%ubkm$9!cGa!3lX#6w#_XJX zP!rTHHQ8D55nC~jwnn2%UV!;Bn$NlIZ3YZ*fTM0ekq-Tzd+?kW>Qn9NlRDcr1yUl; z6YU#PKZH^bNN8y57)t~xJn%={IQPNWcoT?NgVp2&L1LVWx$oWzrlcYQmkYrTX<%yj zovBuLws>~k0sCzZRu@%JK}Kr_W7_!lMZC#A&S0PL{>N=kOru9;)O6SF23iwfnK`D1sq7Ixq=!BrpK~R-osV2-Hu*q%9#rWYRKv4ab zhftvx9Qel| z5PJrL<_e!iTxdulh=X$j^^}rs0uDes4pnlGj@yoI5ur$S#`;6S)nVTmqc#aob4G zD}t6q1k9D+*lr&7y7rr(!@xu%wvJMAhm4yGm^nv5nB-3B|CXv@&Kz6BR1z?}i`yH# zAGJ#(BZN{%2*|rFAECkdy3qd1=7s?box!ft-TG=*S_ zh3~*&j8?MXg~edD$DsJ+^749q1vU@*8q+F#J)!kxH#X04^NXf7!0zFm>v=B{Oq`rY zdo*W(UGo${Q@<-?$X3>XP1=1!@$SWsBJ#(>La78wRyOg|6>>J1*Nu}_`zReff|6?s zQ`mF;V0PikDoN-Ig!iD3etG`p6(M&+`}^{N z5q>jw^V#_BocV4+r~Q}jwuj%8>|M9L)~2cSra}?hLge_q`l0t*s!#Zpp(4adDh~T@ zKf)8g!uy@QfLr28yc9~rg-XuaU_oZOT2Qj9H=_<WZK>Jw zr~1{h{Tf_u7hf<`Bi5=oDvJUN>OO|*7VE@K{ucLMa4pjfohkEmD`^SoIsbXADCa%c z1g32Mi1X3(yk;c&tMuTwT#LCN)DuRe6WSQ<6_C4Be^6rko^FMFWu_K}LaNpp=C zCf2q6Zus8{&MPa*Db{ezQ}+cyHTMJEAlD^tZ=K%ubEm&dl|OdJiNO<+$RcuF~jY-}t@^d`NoY+nvr3 zhg~J1@pDTzjTdH@q-=1V69q1WRtIVGS6mp&8ky!`YOiQJq_L2ZS$EFt>)!T?60b-$f^R)ahrsyi^qCsSFV*4unN;WZVxG;dN@HTs2bRrY)-J?OvGsKL`=IVE?iO;5{{0+Y>FSn8i zctqMhst?T8Iaa?=Fcl{sQjiZqub8B0g@|h0u$%Txm{jA(j)_MNClTRaJkrt)h81F? z`<)0owq-2P^)`8Lt^_dBzKyzxt9LAPURp~xkHwX(D5UY$5d~hZad3cG&8%+H#2C%m zh8pKVan4#R2jl~_8X|#!{s#53(7mN_xtQ|?y2Ysl>rpap=NsN&`C}wfpSwsiBJWzC z#!{YXAdbRvaktgem}Z^J5}C#2>m*$dsVI$p9mPz1r_g#Wkx_b+Cg$|wT18;Io8I(v zi!K>5qow!@3ZNj6O;1j`>W5g+v)%i`B$#UHWR*C0dDgy*m$rf_J6dZ?FD0v=U1Hvj zwg|7UmV118sfAC>*iz{x&D~<-Zthza6K^mm7hda~fsc#V1YhX;H7w;E&ioRe=bGi@ zzGnPkc{|_}FZQ9Mlu`35V3+8%i+p&Gpg{xbS{R_; zsj13W_`B?G=OH;_5;{d%^Fn}zClZcg0!U$c&2sl+h6b}Aq-E)OywM5GXre;ru5xOt zxG@Cy(a$HIKY#VExc+25z862ND%~GNKDkS>Y@V8itKFro5w9`+ z9sSDPBC@2(eK>B!nv@1y8Jt~V+9jnIY3&#d z@cMz!(pk*D{aK523V=8(5470@gb^p-fJrQ0fQzR?E^z`{hK z&%+(A3y1V8DULdkRj4#dzs&p^!-!pkEztb5Q$TUt75N+SIuBrnR5jahSTLoNTn*#$ zA)V@X6Uq`oMFw%KKJ)&bkKnCi3%3I}Es9H!VI4(J%UHDtIq@)LwD~06)cwOi#Aw_qV|q}}p%1N82|}f< z*}-@LzK=`SHXOIwG45~7W7124r4MsZwYz5{|M9%{bbH6cl#rjLdI4Q4b)UW+k>!!I zj$NxO;AT(X6F>U7^7~2eHXX5m`+HEOyhRVJo$9tPkso&Ayd)0QzTTPWmu^!A2_j}F zdr$b8OfHZMfYQ#b{RgHDt0$lMZdA**LEtr6(QF;@uf!HdMSKe-Lqyo7tje}o!=4Ie zMQ!w#xqrB!7c1wP9(=jn^G1{Y)$F}G5@(xYYo$&#Jl{6r=}Qo9gR7JJbbKUFX{d?9 zQ~n&_9i0WAe=%9K-#;!t(iMxSSRT+i(uwo;8J797F=W(}pKIHkB*hne+C3|ntki#v zc7-V8M}(J&6C02I!0jX7XyqIv)oikrx)S)SJY$O zdkiAn@Iyq4uq=bn+AS6QK`l2i=XT56TRVyL5Dv2Nw|J9cb00W&`Z0sBj;M8O(QLE& z6f1c~GbjHe=FtFOl~xl#F?^XuuMpgbRc4y-5TyMGl#qnPy>8ZL(NoFvR5sjPBOU6NvxzrdF`{YUX{IO`pVuS1CwCubON9pA zIek|es{D?2P2d`RF9c@BE|lrt`^(kxKKRPTdAlfMyw_J|8=1*i9YwgWi67;5CYarz z@w7bocnv1FM4e{M2TKI?db0d=Rtvh8-^#OboUp+qNCt(`>WvV^*uGLy)=z2eV}@#4 zCxK&RToI6+hK6cTpq`Kn{aB1+GA)2#YO8@`d_x|k!0nS^!LtlPa9t_@P3uTYMGbF7 z4W|;s(g2zP1ZN0Z;Dsl7W-$w~C*%ne*AbGs>86C+aS;kIH-72J0tV;+_YmC%o#_|tkAAxlaH_wxc^B}?dI0!cx z=0E3=KFoAo{$=eo@vb+8db6|x8+#_d$(cjoZW;*Ok=@6_bAr41{V%K@oTJ6)(4`WJ zV-npzlxC|PxgHT@J=p0!D29_RLzDZYu9J9u5SsDwgS`O4Lx4(SA&;`r$4T^3e42Cz zH5HOp3Q5C~CsWNPrJN^mBar7Wx?XJL$gYdqv*Gg9TDT88j*H=AP)Ns-qKWf>H}w(t z3^tGRbL2gcg{#Tw;D>!<*ERA4_OjR=W_53vwi zb#m;2>2ZNf%%2SZZ07UG#g_tb1Kb`4!iq1^NY>^ z@-@~QaOBza9jA`QlNm7z^n+aKh;?y~H4IRhH489Rnc%D{^he~3fssBK2Ps2y!DVF# zCAgRtb3?_pfj9CMa>%*Ddqw85D@$%@Lbn)Ta=_;&(#-pd+FRmTxhoi1pKZNV+Wtj& zFB4HjoM|E35PxUJaFAp&_h2$|;Rj=v1kwhQ;bA=8zDBi~))ZZ5`?`kFauK-KaeKhc zV5u7PAPKBzuvbu1n5odLC zwBmEMlWB+vUMv++bWV*&z1f$9IYzwc>TD6tZC(14;k4`{Tj`$$@oih9_D*Z6B8IBP zaJ?M|hKyhQw!wvoVe@~EfH-li4{_U#jQC|_!rCF;0{hp=>lzIlQ@$L>Gk1;4jh*ec z+%}sEx$i|qBjP2^iX`jm^un2R%g?G}mGfTB*`oOiCG8`{m%@BIf#P8~tUUzw0*CW6 zF6&}twQG=aDrIw62p{e~-Wn~Gj3;&~Kn&=iHi$Sr{BGAwDjDuX_2ft8WW9y@MA3*m z+3cZ)ULxC=`l1u8i}y?|OiaqIVz-rNfVU^tg$$4}4%L8}ap5bo+R+@u&m%WX*^k|( z2LGHa2qiTkxS%}?6Ek#v@Ko}7rCvB5aWSRrg^UUG<=_hBQ1VXy zJ%Y`#+8D%)G{B$`EQXnGtI=}fw~S1*WB@L!$NkW$&#l)xwoqH=z91^yThmg(?wAPa z9O(?J!e(-wrTWkGvkPU{VSZ(Ytuz}oq5f(}WT1c^$ev22(hss|dN#R|5nRaY=2A); zZf!Aj4MI8)owf#1<3o+iV8?YLe%}vGbDrXLOuVl^$DtU(6vR}1?OB7Fqp<=DJkE!F ziOkE;iS@O|(|gWmxA5!3KoK4vb#GnVN``5+F7CrB&`8vBKRnVqMYkZsoWV6o4R1vD zjbAkg2lP;)Xh7C_wV_}56^6L%a&F;3+@Lw~rak%9Mv{-4@6e%X2SN;=V z#w6EzIe}j)xI71IFcWsfg!?|qt(ClVZFsu)05W#uo$wyvI-yi=;ksQ0-LlonLn9qA zqI8E}F3E6O;*1oVg{Zl0AFUS$d%2wSsds7VInZ!(pP+QF@wU z>?Vv-Ea8!L9GnmFu}=IL)VMqh-ab8EM8>(_A)~#?j63BeJMXHzBG=gp=$=HhUv`G7 zc#fJ>j`&)p0r`e8idM-;a?lzm(9Jf>=Z4dHLTDguOblcP4f6%J{@Y}gr) zkT6)D)}3~(Y!BHuHgZqj7Ee6fnsql#S?N0d7jOt`A3wP3l~gmYjJNi61jEr6v`R{9S7Ssgyq0&-N312Z7~`(tc2B{WC#dJcvH+*5$e&6J~f zX}gkX)q4=s%a;Nl*EaQ^GX3YLTUL|l&K%q0TQcQy-X6n7D_aj-T{E#=YvEMb#=^%R zt;KN|qIrhfvX3Q%?ude!3DbA{N;f!tHjNF_XZM@pY0>A`J^O#O@t*N0XMXv^ymqq1 zs1QXa^kRU`(?1fo^*9H<>@a=yGoF3IDh+mM4YO1JfARI+?`*#h9B#-Sh)u0nwTVru zt-Wc`+O1H#)F>@oVkBb6-fCABjnURX1G&N)Avzd+)8 zlU&bp-}eh)5rVxHaRxqcXe1=6HNng5Q%cA>?AU8c2o++1NO8i!>=7vmKvQ{LG2}S7 z=R~rm2>2FZl->9J&RzrhvMKptu_~HTqQ9QZxc$Mq>6dZYx}L&x2*C0)C}9Shbh_A6 zH;t#MR~|6Zg#yc038?Q@73r6*1T&&tHz9$+gfMCfZ4nwqBrn_q9}c^!B?8unyZUya zBgXAA7=#e;Xba1Av2$zn?v2^~3s)6s_n)dbmV7w;rB3K#NBHNR??7*rU7MyFvi;$1 z&a7*m(Z+UzbuiO(qGI>E=u}Q`^bPN#FE?8fhGMo=J-b|O{3c5h3tSyMl`Pl-g`1~3 zJnIuk?x(eXMLFgt1iaWo^M8C_k`OUW*WCQA_PRSdzD@e*pMW=gSN?48cUM~$>l34S zfBc$UXk$}wvg#KDHP7j0zlyd!UwW}=sJrmrjTFkw$>e9(ZoC3u^bV_6_ zVCcqIqqKq_R-Ww8PL8@y!kW2ry=#9LgBKL+MhymX}Qz9>;^;Zf!1fN)i3I#GM`|ae#k+KG^@;D1W@qJzPv*Dg^AJQ~St#3O@uf zdw1eb`{g``!?_%q-_WENqqhu8QPAW+YIfq|Z>-gj)C)0&ixPqyDa-y+% zHQjVz`BbI!J)_PH`I7m;dA)f>=W)3r)gL@Mrb#s~tZdqH{R@hPe^4yJgks0V?QSxh-oa?v*W03pbv$mN;fh>Djiy=%G zd+Cti>V0eJkszn^GiVzd?H2}9stmk#hWb>=ppAN)^|@*tQnmAh+$bJuC-G0xNcYSs zuc!VX4aRJ$N~V0WN@%33YEbKyUlTa%!g=0;fLm=bF71Z70w1mHd$v#BGm3JaP;O@q zGBtkfzyD&lWVAP>NczcPZJjc~0mJo+3?hMN6g>54dVgqMJ7J15L)v-26D}6%ef`Mh zZEeE;DPTTayoSwnH)+8>P7JGJ}xl@?s#s2lG zzu$=iiwA*(fYseSU%}2&!BB#>o*#o-?`o+_A8DmUvL*}VgQYXsAU0$8zv#H~r zE@C_PF7aS{!RiB@Y&q}8$H;Zmik>AC{ol*Jav#M}oY2PDi5T-FU=CPeSh^}31OYKl z2ob?!tui7$8T?;AK#tCT7d~0m3Bf02;pJfbsjGkXgI%@^)r_MW@hAM+BwLp z=4T|0qsljFV zO_-_MBs|plz6r9+)>-x0$(Z|qnC5ZK!S9^isCG&F?Eo#8 z$jd{oPD~^CP9Bb_kt(&+)f>+`^mtgX0Xw1)=S*oQ)nFn>W|CjyB@ODeMB%ywohFW~ zGx9@x9n0ntABes2FFPCct~(DFET-CY4~j_iE^6L1;R-UK+2eR$TXBl!-7nmd0;8BG znl!U8H{=wjz-DJ&hz#m?MbY%`O&;1LVu(|%+MO3EdJj!7X7+4OIo8ijhxf`0@?6WZ z8tZ2Ae(kt9IYk5P8A>PLC33zyuUx?2vAf4jn=}KG#om@o`RC=fo+ff)BiEC-LRmT7 z=EfWuDdS>ckGdYgNKMepBY%AMPoTVsN3#joAf%>-S=dk)t?F_3MNJ86(3TYZ>1TYuOit zkL_1eJ|1Xh=Y&0@JTD)XI=*T~FzgutqO|_QVhE_GZEM1e6e`S z!?zu^vad9uzxwKd*Bo{{teA!a!t42jYD^52uJYcy;uMiYr?Y53QT;w-4iu* zP!^PH!MA>lzpN@j)LedNS0Iq+$02>&#Nem%im8{{)5x`ECz!*A16tGfCDiOM#W&M; zxVDw+MVF19A&y3@W1xfaw;T#B^NGD(UH4;KE*{gh08}LDYL4vbVvOt!NKo(n4P;dE z<~i-7r(>ZYK4C0yyfdgGC2FiTG5h68)up9Z2St~p!Hicd7-J4q8Dpb};yd?H@b&FY zy`YC*zs09MnOm_~1tD0x@R&NWkFky^7i%M~yf={R{D>dmzc4dHF*cUEZOIT+-%4}w zUcR^$GoszLm38sqdr5ZO;2PIwE^XV~b=TI^6AY)$ssAXQd-zeW-*Eb3 z+eKQ}wNJ;{hRkI3pEdlC*7?5o%;vY%lR*DpRb?LZ|D&qZ0;&oGRw6c{gHU7EeeI~o|mDg=a1Vp8MNG6SB+)Rm4~GdGR@&qlRVqGPszsA<&1>@C9o8r7Tg zvSx9tlJ3~Fe0kUZHL6=Ynh4pD-S)!Td_~8Kib}f&|23-FYFxFte%Xm8>BEKP59ljH zRQ??Ae|ObJ`Ux^BRrWm{YeQjT379>eFKaW^W*K^a-=_xBOtLf2KJC4Co>pqrd;@4y ze|_0*A!Kr;@4@$XsWk>3pWXF+m&fu|?rzqPy?ia5Y*5M<(DUo_;&pXV(}xCQ(h;2* zY^jry{+{2i+rT`cM>hI5*WORwJVB4YoNrd)ntBpwRDb^65R}L7_P<8;+e=UZI}@vC zeDm^(D=DoO?dBoMTpZ*Z0+-gM0|*$WWUhpUE=d8{ji%M~ShZZUH04%d@>SIr!ROow z>+(d~Lqc)ybBvG6d-HPF3Jl*cIefd`?m3r7y-k?ltYn^@Ysi{)F7NHa%L*X~pY;D! z6*IH#dv&%}OoNYQVJMxE@(2`Ugm1d?qjQ47hXfb$qU7BL z+`8k}>ues!SC|G-hLa0YOq(~doTd!1#fWV!s9|f(Z zda;dQ&9Mb*F9&$w{q@887D8{degf$i)TuX@+7I4;H8&J6dDFA;`@C4JBPJ@s6vAi! z=`3U)YyN1C`&4VSl@L%h;zD zLC1t+?H<~HJ@I;fxzxhOp^|ym0@C{HW!!0DmibiUey+G#9gxKOvN+#hp!m;mYIfa5@d!{LI0ykcUmr-&rXUpc|cK2v5-*n+kTNd`{IFCzq8RM-5J>C{%C2`J{{-GxIDG8Xwzzj|6 zVAKIVA^#gLCa>R`&KFVEaJuu_z8rUHA& z+@2Lz9IX*|h@#ZIVan~%WzxiC9Sbde(X#k{SmE#mD%_LcUXp64cE~@);LED_rbWM? z@3b#cJ}YL4%Vk}72y9{}lPos4;#xbXQqZc#+fr%VB0r+D8g+H~;@~P@ z9+-@@#mUKyKdqt|iUm*W6kqe-V-(A#?J?XOBkOIm^*TBezrroXk_0T`A0LWdgX@u! zls!7irAXM~?@RJ(S#an}r*ybHcw$d^$?S;UN9#fHMojK*@`jN^gi442>T3+v*an&T zEc5ku+#tApAi#{ve_W_`S$r7@F|$Af7?dyQ{!**2pko#X(}`>~mhZM4+#a>wc-oO} z;al`W=PUz1PwU@n)_E3{R2{rNlh61TgPC%?I_-bainiXX<-vEUCqF9bbmK=^;l?`#cH+tk!)SL|J z+~lHt2kxhRG|r5%;oPvR;>`=GaQu9>5|a1uOZdGM=*XPtKswFxv{jUmk&2td1J|K( zWK8r^6^~Nqrt_ZW<>=?1J=o6*V-5&%F6o7u(4$j)g%{7jb;7Kp>*Ys3&THPzY_z~$ zhHiOWy6q`yYSHe&%h%zU=f59j>T}9bX-nW5J*(AO>Y3zqw$Q12Lvl{RR_S?<+UKge z1=lhhZE)pTzvV2b=OcgpsTJN9y02XNKKdV}TcbL%op&}pR9Tr(xER?>du6I&;XHln z(hB-acj*yb^xGES;)>_y;v#XjFMo5pq@Mj}ZD`i3{_n!iz}d7-lp`|ShjhkdIS zAtC7RLvdHRFU((+S}nOZ2Cd;aTpifQctJ6+^mQ`UplFMq_$5=1cIp0VZTnvJMXc|z z9EJ7tQV&_(Kspz@kVs1ea*!Llp-l(WK4<5(lP0lB|TULD*q9 zu@pscH5_?{~%mBG$5%%K93GbEk zlVdAV>*0Fmh4fOo9+jzP6-=I1Y9NwFnh`mY2oaDI(!Rh{pn^ovsanbO-y0HP$60FS z4P=_^99iC0pBh1MN`?*{MYY>@Rto(dJYGDoTFBlRJ`pIL6|7o^o5GH1sdA9xf?n&+ z>P=2{3pg%8ne>u6_ISWQFj1{e}7XPU6v< z3YhhVcwgbhO02;`4R0e8dU*a3+SC5np=lgNih zl4@D)C!7zW=-lu{xfxe}>m;Qp25KT&K1n!7eJOLYDKbxe6F%U9-Ans*DaM6xAe_Or zQn1y`44O9;E(8s$6Qogk6>dvByLO)fp1+>#Y(g8-O~%SUGe?qo-Wf$EJ>`|LGu{IW z(nZYi^)(mH;Jk%BB0O$}nEP!y|BcK`>|HW>H0+F!S{tH z>7oLbjz?P#a$Ufq#d=!&p!vU?S)tnwUUdlv9TQ{+(o>V3H); zWX`EcIUJWH{J;_00cG-=jI;}SCaD1Ho&3ThM4H@Cky1z6gm;hZg}v>@vD47zOa|t+&vf)#ye7tetoT zh-Qxy5fMyy9|3Lu0F}>z)2b2dYD7NvY7-va#YzJz)Ihkpfrz9K;C9A<1OS%RqMS3x zX<3&te}G*tgkDS3KPI4};SAOpb0PYIqig&*yYyp;fC@wfQ0R)t%+^~M+L&-62?YS* zjUYgFfhXXRfRAvGhW^hO!6N~%I-Q6}AR^Zlu|2Fj`CXnKV<6&*Dq-V++AP%57c8-E zgN@1AmcGI@;HzJhklYEW(n-=)us9EbMT3K7Tyf|nWF;Q`a)$?i*9ELFfDYqRjo4g7 z0J6XpKo%gP9uxAf1p_r;v_X7aGVM~QF&2<3z){)qY1wT=R1p&%#>kNf))=rVFin%F zRVdswz-}G3Sm_k#7!$54INjHH_}i?K7ZZ_Njc6mFEB+HGkkbsz3<(uUL{{KY*Q?G$*Mq*eKuX8KUk~#4;$t=cM5p$MQ^re} zHdyy|fw7-TO-)$34m1Fe29|;Ib95<-hXk;>&QCB?M9dH#m9PZA%E|!Zy=yz=GP^uL z6M1GiZREuzR1@~G2X=o0fV49k@yG^N+;n7h&XbC#8)7q}m9j93k5Ceqlf%o9s1)F0 zfrg}j5Io(Ox?P@GJVs~%&e;x7`4w?#HQ*JXYza@tWyafJ*GkH-m6WeFk+f~|dkNQv zX&C1}7?%gtW3$z>9#|umxaSJ^$TInCH}-g>tz&!T*AP@G6Ojc%Gy(z@j%%KQnIoXD zFssSw|%)hpH^P0h}$Ghc#7Sa(}cdQqqsZh@_sYh@G z*=&NxyV5ZnV4%6r$>v2g;KKl|ERl#BuSSdXpn5^bXlB)y9{5#v>OGkAs0n%_IYGC9=a7}$4YYkbgMvUC$4U?l)}JDukr5W8k^1CV|W zirA_bCcZ!PkAXcf?qUIL)==W5L>!ix!*~o9j-g+IoKwJ}e~4Zv!UAD%^Upk%8Aw|@Bsi)^U$nIeu<3dLJB~r`Tt;8% z#XO^98n7w$3n{hq3nEB#T^?Uczkgvu79pb`NU*FVG%+PWT ztcDB8d#C(TP#Mg-pazOv;n^p4n|nP1oA7*RAPQOCIT^?u-XlF8RY8s1zX#YF zfOlAd1-u)y$zm~FzgO5UAM1sc?CWpx#4?4^GpUgif06cakAY=_0XlksmCV_We$L{0 z&ElD2T@cd80vb{~2rc>v@*WQB3lt3lc9j3|hSIZ=w2EcX>j@V!@8BJ zk#;8B2?r0g8Mdnkxk8)*qUS%Au(QNKqOVGs-l2FJJdnk6fdu>4f(-`x(W_I2Zi`bN&rX{J(ZL zYo4$_e+~q@PRnD{CS4`^i1OA+MEHN}Vat}`*u zpntxIIe&oqE<-tMme}~`S7~{qWx&Mbay5#5W{d%}RlM3PpbO@YApr-W#|Q~H2=&V7 z`yq*)OeC`zQOJDGd%d^m(5p<0r3d;|=5=7=;hp&6=KbMCw>KoNX-%6vPA60> z3s%B*MHV8K?qmGB%Ji#e=ecU2P7<*Df6uQjH8o}0;1TJ}tRf}p0Bji~&Bl+O z?-X+>#ID^E@nSL>(90Vb_*J*{r} zrSky~{d!>o9@#;|@GK!b<1;x|vI3gXPbAtz?*N}byBO-zmavl zNOgKn4g1DEuS`7l8SY`D8urz3u4Lf62*e?Qhh8N_(#+&8Qw+8}D@qSz>smwtj5pZW z4S3>RA37|^5K%=(6_GyI(z$9Sxo7EImDcDG?vyU$*1!DtpQ zqONUENv^7#_yp=@X(Y_y-))0X`A-gbro`?n61e8+KU91{5)80{8_*5i9yP{1n$&Y7 zPzisc?}WcZDWJUGGP?#`(A!YgvQPa?CzsFZU(f6ZwbTJY4<(76sj!JCwcsf~|(Vk+q%Hzmw5l2XPwD(!i#> zV-p?kN&%H@0@#O9!`emP+5a^%so&y?t{1)d2ptRBQhkNDs68+_^z-D3DTPboc#4SA zs(HE~J9a#JWW3ylb};bw`Nqv!o26bGufPfC2A@fS=$_m8C1s1Iz*eRFA5zm~;=!7C zC*|o$a@gY7E*wFSvhN6eJ|UQ2G@srTx-s!+m<&FSJ+JD-(K3^Kd@BluS;YGdDf0YF?O_E@ zR~}1%NqFiE%fyC?@=r1s@riTx*YBmo{0w_p&h86y+G(5}aH>3eOrVg}NZRj>T*duF$sqA$oFJW!_-sKgoAa>Q8 z%lE@{={}FYC=1M}_reN3_mi)gU`@!_*K1N;m(ny!oPIXdfWa69qh<(qh?t0tqn*PV z+mFi^6El&Pj~^%bYL>h_o1$qc8Wd)on~>>YDSb`=W!Vzey&+c`;8)jfEn-+U^6=zg zCnPOoB6n0IBq?OL&>eO=r8J0|*udv_X|_(LT145bMwdYZXY0T{8j4_Z=YyNK$Nni4 z!)D6mXYL$|j*?cZ>$$7qcf%vY*bHty$sT}+*)oec3;)4I+z-ZAr7%K31k+v+Wz2!P z5$Ts<;yvCVB&3!RW+CeqaPPF6pfV@F=iz;;ezNoHkL4Prx9hWI&O-0ks>S376rCa5 zwkbGXjSM;jNJ=Au?%s)kqQMlC`vUGs&!%g&E^lr~8BQ#7(9ZaU(B};|{F{XCe5n`_ zaC21}5%3fUYwGtQZJjR-s^!fTu@W=tTDIgF{cO@Blouv)j%otMDw;+TNfhxN4vfJE z_o2KqGXJ2?l4?Vl{*y@-h5?0Qo-!Fu$7iETkFQ;g7I3K;sDD*>`7I~6bzu8N0b@d1 zTxld-b9CP4Fp^RhFpL@%uxR|8#OA8(S8JKlUtC{JRkhb_5c2SjQdYjK&^uA=VJQj~ zw8M=zDlkT6D&{ zG^I7DLNh!6BykpebmnnDU3SJa{0X>GV+^A+A$`Qhe~^8Aeg|$Z)ZP4F<|4v+0%sp3PXz9i-l~io@=jC}J~kwh zPlGBvX2Dw2cpL&eIeB_XC?AlS^?W{bHdwRDc>rnL4IBqr& zVM5AyCoCvvNyg!|b3LJAAYY`@@T$^UyGyOiNGbs5x+Ctu2IAD7ruaP$*f ziNj*BM5K!WS?CJ8H{FYSQ6b-CI9^38efrSt4i&`@2wsnK5|@7RcpMC2A6r{;_2*`u zDBhgI&izEbb1XXxo^48X z{M}UTUZdR|recs(d6$WGWF>vy9j|CMIa4Pk0IVBxQAI=7CQ4PJNQHIqB*#Qtti)KRS z-{ri_)0gfZSts_KUUOX_TI$^MTJ8X%nNkq2Pb@OXm%R(IH`tm;h~yOP!dYs;N=1FT zYlS|2h3UDLWyV?#TkI#E^c3pwdbIH(g1mBD3!RT~qx)iu+*jhKh92=P$seDIopoWe z`#zkm_7m(1eU3fYO18`#MBcF;Jz?(zvpqP+=SDZr>1gL_>EIAtq*>sUHB%3ZNW(4h zrscxVAR+~wcTa45&y$sbixryIcP?A%<;@C`&1DbyAw86OS+I%h#yjk8PK6tq=;;G9 zITXhSQ&X=y0aKhpjUs0Zn%lX;6y0S=BB2|Dmqv__&p8bZZzQSaoxA4YZyi9VJFo=! zzY4}bDE8tFkn2bZO);B68A;JAB2yf7WYG6^pvpMup#ZEI@0s-^`I1}}@|d*X+eJJ1 zgDnVo*;v|?V2wVQ<>aLiVdr+9h;UvFqki#~@83vKY;xiXHcvi2yJMxZSw~~rh7E+C zxZRRs$X^&9nf#;)55;lBZzRy8g#7OeOa7*1Mi9-!1k#dZZef>A#EYbh-{-`=cK-a7 zd8C_fWkHfrjj(Sjs(+;t?VX)zd_);oAzY^D8~s^7eZAtX$rz{dhiV(Uf<*oo7e~}V ziAY5eKibo|A|W{pb)unfK+BI2cw?&JDOrbw31tXR8Hkhmy6;kG>wf z`u6T5Eh?@~?3KZ5RpM`}k^yr8NcM=-CN9-6MON(jPU@^e?SjfRX(2+Eg*<@+9W1Np zpPe3S;eGu4YLW?e)=o+&SvHb}x`~@Smh?RuVX%WdMv#X$ zCp%-w&XL7FBp8_qJFw$Bih~F*g0SugX>Te|H;8)&E(77fc5{&N$w!Y4B*cM_F%66f zDaT4uf@{d`2Dt)T&}D7tgw}wt=KTu;1PK(X_ z$2+Oci_#Tw$=^v3$4FtT+fX8*xi69tz}c1_Tw=4x*~rwr!<6JoL6^TQewKD@BDg)Z zWLOcB#r{#D4+1Y3_9als9?Na1A`lBYUQL^PWkbsm2ir(eTihm}5*S1isNUj(JUCNw zH;KnMDFF{wO3^<#oK|7opi+`_Y9dK>o%4c8O~QJzrI+Y$7cLKwm>IK;OoxQ9C}C8D zVmD`I(?f1AsswL_;-W@P6R639b)9%8vkw;vt^FkPsZr1%SS{5GLJz~4502AtIj2wE_;Y3O?CZ;5aaL9eIAv4F* zODs={+g6StKaX(f-m7zY)bYA!%AnfL3>GR?%-nt zNGnm*4@-5*D9~co`-s4Vb2AfmavoZXWZ)={J2!0<$$o}B-%L(&M5(V?Yn@}IiziZR z7%-BHC{S3}3a(BkPECtIt~nzV;+41rX)Pm;;3bP5#G; z-{CY6fjGL8W8){!xWn8GFz|I!v~+GGijwR-la8R60A;XFB&PnP7}~ynaVB7SCbc9b zob-_GD$0!5O_HT2Vt3#f?bPLZuFOTwR@F>@F~;=bk+xG*4<(`0?x`b@7ST|?y z)ntuj#qlWWQW*8s>r)D0_5^u(qd|o*yk1(cfwni*mzY7#Crc{b%bA3=WFpuW-AVfR zK4-k9Xud9g?oj~{iHpOPVw|Y54tDRxz&Bj9{Yt!|$m;9K@8}J3(jCbd`-#Pqfvg7C zT@FQ7nr(aEO@tjeE-_)J&~{cOL-CeyJRzL{=`lRbd%r$URV6gImGKwF(mdi4ha$bX zMVCO4B*Dd`lhx2uc%Knn$_d5f5L4hUqPgPVJ!@V)=@7+W+;aNj@C+?0^4?oA329sA z?JAbFIjfZpVghd|2lw_(WO*(TVn%rTu>m31ay(WRtQ|ZHl~kBeCWnip_Wi=N)Gtzv z^DW~tp(evb#dcfwWK_xAuRx!QxFLdo+DmN_`Rn6hB-Rgs*xVwWv&xG=tmt^^;uvZUt3SiO+i!aB_ zj5=JQWy9s*tTP0N1u5mtdh#P{sugj>f}U4^gU4P{x@85Tq2b-D*DoM~chaYf1&fpHrh}jV zP{}R0R2V{+Br673P&1!;lKt?|qg044Fw*LcPy$-~)nHWySe*`5N3`_*Scg8#wnV>X z?gSWd`cdK%HRyCloLJI4dEp0oUm(x++k@5y%3W9c&B~U@3xz1h(!Cv#gR$1HhUL@i za|Ny&!cO*`+y=q7bBRr`mgletR!VMn@*2?RLx9z&4=$7^pBoO+V0_Z-UaR{pUIQTf zg@~GD1i0>%JQxJsNz`2jmuWX&&JENOBnB;_21+PfpZgp1_*f8}ovTHfe~jlmeP2!TP{4bw9@j+DA+nHLvVXS%<>D#~>{NDWzk zFy#Cx$>6laJjIUq7U_zRUA*(&HEj68w{v|*#~oQ150V;U(j?ODsAyxzr4oN!6^qgu zO3*x*gFUZGl3E9cF+4+pzdktgoie7?J-kUaBC49YQA)ngj!ju>idQ}geh~&STZT9x zC^`JWiPI4NW1SR&{3%p29-FL>1?w5JAW{l-O=qWrzgTvVRNRwKfZ8VwJ02MndhQmt zuCc<`fiL(7wj_}%&4f+ZZ;5h<$kv=s6{&YO&X8Ez6z|DNBT`f?Pxe>j{!pqpW)MQA zsS`y~mdD7>_!R#g$f;@=kkppGn@^|cJP1dOQlgb-ei|i#6d0x+iYE_1dVh$wY>U)G zcXAVOx}h|>KEt~6HRgbb;Js4F??V+2`(beVJlViyl<(MbLoU3b926W%-~K50O=Z&>kU2Z?_Gg5T7Mvvh%p`Zr7&nfc5(_yR)C9vV zP&ArUaCH>FzC_!VK>zNr z*ml7w4+b)WcF5ny9GZ{#Mt+Jr=0#Ej;jrkSTcHa1QM{N3IYCXyz^DaLmy+}mW7s=Y zsHt<^2XOYcEM+YKeB1R9cOCy z1DG&UXPU>oYrg6?j){>lHK2!KDc&LlHw=HzoOBJu4itTVA-eKokbaf9{va3#82eBs zexCbe;_$)ZZJIGTbUDSF7_#a{J!+e0JH~s2@9ZkrAaHs8_+oy9?dE$pHQ_vf)CaS0 zgFuc|D{P%5Jxt|O0D3+k5C}tfYuv1xxoCBcoyjZf$}Ac4A1_iWGv$?Ob%NY{)Ut&4 z)JbA;f9wkBv=>c}MGW2sr)HVd!{Hm7ireqh&pieV=SQ0H>r+6c*`zPx92x z|5kmO4B;g1!E3B5Ej#maRfG9_wTLsO-kQdd#vUG(fA=O|XsfNVhy4~Xr^;wtNzcAoGm3Qpo8UtoBqy*IS8Cab(@rI_uSvq|CE6*ikhpj5F20k(&s5R|4 z+iK0}tWRAp!E|zI7a6!r5(JyOWir&9{RafoBWp7>2i7mi#!lIr5d=UFi3IqRdqDnm zi0*dI^`pwL45dbM9fIh2hIFb78~d@=A)@-vj7CF=za*7CcS_dbWd8iBoVa^)&*AdV zP(~4$us4vVF}xV;ruB@_nW-)W!g7YO&D*o`ju%?eG;14R@X+wbuA^c@AGUdPK3e?9 z)SfgtCuj#bt!15_oqk05wl4>a1SNvBZrb$n0{euE_MP@hFwnAb*ih@h(-XF)X8cs% z{X7qohkoPkw>8GMEL7R%opUFi2g4k6m-gnKD^~7lkGqXu`KQ*6^fez4xcGuI^ZM|I zrKeR_L3k1;ERD}GncrzFz$DpPz$+HK|K7bDC2<<1lg>B)^e&so&#iizPv9(r*UnoR z8US)mv$}iO#lhgY$d94Ep@G8_`uyegMe=hgF4^sDvd0}R{kjzRm>B5hHSOuIPAm(l zqA{&0Ez_c8;5I-6%Q>lFH(WHVf?JsFh$AJCz?QX zlF#t|+@kczbT6iJSO*@ay=`;X=?eVEP3>U@=V|LIZrWyQ-YH_21mO^Z2j%P;3^`+8OGSE)BsNGn3&? zE=N8;`gd^k1qV(71hW#!%c$%ZaoIW1SWxHC#jrbZ?APH=3oM673f)rm46i>!>;0({ z$9LB{$2Fpc(!v;=5+cjRoJ$2Q^xa>t64>W&Q^X{3&qPv^#Sb_Y865Wy>nZM7=~K+H zZ+Yp7+}EnjL14tiNLevV*w_KCX@F~WCjM2^=qm%oL0&zU)s%=8!ce3qp*}lBUHqNc zG94Z^^_>h2so}b~-ly(AfMsf*;f`t=lCEmQc~)1jJXbFtBZALcVm9Pj+U>GdE11v_QaQs@5-EdccT z%b(UXDFI+aAt|PsU*XjMMXy&`QHW1B4!ZRZxj4({SxQvtM9j8yMr6>*{>S^tgmiB*PqcM`%FB?;??{j<3U7J#$X(__OSUk>%cd1dvxBB|lA;YoGF7f9xb%j~8Uf_RSNhTZX^%`f}&(t_vv6O45xL`o`x{4&9=1sp8s+{Q39VA|<5>hySoBoWgZ{hsU zkStx%{_%)-ff;0+DUea6GmIsK)qHM$di{_&H`i{!7u))SWR;HjTG(14hHGon)G+3A z_yca~u_3-9N3X9vMJ5}NJK*qMTCmly%6B@O*hj1USbOKL?@h-sRkJCWZ-@zjGks+M zp77G0_XK3)j!9URK8x|s)xNlQuJjaZRQ==S^(QFaU7-=7;xHjn_Ld;u6V>w@kRd~( zFl@AyYQXkW7pJ|D8zxPd`N1#TU65)6VJ^V}D^1a#Hl&ZKr^%#!voAu4hr)H8nl0si zSb6wso^M6$>MFa)`Go78lzizmo5a^MhND<5mN5IBkLG?~ipz;1$Kkfvqz&_;K)`vh zU{+$IbC)E--e!KTe8X#}@Zs_jMtbk$0$b#$Iro>gHFKc?ef3@|g3-s^cYGc<;upN^ zeFe?9?6|(HcO~nLyc1Zta5dt~p$EguH4Ex{rfpW)%ySoB-S~IHq|@dni+Oau zXPh3#LfHk2uo0_LJkj_F^*uOBHcn$4uSgLLA#M$h6v9?nWc?vu0X6}`3sDP>lnYs2 zJ}gHQ)Z4mYoU&qq|Df3_VG^mN`9hFy-CXS9$5f}`rPa6hhh+H9%O}0^LU3Ff<)TFS zNcz)0AAY6{3v|LMV#+R5gGTj*zJ`C6@!_y5$$MoneZp%!NlFynYp8YiBx(zt-BxW~ z1ZtH|^q7{Jc>!$FG&{6lefk{dWMbF5gxCgHX8vs1219Zk|Lw`o;1=P2{M z<0R0_e3CcCBh#;5<=0W>? z8+p@Uu3^S>v~dq{Se=n~%l6O@>|bdCSH=3EV;RdLi6XbI!n7By?;Ag}IAc;LEcj;O zc&BZ+#iwgFdsf0prO#eEIfTv{Q5F9^DVN<-xUQJSX?y;P-avqfLstQnt4R5tV1xfP zb6v5I_gPc*SIq4jr<%NRx4kD!n#l3Cr@!FK%A7Vg_1$_uhD1X4F;)?!dBZ~H2%4`bqO~n- zCF5eO7Q{fJA(1+RG z9cQ`+DZ)vLt~cW3&+H6(1@8GBi_N=;r3lFP8BYtkq=dfx8Wn(suOxD&k9nyzoGYAa zKq=^>&W1$?zxDf&-c>TuZd=cf`NJzY+;Y}ss3BwE;VpB=0rv0_==oG|`smsArBfd& zx6Me9dKH+vyw74%)pv0PnS>Q|Wg^`N8*Bc9Z+KRET+@Boe*Ld|JkET&tFfO+<~a9< zQ1>M*`WEejt&7cEQ<0KL(enqFqNeAR44ZHNNeMMekVY3+Qn_w0?9;AsU?#H0ut8rH zWg?_!1y+90PR)O&ikFRz2UybwIs*M7Zlj6aoTdMgnsT6t`Zw>?n-%;c>lUoMX7A{l z+lGHtU)!nDIc~}uBP)77-Rlh-G<4zxh@wT8mL3qY7Gi)tU%F}Y?A5mny#X6JyR?6} z(!*nd6Cn7xeBqb-64s1>P?lvP2g=w{k0;O~qS3u4?+n}EvM|Oe!@Z=Ik48$7{tJTP zY58-rmezwur{(efiEng-?AfMou=ti0o_q#G&X$8K!~lF~+S(F-EjQzI3n!o6O#EV; z^RyqeOnM91~`@A1UWz|N3l9L#E((`L36HK_>l%G(8HAOpS3mrl@ zkQ&$-Q4h>TJMR5u&P#NCyBzabv0_*D=7#~cV2adNjW51@osm$5*JsgAV@aY+{HSVh zd%6vSQ!tWbupIyJI!m!*?(7Fq<3a4>!ISSFU;(O$_CMZwhW=mb9w^iUN%B4r`YHj{ z34qG9bGo-8HYgFC1LolNVD5pSeSO@-uOk_HBt03@f&3)|Cv-6N`oG^iG#na;r31)h zmodJcWh?z&Y5gOqNqfaf3{4j+toBJ4^3gRP zvnNJw()hAs;szLC!O>YvLx~Vz^V2Q6Y;a6C&^DI~_9d@07qC`S82;kIp7527<$9-y6iDcPf zmvo&I0VM)&Mo;?a+Gil#H(*(%_u&=5nLP=Wk4IM0;lLinurV57*xQK6b{3kGgR2dw z`x_?$LknyYvXYSce{l64Oii^7xOGUcu<1qAfFMmUAYGAwbPz+6E}=?O1EM0L1OlOB z=ta;_r5g~Gq8K_TY5=8JDS}v^*g=Gx{hpaK^Ue1cGLxO1`@Ys%)kM&G5Bl{n?L2xb z2OM@IU0AUFe3AWRnEi_7NPX60L!w39ncD+9+-V0z^_6xrRQ0Mfe;oIThi5ZfkPHeI zRNnV+V=EwN4w*2-$?1fk8T9xEEc_6-TRuZVH_5v!L3Au(mAm4{3i_lean#U455(@VVyIN}DUWu)1oSV`%i(n>i&s zbjd>AG#L*nxmh$s5jUrhFH+7%(dd|uHviN6KOp}P7Rdj<6@U_Ufq)Ed{!2PQ?LP|# zO3G`w7$%+No(t1mV8yujcpJ%ct*#i|v}s4m6wW1uZbWzka6M9Cx~@x0K7zryT2IE+ zvSRg&2#@%STO{|au1^jGW2NfHY z9$`d*MUZh%IQV?)>$m-{D}*xSE`(OE?gyK5h3lvMqITM}!TH~fPFkZ&S^qb4!9({D z2}keZr93cqRe)|)Y!0SM5sQDsqi2(_o$Q>^lfbBSo$SY2|A+BC3)qz|WGjSl)&QWP zs_PZ1^+KzIs_c(XY93yInX+yglM976SVp{?4?7Ui5R8Qvu7L;MjN&E*eEj4>%mf#6 ziOt4f(e<nVya2z9%H48xevJ(R(&cszZiJfwo2;WX%0|ZlG3qYv zydCkAHxGmDh(;K$tqJOcN(R@pCowt(7*K~k&8vFO!ZT>>?y=$@?tq*ZxI-49gV+nN z_U7Nps~;*&LmQVG8*I}nlEd(i`1sS(7u(`wZ`(CJvaFqzab;e(UI=~= z3<^M+1e9cWRLPe(>HqA2_oacZzd$qqW(H|?6YxcBxqut%b~Fj7q+qu|3pQ9*pq7J8 zio5Ow3@W;ah%0HV%-;}cBjKmPa0Gx8Zmbm9YtnS6A?!VPfn zUqmjj-@z&&V%v9Al?Wcu3!x8~Ow+Ts;w6OTpHIp$Y9qdF%tfh`xVD zm}(xzy1Q#*4VzEF4)M95UOq$vn4}P3i}6V9_AU)zwhlU!>tnT%$oN9r_(9VcH z5xJZ;a%MF*R;3j80E`0hMfhkuI2#4m)w9?OPpQMl?-8)CxNALl5&02IQKZguq-?y% zlWPE&F1YU;7_7Q81N5=C-7Wl%OyngveV2MV!)G%agjDA1|r`V|Sh4BsmH%?5bBR6wMm&itg zhkaU{J`IY! zwSe@|wV+dZ4|v0{Z@W*ei&W8pIRRB#h;}k~;UQET30*`WDsQcBiM*=-K=~wtjgAF_ z4DQ$}dVD+kN;$WbZ$9PVW+X)qT*J9w&bu?H*CSYaAl zQGj{P@GXTpO+$rVw^3UY*jk+4Or)N-(* zPuiqUKQ7o{`}e$h38vOOOXZ#{8pxL_KJ0~olqs)=+qER?3p}R|2aCQD01yd?`1>l` z*u>MPdfz|=lW#toRKq3<)2}SE>(Qw=f?$ELNCMXA!c+8k!Rxn9Cz7|mTs@Y9)p~z} zLB|kOKV)5tjcxAs*Q(o*hW+HRD7_1pU%LA8<16~sYD6C{(PS3zNC5y+=dKfL7= zUJ?mxJYLhc5=0{^NQ0gC-)^i8JtBf!$Xh1ytnER-<|9^S$Evg!R$+VfrCe#!{ngXE z<{qVg3g7kGpyG*Q*?7Gn;GqF<`1ltjkmvc1GJ8lig9y{1N4OoeM4Zf9ReMMcEQ*pM zsM@>iDP3?Gct7(di2CNe6*7q2|6Vr5cRuqRNKr1Jq1u=sKH&`!Sfmh|Y~IIo=Bi z^8klb=w(?GkYaJD8psJ@mPQHU>F-u9M$#2lzdj(pFPK8Hs6*7l??2;NY3Vin{a=EdQD7#boOBr?G@h&I^|nj& zfL^0ijc5D$$A3|w_PaehlUBT@m6uKR&%9fkufF-@y6L4i1^%%2eiaFt1T!(^h#7}6 zAmT|?VgAhHazXe9uREXpIMhKV0r9&jSj)FNdL!ncu6v7@!-cKsLbp%HTYWBk`M%O5 z)pAoaU3*jdi(hBL+}xey9qwRgAzGReJ85}U(Y`fg3u>h+LmJ?I++|hn@hxB^d#5RL z--Yo9d+JNH#s5yoygE5eQTwYqP6?W-JvxhkS$(~3$0U7ebi+)seHI0rEwSP8y!w-E zLCR-4Z{}*b6eguZe=r}H=>_+3U$@r=7wbf9o225_ZbZD*jM!do$bbL9x0`O6e zLlqP$UwXP-e5=mo%iWs4F4C`Bw|aGct=!-s@2PXUs!CTo5};^^7DCa(U(wPkS6SK* z>GDyUAW(BK6ETHr4~-Skm+mH9*XCPvWhD+3xb2;Ew2(dG+LBdNb8Sh)UJlF#c#ztH zSY9LjtGffNN`oZBlA;jep7a+8aIXI0$e!ohZK7JMh9B3mHJ3jIiX5SIH%ydr2OAu` z%Kj?X|EddrIu=a2bhU)K`UtDFS+exh)UMlcQj3oXtj?8h&WQf z-MKw!0}gmRoL?<G$yz4L*Y@9t^5bVI?Ix$z>r1-9I+^&1Fo zOfU=!16+lU<$n!Mw{X>8e(pJ^pxdUgUCD)XBOzP}nz9akWkOZ>>^x}P zY`9#qJN4BO7dy4ml3!VoVe(GDZwFl+SKT}m?b-5Z=D3NWY?G8@p6-wYqo#6J#ywzT zMfPNgZJiV`VzS!mbY)K5%eURWu$=u6wYxX3hbT&`+=xjZmT;wvf4Ox80lxDWF)!+s ze(%fkKAp5I$BDdm%Y2`#@4k&ej5yK5RY-1OF7WDMQbX|JMzPnfM+D;1S!-}ZZZ~;x zw>$flirnONx2-^#`ps0My(oesN8z~E0iuwpWzSUNqClja>#em<2;)J_-0?cis(0Hd z!`T9?6>wgg*ZoNe4_323x5)OHPeT54~C`kN%9xzPw@nxfH5*BqouIDjFhB%8ZcknidKuiF-s`ZkdHjfK%c5t(y4l zgV#o~s>}`x^JA)cDZBQ5!?~>lh_#cDy4#|e;^(SFB3X>{<-AeZ6~KOGeo%?jpKhhA zC{?tctl!t4<+%=(V#?T)s`|4+CzjGP#>{1%t7RI7R|pR`tanouJ3ZHtQtf<4#}LJd z>+h1Jj<#F8-zzG0^WFR1&O)x2zYp%e7uA;OE!e2?8L}}LUQbecp!zWGifHEHXN&H2 zY|GxM4ToM)^{ce`J<2QdZOSxr(N@ZCrL5{q(~^J#Pi0c~|K?{pWv%XhNg0;bGCX$7 zbJWTka%4AAA@dluN^Y5C)$8~^%Lg(oJ4qT=32D>x6#I`E(^gXydIv$yQVdx5X}RCm zAM4_ptUkDJ)xk#_b3H0R3h~I!^W*Kp5G%_|vp<*C$7b`)OHXO99DKRoM_bG>CP324 zL4`fG{N%#vtCfD5kIg?VB`X*7OT_Ukb&$7hoIIeKT)LG}noyc=a}uHPU#j{PFYjr( zWb>{#n9K}6)pi0ZSpu51;{7vrnGBwPAMPSh^XbQA2c;XS{E`yhZZcoR(E+VJ0dZuysy;R zj%4V>G)pu0dOLsWbg7)wQOsUPtk@gBez}x{fBpM}|5@u?(N0T{3B0=KF|x~U5i}zP zYPQ!OL3VCd?r#%Prq^5SH&q}Aol}&Vrzz+b3E^CxNlIzAN1kP$mua-@#~fOjzZH82 zn;w>y+mK>&F=z=(CPQ~D)?4Y=Sjp&o)KE7kG)mo7?Q0Qs=o-@W&Kys>KO~cOhfY1x z5kGXOoHDHPR9E7hktF$Z$c4Ui?PLWBL1h}yqJR_Lwq9GBYESE$HR(iGDZdcUIvLM+ zps6r;z~3pug!X4_S9?vi@I|eY$w%b=-G7bq{*KeB3^4lLB3vekMN__i-hD07R%Kf# zQv$)*#|@q3*#tCq-)r>Sh8A3QJ;Y&$Ob(wlI_+^~^JR}Hz7b{~Bl`wYMl`-P>i+6W z%==erRjM}q^Kx%W-#epBp2=ARcS-uak51k6zzspk$bmNusnA0(Io_NlX8twTU=IeJ8&-H$(6z9xI-O64Wbq?3q>7=oroioexl-m&;9 zt#US^G~6k}_*o@B>HGxouqaN3uw=VAu3K3(wX`I6fpWq>cJR^NOn(nW+#5Z_z9&Jg z8oQ9BDD{k~lX{k-m;G@e`WNjDoiHjB1Ej+BQFV($XS!(1yKjFOG=n8$%tM7Rnqg-4 zr-{-c|CaIohKzS2)jKZ=1cPF2pchGg^Qyt!cd`@Y3uoWZYllgr8&7XMDy$+Yb@3ak z&VGQa>_Xx^RFh`3!zU!zv=mJTf1I`Iuv?l=edWKZLym1R2K}jzxo7@Pb16e|$VrU* znE77Xx3<^nIH7R~lfM!ZarkL*V%8?G!;GsMT6*6f@>BNniahoZ;P24g3(QE$jRg9^_T^+> zPlW3ljJ(D;?9n%}mbAZ1a>x9&Y7dbRa!MaJqsQMgxhZp_`oZ7Ls{S7s6FSU>B^511 zc5TY&vMD$|C@+Ba)F!AJjjTa|utT!i?K^||BD<5uDapR{T$6PneG1l(s^Cab>RMwK zaT%8DC}b!GZb(O_4Z-L*%osgk4${>nbV!CFUV}3N=jwDgQ5zwXhYaU3&v;}O*|3}- zjDvVdH`n2AQ2U#l;boHdMOcxrD3Mc-}$gFY6T3JpG=P@H$IG=Rf2MXXv?ht~D?%zn- zKUcIL!qBWQGWwUglFzt557Q?asc)iO=xH6HxS#_j|NTuBWq}HRp|pDtpk%CQoh}er zPtDB28Ixeg3UHt343>QQ7ha8mM9MK4b4S*7v#$P}4dfX%j!Hs&IgoOg1@pBS7^RK| zdyD>ANY1k-6v`x90f;mRQomaU8l*0uj~pG`5m1t>Mc35vJoJ9v%I#6X@!RG6DfZ5? zB#${}0>!#B)Y>q}S}ilncRj@zpR38eVP|ON%0iH18GC~mGGTBhS2)iFA3laeL}H|6 z5(n4mxUMk~noxES^yP9IiEerIW##*`!ttMz9^MmEu4i$ht6htPyBFadbBSStJKT>z7AZAe8k_&$jiWX$TL?H24O@{*i z5^2#Ntj`bgG{Ul0LXSrBkUeurT60N$|5Ams@V+(@2jvj~=JM8%1DZ6JoVlD3{*s)2eVmE&Nx`i zNY2R0#J#I2Wj@OEM-&eefBL`<$fakz^Z(Hv;Ycp@(p4T6Yc+NZjPS2Iib9 z!V~O8&0RApfVl%1JtVk2J*B!7l$0Zm(GXU|yf5T{3M;S8SPFJ22ar)A!eiNNp_HqQ_m2x zugj*>$_`VKcZH>wIvk^JBpay8dvSD}QZmiR6;g+qU_0S|U0w9IP{N`3ePbq1T#b#C zEA}hw+@WAiu)8Bd5DoNTs&)!%o=Pq=*SkGg(iV{p9zflgL{K^To7`QYO00yEWIg^- zSAI6*pX=#;tWg~E9Uj{lsN2mE+V^3)i|8&O5OzLD&(Z+dkb36vjdt*BX#lA4owM-6 zc^8*0duYyxw)6vwRvPWjMr$y}P{xfioFyqmb>}r(I-D^8?=Qz~4b5~zp!+=fyrxWO z6)K;&IXSt~{^jua$n?Vt$wum#7Tqmg3%evraELX!(iXgyTcF+eU|A>2q#kBDSIF4X zCJtVI*FG7Ss32LIDYww-In|%Qx|KkrPp>(3ue%VwK#kUurkinBKIa*u#ZAb&OgG_! ztVvnV;w|35GiQy8aYS2U%7+gORgT#z@!+`DX5j)!$v`LosmCGKQ6GTrBGr})X1i0x zfdF=j4y*nc#If8%rK|M72j96|qvwm4Ji2H}3TaSJ9Z$_t<*r!S3rg8OxC)I>^GA=8 zG>8xCEVDkEKS^1U?CL@XPRSxXJ$p(J4{MQ~B~17RDwHnb%40ke_w6F7GTM`hcr#tR zW78>_TLn;9ir%bAyB^hu8-y?UiHuY=_!H~#sum~u1e#dbtRXk_H8LwXJ@Y<+37M4c zQQN)eL$cPwo%eEe%FnwLGG7MMD}NN?R3@N#;kI2R9$jdw4a+P!PxBr~vKa}!s}1fb zgZR+xHbj2T_CN}(_L%%#e-3OI^o*sraTmMSrUpr>L%bP6PUa9iDS-wP+djUS`+9`J zwUBsJYL6!w?gal+;BDcmI5IuBYl2e|Htxah%&%)O$&0zY4xOF#jAH>QOaNIgJ0~wPR{C)oH9xADR2XHY=w(v&6o=XQ8_&jp6Wa zAu@PXr0=*GH%ZUKm;B_;&VX)OC`RHq9`TP7}**@>_=) zg@Wh`!gCC>yIQdmpY`piW2(vBv$(cnk;w@jiaoJ`Vo2fG zc%fMuQ?SkN5>PJAkS$-ep5n}B+tL~$--&Qy5AC==*`3X-J)9eog0qQbxNUfpn5_(Y zgbo{4OMZB=?Ts}~&OB?h@bN&l6%}r2GaV%C)zdYW8lObs^v|67u*cing^N6Lm~iGW z-Y}N&ao=OJdiaT<&gg9bh8B|J!93{64tL;_f1hb!3!DflqG$JqP<4OC-VQEVE}Dad zthYBHB~`A>EpDd%v2YvmxLTc-??&xjoCv+ur|9=v*qw!Jufchd>K#9hBzUyjtfK^Z z$VB_BG5dSRyJRNxjtUvkVO=?&BE9<}*B!>jn5U0h53ixSfH7EY=`kS)M26ml7K)I! zOj0h68Q3v)r+kNGM)#?71M$NT8*rWMFF8hQ;<*QswZ8O}T;2B_lLpzFllWz9{k<8h z*p_uYfrj{>!hbEWiv?8+#i+$jcP&5 znf=O4gC^#wbtEM%S@&^r5eueW0@Wn-Xag{#F_SJsM)g64)&u^5ms0u*eu61Og;Pwt z+{Y52E6GEwsA5dr{&|7Z`Kyik21^kO^TNoY^~N9f{~P7Mu{6hDEGRr4hPR<1!SvFu z8m0raUA1LA0iCQ7GVy8$L+h!D_U<2!yF-LFzR62OifYq$LtyvWDV^^WJ6)sJWljb9 z>xP9=r3;YmGUq1Sf=5E{eP?F-Er`oy%L^2dlPAu=Wv>;{lbvD$m<2 z`EM+2X_ASLi@M4bMn3IrH5U}L`D5fA0r17iB`MhoQtOMh?;)iK!Xaid=}EdC!lQWD zCtkF^48!}s^L80>)BISbB1CRXX-IaGV5Id*2lt81%B(v3$dy8i4#d7e->LchCR2j+05nZD)L2&&l-c+ZbEhv^tnk zy;f{JT|5ZH0po~=8&DIzmq5p zm}=6IUmv!kg2p1QhWH}kQ7HxkeS@4!JvVSad6&A@HwD9UTP5%8mMd;2GP5{`voyqX z$@Q@DzqLJV#7U1LGe%}4{b$1Zd(=!x0_F77>=iL#y5joOKOq%CgH}KJiJRxu>WfS@ z3PhZpxloO$>Y(2sTTsVx)jvlRIEjV zXe!BkzESJ(h>01}AD_CJ@SwlxyM}9{Q|3Vl^rQO_VcXY6Z3A@dhGN*{x~*i>S7>x{;<~m zovmfIdb-`_v6%;%k_p*ydkJ$7BA?5hGe?BY%?cRsd5-6&b?tX!c`7b-^3?PyyY?$s z#PNbPr=*eX;b>#(Vt=z%%kd!1jrn$t?$OdMREYncqQ2aO)!qD{4B3)juE z_o~TtST7WtbmBGtxnW7O+-YRPmV1L(joF#)>@z+ahyMO=y?#rE4xuCb@cv~hIMs!x z>|8nf-)DFbIKW|PKl^upkTfk{PqgzNKhAR-oveAp(D~qh-Jwu70CSe{uPs$R;#uOj z615=dsO9qIZb!bjvQ4US`SETfojia^&@t?x(+on3_EoKDp@#jU^+_*(S>z&4R;eHBM6Nr zb{(pbrww^zsv@?J5ZwA{(M}w}qqTMvYxko=2Ob;9QW=WX?*=?iSSX7>)}8n_Rp0`| z41cRvLH&NJKPQu>!w!BU{m8WTRk%uA1gUpsW?z5QOVb-aWg!y{vms$R)2^^=4PjLb8I2Hi$u4ems{J$dI`+p={VApCx88!Z0Q3%P`NRQJ ziFX!e6H#~J|Jf_<-SbFinzbR~zPjNj}6|~3{GgpVth~%`tUdXP*`0}|Ggi(UU-trMX>Sd*gMEg0)K#LER=NvzejdzovB~<4FORl9(Gh6(@j&z zboPK!t=CgA##ABHGbNRsbAEQOT>HGYY<#Eck#6M%*_>xpqSfmb$`C8yUm}O8U+$0x z&m)lw0%UrL$ODa{!jYssXvn$*yq&}{o1+S0NnCrjD)90(%jAs5kv-QJvlBv>cdwFA z-`c;4oM{dKiYUp=OK!t@?ccPG<`>VEM{%Pp0;K>n0CC`@_)VCf-nzY0@}-TE5yxMo zhmSi@{tX|Zv`5BtV_0e13FT2cX^D`nBpzrOPav^S2{g+$5BmwB9#9|Hx{&<&{`7=q z1?X|5ryKek-2xLjS~y}ID%0A<)T0YUoH~Np8?5HAqc0c5=n{@hOH2n0sSsouo#2yb z;x3lX9L$mq91(xy8~$ZCjT2&-bn$W2l$Hv;>4;iZo0=zgKrGS&iU3Js;k+N7FMdw; zzIj%6Dd|VvuYW4qr`|&(xRr;ig&vwk|F~LSj%265@R}V`b4+#qNi~Xj1~Dh4*p*>qw{-D6OFrY*0tImAT6 zYuan3p;4-{<@99@A277gEtS!l@89J6BcuNRiwZzMRN$x3I0U>BhX^q8HXL?811+xZ zGsdYLOa=DXmD{uh9Dx8Z8$5gR|Bni&iKURmRjCiNY{f(RCHI~E`0D?m0_V`d;3b-X zW$q&uTtEH)MECuQrm+tHzMVi7_dh;9 z?uCcVq!~ry<)dq~Uf%~%ffEz!LAgXhY)9=_^_aw9_JN2u6GjJ)kMB+;R=n))08xR; zfNcDC>)bvN0{~HhJ70MDragzF*YEuImdg+k+8J%*KHs0O;nym2*8Pq`_x4$_yK26l zCT>T(J^Typy`)g=AXs$lySKrPP=1db|9Nlo58v9+^ZWgpm2U#h=-a0c68bkjwxFDW zqr)q26VW3E!=ge(KVfIq|0lYCDVfWN6P8+(Pmw<#drkaT#ZQKZlSAc=RMomQ+1R~N zdTp_%j@42xPBjc zX{ROS0iptBa7&4!wWE0v%2G(g#!Y0-nCs@91AIdZsW&R)uLG0`WpQpH4C$QX&Sf2>SSg`xyUA#v*HRZ zqW#%iu>HF~fS&0^$=N-TUnSwoYhmn{P-Y=nXa!E{JH8KeN(~{V6d#exE)Z;lQS9qCMt!bd6Z>=wTzn^Gf!(`_UNw|+hlE-l@5e4<_W-Pa>G+V8NAKig?S zd1z{VN~&pA|B=h{K|AT2&wTbE*Mjr5#Vwv-%wZUgayrt%xi~l`RM!!{460B`>dF4!b=TTh1?q7?YIG_Pn-G+H>7VnPt*% zUSeMMhbt_mgmXvxSo|Diz_yo@b_q!^>{87|W{ySA?V;ZJ9h?_e%?PDkbak353Q zoQL)qi@00k{JYxqObRI4fnN?nKW%@rJa8Cre;F|*+D@^~i`T|c$iB5NPL^uTO{Pxm zDcqK82a_)Uc@TGu#c5fvjCM^iJY^iEQz=%t7DD^ZU>$0Or^fC3PUED)-!8~}mol!q zYL*a%-hEV-yH8cwcOZ@@DPNlR2z@lH1m`g*|jykQ>p>G6zKB?K;FjNtQ*=MpCE;)rz z7sSEUzKCi@qzvp(kvVhltxs+IKeS6CE$VJ&LtVlkkfjup097+Gj@{MEU38;(a%--mw^Wt28L7NSW1ojF{GXs?ohCNL*?4@_(0dsw)4B zw!Ssc;&$hFqj;GXyyx%HbZ3^cOh|A>+t==a7@SAf+kmgAByE0g2I(dI7+fdUJR|zi zk15gFhm~F5|Fe-%&C7^0RI>I+%DSr9wndyClAM?M=jQ$^{xxB{1}>{CxwXa{UALa*mpkR%pSiq#dYR_(I8*dMKk{P7;A zAz}MsRWjnOe4;V^U3A@D`n!Kyx;jRx=gq&$i>|eH&#L!p+mTO$!z zoJ4}5AG(zd`!W2}Cdc%a-Hc@Pnq}%S(oOr9+NVyl^qzsJz`~GHh*@?hd3pCZfF^~D zW+p%aa6!A%&JFmSdn5PGGIac)c`HfxclJr0j+cW+xc;82C@5AiaZ+oZ_1`ro&D#$K)Q;3 ziW`jk5UzXXa=6$P#g%BIg%cxt zZ9Q{gA%jQ;57WcPG?55H5Zu>4_(=%94b&#nG4gZ9??M2!)v5g|bRTG3YKZ;E^T2o= zjr^WoPQew?vC{y)djY#^3_r+?O`zbwEh&SB_<@X~JU4!OGRZ~k$`LW@DAFOq62NtV z2MS3r1uy0^#FJ6XZ8n-iVSpC-+nn>DX}^wyp90t7B#h@m0#rLm03`WRkW}std&zL5 zD3M+1qLG%o&nzXZEsA{{o(Xr5ojHB=xuox;M5=xg`_7SIaI6cig6U-3H0c6pRj%V; z!9AtS7`}s!VRBI5d^LlM++teB!;wQ)yY=`Y`gA%WZ$G^4Wc--;5&r4WDEhp)JUNBV zIO2XQNiFs!E%u}hjgN|Eqq4b}3LeTDg$GsRog`cxaN+5~|5W>+7`}vr@1|V%pV=OC zu5(b)kaJWHl19Q*bCF5?MyRpV@O~pxNtqLFS3B1vtoex5^V0gL@X@>U_$1)TclEF% zho0R@J4eEHkh8N`7*HYKPa-@Z;h^6zRh0kjTqpVXa?mmaTJ8Z{Ipnf{f`v|EN+1|; zrCQI$l(TTRN$5S6FaaN`E1L|I2`i_{5-t!uK=@8xL(@zPQlKeKq zWWv#P6rALIToDN^eleySG|!W;pt~M)4)<_S=Q!s(*f_xg79=M!NdGhVXaC=UwSbh} zM#gmzaZOwd3xcL{-Tn)``YZHm)z7_`R102cCk-Lh{i}4F>$C@9&ZeEl*poIcd_ z1)W6Y1L!Iit{NyVqT=Ok@eC@qm5X6;;=pAtcox`A$_AIy{rvMI6s$6+obRrwp09!V z=fbsdo3b?=a23l&IZ|N87}Rabr3p&q!G2P%MapElv_kAjZ=nxE(hv}nWleyWt>cDMjTm}T4z=^v=LbnnDlozgBz`;EN@W&gk-GHtg2iVLK|^j@D$y zgNO1_xd5h?j$`wR%31g`)|a1BtAEX-KorIKZ%wQ%uA7QgnFS#M7D2lK8Pxz)$m4LZ zpz&PdBmSLSW9>t+rfLU4w9?5 zc_1@Wph6huf;L;+IW`z4;3ROc=Eh)+0N2aHt734~m|FPXntQelJw|NU!)p=;aTaCx z+bS2~W{vOd#Fl^A!xU1AihWl==?EdA66v5791UxWVX#pKUf4Kt4$KKV`&XoIzUABo zeu@r0&l*bX8%le-G2c3O9R#?nJN}|Uiik6}m_8Hk^7o?7Ao_bkguP zy#iWq&$ZsJ%-&fVew5!k%frL^(JV41n;QpaEEu4Qn;TaP)WG}eLDXXkg0BT{z2vgJ zakbYzbpwL78yzJ4BN8S$`NFGtBU zJqIfd=aRHY-@;G zF2MCs3hCcy(8Yuk9C*y9AxX30VS9{VVf-o^ozHH|r=aL0Fq&|!93-ItTra6%1R!w0 z<@7v@L&eH8jD*~~q!B+VUfD9;g>5B)7j>9IkgMS1INiBBF!%?o&LPSj0SDifMVPyb z_tfYK>TLbJCk8I0DH|?DxPVCFi~Qt>Y;l1PKEts7Cr}09WDNj>JD3a2c^;@DJ}$Hr zKMp>3ORqg3UDU$VzBdAzfIIhXi_hc5?#qHH6Wm*4Yy}s?q+)wGH>j$>#6OWhdwf5w zlS_N>ibH_)cl8FJe!L+`R5%smESc>9Y^~ESf*-wrBC-Vx!*id&CPh9pPoqVjCgU(4 zG5BgW%BKs@C1y|1VyZ#b3xa>f!5__LQ~q8n%k19wSyUc}YvMqZS4pLoQZmBY1it~Ks_ z5q=2QOH1ztYO>;Hz$QsAy{L|g@dlF4L2y0nwsGtrMFViz5}76v+D(>EnOgszuGPNHnTHFd;sOMuGHL;_bK>Gp~ zYM*W8d%yS~u8@xTx)aBtH~7A0Nqu+(RJQcq?c7wW?Sv%AoO*ftasBPfFOSLLun(In zyBWF}36>mWKL5tF20^JpO8%RO%s15*FEL*Za=m}*{A4-2t5PVc!SiQ+&g}+f`orU2N|CFI-odn7E`qF#&Opj#kLo{e^+&VdRx34`}>*j@g7|5L4h13i=4IDTK8RjMZVFYGF~$6I&F4$>3vt z_`aG{0Sf6c3-;i-=(PuGeXZP)){U}Tva7GdN4g=i?V12sCjwc@e+NI-5dqZ=k>Jx( z5aN412=c^d)%{0B!4holGa0Qn?@y3{S;x}{9G9s8l3j#c=*x!sWBzOs5Z?%c5Zuw0 zyzGOxdhXk*t>H~iu*fi+7>Q;)ytl*QqeAYrGPV1dzC`CZ_G`JC+a`c=R?*#@NvMB! zIkD^dmApYm$(;%SmMWx81cAXv<=;O8l@gv1WWnH4Xxn?t;``ZcCd~hgKl_UxfLwTj z3=_}>m$%QqrhWwpiFxwH5&o5G*7+(f=Bw{#cpG+{kGr0Z<;@l`d7mc@CYl_9J=Xw3 zyP0!FHCbM59gd$A$Lo9lbt*RCuy0#>7H|(1a3@Uw&H{GeGw_@U%#@2G*+O~{#^Aq+ z-Cqn=Y9;6@N6)_d=F(2|eCFla6 zWf~Rhh3zF_Gq`zANgHzjeu|Bok;8NNyy!?wCm9bGENI+n@A8jo;~0q3$G0`6f^Avz z`Y~dSQ#&3M-ABy~c>-aw&GnyVZzXhZZ|KxNqPF^UI&3$kOewXb?>v|Lb53;C!B_F% z*Nl>Bq8{V<_P2lUr*Aq|S)LQCr&QzE$Ld2iuu|u$&2p?-P7Ig*4;Apef7*{egMmgT=@9cX&Swp`sZ-zH%_C*@*+pd4zKNhPW!B(UUBAY}Toy)_!vA=Ik z7bl!PNf<1s#h2_4#t$@r=z^(9+?&`dF4j+OSYahSqcaKvhEqEP;YTNiCp}0xLum-u zZ(I#{VV3O|?-8*Yy{dg%Yg0vYiFZ!~Wyq#fJM46<4>|>xieFxDc>ef?^^Ly2xvhcr zW+#7>N;^U)x7{S%!YDq!wwli9uVrd(r!Qq}Aw^fD-S;|Kh=%p$S`|BPhgsA(M=K!n z&D6a<7n{taq4A%XUzoGhRJQtZF2Jz@~B zYhc`v5pI^Fv{DxMz0vpjvz74#W}=qd2l_{K2m=CHxPeej6Us7`&<>V*GZgr#^4q__ z+eZzicSJNNyi>wvBoxssk23NuqOS$3t05$9R^x6{nh#Ak35K+OGls-mrpks`gY~6I z8Heo+M48_!EK?@X&Phqir3X@-r85Khw%c`Kuylt;L1 zNQobB-_<=-e2T$|i)RD=+pVfP7@n>bnY22pu)8s&%sI;zDQ+@QX5i0o^!;{2vkwBI z2j9z+^X;=S;j*FOm~$m=dmC0{1Ei8Iq#QghqbEJzJ74s73rtxC$N!a1DjCf>4N9Ho zMW0BQSACc83`*EssVxuAyJJ+{*x2wP;%si7H{&sVE#YA)G_t(kayuMf?Vw71gz4g;M1>GRyp65YM60ci7 zLK?`;J_*_5Q8zbyV7m?fw7W{Q6&RKl`_ops@>O5htR7{JIeF9-dXIULuHT+;}YO(9i^}3caeya;tX1E`(1KE!-6TS?AtLV1l zUOFhphe6-I_;=S*>tpg|t0;2`D}@YanI&J-rAZaMbB+g1QSJtdVV1-jHb_h)Fo^zI z)Jn8tR{+q59@S4%z-31|CSB68R1Wn|(`>HvKQ2VHct{*D0Pn-<>BH*b7phaogcZ9< zDc%c98GZ}!y=whZcZ{c+O2=5K!#@-pS%32CCTog}&Qdu6{^qXzi-CG)1i5zOWZF7KZU&)Y?zGAV$PNodPX_#2N+B4W9B6vn%z-DikcF9rKcTKxKm*3R2J#GNlN=Vp?Kb?CA|Q@G=0O|qTYWc z!1rD4lcs`t5w(A)eRe|W!F<~!UL|7RaV5g3X7l4mW7EWTiKUb$FUHhgwoy_U_w=F; zNWQIS?lb(h>jNoJvX)Y;8c>|A=#u#;FfLF=KxBU#L`m{gFL~%?`YH=URB^{F!ej zFqw8*;hxX^n*S*>A5g?ZLm^37o?IEd)0L@JhZc8x(QRbJ;{1i>;1)EJg-WN%Hr;JRpbP|3jkR#imfD}k+X6@=eKgbs=w%1XyrDk=Y`L%J34t<6AJamVrkW@PAy z(#S)LSS6=7d}^3xMcVmxq!3LL;gDaj&5>a629>N9Gtv!}ZVootYAef|8hCnW)XOzC z|7N4^Qfoz#+R08in}v!FRiX)F-a6-VRUH1U?S8^X>fwco_d^1us}vuK4=DP`jLJ;v zhI}{W(gSzi8jzfyv(jx;$lf6bmwQ@2Jh%7T|KaQ1Pr z$)&jzij2r5O1kN4>|*XCG1umjR;0NmmF8ANSyFGhPFHjr-A1(E`Fwx>{Qmm=!CxNZ zF=w2!^Ljp?bjP-o={KxHRPyqLF+UmA;W=ElpPu`w(Koj?VT9%r*rX$I}W|}>Z zDnaMs0w)mt#(OO4JNGaackR7Bx6w={$Dy)3pclSstKrql-SXQCZh zYZmye`lKr>1@7^&m`8OAcSE^vSiHZ{m+wp{MARrsu$*~U zKLxHlv4Nkhtwc$oF$kb`Sg;uK43vCc zsbZEIb-Q!R_<+XtT~fE6=yeuoH*Qy`OCK#HasT9cBlMQFV13JFRQ)KAU3z5(n`Fu> z9r=a^lEDeg7aAf!XrkUuDKNp`L!8kt(5_^g>=ZC!xDY-Dtjo_Fu`S92)O}lomtQ-#ZA*=d0uNW zgua|#wx(|%NaJRCANCEnoL8*n;9H*_LQ? zrKsY@AIv+q7Y3Ko3xD7gZb$rY-U>Md4p*n+M17KNFQ5)Q2zXWIkT^FO#|+Dan=s*0 zc%%W*Qpx+;R*_SanNcc}F;T?;K0i6lh^c{K?79^KoNkL5S$tR={>uIuOsL2xNWBi& zq*G^M_9vUoBks0~T%7jY&^hJ4U^b*1rWA}(nq@=3hN60pb?f_qi?rJFqd|e&jn{wQeK0GeM9T9t7tijTb{XPWHSL) zK`e8W#*`hSTs16$-W;)%`?*2*rmUd%Ey6-Un# z^*tsHFgdWl>CggOrkU7N(x}duFMywaYqHZE-=;ql?mAS2hu}#xwZ_tX!S&dctyd7H z*m13&+-#kQ9CPfwHtv=tN{;_HgQ<>bTFW)ZJg}M_Y9$tAv4A_eK0ioR$!JVJ=fdVQ z;0F;oPRQ~jQVcK6(Sv>T+%rs+SO(Jv>QJ7@0u=vn|L%1eY$nqhbhM(?{x_^yX7lyqKk?rjBDuLt%FL z;oW(!9@EKOr~`|-T^*{^WwR?Ev2UoHDK2G?6f~WIYl(Ap(xv-Zl|u#?{)4s+RUobG#jOxnNiPF4goPm^WOD)410Q`wMgkr@^1vIra$>-7FYW@jP12kno+ z!?Ap6+e{VfzVUxfQ?0}cyMj9(VoI&lhpkAZ;YYMw-a90Vini@5%^kD7$g;W)SBxQB z-z%@`RxgVea$hjZ%0*Ref=S&GOt?75o%u-PF!SslzfZyn#E+tVRoEY5=pQOm8@~Mq zIp9}-in$H*&Vt9lSdKM1*HT)cB(_v_oxZ)?o-{%W9MS_AlmEoI$$0odA>;ET0%$#a zpFs|k-)Bas>^x~aYzJ3}qy986-(L9GBMzi^Rf` zxpcKj$S53ACkDxpLh3-$Zed)bojX8MrKXp5Nah)D3gKx_kjJh<98GFJwoBI z1-xp#2ocW7CW7-?sXozP`ZGTdq^*J-D9&d?8w@%eL<{AdRT9#sMAsTd=5{WzsPJ{9 z@D}ou4Q&P_OQkqDVI%4mAfD?p|8QV8b=o#9*n2L`k4vM{sS?Ww>aR6YaVBFs(=HkV ze_0sdIhGgwH2=QRuG#>NDPD+U@UyIi@mlq|)>#HQbE4$kdA|ke3*%k03tQ_~nTbjL z005xRERABK$?*SDOoqNafkq~kc9Fsh2$zm06oBpFiDILXNyO+RatA6bmpRu4>bFVH z(PnOjVv#CEOmjX&cQl_2YBK>*P1ISxlpa_*-D4#8JKnt0^BEVXSQkRnjUiPY(xN>K zF?#tvoSL4!*B)+Qfi!WVo_~t;oAi^gE?7_IRoLePxroY#FkmF?9jHn?z;*%Ac-AJx zBDlAl zkURJJ;ZvtsivDPRe`d%73*;1g#NzGCMrNMB219lRHaf|uOt|5Tql-(a`?NdsU(x|n zwG4Z+#aw>8Mr79}h23FI znPV;Q0L2fElXIl|ZF}bC+d0I7=Z~k6=Y>xk=V_Z zjKaz;-H;jkwUg>Z-T3gvhQX`|gh`Sz=SJ+9_W!^U*$}>ZQInnh;RM^TSumVke_gB) zI$VMMGP#>YwHN9erQ%sb<^fWs`;qQBc_lmk%J>j8s7xtprc~vb^Zz~%sX!l?5Pi>> zI7NaVGFvb7iK#hb6HfPNJ23FAd#sXX`AiVEkxzRm;{LFg4|s4smjJEh?`HDKlEn!Y zqfMg|PqVm?zsI8P+cV|Uvp2J(ZP_m`*uSfI#|SQjryAwk;H{(0_xA81$~?JS3pw9F zZDgl|WNeT&AuDh|vqO{I?Z70FsQ zva}EM;)K6KK3SYV6(>sC7UcLJ#%`xStQEn{mue#{*~CYP(up{We=-R2$Ni7;{@Mqu zw0*2#z|+nxQggsW@>`lceM12H$;o!%(p=|c4=mGn^yw2GJI>wI>J|0sMl!bb$|p0S zMs%hlAC|g5P|~+>jaMS;>K0=QM?6<}bCMbPh%aX2SM%USlZb-xg&#ON#RwS=Bm~aI zC95+i19m_h0$8A%_fnk}kPu9^u)w#{=t~=+^k!1O&0t=>dQo7z9GFLm@Ia8oO6Ok& zMDlAEGgvN;?Ga{4rO`dz8myFdr>yqiJ7f|8;MQO}l)WdDWNL zd)PGhS)L>&({2Moi^kK5TFRx-5T=lV0KNNW$CM?4EHG5y{(-5*mnGl1YS~#o0ktEf z#La;zhs*Jp1v~v8oiX`(E9W({b1`+5S>n5%n}lb0;7UhUrKrptwTh%4^J%xSVgJ2W z@ElEhYMwvuDxY!(p2&jT?Cnfjn#*OqQiA(4)3bpJi&~!u^=8^s7R>GaR|{$fIWUQPq^**{V~s7H&H`QSbkdCY?~RGyd|1mV6zj;E{M< zE|YD=ys2@LTOwp?OywmAe@$<31H3eeV*b+pg?3o_zDhz#I`m@S40AT2i}^nN%l%{! z-4_n=$HR8vBb%P{ND>(vku+8G+Zt3lzVp~nF**!)*hP8!z!u@JqP(p~$rl;Pa9BN6m?g|^=qy{~%Ga?zKbq%z zeP6nGAGr+3b0fj$&Mm&6();@6u?Mq|65XgVJi8-nqTcWHuH3*X zOR}mWNOY)Tn5DO^Slhnny=SuAr7PMd7McJmpyo?eRW$0Zb&z~0d}b3qLLd33pyiOd zFvPiwba~l>54R`}x!kC1m^gJen74Il`qxzCP{~Bjv1;0qj&14-!p3ksQO&lI`mZB< z*cYwk5cX%~>*qgKLVk{nl4UCJnv;0d9@mB33ybBEftI+o?e|>DBC{?AJh2v)Xs>{Puz(y|L!c>CePg6 ztq^XJnpwfN?qQo2g+Ny3cpmBh#x)N9`+re^Kc5fN8-i{j^`ej`=kau33H=_1;^+|fKuwRbzx~~ zBeOl9*()1j`)}WvK}DDz*OR=kJY{eJr(EsHb2_%$W;P5wj=SqI)TsBtdRyh*kZRMX znwPKkFP)Tv2p+rp;Bv;z{dGqYDv29jC|SY?_sA31`4kcC;Rt5p*`lBT=VL8Rth(7=ji3@y@T%mu1Pk(5zdvk zK8V*qUg~E(mMGs8cnse5cxBTUXiKyh#IM25E7hEJc%CG=%#!v2*^FC`tmm|Pk!`#J zY=YNiDAJ*4S}+-M7P!Oy;}6;d$+%6os)YC3vGL&|cyV6y~c#KcqkJnArL^7O8CwHyVKahcnpe$|g)fjZyMB!cwFY=+Y@XA2@^Xr}g z`lreV-_J<8Ki_qiG|p{>8&}vk=Bg)X5O&3*4C3wOqGYFc)H>XA_eO!5X{=D^xW-e@m1(vA=AWeU z-d*-e?SrNJl^Az<7+d!>vA$nZsFpjMG{QaFk&^G}1QfSzd*@|S`r@i3Ac9Q4018%C zboq1zc2HRlhvQ%kPp&3Dg)ejv{Eauv{ooN^(~i4&G%bk32nUNd_?}4L}9t zK81tU2C;C(!e4Z-)^rlY&pkiK3V#@6bf<#sx{LaVm23*ef~s7HXF`i4iI@r8Cx@Zs zk__!IUC1@?9KLdmeVj=eMey|NZ+Q+WhwLLRm|Cx-k$cl2h!)r@GuBi^F`)8D`0~mLy?j@ z6h{2Xv+ugIFm(C)hZvoIoZJFR1N!(l%Dlwv)#7jZA$xU*DPtKG&6mdbFYu+6g%r8T z3EdCMfyy|-t67a}VecZnW*!J8?zG<+nEpisM6>y^-uu<=XOC!l3Mo<$PFplV#znqq z&)>Btx>p{4O3^T%U)(jRk7V*u>2^Eg#Eq)0Lhnsz(332Xo()QVl39XnUV`^XfgMNjz^ChZ()T zU-$4~IIE&9PW8aeiF46aqLkXmTyrdUFXLk=;{1EtuBx5;c8&4+V)yIaa87HVNUr|e zmYBOg!T|Bw7Wo&k;9+&l^254qL&ATP-nRXZi~mhD>R2RifcGwid!6ZrhOjH6j7;nF>mWMS?|3_;W58?cam6!dxxsRKO z=S`zsmd8r8Rda3Xw)b3p+8S{}b#+jG$=x{e|H2NbyNtaU=?~Stu@PPA?;h0opU@ZR zNcvM;LvCDubC>c#`soYnB;o(U4zHb^4&B#hsrlCj+_V|RZG#_CPPy6jX{y5dz&Uh3 zKx?Eo5fm1VcKdGj*tN|Apf%Di1?BWTW52t<^uMsfjhn}A+?yQ+XpI4d2bg!7Sxz@s z4k3Shp6$}2<(!BwHJj-vkmy|0M*b}F*gs`7HL#Iv?E2_HROjnE8-L3$R!&+sZ~Z3$ z{qCWiDOpt$X2bJ)R04f&UjV`mAu2w5a4NB6n)?1(CFTCQpTi2F5s7sSgNlgIgOH5w z5f%OFg|`K|e)MTYNt@az9siO0&dVg@=X{FAH{5&HwqKP#$GnZMybm(dyZQb+ss8;4 zQx~T3;lh@sQE-@>O*f6XE6&8IF!R_2s;t&v@9xZfy?Ht{avOqYp*oQZ%{7@R>NQH+ zj?OB`lj&8TI8q<^YRCM=i)F_KY~ARZATSq@Hj*{wZ3}kdR|~h$`v`pRY7Wl<#uyVuXx?m zBEIjf2qtN)k90yQ*m2KAX^R7-@U-m2w(j@UDsjgMc}tkqF`p45<+G;_2&zcYrK74J zKKiR=iaZUB!?%ea2$UP*T1j%Q=2D}jYYtJ*l!H0Hth`r3!YsUYjGnkMtgQw;d{A2B zC8n=xzu9u5%;74pwoNx&pQ;2CdzJ~VJePK_Am*2qM{&WGqcraXYYyQP)I)cQsP(Js znp;|_&;H#;7WO;$L|M1`1ROBveiVA5Xhv20`A+rry_IKYl%H*<{nx(9e*fom{ZIp5X3#iQ;>-GRN^QnL?z z`=)p_UfCn@R6bMg#rvYF@;z5_m>W7Jic9_+BFu_{RuVY6iKuyOwk#MkmS z)%)HuNDzQCDpORb4;^4){Y`|CChZl!B7|Roe0tPQsnFfs ze0Cwep19pag0ZtOfS(SibKPTP*B`m8BQik9K8j$`Wy|+Tt*k|6*m$J_YZS!DpTC>qp1#MA_=;ze~CT|8AB%+{>!UgSBBbcaCkG^Wxal{eY*J zFJ3o5mg%&Or7Pa7-2CCa`YJw*>l&+aJtM!`93E(}v)R;ZT4rZI=-8#+o8kYq=4fBD zft=m8AZv5WMJ1)3Q8CexLOL7f-TM4#yQ&m2rY}xV^YYhqifkJhI?>m5X*72zc2?Pj ztzdEUP@R(VwBMX5TTyOX-KjHIy)#8%cJW9gd08)ESnoo#?k*?tC1#x~e0ZSvxN&di zLON^7>XGD;g7@gl#2c=j)Bjb(w+|hzPSrQQOlyS1RwoceXS6O^Huvs?Q-`{+pZl`R znfh%@(nl(1pg4mYx=|*cOKtgOIT;2r-LDSj_5W39+PyQ=&bs8(uO7Ok^878?!=7jF z3ZP5--*^Amc&hg8b7}OIjvHbWZ=fIRTafMmcx`i(y8V@CX?}x`tA}>KO5$2(vWIko zmne3O`8qqNE#m2Ks^&Ko1Ruyln=Ofj(Gf8Y{kzW?lc0$evkygYaRC`yvW- zaObaH8h*-T_hUMYO0ctFc`F$_3KvWN)^@|;K2>3BpQ_&%t4*cfe0u{-2V#oONHGu#5Cl_XqaD2+AR}|2mnIzO>AGg+WEqG^B(#3Zu*xW3ZA|Kym7jhEFw>9*a9XEKrqS7my?q(;g(!(9GYMw`h7Urmj{Rg!m zNilb}H7a!Ft=N25d6$uk-dAMg8Vs?hH1ST?yZS6bmOmuUKI*Z^Wz%)fDac083@J-Q zqwYr={)RxnDwoK^s`l5S?LFsyclq5}x|RVA3Z)PA$kfR8Ju{@&XrtX>){@R&zzHQk z4#Q{qTK?-O2q8DBcJaMmUYyU*nrT3Fo%`3YQEcVmE>of;b@0hH#m1b}{kq2eQk!TU z6o|s!`NY!=G^;%%nS37dnJ;>ZaHa!tjMeFjC8b?;jxPg5xX>e4LdHsLOBikX#{J0_ejr zvX^+UV?rdrg#0o_0^5IH3*enjW9*W-1VWGqU~85ePs&q8pJJ`9=+8fuo^7>_1YU^6 zt&gTPKx8T?fLt41ghc|`f=Lnj^EOmB2j0m)2T0UMfIageJYpP!Zl@qF;4zK=mr$TA zATN>;t-!DuBoi)BwI+e#`|uNQ8Hd=~F)S#4Or?L2$YuDQlyYgBR`KT~NDm$a{Ch)= zz}OAJAR(st=>IVVWVnQc0s;>AMDi`bc94${{Xt#0p8>XJQh@#i7SjPjNwBDPJQ8RJ zoB}~Nh7*6!9JoeQe6~$B8U(ZJQL%DJfj&;?#F>uu6yzFZAL78dtP_`bNAt;ukUo?I zxPya--z1@AoDl#4a+-paE=6^VP$ME>vkT7`$s5A6IxuNnAe4R{Q}hY>?K1oj%d6i5 zjOo^L#pZtRQ(9J66-ykG@WW;?*2b6r3p<%jkRFYE`t!siX;?l6c&yX;0yu+$&>cfW z@{VFnWR&J)PLUBk!1wqgk0r|T$OwR@_!f@p#Gv#~R=iU$HgZNW#qvO(0ocx-<-_a} z!1$XUuVRzz7sJViA)Uw1hsIK58sZ51h`M0voGm1Vle}zgx~{U_^*{JUJ|fW>0q`ER zB-tsf?D7pD)POiGkZHOp13(P}j+lNj;Gmc7=OZo(3OhvdNzP>e8Pv(DDPY&^i^PZ= zE2$t@X2;nK5NbkDIpSfqhj2d3gAI#4o7Bbd@YCI616=6Co_3zi`51e98lJU)?50#n zB$&gFYO>QpbR7WB2xLC5%Ckfj(0SApCd+>ts{dp~PgTVq=ZZJPn)%tn0Uj#$rp%x% zYKl_pq5z?osGdutkon2M_wfHlbdGcxP7fZ5#F%>V{2Xnd3Bb%-0Po-c=m~HjARh~= zOdgc9 zQ+PPi4|CEOb5|r!r69IwHuqeqadoNieBRXKT>Q`pGeAIZuf~*0K6=J~!lYS4wt>Lq zYx3p0uT<{FnDfA9Hn1-UcpavOMuuO+1F%d+mk_z@rcB#anM)+p2^Y*b5jBaGeNRMn z-MmOyD|+L^y=Br|a8;$PVO!{KCD{jR=3j}r-z<`dzbpleowL|k(N3*B{`vQ55 z0>2NW6w=Yz1cbCTlO^cP7s)WljYg)Jek|sjWIIM95qZBG@q!ER}_MjKfS2WT74a)TS_W!fWRih2D$^`R6?O z&zNU_p#C7RFBaa+lkdMJFX7yh?zjbS0DdI-4T1dM^v-Myyig?nzsWxzpcoLRMDkf! z)IA|G&Y1-+MQIqL8q;gGNcw?a#R)!OuO}gIs`ZuJ8t7ll=3!BFpu=ndoGO;NKtVQf zFoOh4!(Rnh>3V{R`#yw&MoJf4svOG`gM_Gx8v=B_2kkHGV&r8 zSph<{ON6H#4`A%IdQPs%50hlyuw{ z`tj&J|J(8bw_zTGY5|x}DM$bz-Cc#g3t$2)bUzkVo8IWBjlLj2tbRr&E%qH;>~qi_ zE2+79<@u0pA>tW)1THl)z-juJf@mRK4*b05G6Q21042vXFhe7vH zkazKEwIt-PM6SK&&9#)r1E$5dmnz~BD4jc)nS=y0LZK$zS@vbR3Rol$ z0)db`P_WHG+1N@*EI-2!ID_8;*Hs4zRZOU`7>Bdl?4o}0Hcs*Ixy%c zXW(1_)dfPEuFA6oxzfRDgJ{Ihzw$*qB!HSV3fr$QmR1N5gXlA@_?m>YXYN;_4PJ;xe-}^F;$7DP1Hg8dp!$?PB0RZP} zaL#mK?559;RoCp3_7A@Pa_#k!1!f-xwyW@+eA4LhL)cl~Z3Y1a6h45g!1{*l1gQ0h z>>&W&%alEY*+6~BY|j?}@J8w6SfPyHu$Ej~L0`H2NkJ0g6=M0Z;Yn`i8pZ{6W_z}R z1SDnt=s4I9CH|dcAf=Ze&{L?$4b6U}IQSYSS$^%g8I~-P-_3&U<{ZuEz`I4VuSBvE zps_%aohGA4KHUL(yMB7_h8;}2td)Jd^}QZP zCO@N+2a^}p`z7QB*X(b|$FHFt!0Y_m9d2|o3HVzmbDo7@U>bWcaxd|6uSD`sF{qyZ z!M>q-=X-x5+lWX>%q^hqKY!D(#i4~Y;odk2QO-ozK8imlGHS&d{)j}x!| z{GD5cx!lwbLjUzeuc8hWaf&Y9g6%l-ZMTlvvN&G?f~Hcc?y64%oMt--cm~lrC(ljb z8%KD^1HAS2{{g(R=iFP86L=fdW|-sh=g1(LL-^|0tpIvip?yv)x+unfM-3B3_&n4w zroXfn11be#3t7-(A57V#`61d(ZI_u#2mWi%>PlH%`PIs?Wo&Xgj^>lH^YqWciZVX< zSKiC&$FDu7FURl_bkbgrRE2&Ds&_m4?@OO|gP?d@v9gD0cc@L`6x&1J_sd1QtNof6 zwu?XM)Z`@Gu80hUp-G(yhl``(K98Dxi=q}gf69~EGM>~weH(UVrYov(|FxX=2OZ38p&g>uG<*|fIQG;v7{y!H4opE)l(fDJ7krIlOZSQ0R zZ+E}spP&74rG~j&`2!#FojX1ZG6!-D|H@cYcVCo}1`+%C-bF5yfU2@z&;N6;c%c&4 zoV;s2bLGRsO1J8tW0+86wnf|Tsp-oh=V8}YWk&Oqa2rjjkzZV;PDl^8-v2ijhjcPp z98nDRogXRlAT1izBy+NT6hi9}_sZRlpZus3syW}R>O2rJ$kOeiz5-og?^CxW{GmB=rFTW%o;BoXhNfzF56_eMnDb1?} z5_Xo;;&2`oiHu|F8PKJDx)(-{`tTkQaVRJAD#I`U-iXHp-=1e^y!Y-HQ43pR8&)Um zUySz*d!0#rQX(3@Zic^SD!RyXX@IKg1e>Mx#8czHUW`hr@~L>1;TNh`d*)_H!|vKM zD~={tzVuc+mutisgJ8HZkjyUTTa?#1YI0-Y^wA$W?Au3*wiF>BcE@B%ekJ8uD(YRu zHWj|zF`I?UFuL)wd3Q^7MgZcYhHr!V+l$0prt%dNOK2wF{?tZdn}upEofE8SJ&FnH zpEL4K%2}mV>^O7sUR8X`Dx@q5-4PI8d-Ov$0X!#Y>Y0kmhN|w5MD^HDN1RrbT-Zs{ zfcl?Kn;2Jb&px%Hn|It9-q_i225t;T!>@2aE=*53Cn102(r(XJqk(r~@=Y4ZIVZpN zvSf_U@XeH6^zsdnK?}l-95GlmH03ZugI-@nugJ`QlITlZ znrfa?aJ-7*&H4S+c2p1Oh2;3N`>S@F&&R7iVD37r`*c|IvrjvpXYglQ6>yvjj>dnz z5xHGsR5^g8!2D8kPWN6_!UGGgU)|6nL%m=B#k^^F(|c#}k2^=4CVgz%3Gw01zfQ-Pjp!CiY#1N!a z#!O_a|FH@~UK-1uP6G5nA;hlq2j$*1TH2rnc(^xi>jY=i3g3|%`_n4%F{i-1!B;{Vt?ymeug>X)sB8wfnHs*QnN7ZuSlEnYr9A?Ouo*o!=6CY%` zM#}Xo_f&n6zw5z+8v{9TW0tx>g6q2~x?$mpj;y!#P!1XH&mPja%kw4+{R*oi4yy4$ zw6N~O1(QV9QOOwFb$poNcqSHgi~=#QH7PoTTT;s4`q-7tBg4(#X`b9=edbRYR^^>>knpY4*c#od*J;?&yoE# zI~P3UABJA;WNVhve|@c!;5pu-+xzy;|ENd#8Eov2V3GUY>TpSrjDH=4=>)IK9lS|f zo;BcGM>l$rJUtc?Z{rIu7>gH&4TARNVK#D)qSUNQhY`_!^XQJ(p{zAYR2D5M8!yt4-L^zf4W1=cQOAX5)?CbT4En5|Pz zWMp5DT!L_WL|Nwf#ynMvgoPnBQz=*f5kt$X(ZuaqidX&ku@*1IzGup36fVVGxrg@C zD!%LzHP3k1w|TjUu*PGED-gZV)ho{?C5f+2Wgp`=x4}?=mbnZJ`p^61#;c?$cN4Q5s2%&34cm!)! z(hdoDunsjD=XRYZ&#mW@F;s_&@_a+(1a#`rCPhXj1bb#Me-evBx|5j-WC6`c`ykrv zxvdw(Jl7*2PGt|;*QsStL6T@^sHvL)tNsm2uKeeHj6CM40}u5InU7cN9)p_x6fp*D zAa^8vix;;&){L1MYUv009#)#(+I{IzU)IYW`^ZP14}NV_7G8rKZyq&Y%xgX49>ea; zlA2mUo4cYa7Fy`1o6pSDo&;)cA3Hv*+f`=JR(C8>4Vq%XTU)JjL2{>0NP;5e`Qiv5nZT z?EBVlvVaG@r@qtRHVdQsk^r~p^YGj)%+6wZpk>uQkBI}wZt8D!*hwrC%b)kwo~t|_ zC&R*LbJSw5)UX}sl)D`Srp$2O4hmg+mAam+YxV=~w{{(((PlzyNZkW3A|Vz{YdQ|Q z+2!BaRN(v^r9WY2GqX?i;u8GF;q!mQS~qP_S~#XQGY9NFP?uDvrH`6WFEPZ>w~ysS z5TF2F5J{m`alyf2X*aRVLAcD!3)pvtR{H^m9hHq9&l&b(S_lSd z6kQ>%CiSg#r^iKG&q3onx(lBhEK*ol%RO*F@x|;lS_EuTsl<|UBa4%*=QOaAGy;(} zlwa}SaQL;L0`OeENfMUy7UJeqXu^U{cwFh@)5#Q#Lwq_gDBgmVwlZe|BnHrq$YN2F z*K+|LLzZ(7+$UwuruLn8hnU0NxKxh_!y`G0K;SF39cG*+Vg3dy79!_~q zTFazryZ;tr5OoKhzP}o=kAE#|mQf|hC$h4$fb0b*8x_F>+7a^n2Xt1>AvE~p85{X7 zuK7YvS7D(IsMk@nZB@xX;0gn?Ob@|8BS|!-!GoMk>b&j9_Dtn^5W{03$A*V)SHHTG zO@B337H{U4INuZ1-7=|N9I_?1pJ0v;U`gmzqJQ(}Z)mpb&CSi0*$$&HtT zPRT_8?CFQ6`>7X1q|;qM)GG#9;sJD-|@H$5P+vp81z))f+#l4g+etO z%hnXjY<9}AOu8|=9iG&5elU)Ckaxd$ffV4U97;h45Oq>1beD)6)oR*DPdNH&UQ#+N zhyo#S5y@nJ23+PQ^HG)%RJR~yk_o;!{3trsMB`-XmqO!13$Tx5xC5V-It%k!XIc;& z=wwFBLXO#NPM7j+3miRZ;a1idOp@y4bWRF(##*b=Unk0IP*O{`cbamqt=>UXWw6w~ zrFZ_!!AG+F>R9&bPwQ=g;RG4lb__ID+%rxVzjJ# zI51u4c!&a~2& z98vN03E8(%4BtMNlFaQFv9P(-TuULLPH^E#cQyv#u9At5)|qD9xmp(8ZA^L{L}kB} zUbEI{y5%0m9jz@>N;+vlJt@MI;f3_xXr#Q!rL<pgPA5u+)nkA%V>2xXJ{jt^ba|k~kj{)ahpM zsVvsptcdJ4OO>A2;(ou%G2@k6f~W=?xdS;v>nb5$eebh)TSF!D=BZ@c-le%a4rTNAjTc`tR3+&*;( z`ZH4nE`81e`yjC2PsFj*gqD}>humRG+b}K@pA-vkT>&v-h;}ucK|0_4ce9d%BAGsW zD-jz$yZlgIQ^f~6M$s7dWl%b4BiKmGs}F>~%+%jcu=~Jbkhuy7hs`NuLar+| znZrmC)Y5R>)%RwqUo*32Z_|Wu{y-`xNj{i+C1I`dD;H||l^LJpdXqr!%cN!T?h=SW z2uyq}CCJqschvlCK;C?dRz=j`=9 z&G?WB3v;S6P${7C1s+^X>SlwtKSL(I!9U9?EINEY{VK`scU~l}j1l1?WetrJ-7Ut# zj>x@3noaeJXR^faa)cm4ZytbB>xy&jD5br((uQp&L%6UoCHbmX7vAhob4o%>H!DFo z6hjg5PCE3%qsHg>I9|w?1W;<=rTj#ok;Kj!Rw%d|B~1xr)(45|R7)bi6geqW?j*u8 ze!|h@~(miz98N4z}+5Z7cRoljH&r$m!NJ@_kF-!tbJxanR`m2XjRH zupGk%3P;qPl#22>)#f3rAPkOpGUFo24Z%^(K$(YcAPC?~C4uZSi2Mu`X-g(gl@FvJNAb)T8t@Px?zGMm->$Tc)Fb z@elvcY5T*;Y*@x9?S(h1%vhd=Q~PcWuf*zjcA5!DkR<7D2Rr3d64XzTo)+PdwjpDq z?hX*0wxCtliM7YSPM*{|0crfynJEWmN;zZbw+|yYZ>}ZmVFuPQQm_mUa$#3IGt3)1 z?I7h~z>X)W-i%pcbY z+jvWqndHkt5kq}> zQFhELK&xUpX0G(lsb!E+C-Ur%zE49Zv;ElgSU9YTkC^3nq;lxSP^Ogx<_Q9kg*Dld zdXv-zk*>GTBsOH-_+evrl4g_Jd-2peFNTC;QdnWF*(<1dPtP*?ZWm8t9uWa);m+z z-PXk`pPpQo9D+6n56VeG;9s)#^}SL>2lmiFASt=^BclWu4nheXd)krjbF`sC(_5`k zHN;Ol`hB(Ebbu`>9vL`-wjGjvkIokme@vK5X5w^wY?r1(EgR7xerl2HUAcyr+7t`? zdsvBiN7;pO0rkj*@Y;R?RK9utcXmhQbXpKcNWA+z`xYU6tMlOe9$G3aL!%# z=(0fiDPLxHw0cN$LmkTPXM?YRZ8uFg>C&y6GWFi3z}$B8iT?^S5XYL#8rSzB3?u-@#_tx0Q5Rw%Z~RBX zmneWIH4pp)^O2vNy`_qBzC|k6dzCgf`08wE$cCxx{9NjLt4$AOArVNU_TKsZAI|4V z`VlQ#?n3Z=_X}YwQ{~{nj(g@U0V^f`5_9mRc@IgyDDWwHAHw)9FjUg~{P_Q9ji|?< z|A((Pafj*w{C~&nE62X18kC*JlAXpHl19oFHFk-NN+B|~F}92~iW+2>#+oG>YnGM~ z721Y2?L!+<^E;pK@80M6-Fu(s{sYD_Gv>@Wuh;911UMl8qqHh}*VT*bCv0adV-P8D zISM>g$*?1(SopxmZh>*`Ww8QffD0El#9OKq+^H>9F48WC*j)0eWd}HGR8h@l70OH7 zCpBl6A34g?Zmg)r2m2;FX|s3*N6wX483gDfJr82_id}CTJ&Qb`$hAJPz-G1>U%;;> zO=wHH=wjvU=*aW*l>^pTg3c@EsYEY-#>$GKy0c!{a#UJNX+Wl;=*&-sVpN#x?3Tji zm9cFC%_iOl>ZWz}&Q?2LewtT~X?Trl@SMAbo3 z@0y$;3qzwOekMQI{bQ{pbI(30rxz!lv9kGMX;lX1dsJq03lDW>yg%PBve)etJ^!dY z*Bzd%C9Dvb-_xFQd9A2fzk-j57?$W+_Oy>zyN%H2BuBfE#ibUrmN%>Pf_}i4A7h;P>NQ!XaP)5d~+e-;hL8=pb$stEXKI*D<&M`&xG*K^` zya-;`$bJOl&snUlM63U}352LMU+F#DfVm`}>?J)V=d9#}X$MM+g5$&xUb0Xp zqE=~ZDRb&$;bn2RKn3I$rV*!-Rk8BvP%oRJL8?KMXGKIKVr`Eod;mTf!bPuY!Q=)6 z2$Fg*0kgh$SZ=<{Y~0#HB>TChsj_6$AzP^y@Ct{W#=|(|t`Z@-Qsg2D?Y9D#8zheD zBUN*)~tTHjkI+tdGP&p5s|C`y6GL z+nEl=jY@=VTnPwv&Dsbxq)PKBa(IEhd#+7C`!ID$Y-RH<4!HzD0784%Df%TF_Ih5L zi=OT$rw=a2<30aaYS+T#)3;WLNHuIY`GL;0TJ!I{)%snnNA$;`Y!ccNA1K>6GG^T9 zkC(ED5^>|blijQZoTlq5VS^AjvWkAgY6nEA+40Y3_os*p{>S#Y?BC5!9*P30#h?7i z4@}j1zM=SLJ5JqJ#aA33;;5qdlIfsLBi+A?$@Cz8x z0)vWpAYDHHIolSF$`;EmlwLFJv-H7Q~#9~ z-DQM@gTTUAwL#?UzNX&Cxry6EJ~sgPS+-V5lPdc(2o@h6uc4FY?72`O;0{QnY7jC`TN zSr4v}Q?Xl}JL>N%3&9bP${%QJHHT{F|1FvbFKDl50N5utsi0_LZa68CXK_I)TH@_B z&$j<9npDl?S-*VpV(Qk-V;o1ze`twV%@w7t!^h_JO%UT=H< zkS!f5<9prlJ+I!qsS7)LLQ37%@t?_ReCL;E-Kj6PPEr7D(I1T`0IK{(a^9 zr%T!8n|G94U8Y}L08?(#QhRxxkHnyeXt)$i0h|S~Ud)h4{q0u2$S}pI1F7nWLzBZKQkDNlG_lu1q-fUeSd#MO*1x_e9(_3Nps9N2!6T-tVQ=yg>u*K?XG~l{ zmc1AAO_6z53_R78^J7>{<=}_6*=}j`*KAxJI)XjY5*unS8pw#-8`7j3wvTq6a@5}H%$MFD zqH0%DaGh$?w}1ZHvMt5-x;c<7BuhuxZf-OQf>5b_JA$BFf<6pMd1erUa?FZK2Bgnf z_+B(Px?Wk<9v9I@%ev@t3UD(_Se>f$Q);t6HxywIcEq>UZe&L0{P%~2k$T72e$dDt z0X?hDJTc3yUw#C5nI~UGOb%feKIB9(DMS`cWru`AxzGw7FqO8^IOK7CHJy$|6EK)Z0NLu$|(J{mI zJ!S`9P~wWuwamPEHi(S1j+6Yl{z2dGV$VDv9c?dLe|MX^4D*vtubs9~vgh;dhYyUd ziJOMSd>bk3@S7Gb)-DR_lTC_|@eCS_U)@`OQj&hte7n&X3TZCL);Tw`F!iSK&A-#r z+w+I3#jMY!ubb^p_&4L75MBBXvqII`G$G^<15d8Jnrh=A)ZianCfZBLQ1!y?Z-^)g zl?|~R+wFmP7$cE}87wujuAY8?k-7KiU8w|OnP8t}@{xbPjf1GaKI(^Zn-p`N>*~S; z>uCD=mvb{z72csEjq}|_g^_2|yEsv&%cD~U!;ME&HAfZJcrYjX!OUf;t;#k^rj2Ov>weClwcniEqGSyL-qF48S~-j$jh63A ztS#TQNfBe&FGD}uopP{^7d>P#ZY|!$GT7^*A7{!*_RyXkPdl?(kS@6hL)kcHa)6=( zeXng|xs&RdQ;hnYx8)XZ;n9CxOWLOLHT6zAzi?ZGJLG^Y)jet{e=Q$ty}3`ZJK(tJ9&iqj@u9bNoZkE|wa~m9A<& zXmo!J;g5Z`_{!psj4<6#cO)kD$QvuI-{~K`(+;jlEt3b=uTeG6RHmD&IkE-&WUQpB z{Exhm78vInODkEA57#f~hKqwQ;AF^bo#SBFJ+qYwq>`V;To>gb^Lo1VLXpOkHvYp+ z%=KDgbe(J7lN~5C>w3|3s9ebg;<`lIbO)_ime_@*5)B_!WPgUr4FDd=bZa8izR?^r*V(Z#g-C6um`kwK@Ccp6^ zzaATI^77-GqTO%K9bP;gb7RA%c%^*D)HQ;9mBUKAPyv#R)%i3K~vDy&*4o9#EEUzJx9D!m1%#( z_H|b&Jd_)c%GCn`W|gq#a=)DV+c~g~)R=x6s4babAl9wxv-MYac=rzjEevF}!vt>ur%!hN4k zXq*#HGFA`o5ay>UERQzq|GQWI7aQ$W3YEZJh{`n02k(+pjZCPgtIx4#?O#eaZ~_el zn##c@lJ#ZQjn>vV=Yz)yu@WuyX*)|>bAI=BOSQ2__2CkDSFa^87I?Ai7c2B0;W{pu zRabNFkc!6!mJaV(m7$(Xx9m6vl*W$f4=HB*u>)k9E{qxE=w&8-_Lmt1#x)(>B4^CH zn!@H|GH=T|ee0=f@QY1VLb_!n9Xbz`vmEqaX1{Zqg+80F7~RgNXC`e1NW*%*s5=b4 zOgdxpye?kK{bh&Mw$i-~=OUwY0tPXTn}I+Tg`{&vFWU?fAX{CJ(4)I$n*Ferf(fI4 z5%KzHcjD&3m-{9U^cU~!S8v0`a7VPy=Hpxqm$ozHMh!hIarOz75(8f8N~*1^Nsu9F zAv^s%;$T*i%ekRF!VGN-<)KTG%PyiFAFK2=SX$3xl4+a~?QrYtMuUE-nKhK2ln8R) znIWmf@n-TbE+&OnHS(C&`ee^^Cg}i{68d}NyjR%+#}&4kEib4>A}QUNIwVzFir^-> z28G$dWH`WW^6kiwJKvUWxxcr&GhGJrzF{r%klMQRu-&SCg`aWy<$l~N>Wb4nWf>Xa zUhR4%;P_^sdNP(pzyb@(Oho=|irnJ^{5b+YgS5Oh2lVDWJWWn*@#1H)uIgOsS^A1fr` zQOjG+NkG)9CAk2m&2rrXfhkuZPC?M;$>>@Z1|%IXaxwLkQ*LTl8XJ{JOR{?x&_Rsv zpx`FEu&u;+Qfs(Skfc|tF#Z-M8GR5p8qN10J7s`>~%2b zPefmx%S_>AvX?WjmZF&gF(!bm6o}<;(a;q%XAOPED-G%&ZFe>W>XwdJ!wBD}`@GM_ zh~tJ#az@m1GV6gUF1`lX-8*9h+(j02%Z17!-(81$TZ0rl2&RiZpUZu@mit^CctaEw z(g;tAqxA4Xu4*|RO;Iok=S|;a@ zKptl!_H$v+o~0rhlj2dfa2ckGw3`tu+=kMI9kbPP z$f81lD884CZ_LFjRDR>LLBjtB5s>UHhU$U740eK#ZM=)AqGP@5D;COdodQfRAO8SU z41R*JG^UDwipvC6HNd|Pwtp_Lg&bRX7od9J1}L~=-l&tE@G_CqVGhdFo^4cF?#Du1 zpkZ&2YwE}~=mo4#e2r&sO&v9Vl8Bda!UXyFl~BQ>z;Nl<+oqUL>xIz8Q{eo|$ps8( zarBV!w|j8c*q5Qx*+S#=uDELa;1!den0DT!4oQiOv3tC0 zLE;d3B|wG_ecg!+<|8?&$OJAbfYu16^AiMOO<9dlYeWJUkx6W7n?x{4m^>!BNM;2k04r{ty6cnD9{LRP5Ge!$&ru&!7)g^3DDYCMVE`&^$B~on~C)AYNb~}ldBA`obnQf!2Q7#74#Un!>R-~$ikzu zcVv1>@OJ}_{*)j+WDo`T`w_9efjG3Ub8X>plmL|r!IZG@U_HLIk1)fh8qQZ&kg#c& z3cjiXC0vZ5HMdJ$R*+Qu_69dIzZ-;olBxy^(&rn;OzB6kJ0s z2J9AI1|G8|AiM@FAELyEgF7;1b+|i%fnBAgv5!2_i&C!1_HS3k%3I-X9L-cWElP;A z|7a=vGa``6{q57~p#{)5s6+_nDh)HU8-ssGSfmqPaPT#3+|}K#N96=;k8J!4n=<4U@bax6edME)fH^MB5@R&|eX%&YrLiAWC!O4qO(pZQ~ z;T>|}0DY{~<_(EJTIiSp>^mSyK413QdzsC?9=q8p> zv126cFn}*5QTuy9=@P>^eYVUTIK@GJh3BfG&?J1d?zu~l`Sg=LZ7t7ld_6oi0^kMv z0JBe1=^9M9_y|noo@W0e?cA!%3;hCwM7c8n6H+0nEJO?iQ%l5wta|WgTpzj6puuk} zRQ>9o1An{lQ{1Y%zp05@*r-1&#EKQ2bfX0HNJ$tO6k(Bfq>YX#P`wBYKVtvqJj4F>b(!C-rf0 z3}yXL&`(r330on+{Pn=l$@oPIVVXV2VBsEsY7-sf+>a}#qW?I0;{1RUL?DU;P=AV@ z;4{Gets4nXhcc!`j!#<&zx=032A3}k1>;9(FX@C?L#_6Ue*G-M{6#{DbIuge8gl6` zG=g&VglCuamwp?|!s@LHBi!`#A$iH@9FdBYUE}x}E+J9vJZ}0)bhK|Ga7yx0E$A!` zl0;|u!BgO_yvB!!R*}JH0$YN8NKZI*crEa67wQg0be2nfNbBn4W1Aua+IZ-CB#O!|muW># zTcXdD<#`KZ`&T9=51T~Cg<)0A`~NyUGRNVEx!|vZ4{ieXzWgwByx;%Hh)W9~N`@T4 zLu@%H8U>ktDV*_XkWH8sPTXH`8H2hFbYK0{-J(0No}yavp@lL_F~*)~0h~u=BRCJQ zJ%0b>F=~Lzxkq`+h1{MK;Bhke7FI<$3o)%D9#gzT<09i}M-0l_konB>TbWHnY}HO| zKtj8N;=Ll>xq!HC)Z&M=fqt0YN9-c57=m=?iHHIsCpeuEaj$#S%Q^S1?fMcG^m)4U z(RDFB{sUIrBa$fSSIzJ+iF|lKDQGd9zY>)_ntoS73w+OG+92o-is%CU3zvi|5mL)r z&m~kJ#=Ug#k4x~3b$P)UcwrfmqZs*gxrJFv@>kTv+5A0v$KsxqMa=xZ{b<I=B4pBC-7YMSr!MuQ*RU($@foRht;+mQ0&)!R%oS~VE*DIMErzIvvr~e;m@Th z&z2ZX_uw^j4HX81P#5v zfL`^tJvN~5Z{z1fFPSR)%#+qx9aB!V`zws#fo=Eh>^ks&&w>#0ynKVjOPUTB=KRHN zd^xt=v%Rf6;#BK6OWBp%EF$^y)oe@R-=lutZ$2Qp4mgxy_v)y&Mm}VlzL9Dz;@2m1 z`n>!Tb^o&NG1bK0wTW46KdUVzn!5{2CbL=s5>vka+TO(&6#n}X?wJ2%EUClrXpqUY zN)(HzqOj*^LeMLpI}WY$sTk>I@3x@7?H5kV=)98Hb-BwV$7`$U+o@q|A=0w^&IQ;d z%=4rF5;h3)n|)D_Cs@Y9H}^L0b_FXct8#<88$tk=e4W>0dPt;DZnMeQQJp#(`CqgV%*N1jOzxq`YDhpbBS%}+1fJvSH81X$xEaLgNq=nYb5;Ekvih~FkU6nh6kSa*{?mOlbyN8wT^Vg}vOXjm zpi3B&c25geFN^4w4=Qkb!VH%68wz*KRMzis#MBNguTZ=LI~_%B9i|b*2fIHwD1<5g z$rw{e%B;V*>m|Ci>9$eow`iv7Z;c>F2i$z)**NYsgp1v@=87|4v$1jd_ek^Yc^Q+ZOSG`=jt?;MDz!S$V z|ICTh*SW?&<^uDqey#m#khp0!RABuP@~)YxEkd~H{7?Mb_LHh2BL#a;=>=aTLwlCC ztDG4?GgQx>9M4V~a(ta*u*0b635X@yiMvqeI}}cCJ1-D!XH+_=%DeY6y}S#b$i3OV zulDczg+e0&r^;Jf>E=bo?de7*7hh{!x53UT^;g*k861~Uuj{(5 zBK#2K>i%!J`ex}LuaukKXFp6F%Kw#q%VbxljRDQi`9naSle4vA6H8%ee5UM?T z4rRwayrwDPg2dpjqCv*9FlROH z)6D7FDyf+9(ry1LN1N@GLS;--)Gzp7VH?8b`UKDV_`B~k&*mK);Eu>blqyPtMx&vM zo`#0B;g&PGdH15(4rj!1*uj?wOZ}UwP zfv&yT9{RJ@_=mN4;o4nw%}QLvq2c0Z{INaYtwnFqKrt#=M)GaDN|ScIPknc$@=Icd znN*vlH*K_Lq#e&=LzVH(qklG*9GdLx#3R7HRJCP~yLD>>9WHu|l%r?oNhKF~t-Lnv zv)R8T?!Iy(4yt$-tc#pUA?zWI>WAwYSrT7wKeDm6`yUl$vzaO)R3}3LI;5Gm81}I| zuj&o&+MZ==>spe%hKtC(kKIG2=579LnPBnmh8iVoVY&wSw9X-5Cen9($y`YvPxjM{ z2(E|iXerLtsnMYS3#@ZTdS{epDa*9-L)^EuW&1%8a!dKX;3Y%sW9uI$WaIJR_<7(VkREZ>hA@hB?*16z=}uhByB^|y zT}T?)j;}<6m%JoO!OO23f`jk>1}ZGfIp}=_(Ah3v6w_oE6?Y<^dwB%ktKD+f_0e{t z`nrIhiNkE0_+eUuz0OSinEla((boZ5@?)i=2fOG#rbUZlO>Bf-X+HiLFHh@pyPb?~ zd`0POgU07S2$NCMkzf+6_ppv`<=Ufq@kHyi6-x|>;)WEDZxCz$gWBQYfxE_f62AN3 z2odr#FJd!r%j>laJ)uwuCTcj(@s3l^`7qPmAgI|R`03Z}_)))8eaKcho}o2RfVj>D zrTkb2eYQBifU}|zAknzXYZY17^R9j_&iTNY`nEvrVflMaqg#$DzS8H!-udqB{GgoD z^YqE5YX@5QpI(tHHZBbqpYl?rYgIBGfGN2_IzszUJ~rFSAHLn>Timq>X#+){$*&ri zlJyh$UT0wn^+5;Dw*}>djxS-AcQ`-rRV(tRzu!KxdlcvUblJ!_ZC++NUA>FF$4&8T zJv7dla@EWgYBem+V~(~S?KfQ0j`v8aJhJ5)^k!YNw%i@^6?>BvMkDA)b(xZEm?ttz z5w=nj_34U+PXOVnk2Uh$UvA^wTrM!NL4UzJWy|i)4d*In%DSz3Y*^%2aVj;HXREXd zjuaeoe60mv%P@WQ`E%{?tH;@}DqJ%qPeGw{BhbF^-;Rk6!UEnwDCdA^g`78b%E-ZnXLjCK*i`gk%3a?J)@E zo<;5PSSlnGTJ0?1uJ6?#>1F$qtH&un&O5y%Wu6f#CsKLC`xIB#vm+)Vd@yPd{bGli zk`1WbA)ZAons}w18I3JjSQhL5qjH;BQyZAt&pv^6;G_^J-9O^9%uHZL%r=3+P~lwuZW6+4 z0o%QZj94pX(C%bvwG}L)tstK941USy9}}c!(Ad7?MY=qg{Tlp`fHbC&DZE;r z3$bQ0sM|tm4DU54iAA=`%Gxz<`^p>P26E&AgZD~y3VN7O5@PYSg>76{3vKJMHs;)V z#^*n%FMZ6fM|Ne$rYc(uxsGTW%@xu3eN85NRE8OvBiOA!Z0JjwA*`E-twi48MN=+t4?97a!~rtmO# z^E$-r*HJOIm9EhcTO&%Psj#PEnGXE4!`!1s&j>W?48_Zdsu~d0vD0Lk9 zTyj4K=fy&#bSQ?}I5g7{p=Ra|VQER~>XF)+IUP*ZKN%oLEHjr~?WS<`hn+hY*_|&| z5QN>(#5nThWF+$;B#aa|kx`%K#*!ReAw(?{K%>cpv~BL{9k(G<8}<2AIW_Xc<>ppv zg8=54DV^(q*xt&TW?DM79c|;4#^6n6^PFYnlJWd|4_%V8qZkrrCQom;ako9gF#pii%jz)w%&^u3z=w7 z!QN&jB2=#HSSiB1+mT32DPW}}K~ieFQyGxEi|{)$<=Ce`aP70$N7wU2$RZmO2p`g< z8YZ(g-cZuzUI7ysu$)@I+@H%Np7_NwX}MhIhxDW0TAM!2^El5h@N#*DZ@J! zrmvD!NKaJ|pSE>+uqEa4aXP5}XVoWcm99Z9Eg7z6A@=vCG_FDoOj0!}4pxgi+>UU9 zeZ&Qz8Pahro~P*=5OB+lkl#(%l`ssJj2YpAeMXS{pfc<#tnc*zAEt}Xf8I(0&_9%%6t6a~ho~M{^b=y>T5Kp(jFGC$m5mcg8?ZKHk z$5I9xdAu|YR8oQ(L`*4eHj&s@*Jrck+Rp83oK)iZG7*;Qs#L0@&t*ozf3{a)?*{5% zJKCchYJg59$))O1pHyZZZsy&*xR_OOChz8R?1^H16a?nNOF!0pMXnD$REUhAGAwC& z*IBvSyO~6Km04mI)EYhcW5ixN6XkvN?RsXgqcLP@reF@?$x0Q~kbBiJ!C+ssan8+F zS3hTG-Z-8|l2eGZv=L?%OK0ak*`U$Q)YE&Q$hxJ>e>jE?ray^D42Ljw(pok608#^E zYO)7;_$osVAe&~#y`4BlM1~98YE3u`Xe=WZN$W3Nw@x_1Mo4aXggA&Mi#Tp;gu4eN`lZK4LKEtrF$zaFSSu?fK#`Ik; zno%|nvBXvV9nYvAv~0-L!AvHRS|!dH&OtHHX)Wm0y+yw1Lp{txYpGxL#*<>xZXk~Q zS$=pA;dD#tnG+MkCibxFIsWwWD=J7yx&?wmf8NJUqV1d8svpio-ri|Z`R3Ur!X2s! z=egyaa6N3KnM-)iRy?soYIl(7p)46!Ibt>`-I9zrq^}pi_Ic2GbmjS+GaWHpeD|v~ zHe?*UwA;X1N@*Jt ztDgC@`0;e~t2|$%N-$RTYt})pbT3v@N4im`ld(JhMUY{pK}Xtl*S0y2Keq z{Zdk_h3L!!uUi9ttS-NYj0%x96y zk0N#+ANO;O5T(b3YnlHpQI{8?LART}}U=Rqp8`|%9 zZ0>Icusm;eL;Tvm`*+q3TTAbBl!KG`Re8X$QkD8t1$TXEF|Y(dWL!3U9qx1606hrx`6I^$9(#l`My)z zZvD$)o9R5trod;!KhIs<^$cA1^Y|QvEjh_U9*3j}TNoc?xx)-PWPJE|zvJveBDpX& zyl^fx6ir&-A(>ixJ^!KH>(i7Th`@csjv$>1bThkt=^iKQ3RHvUjiQ=9(#;?vIzixB z2NI<3r67=U4~QB+hf)8Iq5ka`1pc(a_7FGCftRXZPn6=&v(+Q4Y$72yLZj9W`z#?t z=aizXzG3&M-AaR)E~lZ28K(q{FgXN5JrKgCgL_rqJ3ouiOKuQ-;v>;d+p*;irpaA` zCIRCVIU|C_h~zP%yv*$7mK0=H;k`@Nq;xi!6;4Tm?-jXNmZC-UN6^zBy~J*@%7oM( znc8;hhGVIGGb0$yJ+zvKc(tm3Nlqxamg+W_?mw4a=$(wES)#fls@jwYOyu{^S^Apc z26wWo1m8Y+U&aE*ywY8H*BR*5I_myN)>-vQhVl#}7Wa!W|2^XUFUI(rB<}HS8bpBy zJ48kY=zV5D2o`s++l(2`CW4cfe#d#LLDVBOpPWK3L)08qwm&1HEhGagw|`%~(`9*xSvg%t*y9>uJQ=>C~q|7-aPG9)Zbl(V)@{9fp} zUdKHyDTjL85fi}!7uV9YSwD*(X8m)FD}NvNO)G=3ws!Sq-i*{n)vc`hrqF87jhele zYqF17Wh_;MZZsSqnxel@FU2=LjVElv&dUC5ezn0dE~@9kHD&*_?>%401ZC;Az%3IU z8GpJ%v-rh-dW|>29j{uE*0HGbeZT+wf^fbUGF;cPlp zZ-4IAZ5BET_V3x8e40>)M*p8Z@%@k=A~WDyP6!cV6dgJ2!Bn)QrtdhXaySD}aV~dk zRUVd>(ewF#^~BZPMbl1=1V|PCADAaracDSzwR7K@|G_-Lo_MCN{OUKFdw#)zS ziML}T=k><-s8c$!w(jd{o^Q9ecqbK^3rNR%=6Wq(_bzqwq0jR za{t3TEoQYGYwdsi59S$s@!}pctAzjQiN7$zJo;YkzReorjJV(1`RNuV%VcX@P}Z}j z-KRgfetfg{18dL4=P&o)?v5_ocOhF*KbS9g&8yy57i(uK;JEKN@ajSTpFtH1!p5~KeltlG`u zjojm0i(kvH^T_ePwq$NW9)FXsC|#*s;9}(MCcZ0p`AyLwBdM1%hePCpQt?|CN2Csh zYt&}cDg8)g68aClDUA?i))FjY<3jBGyN-vRbZ7VQV!@`H_ceE^{P~Ksv&QyUMG+Z5 z94dL)Zr{bXUTdc|Z#B^`mxRe@UZ8tFWk6{f5NuTSZqN zo_*%YaMRXnww+udFWGtX;z!soyY@Ym_AfSdOZ?zmG%D?FH(1!W`RHe;y~XXUuQKkj zqmg&eM|K9wP&is{+@HNcv>~Zu#s0nSE`K;&ar@1@0Z~uwRSGV2<(r*|!DRkG!^O|1 z_WPe~4Y7R}^816s{KT)-2X=bhZXw&gYya@}>^LK^-J^cQjc04DBgs^-l>%p@)h*p> zTtgEjN|QGXrJwj@R7ed}AN~Q8a>>47bnx&)&1o^Un|{xm-cH<3d!`o>|HCG9N=Vpx zSHUcrowHus`Pu@Y*V1mo8@7P;_4^y4Ec1EAON5eRqA9(;Gl&5Qgfm1+eWf@*hrd|8Wz zY|wZ-T!nn`jP)_a=kf!tCM~(;4SROVAI8R&r0e=xQSx7Q^ABcZq5EC}anQPmeTW|0?5$~ySth)jXpVAgfyKCgRKGtO&yI^1t6e#Fxa|^;m*H#z0$=VV@XMvr2Oy@olY-6s2&Hr!9)r}9cWj7V z^pM&iz-EyR%(Pm<3?2Q@$K~OxNRuLe!U^?Z*|VAl+#HlD)piFBz)#5y66~nB&U~ZR zv|TnA{A-14DMsRtY>y&;?l^d3VGlfmo5a^?fUetQca)_Y8wQBQ&%w3~a2UHtlT7iC zONVuopXe_{G;udH3wj|avfL2B@?sdI_~(FhqjU`iz5~C)NRsMEJdMB%5-+)?c0Y)8 z1y1;xk1+O-t0ZgIGBm2d{`6+5{1n)fF0sxD$_Z%C@5JaK3TCH-$KxqDhRIIp(nw7d$D=)gabuo(1jz;|Ap`d0)<6>KK``^%Ct# z=ULv`@pk(9Yq&y>ckVa4La@uDs)s)g50rnz95Xm%o&##e;@~`Gl z=zo4U7v1nmoa?OSGMGCkTSi%PSEJz z3@y8r>@Y~6Ob-XHYIh_Y| zc7%;k)z-`L&Vfqq#%qwo7V4C$ueW^MKOQOFK8REu5o-KvwLT5SFwBH7e8d;nj<7+D zi-n3jRB3FFnOpY3ksP_x%Rq z6V3g{vuLJf*_{kJH%()Mnsr?2*Y>uxbd597&y&c*vWd&hxN?$e7luj zRIS}rgMfQE?4R3PNfA0>i@3m28*yj@Jo~f~?)tU3>+AZOXEx8UGBIzA+g}I8GJxA! zXZ*z~*oZW9e{?dpNc*v1!N+?dKYM4rZ|omvrlAgmq}(sru`v@R#lzTit&8a}dh zCdEo-)FCDgyQB5fKB$Tw34Xq`%>hhS@s_@@)-sly`m(5ChFoO(22aWDcM4y2=!gtc zD?kK?TiB|!r{z1UPZDtx9fG!Bb`pw4P~Z(_BCf|YU_V^$E?IwqO4Ed!hPPk%1(K^o zg>%Du{_#+*u}6tno;WTCUrxcKg2*6%!^+_l-7rsY0m^UV?T)d;Lm-&`U}&NC6Bo>2cg#+!|9vC#2gp0lD#SiP#09{tCNshf!iZwgD4B^Tq(?405juh9AF{Nkr@~~j?$4kf%wggUj?h62O9B3I&+=M(Fpy#EQwdK4JoNF&wIg zpMm5`8{?|gfzUbefN{W$=!$E#<~wEu`8y2TV6PK_6xzj)Yhu?~7gGdckwBi40PH#< zg&_V(#8wi4BCrVzIhQ4f8viYpYm6!8V6lt%O6e@P2yULqz;)9J(F`d}zCkSQ9t&Rz zkr6+gMdONt*>$=AwWBP~R_&sv2+|KwUW_Ju$pF`)o3+I^tTzbr$5y;44YpB>&>3oSEz`!g2NG79`gtNVc z+W3u(5Qyd0q$v91ryyZMDn4SqGX$|rlug~j2oojw%lTM2w8sfqbx-9nKnVdjOS(FxXbk#xLQE~hl)j* zpjn*UEqeGdvhNh<*l^6@Jx^qhLy)2Ka3K%>hEt9;E4_dzO-w3hShlS!H1RIQVH=*;?7<$Dz6P6TsJrtGi@ydyT`gh~SYINsFM=GRrtr zTL0clp7~%#6@H&aIN!r|oGkyxD$RBRirMH=YC;wSbB%SP@;%P@R{&>SY(@}J#R8S$ zOwr6-i3WP@dXBi(R}d_Jb|9&J+8`5&Orl&j*Sm%`k%~+&!=)Ex^bcCvy0#Ha4!0 zpY)ET4#+=KQTErgxEtcAO_@D{a-_y-H8WFlK z8%Rc;WTCFJF+&3E5aq^9{Eb<&8~1tmNzM)XaDs{V^=zQ1nAliO#Z-a7CJWaDIak5O zfaF#+1?#zvDdy9mE2tKuL=PWKH3!@O^n4pVKICInm-ERrZ|tRc@jLV@!^Gwe65L?- z<(rx^BH)D-HxYFz^ksqU%Tnq49}z(;NL2}E^Z+W4kE64!AV=<-RNd7lH# zrvtyl#rm%N7jotz6X}?{&N4_oM2inkrD8OCHQS-yp?b&&J_4!-vZ-SJoLfQ~5;lm8 zpx=t!0#2qQkCVHF^joI^^x!yVo&;u!#oiHnK2Sv;QE=Btm$%#stOCar1Q>_&KotaM zu9{QsTpYSlWtoMAJxht|6KCuMdch?GmV2s^%<*ifI|o%xub3b+9!i)+mP#8xz6EQ& zHGbt*02eu>h1{{_@PBz^KH{u7GL(CA{3+%!p8#JWyyD~Ag&hAHNG)JgEu>>=jsPGm z3~M;y{0Z>P&V~Ea4mafr*|_rery-uL4$-YJz5hW{xqS+kacMvCwKZ~s8nPF9)pUao zf~D^h#BNyrE$M_?rZL?%nuq-%-RF3yR5F^yLtkTo4@Ou7dLC1KM+6l>NOKL)7$Dna zSUv#r$4+vXvWDQ)!tOG#OWR046`=W*bF0L|VcEd6e33B3&Lt z1P4OyZnFpc*ofnhAqJaM!b9f@d6;MX|1#naxrFUTSKB#fGlH=l+>y+LfpSPMw6dp) zA6^0^A;gn@?gL^xQ;(0+!4-pUXPogu=hgS&J={2xaG+NZKwF5btUC)6$-RsbKkQ5J z(3bdT4*W-=lF-FOEZ65MbUJ5*Iu_l^+JAl^mFN+JM3$c$^H8En3{r)V3u%>huodd( zCx~3>!xyHTV{>jP{krXqKxUCJxkT{zG2j%&#Xp2O(y{e%Oe-IEhk`2wyTqZ~I~)|a z<`GZlrIKoj*?|~i?D%gggIEVkP8jIzym^GP?LIx=o`35fu|D9QtuN4XZz}xhqdT{O zz6f9h@B31?DK3}Y3J9Qt{-)!X{5&?|db)6f5W;AJ%-!(jl!(}X7{o0XnVKMPxH$X> z8%^h-OX%1#FW^HT_meiDEW-}5ZcBb{>rO!qs|Qj{FccrcB9YJpvfs=*92VZ&1PwC& zN1533Er0&SX$(o^Ugz4mAKC8)@`QeNz-UarVx zcdDOEfTjES5oB&@UO)y$C_{KfA@Bg4*)RMU9b3*hMR<0(kB2_OMRxshqk?notT7MV zO2Ew%S5eWqL9thQ0e{iTSmNKQqDXNazo~5^kkT&@B>;XNf~nzS;eT-lw8wZ6z#td@ ze5Y(L>qHL(rT5nB7zf0M38$5w#Y+0{0K%;}fTjbmXeACY`Z0J}lehdZ493gp#i-Yb z83AENfWJq?Zri|BkkDWgexYl;or6-AS;{?IGS$mPDxorOP1YJ0V-}n4kWN~f0o*G< z4;y!=Z%S9^m5$fQR%^&wBl*b+ZNT&s>aS#MNG42!Y? zDtK24H01evGZOWd$S0q-Ql@GtIg?unk@sr``CXMiaSw#x_KDzZ6BP@xmdWLS#Yx~8 z4>i#Hrs3ZI;_Iy6ntuFuKh_Da(WQM5WeZN6a5rLh3zTb1sbFj>CV0uO5ugFV^ za2*LV4g`1!$&`VgpIn8r*{7>&k+q$uY~F0VBX)Qi4GHXT+J}B@h%}Y>g4F#23-KzV zV9c}PB-#M@=OGiRfTFA?_ujvR2u1Z$#%m5N@Z=t@Zx?PJ1^_AuiU$L~1#c5x3t>gb z?JZ29KXhxce?{us>nJ`ORx;Y}hkyTk-bYjjNhRKT_!!FraKL@^1Q4*0Cn*o{P2dZ` zccC%v+Gr*Z4P)V+egBWP{*@H&6&uSfx>gOs7}x%T_jouNjrI;~SiO|3UWRETq2(q~ z!`c8O7YM~-Vb4PN!Ye=G{O(<-F8BaEp`w@q7cW)FVg*52K7Ypu!`qsFNcpPz{R`fG zH9qHEGQPa36L-x6`e+|84C?s%>Oz|;t{Q~gnvoCc5}%WhA|C(}2nZkZ?hH^v0X5(S zWw2RbdFLcO?<{Vf7TCqYI&0P;9)Do?@?a{eos`x{V+-xe;QnsEMnaXZ#LpcZUq1xs zemEQPX&kl(ALIM$@wb0b3SR}NWCagaSNs!d`D;V&Yq2>X?!Nkj&#Qp1f}xf8_%T?I zyJRp`51(>k5J;xk9j%v$qVcc-X-7OsqQ?#x*Oolh(HYJ=2+CUsuJ*a3YAW~n);rS;%H+T9r)iUR9U6GGIuI1A( zX5nREy@U04UK$M`XJ1k-b5V(N_{~z&=c{#Q@K{I~vf5V1$ zshrtAj2FJDcaG3j7Owv00kzTOc<3+px7uD$c8aWg&?9BT3H(XDyj z6Yt*=@n?}cF0t499H`Cd*In*<+eEF{?I43Iqu<}%eY#L~bX?B5I%qJfwCMH0+V=PS z^L$;uChDFCC%^o#y1>UINl8{IX=1ldsnXL+<AX)3ne8tt1s|-nBbZ=f={jst>HqrMDvkZIYtWz!f zn4S}{_10Ghx15py){O_uw$2LY6&P%@E)z5a`@vr7aF@?g= zecs+yeJVK{h^E}2-j^0$kU0LMLS=D>tp`|L4e)Fu6+Yb)@WZh0y zei$m^; zEhN}Z=t!;;x_3y;TEum|La-jgEQ!2NU`ikH&iQ9g=;E3K-srJOqrcir!@t$e%_Z{{ zun-$xksQAZM{~8cUm4hOw6l-0EO)+yhUF+G{^3{KAD&Y$3803|XQ-B~EPYMR;jpt# zy|`~0ci1*`PQ*F1(zYvU7q*Qf0SwTJmB5vGL@Ax@RhGt%kI-TZ7JrvB_w=m3L;PQyjj7C3?aS| zzE-Z-zQTc?GB&t2AS)!We9bC1u|8ZQ*PEt($WiKFfk7Ld;vK%t)A-bx+rH^mN1j}7!W zQ8}5k(Jj~Cd2`->O#7xNfuPkm;4Ub-zGBgC-#kvj^En5rG%*k!4Eot zMV+%0gYIoW1BmX&%zn8 zb#>can-h6HpjnaY?0$Vx7fTR{qxhYc_H=-vuvHC{uk5yXp1`yUEzn*Br$=garF$gI zicN4Lpu5(wIc7?-<)dNN$)OF^9WxjTd&XjaNv(T}xV>*X4qc&oC2>=&xCtw=_ehen z{6C=*;oKf&C!tKgf$l5hvuIM>)4VVT2pW`R?fqwtF5Sz4^QXFv+C6dv=dsG*N6tTU zoUSn9Y-q>7Sed#Tpom*`MYWV(4Q5xDPG^eFr;Q`R(<>q?a!a5{qYO*kC()%w1@kmZX=yuM9KVp}=6BAq_8)0> z8{Uf|Hh)Eu&A_D!9hOq%QxLU}E3y$69t6w(VHoes;DSM^0H2qN5M9ZG6Q)5plTIOJ zUP|)H1EIa_ZuzReRSsi|xcpQIL0kxBORN&DJj5WbC*1ff`@^J)M^_K)LXnVh9VhXu z31*G=M!n@Mf0Er;`KTdu-_$(^6`rt6PZ};KOJhffF8&tmZb0cCkd8hA( z_sub-P5FujMoH*%uUnkeMNblRwbd%6=WefJRWEsJAC>`Gu8z4gWB zkh;+#17v$`QX~)rg6;uzS!hq^$#5-&vAb5%lxx-B7FxD$e|aG(z73ncKc4XkIhfj! zQ62oPMkImVLumOt8qgXkW%f#a*+weRPhe`gWGdpqv6m_~uTFJ28jg!y$z>^Aa#|QM+5mv^6x>?_8))02!0@2;_RZ)}S6_{HLVtQRwDHvy< zKP8BA2YUCN_OM|+Wu>2LQos}sFmzt-XKAxhAT{3wqh6 zbx-Mn0#kA4S)RcCpw!2J8*~5o+~6x2&W*lzvFzql@S-m4nqeB(g|t=Qvc&H?UT|7< z&1--dK#)ImLdmwXZ7V>_SkCHTK#(kM1_BXRU;{Z+e(a zg1YeND(Vo^CfzFv%#co^i!|LS2^Ts5Gv6?~)L<^L0m_{+uU;~@KpwbvBl{=D;KIAd zvw131G&6cbz^T%bxu7sh9sIKB2DKo-OgA72VqQXb-%x1pDOH-q2!@Zo3?N4~!1D7f z%K>=59On)DLH2YCzyU#!D9Il%>Jst~Mz`@VB6<_)!G%S$s*+h?KB+S|hn;^mAWcgk z=iw%f3jqZoUvsn;{4I|;C z_750K4k1;{`)amVSFfnvrq@-EP1Ye|#$9QsHa1<$Pxla4WY7DIG#T_EGQ)Ty%}JVZ zxXPrJ*ZAJwswZ>b_6qC7GV5it;vg$kdg@xTpCFY7!I0@hGR$L|?$$|nqEt^TXAY<3 zw}hf30_vW66+`^f#Ks|_c?@@Q<${MaO6J->$n?Ci&Uq4Qo&|HJm1z#78guDdy3ly~ zo}7VRmkXI<8whi0W%n?LA*!s#7Ru1t^r|I;V1?pOZqQ}cSs-M(1TtMz>Dm`ARAQLa z@TKp;%42E}oII_U+X~LU)fytrENsL)m`WvZQsf6x_9Ub#vcTc9$mv;@c5AljNw69# z6$rc?o(d*L_2p3USEPk=8-+vASpNhDlTz{AQSKwDZ`n!xQ+iI&21Im*lgx!)oJR`( zAUi7$)Ircv4nha5ZZTVi+o@?HH;p+2+uMJULu;jNC5-&WhtQg=5tQ1O4Tj~kg8gRp zyMTLVw5oDS26I~FLPsIfF;AWd7K%2|!~Q+F9LLhwJMBxk&&;k82Xk%GvNV@!w8#c2 zoNP@cDbXf7RV` zrJNGy4|0~RqqBW=_5DT2OS2;_R|S z7gXb=L`ydvO2b>PK0x-X$YXO&Je&exE`*tUyszoUiICSrK7ejx>Fy#e(w z88(`$KQ>|BDs8MtQTS*5xw1LB?hP|RnsgTgC!WWbd_#KE(kxaozbO^oWMzgU`y*LQ z_g37ktNoGEMPW$Sd=#8d^>gomqBAt54@on_l1l%qc#`(^BunoXZY+-ixkRnFwmM`d z3nC#2!2{Csr3`D$jD8+-H+f^71M==zWoc-@yr{!u5}llMx9xo|Tj0=5NP$p6+8dXj zd5?QciEN|WzA+K-k! zGLc$p)5?MCUvSfhdRwTpJI%7F^O8AliyiNc;4fxI32eqmltR^)@ za7nsW0PW;gbRLYFf@N{U+0v=%D+FuXQ5lGJ#5VFV$i)$d`aI7P?7UfQd&NRtmiWAB zcNl{(6j9Ku%_T*@={G_eriC0?4gqf1u-jTXXZbkP){p)hoPihUdw7~k%OB-f8bW!UvjW@5LMnM*t+-ZJ6z67Tt7H(s z2yGJG=y;w3N)^l~B(uR2+XyWVM2mX;)~Q2~O1)O{L6p!`ix3D#&C;HNRG(|y>xANq zevlkK3m4A(kn5MWcL02-WT2Y(EO-U>+t1!S;VB#BGIZj3=^_8GeTN@9jPaH%a~(>m z$I%sxl8?N=t|F$>8p~n;He3m}`|=;?I+^rJp#RmCPFwU)Fx@a$Isbuw`vV(zG5HD< zmX|gQD7GcQk)i%qWT40oeh1CuO#PU#Qy7%u#4_{W@4YB1q;E_Jfn#GlO_)2qYsWem}GE@TYA z(j9(^e5HxGjKV@UuYE3OSVqwuN9`-vs&O=w6&Gr_)~QZZBN)kT&L9=sX6;VTw<3ki zi41DKE*qq3l^y!2?UvstvNii%SY--ffEl@Kj%{LQb#3OZAIv#w_sGRe&z<3qy69s? znO#I_V_Z6=dx681Zg;p5Py&n7qaR``e|+PGedQC|36FDVile1lZU}xFIkoT#M>r%< zP9aD*-4$)CIlgHB4-&JKrX>UatnvoPD}#njN3-G1()uP?l78 zVq%8YJ{R7OWG6fhCt~h}!((A?DhA8|D$_?`EnXOU-uRy1&MBxT;7Kd#)tSsVKj!s8 zUcd$J6MW}2C8ZIE<9pV=FW#XFyblWb(=WG0b$5w7GTE8~J`gDjH8bQKQ0 z!qO`F{D8zYV^2_hq_F} zCgK>2d2NY~`2uyfl#h&f8}k;1{dV0L38`!Qs{Btx$@74mt;;|O{r81O6;!WWZeu_Q z+>Zki;|b;i^0WcToLiP*TgceHX~S&da!2L?#zNukOmhR~Xx(7L*-%cVSQ}-onrC}( znO>FJXQv)RCNTm`Q68hwJv5X%iQahMgzsFE{T-inW%28bQ7CBRtK9}&Q1S09ar`(A znNtNJSSfp3Qx7g8LEPNP+uz!xWla3s_)Fh(nadA04&-e3uv^pP(WR1y2yvg`K6th8!AsOl8A^N9S@jpu1*R(bMpKTL=d>Or;|~nPNIC*gEBZwIsq0 zkvMGKR28$)nJw(P2Ib`b=tA08@!zMH0j^v#Pt8xd# zZ_{3EEF#HTuu!9p27jgxkD{taw*=9}s~AtF*j{yvu1w)MIi@4Q9R138=Kc@&f88J? z&|IAmI=OP;7pqX_a8BB=56H)pV zyC`DBO|yuKVYhY&%>IyQs2dG}tx1pBU^r6KG{Z2>Z&RI!Xn&KY@Qq_R18@&^wIcz4 za`hx7@(fcR^kfII_wLFen)}fJnJ5rsZU+G&7en8GF)K)OzmGW%$FIW7ZmTowg5fbs zu@{ZzTBA1jY(J~0M`JMy#VTRUFgAlz^rTzgK>1SUL=(ltPeSk6u;BpAg9O_gEe}t) zviJ2wZ0F;!jW$I5@2l>i5N?WPRCYCIB8)6_(U+#=m$owiMj%fVfiuMU>E}xs?i8N% z157k$!}s(;n@RBJ`BQ^4Ea$7n*H&308>CPi>e##;`!bNb0reyG`AuWIq*Fa;7SWw> zHx475TlMIE;-ja3$oe2TQUEm}`)AOL>Z>s1=ous}bxN6*EMPi7w5j86b;fA_CHesx zJ&u+1anOs+-NZlkcr`E^<;OI;&A@dT$$v-2aGB9GX1HHz$PzT4fBB$n^{L?ThvZDY zaD!zT+pmR9y$y)3Gxk>xO^aMe&Yq;m7YP?142s&xA+E8FXKc(U-}*e^d+MoRP| z$8SZisXi|^3l~OKA&Yc^pNPT(C9`E3wLw@Ak_s7-N;48SbEu2^{KSzT>Qf+tD;r3D zi9KvMbt<4GSveiIwlGAfx8uXVly20{$fli=b=6xJ8QpDuYFc`0JiMxppNv&%ax5R! zeb%9`Z)DUmEU}jdpU7am{$6n-`Q9=wuNlx>e%avLeC&I`sR=qfmTXn)Oe9fzIUeWX zBTx_+Bq=Xc0KjO;kevnY>!L+o2tO6}_viiRPd@8BI{TLy_g3#nZ{padn$wsZ(UNj9 zVI?=Ut2bZHO}QMX3>}P}CeVXC>XPqTw!r1WZ{abze1|y~t5KVRV&gY{vy&Fd16>s~ znV43E%e&5PjDmECO+(snT!D+>I~%b~aQF5ROGytI?-VQlSfzp_5upNSD=e7!6t62C z)@3_b%dD`Z>lTZpn8KDkZ4xe|qzAmP(J!`|xNr~^R0IkQxWIR~WTILcUKU*^WJ&}N zQ~GUsaK_IKM1v9)ZYj)J2e?AK^!DPakO%Fwf4hT(-_(oc@1&oNaFI-@9MI=qh#WPJ zlv&R@SVaXp?zybDsm`s;I5*+B-$2w^@A-Q_S3Nfnsnb)Zv$0Q-FJDZlG;};O2G*CM zg6>qK|BA}Tt~cJaGA=F}A@Iq1S}kKvnlT^{kpxq10rZOvhUsiJ#B0mrt2MM_HruVs z<)QXbDGd`>znJZUX^Yyev|YBDO%HXRY!A(oC5w7Rv7{$2!FEVtt#C^ma#uhU?0MlS zFTLJ`@mo)1CSE?>a~=d9cy#LJD$_Q9d+tWR`pu3eOFmRE5OTJy*V9>@-MN}}9zzDK z05pRl`M_v(KyOUk@K4y7qvrR2!Ngl#gIc|mdS|VYB@YPvk%qX9DeAkwmr;p4{@b`# zCJONuFh3~piC36%t${+_bj?{D1pBO*CuIECKh$xom!B}_g!`xMc2oVYN0vWkviE%q zxf3R~=?+{RxjK?Fgrjg(7Nu>TO-esW4hYFurykYP7BKXp%j-lJu7Un;7VW1S7w<<0Bjo*2%#s2(y z=ke){g{z;&9~f)2T(BD8&uweP5~-vA#Ok;iM*@KANRAe6ZG>00j|%r6#1jLZ?90lxRKu;d_IqEqW(;Fb^(a>hRBr< zzJeK=91t7lF-6{3Nv-obMrG#h>ZVh05_&xZ(MGyQDb!dsG%J}JpJ;nQQQQ^DRPR{O zIMkM>%MGiMwrk8hJikZWrt(^>U|27Z*17hW+i&d{WJ+xx}U+~>H;?HO0+Tknz8+@0m7VjEtu7C00eq;QQTa`nB#-X8> z8x!@E|K&IKYmWIabnoWmfBB973w)27XgD-{|Mt882Hzjt`S37lZTUZb<4;d$5X^3u zR^CjHjELspjtyjCif@1beD`0Ods?J_^yA1`l)!I1rz-5)-ttD1f2ri~v-Yn;1c?VN z*Ing44~>Z)pZxgY1UjB>e{g5_v5B>a8PQ~{!t?S7{HJHt&X;9u^w#$5zvcevz>l-* zg#NZnKEl*y-|C+Br#I_cI|f9TzRnHD`}Lx>W=cMP&GoBj`>aB7Ns+aL{1ZvAv^SU> z2W;hMKBfQ}Pt#(+UB5)qekn-JFel!uh$P7~2R_jGbhX*^o&|QApnmP}UP`;)Pc|JA zO`OZFTurb!XYz~dpLzf;P~+}LM~8)2$SX|exyUj&UHun|gHC^` zwHLpnz8JqhD>@=bvouLH7$&H>OZj5EX3LUx`6ypYN-e4&pIQ7;e?1wl@!IVoI)>;) z-rYbv=>M&4shZs#cBJNv?o?e$fM@x|{~`r^EhNqx6ltL{bKUA`T5RO-}8y>x}_ZypGFD%m)?@o?p$ z4RXZxfs0ADj2aC zAr*}1)zL!YI}V2*54OLOST|r%!WwtbeoO8du^2|SjOariDU5bw<4?t1xM-jUkieGu zzyNgHBhml1+h?b}MZnq%9WyblQJv>obIwZFpJOFs)*9+FRroeunZz#2n!8@xR@w=z z3h}sg-@uldi0BX_=%57`FujAu-~I)G5MBd!W?~1(cB%a?@5b`t7w*QC9^u6+O08I zM|wPCBlr-uGH6QphUy=Sa7E!csRwW0Ayn^3{}{CB2OV%GaR>B9492&tv8v2(V<_D_ zepNAFL(Ju+1{2UW=Mz8WW^G8oz@AQP;Ai>H>JO3gBl=IUKST)oul~r@JbUDm@*tla zV!eU*V>tzNsM-@Igl+%(^yaUXTjpEUqSrw5ZKf_@8+J^*uK=zQws=3FeD8_Px%@lr zoqGoq=yni1Aq?w@@c1?>)y(UiLjHK*PB^}3z6`7=a1x<_O>T4Eo0nF ztbj|MHyPYfdZFO(6W07Nnf_eL$E$a-?motYS1DY}4cIgPJJ)>6Qt~_GJ@BY^A1p!v z?cs+K=bY@;d{vM11-n10Y7sThs**I6chG`{W?8HYNt8(2?m~B?DsMMBKG0CKsv|#5 zr4SMJOIDIACHtgJM~ust=;|?+fTxv`>|+PJy#ygtY3W{8uGX+r%jsg@H{%MvQ|XK( z07_g172I#P0(N|vI-OByw<&88xi)kfTUd5@YL-mG54UvW>|JRpG7=fTp+^&JN%ns5 zxa3dQx}~jTO`evNSH0>)28%z5TC~98v9T^kWdGHND=$y;J5x@&Dd2C``9wuaI-+Y> zU8$)@JWI+{Hpz$s#8lBT4qb8G)6J=*TWWLVR>#HA&XA{n(7a}Dui|Gl zwxuk+uq}b9>mrot-|KB-c<&3D!+|OxYjAw>QHj?>ukYV^g)ri#ie%B?#?VyJ%91`c zE8Q1P0`Q$bAg_ki)lH!}D|AiyD?N#+(Kb1F%xPoP;;;htsKK1Xm1kNJ#(y(>*|W{J z0Xxkc%YgA6B_NAx<5h3!p6b#q5pCcwnz)f$z}LHP-!JYU-Nf6g)XR~X9<@KP)FpgQ z`a$b}iuS&bT{#Pn=h}uJ!A*fx5hqd=flE{W6jsS{^ZQA7*%8OiioQv76@rr-x-F(= zM3U#{_H3;nET%ER7e}r<{&6kd;-9M`k9R{Q+JQbYaVZ1wHkU9+u1I=%lMFlEh4FQ` zOMa`#{(CTqu=b31L34lbMam?BMqI&8{LW0iP=&7|ELep8eF2**J`;>glNwnOk@id5 zwawAF`0v%3UB5RTuP6O$2@gU0vRC)?P(G1pDH(R&RpRX=xS`8&s?@~7IX~UHV!ke1 zZ%YaF8uXNzJd&#y**ao&V9m1or-<7$NdO4{vDLohG3#f7k*Lw{D_DyR)O-+*X+0V$QyZnKwtf%oE55O( zF-c+C>=()$tDJo4G)CO5DEx=y=4f22mdUNIuSbK@CW~Q4ye`Yw1cS+`{{E9!eLXTf z1r4BfX%!6u{v$F8|k=;cHOF$NK2yE4bNo9QPX5c3hdfCVr&_tIElffs*E;kS~7%wEY%fe6Rt;9$<~~yRySKz|xwGcCyK;@gKo|2hSS6H&8vE zl8P$<^+Pc21WuH$y||#8YkCXW{X>6x|Mv@pf8{}W0S_~0jEw5MMZA10T(5Pe=24b5CyBk@B19HH&I@|5>0AWi_M z66i4@mYGgOD}4QneSCxE^a1~+RLLhSn3jvj{a-SQbE@gKnS1n(f6##zpTD|c@l8Zx z1<-s2>D z&VYzK(U&JZm#hGxjWf?lI6n_sqAnqWg7Pr}>N-7&RzxlWnu_|GJy*m-2uEJ}0^-Dr z5MAeOB}6F%#baZ7=1xF#F(qWze$sgpWyG}vBX9`n&ypFVJnb-)L5Dpu(NS}euG13p>JmQ_TDH`pw|^H)KJr9Au7|7je&<0%#+VR-LEuP4^@pc zbin{1=nd>TA<;(3j-P>AlT7YASbFIL8)2w)Zvie3cbq5K)3p36NnjyF@idx84XhHV zOldei$aR!$Ofo=~P_ZxAm}^v|ttz5%R+L@>_}Sop_)26-MOqxm?j23n&9@=lJGFaF z^A4 zp!D@fiSNyrcTp_dDrT0bEt5OyLFP(7P}(+{;+kLgK67g14f zrg3}#`-F=1cErBm>7I!~MJef#@p)o-g}#*-vOn;UeFdS5%~n%NrWiI0EPp*$xQlx2 zB($eKQsy`f=5g4+QX_+kZX#dKpqQ7laeNZ4W*zfv5j#%B4g*-;C^GT{ES8$FXDoDW zGSqVl&=JR`hZ|a(NHig6LrW@aM6~cc)=?$~Y>CYP;TlNDe;k0Je2JD{@bd!jpI~u^ zfGz?t%*5i(ldyLH>}`8&T_>uIgYXAfItrMB{BR#u31CA6$TBu(1|_}@D%XNg!=p$V z2-_!yeQ7|N;bGIL*gGJk0C_)0KzOYrsZ^;<4~lbH8Au|~G{d|}L5;28hS``q97GlA z(w!B|?Mc)f8aj}pfiM%TKM1JR=F59r4@yZsU3#Ul$nOnNsbmy6xPrNAjct^^`e_B5 zHZ5>2BU-2>=Sg0+0IVQVB7QnWUM0B%q}NU{YA4Ys8>q+B>L#)Q+9pdch1J5wv;mmq zad-IGb&T#+H{DY4F1`NIEU1b^0-zaAD2Q71+&7{B{!})24EJiq^Bx<1*aw$hYcBCq z#Fkg*-3U*npbGw=Eaxyc1<&`p73{xCKyu;!M8X9f-Qz!AM%H*^4mTiUS71uZKn0+NuV@`1zOhT}I5C^%+^F&$k z;uV+-U(J1YWy0^1?x-$3+H_1}*9kDbk*)&l1OTcC#JTC1Qxq3&6;QkkPy{O11oQM) zs86rUpV;F*kG>Se*45W^( zS7|Giq}+okuC)r0H?_Y$hBrJ?FbwEB7OO8}=mar0(|*r(Sh z?&$5XJkoiAxSSb-L5XVepe2K6&L~(U7bGK(UuPJ%%C2U+D3!(&TDVj!$lt}h86$J% z3046V;(8C3y8>x6&!DXPh*qLLyrEyo_5B4c%A#g5X_r!n|C z4hNoBew6AG&QZ8gr4dg>UR;6S{Q*0lWYJE*JfY#>zePT-VD-dM2{R1vObRL^1Kn)D zASd>Qf+IAepJOEJc<@ux8GPfBh%wPIQlG^)(b9+bm(VJR5PbhrR3b&tQ$VMYRE#$+ z@;i;D_0Sch{Us#iIS#UyL!BDM#jJ@O~vGH3sxo zaqlQiVR?oZd5pB0-lMt>epxq_gszNrB#SrJ7LZhqcET0)QN0{YJPB6NnFZ;302#Zq zdk$NpkNZuup|Dav(jL{@0`ezF~2TX28{|Exs zw;asA-;O09I;Ywa@CH2zX^66$A~V*o<7wdIu9y*R@YsQ?G5Ck0sQ4zB7aJA`LNG@i zqFewm2#SV;XTIV=6mV}S?1oIV%4@_{?}aAu7F66ZHmlA694WQirp|z>LtIVqYVFT0K7{mE>5bUyQyOgRsGKBEX6Gd?8B^6c z)zt*gChZqHg5;_I>Lek29yn0{s)fJP6DpE>7Wn=a&|C%UR%$%F05zmS@|!6?vrVXM z7<{)1g^j~#sPwKOKDgAg)Dv^*BPVrIW7 z*mr6a&D^EsebS`c_oL1B2--tX4bvwn0njax7rZa*_T=hL6yc=kX%vQW#AmFyln)p{ zg&40WXc+`bquG{rFS@K4sJ#XxvZqxh9JG<5C!_I_GNM@NsK(hzKF>jK%{OB@>|(2} z>*HF#1)0c3whXZE4AO`WcE;9>pApKgD-daUX1)c)oJN!7dnn$K5t z&I{ZOm=AhNi~88ODE_`aIemc#Yy9Hunsc9<;Oe#Vg3@^<$4~z;Fhal_Bmx!Wz?*S+ z9`g`)=U;*nu9#rKP)TxKSOgyzO1uLQNWhU+yYJcJURrp{(g0MUpc;Zh@sk043!vdS zFv$CXt~_1G?Gl0Pw1ifw_=8Z5DC-Esg+=lG1#B zDOlJzk!l#IP#YUB513RtB= z2$LtYejV(w4*2pvDVebS)D1QYSKmcBzL7V|0LJ2$l zmo|J9wz`u=`yk!OnS!AUH=3r=`}PAd5QboIV`~$^_}mNfhb- z*sHTE6*7!S@x#3(9&-Y}u>gFR@tk+aS8=^=Q|ehe7^xXvRCr%Epubd8VtmscQ*U>O zfBMg6y|eG$fP3fO?w84&xEn52Ywqed3@9^rbs=7@xJgcON`nxlhUaK~S#r>&h2{M{ z;C|eP|A6n>Blit`&Hny*AvGG@nX0ZF@vSPj`h?}LH~KeKX5Du&gq=Q>nHBi9Zuj ze85B|jL=W|gUHJ4PI4W-_YE`dZi!exj%bSNf%vI}rl}>V5qADuffj0SI`@zsSi{I` z2Ux98e_dizn0#;*CQBFZf(qolgT!LG>~R&-BczZyoC&ed(D%@!lPWzKv=N!2p7b(m z=upVl^x`1#A210QagW}7x1FPrdcr&BYvq@Ovs9{DN}?U{4oYgCctkOM13?XR>=e_>fbgxryQ z$Nr+#_9BnGWVld`Fym6&?>*Q-X9tp@Ybn$v7sWJw@Mq{#8{qsP*_qd_k^SMfZp5^x+lqe|U-pW) zH(AI25Sc@XO3}XV;*b`M*oYK)T{m+zK4`CvjAW#aQ{WwoU!3zww~nfZi_bD|s3NTn>|RAsN_7cD3UEop*}}v73EfaruCew?#gO$a-fG-&GuUKjD^Rf-J`h^j>iWhdFb zND;Z<{0zI2E7Z%0=F_Y|;-R3^5;yo!9hJN6lp1S!L>05A<6U{}v%{S)TxGLPg!XOB9JVLe8xY!rDzVVcGt8lfp(p;FZt*I1o&r$crex;gj-4o9GZ}~FPO%-1B0cs}@R?ABTe2^v z;fAe6m`Cbk?8{pYhE)8>nbDLuER371do{%ROl0yTuD zk+Kr1Wyka1TlC*>xpd$KoGC43SKOuEu?>OAjd23Gy4k_4RbmAosN5xjE6$r7j3JS& z46DW*Jy-U|N7Z+17_%yG49ewoDXMl)xEEXLfFPU{#eSa_;>u-^{43V8AxB#3eQ%ZX z$bO^#RS~zu9_{B*bd~ufuexrmA3PydB|!!;7i`0 zjJpzK`?aHrgz|GhltkA)+q20*FqT3@SZPNOhf9LQUxrBjIO_Uhy{tmu8!9Tre4$F* zR1u>ooZ*f2Z(DF${oalOHHCe*LXYawlMD5mn+6vmZ8f>qW#Rhe$PZCI4+CCb@0Bp* z`5z767x-4AS32lM+_6&+-vTx#9z1~^OJHQ?jS5e;{z-XPZPe6vOu3r<^qymA<-S8b zJd_-<&%uZ%S|Dvgxc?FspM*Gd<7f1I`#7l|FHSi8>%Q;dS1YdA$6pU`zP@7gcLZt7 zOF=(>JNblP3ox~&{XtSwow5Gbk}mk1I0~e8aLFd-^LZ-TH%Zxxm6~nmhhsKX7D~d8 zv+SD?wpp_QsN)~$wjH686*_X$O72pW$xzuz6NMK9rq((DhJi9Wjo?j;U>-;U@n%3m z`2SL2ISUfO*Z;pnu&N6rssH~bg1b=Sy{xAHBN0qDKtGmdb=$nCIFPo};n>0zsIUZy zpc83GwC;Z4CP;SBzfB(N!SjID=w=I_cD-nFDa&~QV z*MAbhd>S8hV5GHi?kOslELc2E3>j2-8t`$XP2cGmpCj-8e)VZyV_7xr*GT)lqb#?} zTZCuFk%j7aPkjBDO&VHyL%3`*Y^6a>m+U5Io6C{MeZ4xQH!Q zZ8{a(Z_tO|EcM=Xk-s%L&5%B~&Ph=yWnN{-Fo{(*tsiPj9P6^Vvl$}z68XytA*UH+ z@usM`3@?+_L(Zt36EK!BytFcYU)8!ba1(VSEX|_-mo?o^TWCJt`{VD*R7@8!k7}*u zaioa)`tsFyYjMZXyupj~u#(t2$ndKP-Gd4u_VAF;7N#9CpRXUcv#cw=0B@g9@Fl2~ z6rV#k5Yt+URNh&n3)k%7WFBldeD1)|?_DC4MRpp_xs&egcHN(m$`v zy5;>H!&>Y8!jJgojQFzWnEIq;v%M6V~o|2PrcFj zKm(m^my>Ss=B}LYm$rY&bQ$kCHvHVVp#A;dt+WI_Ht(N1JI}a}obO%j#O2u`j9^1P3789p;D%s+~# zoyiksSr>lF>(9TXY&J&NwDOc}C-ka0xh05|9u%g9+fMsDJDvLGwO8?EpBl3<_>;!m zyp2`=>ybN(XJ-lpXUe=gH^vm9O+mK2gLhIE;F+Rlr&fvy2iWDGb9Pl$#SHzhWo)p0 zD%F+4+sTi!=3(f`H>s-jO$@CXe4eCfp#Rc_af*Cp5aOX*dw?NBL*KUj>VMGj1@+Atv@wufB|5u}EnZ)k}QOx^&Ch*1s5<{=l1+l&FmV6DFiTe*!Gd zF}>n;Ks4t;*{sFefx)Ny(RRhM*(i8MV>W~KQ@UE<_{`Mp(&(lSqI_mj2m#1*A>IP)8qYxz~seiq$ivoJ(?AR8>wPZ)f=%pKC%_7Y<6oUz9j~*E zJvYJJ5L29zcaU<3aAL5VbdEI6*(|N6ZOk;?FgX4y>v00?%tep*s#LJo&vDr8{*!_N ztfO03fas9!Q!Dk`%b&)VOLQ)T=~}Rk+Pp@=(?^Q#C_75oe4KTg6PIug?C1_bba(0@ z!vvy-o550{?!CJg3VK&xS&&uS7@TGvIHZTHg<(EJhh4jKn;mHWF3*W?WaIR{RJ}gI z=*{u|1k8_3@ZXa+-Y|GxgafsE9b&(-pmU@-7bXn%#EQQr> zUvaqdz+>S+jk8RORlI4zl~B7gC{kRt;!a4qqjI(E3!0rCYcWou~yr2i10v>IAWp6TlMJh<*AyjUf?RN;1RJNYXDJqr3QI1B&V7-+ETs zty0@P+ci=KE|l&RH7PO0wzJHi!A3~;$P`iU=*E@K)?$TPu9}XE@`^hcE=eM5x1odx z4_vg(k)BZk%YdVhq0U_+3|EKcxi?WAenfa)Zn8|Q-GrHw!F-8_(>8nSR&#@Gte-wl zup?!8M0$x!-a`mMjzLW#oS%8??&n$JRo_K8w029CZ1fpi(nSZ1wmol|>Ql4R#hAtl zHH+41QHKJT73G5|XlIwkd+4(g1ZUSg zpDVphSqiuxk6+q7vw9=J{PqMvO+LaYFTJ^jsfuUWlzz!GK ztI|MpZRpPB@x_F4)6}v4z_QgWam(4rH{E?NPR5}B_{^T~gsQ@IS&o9#wm8Y|&e7E$ z{uf#o%ab7T$M$CWUQHEaZuD6E0wG3T^sJ9Yn`mjbR&KQ%E?K4PkUq-W5Lop zuljUIjfl(t67pp8>MrtHEb~CXaw6uV1#=(**Lha#o(?{flgSL;ZG> zHshSsc>W|G|AR0^%?X_L)hUD}PNSMhm=^XW{t9Y*1zT8$@c1plqn#B<5K`38?JJ2n zf^>|8Dm6xBj3OGz0&jr8p@dmf16n|sNU3Cd5BO9b43LuiW}p-}3iIGVEkO{qsy(V{ zYJ8sHIw;@M3_F|<ThCIub1h`q)+&8MQ%D2SuKMFazTjVqXkWK1&$ zGfcw`at_r;qCz)BR5nD2QK^uwQw#R^!Rgdpjn3;{p##4pzRtS~c0-*02Vegg)YSh5 z-l8F->=a-Fp<4n|1)RKy>n;o8)otfXp}dp@>Lm zD6d&Yq?b|Bnn@CK(DVYtj|nj)B;X8>aRvr7lfckQ+$c=qAsL^t6VpY)bwF|eE$LJJ zph;A=Qk_+V&F*M=rZolf#E74?VKG+3yKPvO9E2EvqD3QS8<58J$P*xj&BnY%W8lkJ z-{!CbZ?W=zA$6@l7X_!K#q1$NMi+dSFl&o>9@a1$BZli|$$$}_Ho};YkkDI=R(q-9 zS*h0VjLEsnI`iQOM-IY@gAmbBC&-vA5Zli^Xa4S3ATw^7gnfAJcsdtd&&4&bNhv$w z*z7DwL~(WH91v2B7b`?AhkWaoo>Eo1z9QH9#?q67a2HWE?Rc4k3W~<+`;QiDlK62fK*oMRpw0ruIo}yO@raH0IvUtF#5tUQG%CL*}ZV#?YmxjzrTdOlR{l0M3FKP;E;3ip`BPb#YDzxGvYSl^j1NF&Y?hqNJ@s_aL5BZ2Hu>m&P zS~l7TG}>1KdC(GE43NpgvKw0&3rH3u4{){rKbP1T$Bg8?{oD$-ZASL`gV%59sjCQDCNQ5M47vP@QU<

i_orvRI?o+GXxJ;#wibcWzPFS;K??CbP(PQDx_sJ`fp6u~6#4z{v?*A`W` z=Kj9?&=Q=~2BF#9AO({mM0fI2dxf}*E@}0Hxc&*uo5##fUL5s9owg{od9AwJa0k7E ziftfbYXq^)iy#!x98Ci26w^N*Bb@o&0@<|AOrj5yuc&-%Rmf}getLQSNvAj+gS`Xv z3UK?PFr8B`&#tyQHV2c7nPJl! zsF1blT4(gxF=)cU#y=qAy!Qsz6S3cQ3g2l}pFDpJzFKxfrMWWclH@9GkRNx3Zd|2{R(oGTjCe(Lk z_+zbh92+2Y4^o0_gePlBU=yjoRsel0S8jng^=Jq!z|;${T`(N{az@OPp5d9 zMRJKG3HOwIPmz4U!4cv^Y6OiU_FxUH=T{uImRDNC@2=b#?CFd7y912Ut%qOc8T^tu zn4Q6;T!mN*{k`Q2?~357IGzwE_w!U>=WR*8m#AwnB zo8Yb@!IfrG29Fo@X=HC$5prhP){7qRe(G}Wryi={9>n&zTtGQrnHTZU5ae@+w5>9~ zCbx<+4N5*Eg0E;2R&Nh)sls(}V>+K<)^~sh_9RV%dCdYWcxRfm3v=}2Eb+;;?#W~N z=wjUq;O+Ps^laIwy95~cK*SkAaA2E-aA*p80fw8thJ#Ag4z3CeUAfQO!9(NzY2N$b zhMTfqZ#$e7@a9v$!SARay9bI@lHG1Rars;=5+D<({?KYwf}k^RJ-SBNd!O?V;VN;w z23uK0?;uunvb$;^b=fma4LhiY!{G? zs#GxLOrijB_FWR39#G~k+wl2G8106O`>8Mx6+yml;DWll{KUBp*DUOvCP_Xasc3SGCVpq(27WRU6Pv7hmdjMZu(%>TEA%P(2bn%|Wk~1%akLCW{ zc!B8bNl>zTU9yOlM$X1yYRqu_P54%R>=wlq5e%IqNGjc^mlAmp7EU!RGX<@Oisa0LGpKt@boS^FI*?$^(3MQKf#W;VR^Ri(37`)yT3rc?GofZ{*#I)1y^!oa+NT25bwTQ z;_@VLcL%P7g5~jYZ2m}9lD75y3K%!_pbF+uRx7<*jvdbfwW42}?EtmgyHb_$gQVMd z>Ed^(a@xCLSelptLq2>PnA?aIymKrP@0{B^yI0;g`u0Q$&d&5a<%(CJx|cN%&SyY7Ym9;GqiJ z!OEt9sKS6m4myI5mI%s7xjJ!UOFh~q^~gb72lX@76L&Tk=MyWZ6AuGHxD5&UKxs*L zD_%c1szl)s#pi%k%N(7I-<*ByGh7nR7}dFwJrWVMSs`WTQxL)xR&<%`qMH_m&c9K zT0}&ML&?2CsLYW(zxuyRUPSrUVlU1 z<|}mvH!DAkoo7f?GUEP~NdvO@N`qj(u8?gl^Sbn|P=`&EB^=$1o`16$5NoK#8B+ci zh?-g1f61p-N09`=5N5|7eWLfqKJsh0HBng!IT2yXhrA@pG21SHjr)sH))#M_TFX3IT7E z#w+|T8fqv7=(I6Pv|Hf~cFz#M;TmQ~17FGdQ`R-L>81D&Ti=AMx)1{>Z3tOcLe86t zgZ~y~>hwiz5z_(Yzf9LfWpG|27>I-Z=n?HsE3zbn6I5GE8G zT$*^k9uNSBRL~uyh~jkACRU}Fo9aYWdW~ULWnwY{_H@J&Z4W{@7{oQ+Fc zL~+1K)kH;rBBpWfV=dsAydgc8S{*v zD`T@gD3fM_E3HlHQTp*=2T7meDO5!kar(e5)1=>fr5s$QphC%np;OyWG_8wL5j=iGS-aBX)-5WC_PfV$7K~+$(XvVGm|TqcEZhL z0oEvzJy2|?Z_zOJ*K4WgteA!(bie$af9miyK%)KTYM61mS^sdT}57g`X z!8-MtqZ~V|4|G1yVTSKuwtB$4u^jlONMdp(BW_XA_UrpDP+ooRAo> z0M2DLuZ2}7LLJ)YHw}4-S)=-KEAXX&m)K!&yHc4JBSg7TA`u@d)4XuW4KA%JvcOxA|74 ztaj|eAQVGX9F1naPNajGilYFEw0*@2l1m`zp`)(K^*xyfZHSALsI%WSLAxS7EKO@% zbNf2xLw-G>++<8a>($j;8=2@7MWiCv7{3cUCX=lC+FI8T*gv@}JGxLuuI6WDY=VwS z6hq_(sUxI~Onj7+s?TmsHYgS<)6QXN9V#n`HgCv;pL8_&xR7Hoe@@?6qz$+oe5v8K z(IAU3RD1REn4*`jt3o>$L43{4j!Mnc2@Ke_m-|ZZ`^nB-Pe-GyW_N1%mD)(HtWWv1 zI+Xv^%{z4>qtL&PMa*=|B$lg9ZZX?FMhDte%M~Zp48od&W-!xsO4wniusxQYcve=mmo>iESR;FY zKSH>z1pJ<9+;=nAS)pcfWUDS6TU)uB|Jiw4#ZqtHRc$@RX;z-7K_|o~lf%|w;^(^# zhU6}X^W{4H9HQ;=a?3m;u^vRZwtsJP_soYVj;`$>_GQ}Gt*I#;`fNv3Os;&69Ru7q zJIPY1D8-Ei4CnW4#iK`1MievFsP5!}O>f-Y^3{~*K;R>HdN{&OTrmlj>Hi-*Xeo<* z1^phOn`*1>0L?8`&R~f;VmUTk8>vjn-0{~L{U3jr)=ocRsPd@5Jwj9f!e)tF-sG2c z^Nm8|X_TF8#`B{DMASX^W!;Rr7YUzVdZY&A8SMTPa-CL(JHQ$tcD;oG;R`&eaR>0KleEJL@2`-DnGw8oByhhXD#)a096vn=0G zvaJLTS}enfQk*9EZzN8Cz2lw16BEF#QqASTh_e4&zhmOz+vh&JGL7$?0}1`dh#^A? zCv(;dsay}cr;4mp96JA$3ZnKXX1l9fd|x`@1Gad|aMK_+YX|?S+(Lr`>5?jY+)LPJub`w`xLg6=v)CxLU7m9<8JR?DL~PwIAnQOZzKh-y}S&{+fN5^^ewzhW@yIqB=qv zlklK1(~rKD&D^z#FzyQ6{)09LuSP(nE!z2(Bu)1}@}ybWcS7T#B;?-iEUyKm8%*3z zM%tW*2m{XVsy9a|F*Y4xM6Ds8-eLGr7;bCX&x>K13-*kpu82SOgA|nty3ximDv`z1 z4jdH?PHKm>7W%O=UT;&mu7r@dw2ez|l`vu`&>D~875ew%Jl5cc>BceiV!9EJWTR!A z)tpXcMuAQ{_vWb)&abQ3@Ts8H5!5Q z$_oDj&sRf5Qd_C1%)=nkA*sv^_9p^A-bOgIkw4!fJr1ZdSd_4QtL{_L=qF~xVlt!3;~VC!m*(-SK^(D*MUHS zfO(j=wH>&f;WQHLq)qBK81b*XmRhK{&Iqr}LRRK|@oz8~ZV4hG(_^#t2}cZeUyfZK zGD4iE!rUL_G#}I|r7vXossQ+U=AC}F#_NJAv0^=e7@Z5FLsok&0KJB$ywAE=)1A(m z(1RR53);*{!wi@lE(iVuDmiB`Jfg2TFEHB1a33xsCtd>nd`9>>(r8w9yR(7Q_3jU+ z2zIorrAv9TiojQs`v&9rb^)w-&e#x$&!4-hy&^68vp+9mLH0%6-E@HVS4Ot)mCUDg zWbD_Ss}@|AAg6kMXA6rTdAaWJDU>&5AAQmtYRzw@!K)YG=c5PjRbi$;)+Qm&)A0O` z%8cj@wCi8AhoK4*UUSo*;6Orp@`wjOtoSE+E7hiZUwMq=o>!%~PkyBRLnOzKzzGxJ z5&eo$TeqVk&?^hp?eqYCjFhe)HRX8dX%m>l1aP`?Z^=~0kKLzpOfu%{#Eho z`v*Q|Sks6z@#ks{b4g;I*QmQOSBfHdec=?ue}TZKE``CB484B%^Od5!)q)p@d(x)B zYj~M`Q`O>1fkPS=xsIpXsu z)o=P+dE&e|uU*xZ&ZM?xrUU|y8gUjhxR$U`TcDz~aDKB=`IFg9l#X;prM?@D*hKX~ zPBT_inStS~aEkI_69AKui)cfb??B!o%^4>b`%qO(WN!Hg8P5qU&;)QG`nr;kPM!$8 z3v>)8_sI^+>hWjvetZIHoZ!;@VzjWAYq*CyqyF*{;uIgavaMAD6EDuZZUR_!O^+2Yg?2zqP zI*3e=18N8WD-;}m)0Q5Mu;XR<(Xu8t1CF5CU_77z0^zQiGk2donO!_pg>)shMK<*WZ;|@f#pJ(!( zQ2iK{Zt{UQa5rRnGeGZ49Lx5quHuJtDZ+DtM0*Ji*F zc&T!8n0#mO*O-FJTS@pDTAV_Y1TPF@mEW51HV7;|OMDm^@3<)^I=4A|L0sB%JPUj^ zwARG{$d*gQ>wXb$^?(<9fKMwXWYrM;WMmi{<+s$A$!0^Kxu+Aun}~oi$Qn+*87pGt zpT)F6AZ8-t@kVx)&+8%kww6lYZ+IHvF8$IK@lGe~Yq5&vvYy{SL~FllOd86cgNZjP zaRzJ*GytkEa5|FZuMZTjg#RV5jHMB;Z>6dM)m z)w%hkGQ$d}y_pwI#0Kg`-^rEy?7|Xm2X-ND2d0)<5wXo1*^NfxZ89ulr%Od!-rGNn z&4R)3YjCq9hVG~0ak!zlJj=GpkIrUB|K5_I`~HqoM1H%;MPh4`Hn6718ap^eexK#5 zTUAu>CUj3jtbiHox94yx^1KQnUeI7_EN;Y#H<*mo{P{SzYNiy&-}|S{UYv} z`V?A2VJI2)k?anSb;Ph3P#R?iH}R_mYjF!pa!%4{B9P_vWfXWD;un#m{bjJyu%!V? z9=pm{CXBH8pd4#p0Lk?Agq zAJd^L&C{jNoYCK{byOByf7t zaQDZtp_LzWg;EP7O^$@v-udlE@`3CV0iuca!swOeMBn5(-J^p}^5!hS@s?EF)x5=@ zsTutx&*WLayDYmrph0UiR`rX=36qwE;vbVf+VE;G5b4J1b5=y|r`_x!p`vMpert#@ zGUH$?O7smCv?fj^WqEMR#_rhhB5=zd|G==~!L;OdC}smO;B^!D^t z&BBzHC<%9hlGejh-cRa9RK8VME6jW+4VeUgQRBztMr5pHQejK6Q6C?9K6|YHJvfQE z<<`5!V;B-md=D(kk+gfi7DK`3X)&X(=)<}dFDu0f<;_QhauMZo;#WVx&zqkNra zj{-Cv;u@gqiP-RladlWy_c7~TL!(p^g zcZC_#Z8A%jrJq2kH*xZ0c%EJN z41Zy5V)>n!V*W_$LILT6VV+hG+1ORz>F<85V$<$z5tc9efwSGskM4n{cih4 zmKqcPm8o{?I_s(R;QY%w*3GO8XGlA+uqk3sEP|;mntYkJ!_i~EJE?@~b=Rz!^VLn0 zeWT8|qVtaBjw|ICdd9Z5ZoHhfHvQ``V?1lV{|@}37~dxT&qLK#C;iX{Pg3vYlt%Re zE!ztFsKcucwh>&_z3OFJMw8ZOOtxp22YViEvwQE@_&!C=CVbwyTli?+>%RWBmpa`r z<0*gPBTLdS@-dd?azzi~i8@wn-x@^e8yEN-5@a<;=#JMtQ|n#c$I_Gl~`U#t)8;-qoThh62R2nt0N@ zr|aEiXU<ET^`nfL5j}b$L*w zlg)$Y8}LFO6qs~U$V8ZAyiK3Dw8U45y%SUfEAh|fbNvo^r@kM33Hz`%tMXmUi*kEW zaPg(*iL)a)>aWk8-ScxX9YGVbc7x{`{y8@)VN$6}A;RR2CO@)Eo~jw3q_e&zz}*z;o1(gW#kEC8p;=} zW9{B?Sgj4I@KIrN*GY9%(aK2Qhi^l*a50Iq6YVu{UgZuy5xB zH?mSR$tj-HqPp!G#@f=gsS~Q=T$%(d1k14)Bb0FY8_?ZEl&QUfD~-3!RNGSIlh9b$ zb-f9{v$;5{Y7Axovr|87lOF=lgnjvg-mdo2@nDK{-ppwY6TL3OurwKQym6yuoaZ?< z3y`;9X{^*>?j;v@tBN`0WXaPqU`HdhpJ-|Bex-fiTr!$0x#GBU`^cUAO-C+r8k(%d zf8U0E|F$*Z&uuGYfc54pZgrA3-bmq}bTZut+r*!|++qVr2U_(sxNMAB>wK6kD(-27 z1w1u!Pm`uy>S@vsio{5N@Va@or`hcABqlLHy8J^=i`8FkN@m)$WY?tXeRvzCSM<9lKEAf8>VnBoaI$9kY%-$vKdeN;ax>QZ=jqm@~1@36==XfKh z?7H7QXx)DRaoD8$!((okCgQnQ-{+_O7IXKCEGAz*<7KLxld))wS)MGpU*Huu@aMK&3Y=#DGVxS@7<7y z&@2>gUj@gc_pd|==ot692k8cXlg8xyiCT489zAHP^AEb&GE*322ofBkcglDkilFnk!G9KWG@~9gu8+!aOgKknlvXZ8em_kD#m83Nu_B zwcpq{9iCOQx$WK-k$ZpuIK=J#-v6c&ko1GZWkhF+;BwLx(Juwxn!6wMNtOM~lx6Ga8d9W1N5-XJdR$K4FYPf+ zi3#~IxH`G}VGcOCy#-%-9Z9e0yhExW80KoeQ2ut;taCS*WB%*YxBFzY-gmye!r||; zPMTM~@BO9bR&vkvRNkVDN#Lit2S$3G4ho(vLt`gw2+3p8t~B3Ochif{O?#Y>Vi!lP z5r$*Z9#lP9DW9vKukb7uL_|)3@5}9%mzI`XUP?LIF1Ne?Y;#W?GH$YYx^w0PZhaN}D&d-E(R_#L|;f*7f3$Nlw5Y ztFJd?4O#E6!rLxg|2p!`^@^j@>Ral6cW>bsJQeq|$j1*g<4-wC9lt;S>p4xV;dlOvpc`qAtwfB!R84Od=da*Kf&N>+qeCVApG8<5vH zqrCbw-?5CRFv8ZYu$c4^F?qw!_`q&gnE1Q1lk&>)!%Q>XnQ66`Tyg!PoY~ymV8{t0>>@F_s-!^BC>Sk|~mFrs0)dDW0T_GLJ$-i_=cT zS6ZOu*QrPm&-*WaojlQ9Q#4^HE_M>nBQm$3Agj~qP-T(RgwfH}Lch`x88+oDxnA3SU)cnvsOT9%;KbJF zg@9$?xJ8VOs36)&T=~8qv>4cl58eJsmiAhC&(o=ve!aRqBL5LvoPTz@8}v;{Ll|CK z&5tq-QV*J;>`w}n(C_i`R~d1+_0^u4T_q`nou8U3FFwP#fYexW$q!f=A(XF;8~7Rm zt|G*!T=V2d`J0@v3Q0uIfs9#Y^@RiXHL}qox|4F(c-|f}aG7@Y1Sz^MFBno?^{$NR zlp9JMI2uYw^HEDgr;K~**Bu@YnoKH;diKuk_D<2t_LGV0Onq7igljX@4jL9v*(M4- zGzUHAYGE`@8l$H>sycmBfaa5zx$@?Z;dsIc2p6lUe zD_t%?5UI1l0W%}LwQCM0wpfV+yk&`8U_$@kGS)lXqzZ!0Rnq=US#wp2xyNZgi%4We; zp5On8?V~#-5H&X7wGoE6hsw6nG(OTaAP{TzsgBUY&ALLz=R}IODTrVbB+J!!hi4X7 zyFe$saOpgM_VPzfnYO}4QyVpVgi zB|{Y+q%sWz!fdb75keZ!)g~5_`@w2ZewaOB;_I2Sum6v1p(ygiP#9g1-m|gwSQEqc z=14c4WJiSGxaQDBL3O(Mt2%}@Nu1*i?3kHEIjq53n?c47Jp9Qy{c&sGpuAZ7S4y30 zkWCsq_^)^=E&-1Z=!)HjPZW^1z+#cimErss;C2Cgl|>zkX|Zz}@F4B~$gF z4K9Y_490&KS1<@O9@a>HL@X-#}D;E<**}5sqxt36CCSl)B(Np)t-w#Ums1CL=+6z?wJl?hK zU3Vd%JU#a(t-GzeQaMcR2q)|LU1&ln#9XE(6u>aIU=qW;gefBK3<*5LL3fUy3_pPD zFvXqXV|w@r-Q=@yRb1<1@V)PWClxrTs0e?97ejijJ_dV}-Tmll$=g65D%2iEnfW1i zMrT_3A$M0I%vq?@0(2>ez0SinQ852gswZJge9$G-11XSXh>M0eXxy*k`o0IC6@e)s zzKIyeTtcgieP~62fO|65nF`)82miDd!aED^5+&(S?wg74=Tix_IjOP!HG!t z8eV*;7TDj5?J&!2u9R*}J&RFCCvs8OLO7IA79bD6#C6G7 z2prE_=a%eVEU_9W8C5LZwTORA!Q=~pQYyd{N}XdTocf7|%w@-$az2#f#)uN##ABN$ z!&KHVxISt^zx2{XQ3nlkfgD#tq0uOqX5KkK)zf#iSlk9>bQE<+h=8De5m36@BL7Bz z$p)`t9jp|e#lNOOPa&1hF5Rz*J8sHor$yWZ%WtxA-2&W966JM&)nUw`!~Rk2;5q5p z_(o^2iv}6SAg~-;$%T5v(gJ(XavT(D+7jjiyPQx_B-HVo5@1-0Hzg$^*5GFGx7n4D zHb0jHbaJt$C}=he4|#u}2~jVU>l9+1zQa9$;RNIH9W-jQh??9XNO<`xg}gaf?rbQkl=-jt7?UyiK<5lrG3I(C#F#_Zv!FjZ54eve3v`Ccq!SppB zZV;lO-uN^XUuJ>-=K~SbnD>qnm4bsIlkrBHXFDion=Pb2#9Vykceb6HeDK6s329ud z0NN=D2RuC^Uz6=sE8wbyr@5%eBu+KIf~E~(?{MyzgJm!blY-kej;SSK+qpUQkKzLs zFhiik6b0)tMGf}5cs26k=1S=um(Bohv8|88DoNPJN$@7Mwu1y1n;?!6tKH`JPJJU- zS%L{%RCgu1nxCB&&?=%zh!0DOc#^rIG_WP9=Ic828M2$9b~Pt}E#N@FelzrzHwTn+ zu|p(mA`QbOUF_gt%3z1?PQ<^gQuLhKU#axN;yx&~9@dMY)#s|d$RhHN$AtvNW3bz`J$}Qq1 zoz-Vjf4v7kqwq58Qa={uVX*&^p%X@O3ikF_=Vi})KtVVQd>9qQJs$#r;k+)04Mz>0 z4}*1wl2B%%I1b7Z6+lFtpeEofBwtY^#X}@Nk|g=uW1^(1P)_=Y8Md5{DWiFQUBplr zm@Xz3v(EZj71~O>DAidXu23CP_RYUN8n*g4c;eh7L^L81F0p*Q~c z)yL}Cl7Ooa!hVa|RzSs^GY5+SAd^$tr6El{Ro$g=gs?Vv6(?Z}h%*yC#6O0Fj4+&csyZR4NP_+nD7`b0OgcB%01_+Sn z5UBrcPYD^qb_g<-cnZnEV9;M&*>BwW$@o^{vAcZ{Zh=>8Xr8ZfFx?=&lE`iSDODE- ztjU!li?~fI3BLl5BR35XU1AsY~qxPJbtX&%oD zwfPCq$;QpHhb^lD%5dY8$9Dc5+)^ zO&M{>D7Qt+h1t!;@gUdXt|EMLEg`iJK0JMMX8QU;*-2&CMA~IYnWacV#PiY3{DMIc ze?jZ=%=NijBy|x+I{ugsk_mQ;`knnj=Wyv8M%(S$;pmd2P!a4<4TSKMCGu1xl9<>z zGQOSc)y%({{1cZ6+aE{0ix4|V%epNh+O2L#H6L$VJkX3Nntl`BF1|YcQUio`BHH`G zzkd?M@DqxA9`|jMh4E%Z93Bc3GvuLiIY~X_&aQ`Z=w;l!%W8o_9o17{tU0Cg1Qy3xVcoHV}Ag%!% zEvI1SNs@Cs`~xSp--|fkx@Z^#(NgH5_}=9E7Je2 z!l|H}H{Va7+%AH@b}vice3;gYsu$|0d?s&@c zcUp8z3Jj^ig<)YZNj{Pj543YGPHn90+OqWSIX`=|y1^N6FL|__i+=MZrCpeYGfWTk ze0Z1O5@!am+3Z%|dvl;9pEBY9Fd16Dn-Jnt%MSY%-!};Y_xwWk{gvuEyW9>|i}>?l zmGzsQ&&fVdt-%FJJqL$2640~n&K{D9RJghrfq~Sw!5qN%&!g~}nRSu&w@1+hug)yF z%vpn;#B$mR1ReYKFj!|(96Ta(H06t*&41E|9>xpzo)Ofg{lqU5DT6e(2{v704c|da zNl9|WCW2}+!axaB_)SzjICQu9ZU4j6@LvUA9wltx0)<0ty*)3nMLC4EPuhoMkQ;*r z<+w)+KoB3OC;G#Sav~01A7aI_Ztgbx*#AZT z#121+PQ(RvXqdZ4Z_<$|zC_+1seVBUT=li-(d#1eWR~s=m}m3Mt@QYRSCqVC9_e~a z-$d?^n^EaWpQ|i*S$f&~icRpN)2fP)K#a6)`m~KR=vJjqRWA5_8)_<~cf|f}H_apJ z9O#T3##Y7E>F#Oji`ZtCPwgmj7tP9?JQA*d$>)mKv1*@>zAZaXR9)&u%U<&9`uBcp zy)Z^UDE@@>y!zM22GrsHrSbER-&aFh3m=f1{64C*c>V@Z8*f}D)wWgGTX=n~^$%6m z%lW-?=1X6a>SCpf{O7I2D-OA2XC;)I;@Fj-IJxK)usNVdWNFc;;jZkEd%rv9c? z+#es}cs_9h*@#H6C{%J0Ve1yv@Yze4ZT}46%=CKFD9-4g_ItcjuzK_z_MNq`V&^Y4V-*SZN0?Pn9QuS( zRI$IK=2pY}Do-7 zV!vM*_z;UNb|hl1_3r)nCRXKi(5N@p<_p}kQ3J>r#_va8RLe_0_%|ER{N?a-Df3^G zN2$xfHl|ug!}8kJsPdx7Qr!irUFdI@SVHc2b-niBdvk3E`MSs|`*W6eR%A#{Ytuh# zeNHP8LT@~Iij*V$grec>?|96mL}YvgpXyDR5@9kj*4_cJma>C!ziWO5v>S9)zRcDA zefaZCOflwtz7i(wPpwJ~HjJ3PRWk5S(IfH`84t(d#?sjOWR!AD*U5E+z@%e~sIE5w|D->~7vmyxVV^%!gk>ZaDXgFs> z@I;hU=F=mUf83aDu8#R<=v8E3J9Fm`Px;LUSyxi>s;ns4t9sM#B*n4IpSCtpax>gK zF<&sP`_k7k)XYORAM1Q?Oals2h)Lv=B)42=5>T4BEyUOY%%W;n(*1yazKa}AA zGD{cAGwhtVk!(CwpnLXqU${vq1&jBZD1 z-+uP_O9twzL(tEK+Xv6RM$$wkV)RS1&Tk^Zb`0VaB9}OCnkAXu+`<^w33PI!p_xJ_8paICri8P6la#=7=Uu9fuS6V zWh7}Nh8NJA-|ZqUSN{iOz9wkMnZ1-v{eAo3-j^4lIa{Gt5X#ugg)PVR4qO25uHwB= z3e4&JK$ifLuFP+uOuVNTz{srSG}gd>~gEnW4plTi!v2-GZ^4OV#9)pGCKc8kGg18YNri*TK`i` zY1W)bjQ$~NmpdGETYD+qC5vV=Ru=6<5X58uFT&pZAF4kN{2gXrm}6h7u`j7cB9t2Y zk~Ff5jD3j=ZA6S^#;%biyCG|q2FaSnPAE#2QjJieMLVVDdp_Uq_i^v{-XHG$56+p# zd7Lwk_v`t3K8eScXmfY#)Vj4zU?CEV+=KfvBzHy&p?1lFl3lS~gkO1)#cN`Wi0 zAcp*q<^mg`kmiS0YyYOZYB=l4dMV@kUqP`3mn1aPQTfX5#&U8_`Uheo11*e>kb@J& z`>IF1i1~a*Av@5A3Vn%}DumKab+iLsYBM#-d}fjZ5dmk=j|q#TWzIQ6$4_A`uNX|2 z10pL@W6W2_TQ~`l8ja^}6~D(vP_)ahwF#H4Jqhs+6DgVLpLVtVUbx?6q=uxFk-xTR z(VHRp?ckd|VY+=VR|SU?b7vGoDaLAu=NVZMU202PW;!Tyfaia)kWlpqb3fSUl{3U! zlJpclg%icut?}_wr7h3I#HAkm?kUW9ul)%)8t|+!^E&6u@Imok=`N5NT}|ge+*$Kc zc3dIhnXKi-wi~7_Q@C+k2gQQYf^lW}infyM&xsl`Nwso{Cj`)b=KS${Uc6X8;yMs= z-}5L(GzYv#v+Cv(%ni&#iT-0zSFZJ;MFAM3F^q%h5caeQE_ZCz7&j7c@r2fW+GB?u zMi@491mqZb#qEq>9nFFJXaDZEylF;!)soKLcV(}!SZ885AE6=!s~#5SIyJuwb!Fh& z9*O*#>jyR>W|53!GbyCu);>wqGU)@{XXyv#zp`9&cyI8*qu-9BHq{}kUc#ZoL?!Du zmFjCr9iM(5NhI&~@-$2kkqv(+{>o`~c4J6NE-Qq>&=axEH)_1|g|0!4JD*i)tN1$h zVr3K|w2`zc^5y5=Tii{&BDQhNpU=Pswd?8t;FM4Iprq;tz-&lxv+?oveKObIYkRfF+D zm6}l+*ubrhxO1qX9ixc~-eSy7G3-Q+G;*>1x_P_fBq3|G0~WoW;iPyf-ctc}?01sD zlPb68M&4-*2WI-g{CHVH^5J=YCz7u5AokGA(K{~i+hGDnoD-`F@uFKu`7Kkm0L*?M zK`zI1B+aBZ!i11`ryWY;Bl78OB^>KeH9LdS`7(&NyRI=&C3N(jWk-A*G4n=bf)B09 zdj;dqPTRcD(zBJhTtGLxD&P}P6U$CGi9+vV#S?)9a3Sr;=7<&mU31RYB$@lbR6i_Z znl51ev>Z4Ar2%X4d)MMKHU)Wl7t;L2xB>7ZGyjKal%Zh zSNV0lMG03(Mj*$ykDDBeN<0k$Yf~64s#uvKD#2%LHcF$90(_i*V5LO^$d$J9a0r^& zdZP8zhg+B(i+B(Pr6D{lG;0XB;Cx1<%)6ChoA?Yb7ME-n|pIl^ReO%OTsBzbdwhtZ*u4L^!+a*5O(aWYG+ej zE~0rx$YeUBdrI$4Cwh2rNJA#20Gk>bXNluWtjY$yJyd$q5wA*x&Pt{j1sjn2PnIv; z#>z?YucW?gxXXi(_>75g&tSFz@1#a1?60-{-2wB|++zVj%LU1}ES`KVd+@=848)nwlw3&BwJAM)#K>h= zppl-(7Xf|EqPUI@aGB^l>coag`f*}n%M(K~(>Y_x zTAdpe5l9{Qk^|_g>mM6K8|0gyL4x1;XsRfB`{GfVs>h$Ax?>?U30mT5+RZxIL*`LH z7X*=Xq|pZiF==!qaKB|L;UI|;kkd1 zf>wsS%MEEh^YBz|&dr(BV|^*d3h3H2D7OdDRUIaBre)#wBdw=QN%TwEX-JozQ!ArB zwTyj4TH1IVPa&C)f`I=;HdbCgOrra)COC?yA;?z}hP0Np|kDxi?H2)1If1{}A+glb&4 z?GFfOuBNt6!6QxjZG_N9GEH~6m`w;!!h~0a37G=b*9xAwzLdEf!r~)Byaj0T0f}!` z)VlJq@sQaE%cH&^c8a2%xkRhPp|SJTOzJGBHem)Pe^3l(zj?qaD`%Za=N095cG9$) z$lw_zox)P`iHDtVuDLpGcSYMpF3Ri-SS=;Y^o~1S+l8j+Hu|$+;MGG3w0l^zuqqdSDlE+Nfj{hd!`E2Z3SkcI# z(z)}`8@E)gK0hOk_>0=!J zjVX@hHQ$}j2txHYOwk|7puI1qM(Mc`8`k`1!4~}ZQY(Tdl6>{b&M(dS( zpT$GQ^R&eeg|UV5uXoZmp3fOL`qpDB7CG=!(~OTX^k~liHemI)GYsxct`Yg4y4aM5rvnuNDz%as8eQt!N*Ag6=DbB;7RH zuLhH)KSjU!yD!Y~T@*jW&4H#=o9M=Jq-8VQI&_QZw7nFl^@0|13x29~_LAdnT@wA9 z?(+n(wM0LEr0R7SA|i+uU}xdZ+dTx)oriu%Xa<}e7aZ22tdcj@*O;FakN=A^ONJ|N z(;em$q>~|V@_!X+PIR1U10y8JFY8g!Q3J2yw}JC|XQ3dZpHD};S8(AZ8anf1oM}C~ zCJvC25?0qrkL`}dpgr@}>ltF|ZQAfDh^F-f=MTJucz|EBHx@XQ#X=+wuebSact;u4={#tubm+|qXS$dJ@b4Kmkk6iKdpX#cMY}VAmUoSbHf5hML6jAd*fek|xs(kqdMU?!lE^@9zKn42#YEe1WdNMyqmkhu_?M9}}1IDezzE zCeG)TSiko_gP+2fcqS8~7m*JtiP8t-~g?x(G9YoENRPSoOfe!%ke!~b%J#LPL*gz$zM(^45E z9ZOjosA>6f7LO1)lw#v&xtIxcpMGxU^JPkw>Y69@B3kh;ZAI9nA>eJ%?X1A*G_Yy= zt|a1Z-MiB0pYPw5(GcoutVHpkwen=;+iMl+I_qnI>qfq$QF4aq>4Zm~K zp&{iB>{NYE4JW-B^oQe}2fG8r_s7$vZnTDY-fm0%ul;$x_q$RX^dqLJEF@fw+-NEw zXWzN;wG%FC_ZRxvaQYr{ruB!g{*b-Yt3%}{&8B5GOFWW~O!cA`h&cjT`!v?XZ6(o~ zM#p8#&!6<^8}e%t=Sk6fej6#iA@^K!Ybmv3^)wq!e+53&Ya9GLC87ABSS1TKc@%JI zD`EIH>>pUs>^im)3BPG1vH}w|)estb_T9Z%&H8WGi$kR@B)J0|S$r5Qg&~mj^s2$! z-P2Dz{3Aab@4eID2}GZ~d3wfWhGk znixv{nEOCD8TRQ@+~uqxkER2M&W|+3d@q_C<>_6qFxGf)+h+9_GI#IUFUytB;&Sl4 zUv^zuTD?7)X!{vYc z^+peU-BW6DnZ6~!wlZ5f+0?6aU!m42o~JM>I(j%OB(OSe&)BojM~METeW{6JQt=`! zoIa*c13h!V>W}W__K)e6u402rk9nA%omUD3Fv%hnmC@Oana;ijRxmM<<2NcbG>ECi z>-~NE4;lwuDrY!X+DlZk2NIpDv^-$mk~il|4~BnGEh|6Oq}o1g?zv%+Dq{C{&3WWu zwCzEUqopFDtBuDPZ&Bu4L0{7Ha9`wS)!0LozAIJ4`@!W|NKLE!)J^&UiyMc6tgThx zby-ZqzU(rbfUA+3q+N(7dT;k=2kc;?qI_a*-J$Hdt2IYbCk|dQotHMzO@8R+H)ikQ zj8;aDR5S81xG4=|saXy~J134Xbm*;S($tCEss<~|LjFAhPv|!4pRGJ#1Bd3=2%^sg z|IahZ^oNm&=X;wpG#W&}GAqwCRP8f13dFu{2bz|4HWYugwv~W68|@~=9XU?z*G2ZX z9$W)cmXap>Zj`6FPw zE%pWm-M?^^b)Y!7z(JiW{NXoTPcmMlb}LD(qAxv`q#!*7Ip=(QBlTc#Ut_ufKIn>B zH#*&?2t*z;IQCs4!aZn8x# z3+;2pPSa}g`=!LE@^^96{6UQvA)MXfW#Lq!*`cHQSkXBni9rfNi{+W3jq8^frovT- zUs7y$mPOqEnwx>dpBYtNvSn%jA3$ch^hzJOG6B3o)L2f+si77gx&uv{=9mFK;iggg zerwN9hNL$QZTY4kwn=yG;1?UGF;ad}QkLGz_oQwi6-70ZW39dL`L%QnpD))Pinl}# z@uCi2*0*d_8ymd{uWJ{YyP&gx=t~WH)Gw_pgmszf7t1AGR;vDJYvWdqS79V7sq>+9 zAr+#$A>W?y}#gU>n z@q6a~esZx*4c-u?gX3rng*K?Pe>(UCsX{29%BVUX1}7!=i=|E(?^)kWGO&*q@7>bh zciC{>)tO&pU~6zsfM!~0S;u#D3S3>6FZr;w%6^a$Y!5t3*W@Shacj)2Soy|n}^n~csNqN)i3Pe=k! zIk+bfEOjcbz!6!siB+(0TQbFVPN689$fiyD`zv06VfdOvLVZ{))Yg0IF5HZ%cc~xh zK!)qmuE>9d8c8Oas9v$9BCZjTAoRA%2(H?+bF0Qa;E~awtL`crS%AQXY+X~>iUCtx zG!|B&h9Sy_ZJ{yFCreXR0pBUhmRm4G3XI z6vPD%DxZvL05BkqmdOP<0b~>fQ^7)p69KSH*E_}VNQ${j#)2Z)S}vxI6|X)DD4V5L z`M=r*tgEuM+5;|^Q$aLp|`rgDk?@O&T1|P05geR+8J=qq<3o~g7+@F zZo*En6)c%}9uuz{v8|hjALs-VRj5OHAm50GmFFY-^3%~dW3@S;Vi|PAmI0_lPD&mT zlTE|i+`>yZVRJ9Xzzna}Q!qR(W?cnaeORbu<05PK6ePy^zC(l`#f3lbTznhZLr zCq~>ee`2Lnu~qCC5JW87L?5`!Xxj8zb{0+`qT5(0Jc=*a>H?7s9;+x^N??HmJm%uC z&soabtcPgCSs=idiSQx-Pb2ds`UF3d04pg}9toRIOo6yweG>LS36ewQYhG&E!EY7HpoTa?t5N zlW$8EDd>XjSZsuPp5m`t@^Ll%D!^+epp%O|ZGMXf)I~v%*N7Qtp7-V=n8?ECC0L%i(dNn?T(x1;fpc z>>^{)zwp=J;hs{0Q@P9vHs<56h9HYP1>37@PPOoI?8R;T912^^3FonpXC)|uQ(@O= z;Z@v_H~LLmNmbCWC{S1mrjHOQOwg==1ZA!vAVA1zHI%taDnb=f?wZx33#TxkkeWX$ z2ZRZuh$yH(d*Tw&d*SotI9 zhy`T99BY_~1KX(}aEJTT=Eeu%gFwoB>JH^sxws;{r;0%Xj^}3alqF(HuM;H6C`81k z6}Sf%QT(FQk6d9Hh?`>8caw4U?bsH;FXlv?-fwh1E&g=M#cGJa7!A|S{;xF*=8$8K zVBp=DCIayAH=sBdgN@5rJM4zgOs#6i_K~o)kt}{qjJ^|cLgGG!4}zdr~~=;hIR*EirRdwcyMC1oFK-zd=Jxy%w+1XIF9!6lBs zz-BPHJ*1d$wuy4dRs$#|V49h27rP4tUE(Gsa`TvF;ETg^`3=YM zo?)!_F}pQ@f_Bk(83=#*{mVz;G+_9#pYK&8t3bJ=S4D_q4IuMKxfdJZNt$FtkAAx7 z?M_8pVI!GL%q=RDK^g?9#d(gvG!ffDt({YKD-*{Wq$VS#(X|xNIE?{)&O#ahQ58rw z>v<@B`QZs*_eL``16cDPhsMQ(Mgf?YBF|6osZwFr$mz`L+WR;a=CU?!RczvDLLe>m zjQ)UDF=ECIk-7I|UVUompjO6&(*vMq^e6T;NN&!sFzqxP6TqHPb}NRUv)Pyd0M|@F zMlk`~9!&jISlv%W3c3#X+7v?4q^)_pqQawnf0N>D5ky-M^Gl?0t@|MAD#yC_4+=mi9BjE0Wa!Q4KK z%i}s;B>+*>s9-WOE8lkV%9#PIkn+!aq4%FT`2mb)UAjf9 zxt~6PD1RL->>9RD=+&PW8+_p~S-)aR=~}x07&&N$pj#mVy_}1Y8`v@qvvw2F?GCi7 z0Lt1oo_+^G**B$nuN*%DyVEMMhB(zvF&`&IIO%}D`-mzVMkAh$#^CIcEjxd`rDE!~ z+qGI-;ZbDFYa}+0f_75DF0lp1xVR~9cN?d`-3-@C3FxMv-Pud%@>Q9blR9Q6gITCM zYN=RHFQ=2KU91>r^LWVfBCIryTKZOCmnf73IneYRq$Ne%5vl)EsQv(gYo8oHatzq} zPwO=AChp&^xet}AH*Z(npY(|(-x{RH%OS9@*#edialMet3RdN{ad>s&BR6 zs`t|spJIyF@3EK)_XZU|Of}?&cgYJs2m6{35m7cI@d)rjhL1L)MI&G_-5I;IFZD7b zA245}Jydz>jOhg&Ev=*k{pRMr!_ToVjqk@Mo1eYADX<6;D0IejlLc;>f^lthatAz^ znF$Mvn)5jsrV9KTd8drT#;5~|yNf{eViRfO_0P74duP1`-VG45#=1AOrqQ8<1A-** zY!9MJox!|scb94(@BNT;8kWt)lt54*-}cr(YVQ2pY~{;}9;Yx6lHC+|#U4A$3qXS= z`^W5}0nqJE!d_#;4Qv3ZPpdNLPv$WjHiK(Wn(@)UW7v@M#gMvBNq~#{u!*Ld#cgca zW{x=(p63MqL5R7t9XwY0!QtJ9=>FXqY+N?Uw`W_l`je2#fs^w4eg%VeWWsti;ZwiE ze>*J`#33G$^-H5nTSrJ^V#x!7Qhs+~Ou7eVm^xg9l}|%Q{Xq9}Hc^wJauL1{NH{hb z8ASuVyoDI2*-mn;FJ9H0EqsYnkgAWS_eu%{eWtLNLLrDy2x_J7)*?;d0RgK+XRV*l z>ZAV3o`OHW4;Vi7shzQjKFekk7_UYOGfx2#(%b8YL5p)?D{u2&$BvkD-nip&%$X@< z#p~d8^9D@4*JR-`Qs|Fsg<{i#TEsX>#K_=3vJ0ngu6gIq}WDZNaxh(ycaKkEVa|dXph<{BN&_-a$#-RI~T4 zzCkkW9*^#6M*sZ0pkaSE;1d5gKTY?sOwH1sC*Ss{Sm*JGe~o{fsy>h&9kzd$v(Ss< zEXjn%eLgb)y*%nOGxTSqs#zfSevh7nC%I*X0xhx@p!ho1* z)0>995#GI--y>487j!j+ZZ!mLD?Nz4F`y=4y~4!g7X90XH>MXReBlh#dfVjb&jr-P1i-ey?JOALR{qy(Q_>;BKAICl=4{t z(?j|O>Or@U*=KG+g{>)ppZ2chVtCW?C;#=-?wpb$a%pBo5 z^X(Y1%Z0wXCr44~g%t5ysw_&jv!{#qw>c{f&8jS)yPg(@0xMJAO8F1BRbrn#4?cBr zG!tBZ^zxam70Ea~Xd>zq{(LA0m?P!YDO7K%q-y^hwaAKvg!$g|*jx`gRuJ%|D*M2{ zTE)Xn!PhVk+Zb^{g<=2H{H4>yOYiw)8|X{jGWeP7SMY*(RbD}knQV3PqFvKon;}HO zps_3x=}566;u)w#DD(AlnjDW+Nax*0*(Lp2?5 z$~3x?< zeS%~{@}{fA?GC;%Icw`v4$q7IxwX9KdD4mT;PjbKvI_RF<%n+?%tF&lZRz)k)vinT zzswd=zNbkJmG_$wz1CZMuWkR+6@4cx96{hq7bX#6VbZ#gpcgN1roWpdBy25?7S2cw9%_CgI)KN`H+fw`*bdzj+Bfv zRyCA*Xmf8Y`{TITIO;GFI;$wNxFxK4xuwnZJHSXO&y;^iLD@9$pN(!Ei#b13EKxor zfrY-2QL^mb_cAQ|iPQ;&sk@!(|BSPL@*=CFnK^1 z$(F74 zGpwPTr2Gz$oS+T~v)D|a&?|)E1sX7iGH(Tlk z@fM~?nkZTGO=N6k=ouJPd&o-V_!0+G}AR<%k0l`J+q+y(-4qGskZ1O6oLNQ;Qet1;Y z?c|6UxmAEqK?fBV>i9!wH)W7tl8@uHl%Q68lGOg-<)VkCW|}8SLFNUiSf@1pF4OsE zi{$nIKmR74e*!LP`rg*%Y|d@h8M(NhJDj;qz^SFhA8LF{xT-)nstMM;6X6^egE)Mt(sI9t*?W6T+3RYpvYJLx? z@VlhA!~tb~8OfRwZ*LNgeckgO?j{-xypElRNWLJvq51Zx8&eX6couQW*UmYgdo({1 zeD(U$+MD@-zXN?|3(vcY^JwuJAC|7XfyI5?W%m7Mrcb#sSAyio0#W>~yg

t`l#&u;|xQCpbWRH8SSNdbT6^a9bzng z72@vL6+UW~J=fzgd>wf4+wn*LV+G@gKJ33Ze$&KT(wlY5b?_bs-|Vi;Y7Rn1YT#Y` zegf?Hl(7;Af|5B8kFKs;&7LtT{SCvg#v?YgSejVfXwMVMwS7Y19+q4?GI;V|NCrCY zvt5#^jKtj&I$O~zJbyv%9w?2|=K*oGUO|YTUBF+kIWs7H4cNgt(#l7!{xUIZ@&5-`uyr#?k?KsDbE9(`5}7lw}4Eg<>E)& zXtREY)B}sWCY!S)-r`#QttE;LmVj>RlzTzGTbTpn=` z&4Bx0{#@vLEzhZmFse!JS8hN{F7ki8kSe{?@Lz9CfG1xU{HJB1Yu&>zCB1GUJs~6ft`uo=gE7M_1*^z_@_2+pG)-}6?juV z#6M`7-ZA{HXg^p5(w#TSAJw>VFw=(sf^K~2tbv9syeX>J;x~PYl6FBJ;p_}o66ORI zUk@HMi(X9T;|v~NGrc{E3fnm-yaOlgAgvqF_W7NI`H8_aGt2mqT5|i!3t8T^74t2Q zMY{D-2nP}>TbDt&9w`iBXwW#o+`Ty`O$(t*9KPSeSHraI;7Y31!4_3bQq%|iRgG+Du!LzSur$U_ z$2MD!qL>M%^5K7uWKx_N0aOMhg3lX9gF_^%lOGP$Cfu5+wyf1mS1m78g}zf5@7t*? zF*ypdkvX)%uPKP2WQGfs#s`i)bmjiu5F9>3H={mq%26$f>`b?~cL-y3!0^_-ZFr@^ z#LS{BgkpeWCg@5_dHNtQDG2L;hoHak$U2mkooTj}@ZgLFPuepz^lRlbOgzp0WU;1A zG!)`K12Nc2bW0}rF_|IG2vrD#9|D1I#T`;-Z&6EDg7J?;A4e-b`Z|L;aVSn-m2PFp z@SkE(ISk4aWH$Y1+;p;?$>YB(k28DpMAi~c6J&!_lS1MwO4@-A1uwz?_Wfg2 zE}2}^#0Tk0s`jHzr$yU#^Aq_DrV1&ebV_X^VTzWx zgA}3VrL*FWoB-)ZQ!zN$;}air<2N160yYv2=K1ft(h^>bbaz+q z3VNZZPMIq`J6)2th@shPLvY-^`YVj9MOd$SC{ESXLi^d7A%~6toAfnWSOnQ9Bvp{8 zJ2vsmOMA9mcZA`S>T9oKt3T^++7rS(8GS@4pl#M~0I?c0a&C3@dmJP%b2)8FSCVvU)|kt3 zSQwOimV0U8CVe4)vMc%IWKQlvzQF&Zlx_Y0r@pE%O@i>dEsi$d8o5p|PL;K6sT|8z zwNrQdV)TEiuTW{g(H2F_qcTzgW|tLM%1+ROeck#Jit1A`zhzZo)pq;YExmZ)Vt8Bq z+#OJTFu-#&sUjcOSEwWZytI3W(Fsq!5+QS`I} z>>T=`;}S#m)%OA50s1Z_Nii<~v}5{sg4;u--=TJ<0rPLt_x+xm7Mh%{RY*F1aYV?@ zFkh)C{fPJiMR0S0DimW(;w#P~3pzX65$@|Iir5{MTFv|6?(#&)C17kd|IHU-Vk&%B zKo-UMpRr;ARo~w)FYxMj<5aKVx|;KQG6R?{f_$CNOB3IYb*xyiLHhrp zG>$>X+qZ3_8rRqB*_V0xrj;UpA=0;+-%5)*9kUrU7UkTp z+hFU|MZ79+du#Eb<+yt@tP%g0rO`SwD{2}fy5RWno?5vjvsLsj2Wsz5J=bLUO7O0m z>Cq|1M(5_)oKMI5?x|1T{qlD2XTvkjD<%?u*Y|Gr!Y20$9X8ShU7HXhmdD0tIGTRiPnT9xNJneG;b7ATS(+-6P8KL7mQ%-1j)q zsm^--t`;40*+

RSwtf)j8DQkM&r)Zq8d|81MQ-*3e3{kxh5_W7;%c4w+!bsFS9 zu0-U9f1EVv5P2*fpQQRaBkj5)-+)9D7!)|`g9%ei|N1X(NNo6%Z}Q!T{B;poPaIC~ z3*9Mr!PvSkkujcDP>GR!slZgK6q5IfUh?Q7!jPiwAbhG8FO zL1ktv$JJQj1T(C^;gQ70{<~o&kGp&fUL%tX@(+O~NjNBJOg(MQ4^ShFrBM2hGoI99 z@9&IkNE!`3(G)epZpX_)JX22XB!~=-GDww6xHw>0qKyeBAdKvaT2M7E^JhDbT}+(O z7(&lzj7t38#Ge4Mk&NVF!#qu<%}zpvblW;(W}(vv;fZ=WU3a(Nin)JgX%DkDQJx5< zpmB*($@F2Zd3CJn!ynbW`To70BRNODNA{qH3R`gb#vPjtoApSh%Gm=-&8 zQz?;I`PZGK6`rtY_66m5)Q|wD{lth(ze54%)5>q1coQPWJpESrE8-w*VdiA%B`!=|7bGi^<3(b( zhK|o1#kxm0^W+}ThK`%@r5yiYhz}=!lvo^FKCV%YxK|t=QQK)ToqM|Gmi1`bBmak^ zOQJOtZgVlOIaSYzALwH;4uA$USLb*+bLDTxO}=5-agn9sG?Zxi}7@Jv411d#Yt33eCZiy?Yi{Hb4x<gL5!Q+0*cl5AH< z$!D1dS(}m8({VSVDbU_OB(-b5_*NNHVd~ouOf<_xQB@AGalS9|n5eN(Aao%K29<6G z$*1&G=DmSyy5V^B`%Np|v0Egh{(Rhe8U$LhNkQ^x_id2Ei7J(b1X}V?Hm?=?14w<~-1spky`o7C(bIn}&J4)`N4Hs&~5_8}}YhE<^g$Kct5GHJA3jdGF2uNnscBBT>rq*qx)>+_xQGqxnnny%ACY>o`1^svy z2&O2zH*phF;QTZG=c;EdH9gn~aO?mcJ5i^dQ;>3Gpw9ye;&f{%hlLQKVy8ZeBHrjC zTp@96$+RZbwDq-A|1G?qDq!XeRLr8aBhPY>-PJ|u*7mkJdW6FRFRcuVi zuXMq%_?D^Y#Zie@&XlDsyeARiNlxWWrM~aTx;>w{wuQf<3q)Han)_j<8R!RWY%h&k z4OTD3aMKWhdQN(f3a}`SZQ;={wxRW9wx}q;{n&D!Vkw|Vn>pxf|l8nx`1H;a9k}zP)(Rh zax75=eyipjSjt$Rxp`?B+#N$s67wgi0`y3Mu0RAokOVJp37)jXuW$q_ ze&Wq_0FVxdrJy++T#-0#fR+amJ>AdFb>-l=VlA1sX`tQg8Wf;xDj)E>Hv1UI6t(gLCIE z2<#IGuKp*!i3P@Q?Qel-54AKj5>QwNlpYEd6RmAMA%YbC@WGog3pe=+5rKqE9d(4h zI^v&R&A)9tD0hk|y!9s;cm?2m80CfA_~pndUnNXE1?_;rvNr=2c~0RO{uutc(rJ`P z5dt@KugKFA0?_#FHjxRp)v_JL0&iQG>mhM=ogP>u-=DC+|U{X#$1mu1v^J|vAuoQ!mtHC*UHU-m6 zP0kI6QKv~xU&`Lxws9rh;`hw*rq)DAXTg^;aPKnCvdZ9|xaCd!%l`(R0#AuRADL?Q z1MQ=Xxy6ax*2V;hW3y?MUAn-uAF5(17HBRVxSX!E?&tV#@m}>y47PycHpn3s8 z5aW2p7GP9it;apvn0Y)}kVRod*AH|n5m!b*SqA~xo8^Sx4Iyg&@R7y`xmY1h>|M$| zxLk0OYH%mz9#uy4s~UhH@hJl^PzhH>NPoZ%?B;~te9{uoNBxl4s+ZOZ4QsvNULuOCYlXg$ar2m z{FdEyMJTiy``Q6JP~`_0Vr{qX!KMRWy)P+N?lHD)*QCO)5io)6p=v2Dz3jlABCCrk zLglsc-kg~45#c#|u`js-gFLDaB+a9jjXUpvEFoa4N#Jwh1?@wCGNG?U9lo>_kTP@& z1jT)rC#VWx%?m~OH+HTH`JLFKUv6UQ!K3P+>u9Rt zVt1Vr8Cgxnf^~QfJ7rpCj0YK`X#lS^)a(fU4Q>)z)&tKhF8Tt+muToG9hLQvU>-++ z2aXdydQY&{qA;w@%$5g3EuM*M-qo{9Ki z6&{5TVcTc}K^p%;_K)6GUuZukKJ?@Wz+pcjrK{bg{D%epz)5ZJ+<*^?eSgHU4z7NY zY69JxD>os7ImEv2}oX{{K zSu(w6I`k?PuDXdwY~rPf_8@wBbgaN>qGTz({) zZlz2%!h?*==Jd2sCK>rHWiKXsj?7(tsanNCdCwvDeUyxvoC{w>md$p7Bo?_1O9SPW z?8aL^(6jdtX6-`fXkPi$^kM&K&~WH-4H$63n)2>dy1yuq)qGC>AiUe}Ue_j)NcwrX(oF&kKL8WeD)1G;ZPuaitiEoh= z8d-75Cr1tyg+BVl3OGk?C3Nc6beC-`2-|Wz1w^zYu=V#{1nQy~Yxkg@V-Iql@EaCp z^h^4Kr(V5&hxdbny`L}r>)zjjuG2T35CBD`ZS2J;~H82TJ-t)3NiLlyYZ7T;C0qTU&J zIp#TLnm*x-;99AjB*U!OAEM)CpmMH?l92=4&QzM4pxj6l(1?BhI6f7_nJ6i`Ji#x7 z%^)Ke{skZYgeAm?jvU2;&}9Y@b9NkPc{zEsXC1qQd&I(8MRY0IBA%9XoGz7$uLoKv ziE%(>Q=el$0@8M}Qev;#Bb180YZM<;D@Y<{Lyb^v zW7cYm+FFgh)vBs$YgKil3st%Ey|4S1`?}6QaISN%>zw!N^?W`aH1i7l8~7>)<|4$+ zs3um|2}i;O7b)l&09#EfI1)2Icg9&Y##~LPz2g|B_$#cl7mn!`3_|{*!G{y=IX};F zLe`;bA{6qE6kNTEOGNp?D}*VC}%w~QTrzM&~4Vo0Hy>0^C5dQ zIqG-Olf~L{*d+Wfs}tL6DEBiT{@yfhW+WVn6;z@zFTAOAPHFukhkE`(;-n%h^+pd< z8umzbu&wGM*PsJy1oi=myk6}i5ay49X4wOmN;ZZc3)FE6gX9ohQBhUw zGx#6xW}7e2z5+Yyo$gn+N`E{2^__p&Z=_x$BKMbV;1n$6Urk+u#*meJV9W;6@k{Wc z!E~|b4-1voi|{fwV9ots)bK%CsZ2ATd)1~+`}(&vng5F9J=zOo%}+nSbMbegsYhH8 z_Ak$9sVlpzeSBiXEN*f0t=NUFumhI{fT@FnY0uQ4&r3X=m@9=axRGxnj=j z6i1Q665%WYyLp_Uv`U*z^+dIVsbqke1TS<8U;s4|A?m|f7YVo1FiwFt zTf|b4h`Pjd#hi3yd4H~d;m78MDzG*XFWOr$rfQ^;g&@#)X1yyOYNsa;$%l(rozJ6U zO(a-&kVL-p#3=^~pJlPUTKa{}om-2*$^CoGCfsb2x^sZX8l2laR=3jz8mA@CbC|TU ze}>!GNnkF-Qd+#?13JSUM`#9^ zf*hT3HruQ%%AoFL*yo2IXRS=wV_e*Q>ZWC7@a+dSHVE*VDFfh4(75(3WKpKn@OJ}U z>P#vcbxMzPvzB;I30Ey|n!hSrcA-N^R?**G&}KOcln}lrOt~W z7$R}i{9!vm5OPatpkcn+=(yy+T&1(@<9jOKwB_rwc)iXk%|br;Wn`F`9#M2|1Xmzr zhxHs*0@O7&X)J~|$IWu1LdX7aTaD5nzBbmA9%?`2uxlq|zFGQ1Gi6Pt%*QUhhNC1x zD23vbvKXP)aob+r>cOG`TCx*hnW~a*XCqP#-o=lUq@N0zv775E*nFAp_@Y~Ov-_W1 zUwTu@u3%`!$AG!!Vpg6;i*I}iLg@{hRs*=eXc2_w(>`Psvw@u#MQ3rs@K4Vrz>JZ$WorD`%31w%j?5CJ`QHQQ3B!ve#a&RbA;yAr=XW75wM`xV5Y7KKr4>xdjML!4rxS0ttr9;jH z7IogXeWyuCz$c*INFdwpL#3>%=({%Za7KX*aanApB#|o@je8KF$lyZ5w=5DYfc)d4`J6ua$SN%9y3NwsT;GSc48IYt&ap1))?E>Q#;>hur>NYxz&qu-Ow3qZIm~jr>hgW#{P)zqbwz` z1`|GM5EjD)RrM@K-e_}XklzCeyI1ATeFf>RRq&uBeux~RYU1nY==(20@~*BXLHxA! z_bik9H#Nzd;%^NY1?S5y#*Kvm0BB?Q&(<7_w5;P5*BRlO8fuy@r_g)@=;=TpJTeEw zOG+AkHPt?qPHb1EyI2qiAW_N8?;hwNSdZVGPx9O%z?6(rIvg%;c_4ikWbLd~8;c4v z&J<{DX8eK_DDuqnhg;>rP&(YO6ceb8cA<=fl2>`Gjg}GvwLyuHg}tA2~YF zb{W9z!t$Squ)I{Zu=5ISP4igO3JY+_hw01&o152 zNF2;l0bl@=l5VKwQSJb<|0E8}EeP*F^PU{O91eQ*J&T_U8>oVT-j-=~X8+QiE)XC% z+(3=X!jSCu&75C;Z6zi|nrwbul_a|v!_WQAt%rFyLbVq)Ff1gfV$btkQ7THHhXyq0QoDGUsj~3{|kiI({t2_?m1BANoPV(sYW6(crxs- z_%{Od=~)|LIPAasu{L%W!}jdL2!6?iHNzsX7iZH1K`j=zSaZF9Vpk(=nGRbgecOlk(878qV9R8Gx%@_rfkqf7^W>cyoZP~ad{luk&Av9au+$;6 ze+xi>x^XUj{gLE<2vua<0<-Zv=2LXmc^vi$&U$7@a9Q5+T>S!*jxYe6um?aAhA&p3*AV6`>`f(qt6-5a8HxoJbLzr4$ql41fsDl z0z?z_{+tFzb}j5l4V6o4u=w-Coxe<&wpQZ)qu=_20>yM+c6!<>flmwiK}xRS_MjL{ zN>uv3&c1=T^icgEN=9Kw+SNqf<$+B6kYEc06ALkQ9F*%Y;f}vxhfG)6G2vD&8~-?j zR7P>}3~Oi&Ynlyftrs9%hlS6@59{EDb&H4fc9_rA4r@pcpO1f{eff@fl z^n{2WrGECdcF3o7I(mZ2Km$VA02>?gHC9fE~=wSyYi>UbXAm!=qhCpNuck` zpZbg1u7u>Lsh>SX|E-qDNsAVKh;A-@@TNcM$EP>{cVGTL^h9b|#H(TAqs!S`=9|Ui zBq>vSyIze61>mF8T#eet9}p;$TrtCx2_reD`p|))|Lx0L{Xz=9uC+&%lW9&pv;F^> z$ivE@;`XUM-?xkJ=%#P&SQUJjuTo1rQ=1^kP)p9E=I&g>ecMpdp#?WQeR90Ncg-Yy zF^QQ&Of3zj*FJFLNdM62kfnlGQI3sRVctt|2%u~tybRB_zx$*Z)ATb%xoYwgOGos${4mdGzn=du#!OJRGWXcI zOIGt!^p=?Ou%46_{V%34GHhOLGf&I3{7@M_Z+mkY%~^jpoOd?Qa3X9Op)jj$GHCMj zYM`BFaN=~Q*VmkfB>{R{N`&U_dDp_~J!x8->CuD*2zFY2cW z_7=#O-67()zDe`dC%#I7b4u6y4nneg8RxR1)q{$a4B(nNBbv3mAj+KSd!ncK8hD}$ftqzv*6F-POV>m5`m_SVm|2Wsk{!CjzVk9%adNNqk zMBOrLWD9D$r)oLKis=5!5Q7}H(XjZ+53(l?44?Yt|R%je9X zT3N3w%b<_18l3V*N+wAK2*u`~pOVty;G)eK7&fKtPNysWDc6jzUy}H2Ca+RAN&1iA zh;9qxvD(P2DgUa0yZNf_T5t#nr1wZWR&x)>?UL0Tg_Nuj`-yh}g<_sh$^11w4GYNdw16s(_&yCtmfO8HfmS{q)8$WGCSY_@k}dD*k;CfBk2$(!jAEt#y%8VqVS896a3k4&$l)%vgsKStkh zOQN<7d_x%!?#+LQ9iTAW)hYRd<(@>^jKLOU>aisqh^$2a1)m7Tr^6O&+ z2iK+Ef$&GBOOYnP<4h?th6?Jx@heYtz;btr!d_i0i@DP~oB`lSnN0Ya7*O;&z_bq&MeylxBa;^NbDV@R{ihq%>TaNd&8GZQ{Oe= zcz7d3jEH$WzeeEcosA?|XP1B8Gh(f6&A52)+;cdPUAkiOs8;@7?UOapFtCcb1xEz#JJwGR&;>fd=F zrde@+{|V2W&}{w3JnpV}@DN|=6{p_`tuN{N^uIgtI{tC2mZF%ku>^?)KC1#w!Bx8& zPYFeDWDOhtm58puvE2*ZFwWfbV#=F2c2QlA->HyL)BW>AgA6$~lNFKgdLtVv;e34? zcO@71``miB{zM|brSD_kRL}(5lkR=B%i>Pil0JU-k>`qPeww?#jKelZsqxh>ZG`Ya z)uX&uY#*<-dzU`A(Q6wVYytdQuwW_CYsDqKM8YoX0e*d+yY@7W@LARjrqI#B8x>8y z&t7pRG?|x+nImki8NQRTif?+H!02%D)H3>=X*~C>=ShV55qqCMj+GXI+wz40uYeP0 z5Sfn~4N-|YDc*m?g2}g^B5p9{FZqsF$hhWD?hY@!dHe~K^k(Ydrp`)*%sZDU;lMAF z$Jauzr}|qa46BrGw_Ho3qQ$E`zs|VVdHYD0qrfTuJv7QVm-d`w6`Vt9}PuLOP=w4jn1E2=NmBYY%F8f{m605+jWofjTQxU!YF

qN<&V`E6-li)jnoD&`W{>&_8s z2jQK6JdLPkQhto)n8<)lkelXzs^+4`yZ+BJ(g&_OjT7WV8{*YAvBaz99~e^@{W9k8 znA-=8=cpM^rA2=(81e~7YaGSD>q>W|rXTWgWBzmB_zms=xplZOno_-lx^dFHuAci5 z76MiUWl92N$`_B~r$$|c8#3QBap@7#-dJ#r{wH9l!>2HAbU`46V*K)>KfDo8aX-8V{Mb1=EF`=C+_i_jWvkp9;&$UJ#ud*3#3y1^rDgl>U#l>v4H!_WgS9o9G*9AO*|^AxRnykf@K0V2VG6E=NA~l^@hyGOyCORp*)k4Hof_8L-EBW zWpT`s;(OM2wLp4&w>CbISk%k#$0fHpCHGeYEy7BFt@?<2=F7?z-`^DP`^oWUC2C$k zEMX!>oQIGoQ|4k_f_({}&5BlC7C3q7O~{5nunv3EW)!Z?tx_9(9^qf7@n6Go>5D26 zgRC;Y#q#eK3{KeMW&D>Xg@*(^I4L61o)|B@H<$Z8wfnhs%(09M=hk?u3^=Pm zUU$sp0)IoeCr#5a6GR$ZpIP6DDjQ9!b41l;t5#(jtkqmNsTtZ!;Mo8T=vH%2x`vE8 z&xDrLd6qmJlOQjExpUMe-y7cM=ayPDaGWpsn@sVN4>(%J^nZx*o)UM_cQ!rYaMLXt zAN5k4tkMas5cdjonU9iI+kx-u@zZ}6jaEJ;JSnWtrfG#c zuT_j|6NFbQpNHM!mP=&qs?k^EN?wCIE7sAIL_SC{{E0JTo7A}tknaXJ^9Nn!smko8 zhAvLqA@%SpDR4?kSs7o6=w6x1WD$o)XhuTGZS~Z*OO1n8^-}3Atb;8UG z#OLeE#xjjZ{q}K8%=TOqOc)d!=T94{F7DV-8|YxHlka5a2VXl8G&m!$Eu?Hw70 zuRZ*8obrB5Fc5qJmnd4k)*{vXNcJ||y1&N9IBBiiz{s&OaKXnx7){S6N(&nO$Po=gAqz6R=g2^ua9Z=5phm%dkZ8sG6V)ZB6_6gCGRr}z4Uv^^0%$hR%(5vQomfvE!fYU0ld`w;L+MGtuTqz+j?uc0lS~uEWO&- z3B|LhU~&D{d`MHtCHP$)P~B~BSbwit`Xl%B+7|O?FO(#mgsE9!X#eE%SrJb*5JLn_ zYIaA!w@YNMT<`Z@UFmMrvMy1H6!?#oo8Lb-ayJc0UgFjGGN_z#;jnKI2Nr=`g7b_r z%E1uEB06j5;fTX0hAkauM~%%V;5O3|uJJ^j96>$h!CO6QnYWt-@;aRidZ*7ju?m4a zBJTT;+}E-VviipY(#M@NM~4e>(zh>@$>ng(SgvkC;c;htYK0q(*)l=5PWsYAB4?N8 zL8B+8+hO{FdttfS^t1n7TiKJwDm^d5bVikXMM<#s`v(0?2T!i_q;lO)y>}|{Y_0a; z*hF>C6nV0xI%Nu$Ui&xffinx_MN{G=cS;QGsoOzA`{R)tIS%$unjop-)u&f#Tj~*U zvj`Jg(rM$+^z8a6hwuEvYtC$9cO^%6?!8kE45^otHv>+eq2$58r3$aZD5?lY`$Op$ zZvF+QUAhT5LKOm+Tpx?=Z2Bzwf;+gep@QvYlBEcf-Bw8;U=)bdW#I0Esa ze6>SN$bR;RNYGP|^PS7%CmhiLrq44A_|YEUuYJ#R1#?t1mS4;H7_SyDfOX%v=wBTD ztt@h>Z}#o!3OQMS$Dk`95AFg?bU%GkQ5bcUwftRVb(M7uoxXg(*}s0sHRw7hXrp5N zH#pjnDPflD}20&YZXtAmSH7Wo>7_mk!+%KFu^le-#+W0BYknq8t3?hvFfdN zfLto}H=1rFM$Qdpig3%zp- zds%jWB2ezyYxn)5g9p!FgQqKZfKD+HBa9x#t5`>t4!Sv2f^9^CwGIiRGe~*?u*U%A zdSljGtuLKF{jAW_LiV=9|8*QSIDQn5Aagc zAH^YGpuYEQR4&{v2>2S_5C3nK$uGJ|@o*r2ujh;l@h0jyYe4Ku^@PjP(S@He0BAj& zH4_7)qrjfeGCzOH`WVSfN3u2VGrzSsk-RruP_#9YTIlu;+x!lUdIsT~I|3~nMI*m4 z#(u~7?60K#^KAty-Ea)2`OiW(cW?8I{ftdqFz;7!6-FKJ##d+&Lb8mFH_e~nQLw*p;IKJ_XBN~q6X4vsDeuXb_z@UvTb7pQST6L_ z&g-Gqw4)!3Me}k?*qBA{;tvaU0X*p0DfiLMZ8`uZ4G9u*^)n%w3!i0{ESFYNJcz1wkJfAF@>_h%y4 zh$^6;SY(>3$gw}4ykQu8oc*n8;s#4SoeUoNRNZsw(4}Lvg`K)5av#

cJZ^??L`i&=w;+ZUUHpib)ad?+Jqq3#$$43_R&{fBOjfV)LPwYPGh3IHIYQW<@~+0e6JcKEJ*6F+Af4^a;Wc|}o9og8xE#pQA3-@V z+ms*o3Yru)Yv1lP=G8sEiH~!vgo;LobGTEa^N8UtX2$^Y;~qzTB|@v}E;D)_CjWA^ zV;=qpovdaWnKjn0QiR#3Pya9jJ1poqwVpTT^tHSZ4_SZ~MBlQ#1hXSEj*+tTC#Ekx z`ZeZh+fVp@$*UAZqv0pO4pmtdmaCNQ!hTEfmVEE<>vfYSUlP4qw7gYfE3}_GCknXF zjz8r&bs;xjX2@?s9U=->JuE_D#(kt(BedG$;YUAL$9 znCRb=4>Pnk!LnTXxq-Zo7W3zZ$De9!y4Wsfxg^)SPOMSSaMu~F+g>EEKZcXN{*Yk|U;e z>_+5<;#j`yJ~)Dh6U?4dRsRileh%tR7jTMlYX#(mLS#k^qfhY z{KyHBp#Q!lw^INr@4sdT7#lCD6-S@NT`F?)3wolySiU)0$_att&C{L{G1m1kx zbF%r@H8&0CJovxA;MM!(rhJD#`sGevJ0os_$}@gxz3fcus!NK7!ZD)^xomOWxNVbf z%TNWAKUX7;DTOTdO&;}5Rd^czuJPvq{o?nidv^`e^i|3BUL&W;%=WMMkN@apZO{8g$_6oZpIA0 zIm=&59F_DFkkDo;KWxR%U$9nwpg+I~w%1tQwsoxpoq2rBi}~;Sv_X-Id!5CrnBfQN zdE4KaI{fKxMe?XrSBCsqOva>Uzw&-;5KA@jd|pQQyYqp3V9QbaCi@sl@8!0>lhJHX z$x4aoP%R+u#}c$~pIA9c1WhOE=Nmn8YIo2|olvl~JnDQvr+1~AIRoND*&NX@_1Q^X zrbzu$r=OY<&ICWJK{u<&aJ@;LF83FzK@eBVX@aAnimRj#kEGy76H&(JKyZOLUC&O&JYBozs3GmM-hIs`r#fGYm>V;pGGwh3 zO}QlLV-DIJpd;UaPkc9RKl~(PN)6%>Jh3Nf*#wXdxUn&sa0auKx6gD(=_VDLd(e*X zP#RLu$zT3;rSrb}tT3Lzg4(`#zxB^}!3|CZ3Guav5cyPZG0gdIN8FuF2FfONt^S@$ z&(-b2yizrvBQhP_U7ufLo%M1$Nl*MQ@TUt~WJ6_rRED4FV7lj^h*YI?lp$#nI_D7( zj!RW42qdS^eVY!9dVw`6Eo&1lNCI6YwI5~tbtydVgk#7{?YIidaZ)#2WLC~Ad?B7# z=((}yeudtVKa&of*}7an_qjg5dt+2(ypCG3{1mLl5fbB>K-ofaKRCHTF{3Audf5lK zdLnU8miCr4`%BCd@&Y!&D!2pEdQKG8#}^+exb#{`u&qnCyjA42W}ldG^y}vT`%y+eW(_K~A<`XxcUhvE#t(lJRrJs&A_S+0 zj%!PDtI14@C*Z*?J3y|DD`j27fxE9QNzHQMgQm8akg{OZq3Vn(`Po*6%sWQ&{V5tg zzRkbKLX@Dtavu0#!GAMpt>agWv{D{D|LV}NbRP?*>7<8p1TEoGxsaX=n*rU{+Cz_7 zjQy2DEg~Yz;-@p;5Z|1>@)=f$JsyhK!q*MhuVqMc7aWayPTI%SkI1z)$;#fHA5WPr zr3u+RGqWJj!$vdY7O8l1<<0yfS;rLJq%CB^i7x`^<}pU(_eNw;h*T@$f!WPphr@QR)Gdb`dvxbHFxyH&8#ZW| zUq8?KPIpsy%A7UU7USrF>%^|)zz9HQL5y^}yr9t{b=T)nOZ?9hA5i}@2A1tGks-Ur zEwrEeh9OAs4HVtfGmm1`)9GJ6wd-gC)BHZZN3S^yQ-1Gm}jNbICUZq?fy;tCAzaxT2WeZ2?7DgZ{5h z&0wgQ-3T78T0wICjR`F~^1wo>M990aJtxdM@5*S-Otbk2)AU?MvC2mQ+vrULi%L&` zFr+sRs~aQucqJKyV=qqZU~I2E5Iv5KA+yVMm4=XU@mXk5lg{E3Zw@^u_{cr->|;|C zfAp|ko}m~`glKNqSjk9Gs$;5-P7 zGRB6LmN+9)?q9g7WwkiLcXy{LuCSu*GD&xbtdvN2a)$dg#pu$MV->|f)dVj?jhMd2fdJ1rXtd1;#&vW1lR!KtJ94#dH$5PRcG@QkRan2-we zpGbjB+#KYdQK`#O8%nqdWZGuEH|3{z?FKTnf7D9cr``5g(8sD{QeLX~+qreq^4@%* z<8M14j^*ef^TkIF2dr60d~C(sbBCv(C+A4*<^?WJbqaev7;{CxB)k~A`$aAMnb{UT zFSKT^>@^5pQA<)nH~J~~Rl>AOX5M{EX5k-8GoJqO2yskX{N$)Ue2Q<}AXYiv`mtgN zPOuSzLpZOWof1wyx%%JM+=XU`J+4G-ANL7`8@lf`VqC`p5W=wWaI;FV1mQoJ8iyho zzkbqC+69Or?h$h(q&!24?YjI8kA4I=N$k^~i^g0LQ8Sy;i`Zg3=CjjbLYY2lW8 z5iGTTq{Be8>lgP5#;V|P3%%~SU^WO(9@0t9Jdl-XkUu2#YToRL5br?xf)B}pXs&YT z>3$ArjuK!X4bl6NE=~-x$eJzq2SQm5{xrABtsfcX456ufytq-VIQSuWnWnN0HXX4X zuNfgq4E`H^Y^F6By*#ALK{bN#^v{Fell&ww=GYM$l9;}qddb3nw*eQdT1kT)sf91q z?)kE4O?#Wy0#a?tJQ#`!8UdSg?UV!%NvOHnbcWyvvQd2^XQD==da;K6k|-gI+a5+& z(!_tfwWXj`CvBumKzrL~G#cwPHAh}zv#uLvjBjTi#$@fXxo;+b8>Hc?Wf@ABY%L3N zjF!hlF4bCCjf&2Lus4WmI_7-CKnpuXqfM~dGHtVE33Tm}VR%UILX9QaLRtiRL>>A> znW5*N>2ESYbRTwfnk%ZJMAZ68JOQCFBdAI~5g-hECGN>Fa5vbt*iEDv)ddqpLN(t| zth^UZNPY%R4kpy$eH2TOn1I&HK5I3)OG^mH2BGeNY#Bt6C*&hyP$LXnkDcM-am6TD z$^7Q>2P|>1@`)*C$xIN~r-GqYMB(jBFa~C10@2$B%Ol>nm7N!V0#e(t6v3DSPiPA6 zkciId7T)N7z)}gM>=>xxslN#O_R@^{j##-Qhc70pXP7sJxQJ!yPMAyN6gq3AyFMif zRt{HUg;bp&5mv!Qm@zYsg-m6z=Z*?FJOo-vgVa~|VQh??8gx17&VY}^Jcqc+4WOAScQ^wuzG@_+(X;WsXGH_K=YekP;I72MKG>ky6An=M>KSeDo|UC( zt(6f0qD8bouw@Zt(=)crI1R+2n7nDm5aF@;MAxD!lgOn{bXhJ9xP}I(9 z2BRq_ewQgb)3n~wl+-k8VyQneG={a1oadl_G+NTua^9#Hek}H118bLoqhc1#HXAGj zk_|qxaF0gG7j;pX2`A#|8gV|d#O7KV3V5jDZzcVqEc{x915#)~rYugQlA+NHh5kRw zb6$e-+{FKPdCo)+C6On+|NmW{Q+Gr8*R?m?KTinx-|}3xW#g+?lO0zdT_$Ea-$^cQ z;{I=Wu9H%x&QJWZyiwFZY&zNz{d%ga`B|>*K;CZ0?i-#rAQ!hW-*7F@Z&Tk*?f&p| zfyMUx^zeVmb3t^iG#bMdR(fW9!=qRcq4dE(c>+SuafqleF z(F!B-BdVzhH8EVuuc`jne5sB9kp#pa`xqVl-_VQ53Xv95t|Z9DgWD3na{W_VwMC*= zLlDC1TF1D}S!v3@!<|+VUZIOo-N|D6)^Ae}Y^+!n*KN8;1|UMUdOi~B$BbXd;814-dl%qx3#}+o5h*w{`*n;$@$;U`G{MGn{J&Q+4{9E%XbCLGR@k> z)tM3_K=y^b>yiA#N3PCaikyDf9r6!Idsnmb{ohWS__Sz-$`O#*7lb3#;sd7V_D>1* zGnnlQ+lqFBC|_QNbv53a!z%^{lZ-T!93`hX#ac0o=+3|7*y=9WzXBD+r@8=?jDD^@ zo41$vosBZ?paUYxp$?PgEBrm*n3U~05%|oah;|o|0SW<*tLKQFmzEKkYREt<6qM70qY0DcVR^lqqOt$?&BaM6v>4$0^<)UvKBl z>pCB5r6k=}X|3j;j&cKKoJ`wx#H+N!)cwN|M1%YKCAG{naxgGl3DYzcEw;Cb*J{j1 zC`gq|)(fE7c6GYStaSddo;sY({y@~*O`P1NZ~Lx=PRQ167MZs>BMAQa zEl!gqtRxY7Bj#2LfFm*9(5NyHg^hO2)fPg%xZY%ud;n11xgu5?33br%Wx3*^^||>l z^K)B8_S=~GNBJlJ(?{Rg^ld4g^V6!7}65)k7%m0x0jq; z`O+TvMlwUsz!7+;Q!fi``>bmtlxtQd+(WGUeCwl;o>{wfbp9>ra1{9Et)fM8Kpnv z8_4l{pV6O&^)KM|S@-AqKio9(IlK!RHk`aGajIbC&87AEEc?`lK&)E?X}ZG2zIzQD zTFS%`w_Oi9+?^$ecP6I1l+oYWim<$alw03~JX#_hz#0JqH}?!u1S43mofe;L>2`9* zuU)J-k*?AsU+pg5gFne(xQ6x53@hf-lGGDj6ZAC){02cmr=m|><6=L53a|x70ZH1i zyTLSNA9^^!Ipt=`yWGGw;Y$N%vp%zJ1$|}kTKU8QjjNGz+Hy#xpz%42 zTQ=%mEoRJ3hWq2(dX%P{Tr7(h(3{f3&<8e+98dq6o4#bdWwKQ&Oh`h!nxC~{(499Y zOW?!!1k!zBCPRKtjxA6^Qu)}JXr&R&vNn_FDP%FK#@?ilD?WkdCNMu#(*k@U!`!nj zrc@J7klYo*cUgTGmyboeHr(FN}LF$W#w z)7e>3#5&i5kN;B(7jf;k_kAKGCCHdq0b;*_EZRl5^0;FiK`zd4J@@&7V)>4r_We~y zbZ(te`V9Yl$Jgjvy7`Mu;&o`krsDmTGZ`}F*`u95$Vjj5{(=vIZrlG63CSA}<$IK& zL(XAfuDi24eN8#IAPu4vcnbe7A__^R$M*?rtauCMFJezb&qki zf9%3rIH775qmVg?3ZjnYPZ)eckv~co*B%Y1*`eX^imhs}zl_;EuSGH#Pz7b6LV+D) zJY>I|=|@fqeR0M;-`xJ`kqS!#rz?=nNR#nERGN&I{P$O|gF!`4)BB|G2LZS57>5*= z-)8l)?t^-MAt}y-PbzCw*5&{KvVtz6^i;UJDDl%TXRaxLw(mGfNSv(A2db~gIU8#Ags?MU|l4?os6Dm;GWQ( zJ`c*@J3)UA#qfo`f1H6j5&RAaH&=tZK}LWRAYu~KOZ0z&s1z8Uk1P-o%0aaM`~i(l zcasMxumx;+Cwhv*6w`t>Ukxg`o%8{be(NgmghmIiVcK{;bv3TCZW*Rh7;idMJ^|(p zIJcHEzCH^or=q{h5=5kkMy?08Hi>Qmt>)syqKu)ZJMTUKURnYr0#x)B1WFy9B*NSV zFg;>X!fpnD6-v!m0(}Bx5q%%5))#E=F-5^@zxArK2EPBu)Jvh=Cm;4JKT*0D_^bo? z>k^*`GQ~AGN!Q%{m(oRC4ntWoPsCBoYe~m`(?bE_5CK37GvLOo9&L)N@c`BK{>AeY^rF6r$UB zScTC-dKg-`PUz*q)z@V-t)+Jb02&g$uLgOHavD;EaTbOyVXjQt@;+^UP?)*${m0|H%ON*CDwlfVHv9-q;_6q!B+3c=R^BTIk+C&ny6 z-n9~Q6wnE^_d2>1tB{d$ZwuhIPDp2jBZ#PGj*HqsgtCYrPX*-Z)rtuyPg44 zhDWbN689(4z58^4N(muFipZlYJ}m#Dnq zmL9GXsIoF~M)2VsLBOs`;?dImyAC2BlJ{LF(a(U8mr1xqPStq^<~avjAvgpxks8Yd z{_zN~1p>4d3oSZ>T|f(6FiJ2~85zy}9~+nE8w30&Im|_9-Ful zH1QqFC)Z2RvTGtj6&DFsZ&sm8$q0a!_dpTVuet&#c!zE$V`P334%r|ZM*Lj0X`R#r zU-Z?@>QUcL(4H`khoW!1)dmJmNmuh)KlA zZ$c#<*r5-o)BwNfK))yvoWR}XpATL;39gOm(E}PNeiy|tXp?6V;K@46AU_FISv`xq zOg|RPCYGPaJq*mB7c^+cN;^LU^7dtH7!Zen01g=`yiQyYVoI2o!BWVdw-eY0(d8m{ z2}}G)Lvx=aU~=WyZOz(qZx-aa7jLpQvr((n+lPlxb?jH=^S zDVktVZ)AOFs7@-T`?l*9*;6t@MnrLv@hUU?CFj0`CuG&gc+$NglTKZxdNBST4PrkT zlOUY{;{*5^Mh-Fq_un&|KvLfpRy`~Ccoq!|Uh%C4Fh=_2`ooF)PXkpVg0T=#;YfiK zSh);j8V&wngAh$h5sO%ExBD(raSN1+KRMWkB21hU&`9Qaoxcrs?Sq6N-x$*QG)apf z4qAkJUkOCr02~hiE5KuT(S6w3Fl_QBp$NZLjb9T?v~2^{o9{0$(0R5d7bR?$`Ta9U z>>v$2;-lL5M(_O|==Zm{PokT%KjCj=iIq1-gTwA0UhtXZv=V&M`4miR4Z>H@50Qem zRs;DcgjOayRO}@=gSgTp@S?j&0N@npS|8X%it?#1a+~D584+DGF3HMIB2td>u4I$Z zjT}@NXfHJ$=p@lP;?d87{2tB#kG{eaYY?Xe2r(moK}L;=?zOESIis*Ys6u*eei&SY zKYkeaF@Il1z3>AFr=NXIsTIFKMN6>sy>)=?B&>mqxkKI$Gm$jsL;jvLF44fepyEH1 z2@0DF9|Msbj`3=3)6L@1J*CoOFXAgwb_W^e*L59L+uu2h8y88gxe8(Luzl~-JO*k$ z6_^&4lJ|xo*Q7K>gvf_dkp?p`b(s5K!oixvh?+#22(AxD|M^WQqI0GGG6eq7d14;C zf*O8bfI2`$m>7CNi}(y0Ic)f)dx9TQ@? zOR+oza2|e$jFeEJJwTF6C+7K!x|Bf_Vv8T$(i1$4x(AY6e=ULdFrM0PqS)R4)9W>8 z>c?Ng;p*4FKM_yf?fU+98s>vXw;mGZ2L`+77?<@K-%pkNGqH{=YXa5wouc*VNiFo_g`7^ zk(?z*-z0W_B7VVz%t$^3{36JFASUkue!i?s#!Ihn2S8mnptX0!q6th9E}Pzg@HUiV zvO8#4)%Dr?z+o4ut?$DDZxD8o+Jo}JPne^Q38AFVh8o^Lw5{~ib6{jPqJ@O+A$Tp~QUSi&EO?Y9#XKV3>q^ zjlU0=iU_6>pxzD`(gQR(QbR_NU@AiY0X$3?7K&Gb#GI^}~JDphwk;1JO%LZHPahsR+T8RzaJ`v2e>|h30hpec7QuTRmSD z%ryPI{sUW5=W(nnQu%?^Et}!D_&Qd>1kH9R?@7aDL8M~=tal*yu+8ykKQD8r3?PW{&`>&a+~@7SMRy<=R)(i3Fh?1(q+5y zKko{d6V?M5vtiJo0_OO79Ih1zsV~Uy6SUM}QgO{`y%QAfIN z@Ylu&z&Zj`dC`Q={$K0aCHq82_VfHU$fNwTJs^_7%O$$i1Ei$bw zJ4~ZGNeZ{uhWgQSAc*vI;IVkukyG)T)JHS*m({}4R1jqv`|DRRf&Yl_YuEgeG&J+s z55vzH8zkwd9{cwY*<)ykHp(-sV}Ktt#5{ky<>J3e>DnV7ea|WX#=eQJbO&$f$i=o5 zz16KUHTrsYy5JYAe4kl=M*vd(m2AJ!ILHEPvNLLcm+o@2KrX;zp`e}hKBP53{)I)8 zT+r4nqt+^$?-bS+Xc_2kRx`ty*6x+9{os16Zvkp<6swUd7jf1BX%VfH(65n)jywF^ zxNfEXLWuf>cVbWW@Y-?>iCkPya%AuQ*j0}CJ$#S(_50h)9pcsOok!omnn?k1liByq zPsseLJ&OL?5S00&v4iv%-)7z`tLQRcXxiVje%TaI8FeTi^P8^4TqyidvsLSHhqFr9 zhO68=w^NRW6W^Z3M6=>P--tfuujWiF0Bs$+nA~9k&C~7Z_*$!1CkZqLnI1TIH{I~B z^A7{3xKCqw(GX}dTgYDttrHW6ID3*ub$8DYJmP=cMY!sI>Uwc@>)|7*dRcO{ktnzV z?O)~U>n~E@wp4`9Ty<9xi=Ulq=x(Smi`Vz7NrWg$ub(4xGH_AWn_UcN5c-?6k}ftm z+Lx=B?wfogPSg91SrH9s1UZXb$t-px?T4+}-Lp2IXfN$jGx0iqBji7#71l+GvM(ni z(bU<2n_!oY7?7jxWcUU93nw`C3Qk@CD#z-Tv)!LvEZtdO=;`Nc_T11lwO77XRx=N9 z|B3WGS`~&(nLe1H8RltN>*aPdQ}-}W=d8IN%n;s0{JTL=KkDJrWWJ|7ha&k7VZ&8> zV#wL0?ZejT7!S=e+Lg&}(Q)vEFqiOk&aNL@RLX1S?J9^eI~28273b>A)4I1^u(m&r zH&Jz%|CVn@^4aR)6hh8>uA=RAURiL=(#<+wh5)q8Kn`-I4Lp* z-Q4Ydr)sJQHW290?z4$ni|FNk%yM@CE_?qMwP(MEn$x-lb0`@yGnpfO@0)OoJHDz7 z6g)OrYx9~p`S|oll&i;mDeJ;lO|_#6{>>!QYhwag%|lgh?cYXm_*rHbo%IHqlrknR zr*RY+DFX%A@c#X=i(B5!xmeE+xW(%B(;u%tEc|_v(|S`tT3C1f5;G-3yV6*TJEPnF zk7)EZEE3}ligbCUt#=mOPMYSx&C=BKP0Jjw^oDPuY<0MkK#Nd1eqFN^Uwk3PX)$k9 zSRig_lG3ZvZ)^ihH23fMc7H?bMw8+-j*9GBZcwV_(N@XgC&mX+oM{-T<}_nCGdNWL zRHQZ+GUH7&?W}BARBok3`Bc;LX7uIMfzS_5gtqffoL3W9cIh7C3_Qa}AF$4SBU7gU zU0pxKdG_|vW8_I;dsYgy$vVT`?D7S1K?``Pltw_L~`CDD`e-f4d>9Y%;Z z>cxp*JZ%5hzt0l}a^~IkTW4LhFCQ&*`%Ok4)xF7X@(h)v!xdGYvW(ifZ?#%ZZgu44 zpQ`qF`@!d(S_Q)?<-iY4t4X5bbl{7=D?OIoo3)J1aixHzdB01SZJ5t zy{AYR_w5H`Ri2cX+B>-F>93u8^ZNrSaHm@fwY%`vauk4X{pQGR<>O!M+4?A=-99n; zO?*Mm#63oqw&5D?OYdydoA1L`<;1-w)H8SA-Eb`eKRslf7~Ba{l&fYJ<=g3&?WJ}d z?>4%NPaZc^snDIaE1$eoRf2kN0shM^uy12Y7{ELNPzmlCS%ul&(?AEd0X@2$dUL4@KVIy2D36m?)GT+vF= ztWs>x4Zb0T9!_YNu6&V2nqeM)5;4>NGeRTKtN&eIZOW|}o#7)PI@_L*w(hps7nMo> z#)=&G%(u?S3#^$~HbbNe)#@^s@ltp(dtz&alwZORf>;uy z^1D>`=mQfMQ~NHb?@@te>u2-E)`A;7sH|a2_SwN}KF5nbwlJ@MN!|6`N6A&ZZ|V4f zuk!am*+v!)X2{X5UNwh{{s)%6Fz+8|tbJT98Qy~M>kp>?O_maRuDZ4MeVr2qoo%hu zRB2zoNWd_?a~vY&PV`8((cSBn#@~EUEIabIjlZThH}{dux;yK+&4tGgaN)H4u$unA6MmX>TobM`gAtJ?XmxQ8&#eyWh^P0tDqyp`UQTgj2{ zB;IE#RJ{mjdXdTSIuN!BEuGnvJZ+Xm@##+DcMmpf^T3}EUD3gVJ9X+mE=+ORv*hQ zbD@=a=a?1e|NJS^2DQKGM}|w>KpDt)BYfE&4X@eyyhTiP_$?NvH^(|p=|Xco!+hmW zR+9RKz`(N2*R%I2EB%hCZWuOe%eA+OPzbRM@Z&qAZtBwQhTFSYW>9CH)J^er8J zAQ0w7hRK)Q<^9&^3sg3etqAWkY)5gz6w2dEn)>L?b-ZmX(l9G9J9K5+g_x^>3UWEk zFbW$MLpJnThsDt_zT2IXpf`Q{)U;|z0fGH}ziOc}JvlXSiPOsuXm{Th}ka|d%1^M@~6mF zu{Y$}=vbhhze)Xmecr)q9qEkBmLSN{X(WZ08MvNBBWE9EXPYhoG~Js%DJAYPb?F?| zfFrwQ4nmQDbWPCfnMf3ID=}6+jsd6p-6d8+bDN=#D;LrOZAv3Yd*VmGoXk+XmU)0= zY5W}QISaE(b_xi(Z%|>Rwoz%o28S#3j|G<7=HAU0Js3-IeOrOr*;6!V%dQr}-RjI) zF^+wr>aBsSy>l!{<=A)y%mG0-H4m@oBgH-2FCIU&)6y+}akB4~K~9t~a}Nd9wtZy4 zk7!*w(Wl6eC!xG%vxfWB$daz_Y}RDZLPSusLNhp)gVo$ zd`nq7s89(Z8A8q;K9$>Hf(YPjHX7RFw%h^evfTye4@8z}ra%a$@b#EM7B6$`G}6-G ztbu!WLdtYqVEGN3uJ^>*w}l+BlG9s{r*}hxRJKW04J^ zSu=(gz1=^R0o`CpAAPSR%d@LU*BYFwfktd#@Ci)I5RJ$L<3nMa9C_RhMY!F(1X`8q zuV?t%?x`AeKKBmg>~G0?}hbTJe9%Q*8_fZXH0i9C@bJX)71Wx!RL1o z%gcg?*bH6k?LOUS8GhK&Or%0(<~PH<#A|TBT|{C~-pY;O28)|bp)YQ4wgD+H(z}Br zYlCLph>Hu|hqE%jMH-I}=8s<(H#KUp3zX_M(rxW7-p}E-(l_y7E0nFXx}U ze7THK8o`KVt(m$b(wV@M{B^fyHw&h*HU(VG!yGs*1r4GHyn4c(Y3!RbcC=^gTn1UUj^?NY@0oADao|Xvunq$;pND+ArQ2 zVk@_o(%hWIXL!98nev=hYO3ME7vJdbZ@XHP9l}SvU&z;Re}gS93^H#$*_V58Rx+Eq zCr$>38$>TkIC~h4=9!{-kE{8!LQPo<-?t(-X_$2y0+N@zYH@tgeoLfr-t}LR5Pxup zsxDaTq@T^6p|=K0?u|=~P}V-hPF779vk7Jy_;UGo&ejpI_w1~0LY8qLh|;pOH+p#> z6Vz*jq--f_)_j$-@<`?;l(O&Dxn`&=iQx}_OH&~$;_`0aptwcX`tmE3W zhIhTkMUT$rz185_{r_i5cFXKM<9}1Kxpp*5#rc08_S+u${TDrNx4gWQ^6mZq>tSa= zFsfeNk|`Nm#$f+=ckAMV|9RNGdfJvBR+t@LY`^L9Rtl_^R$F$15x&rBaAsM7>t)1}jQ`(K)fj%~d8FhK77j-l< z>}}TS4x;6}fG>wp8q8xw=$Bbr~CRN?6KIcZtQoW>JNspcU?nuNb z^)3;f$I9;^W_gUgCD_LP-a>e`wz68e$u^<(a(zqCAkj7Xf_~NZ0`brHH#(lieYn{z zmlM}=Eh?_4Vf$ez_^sx<&sJ{j#1Zvcn?kMS2=`3?>;q=Np1vJZak+=P0ux6LpRY?Z z_}qQ+?gO=+eN3Wy_?@~x0rFIp>jFTGHOcHed{_PQoin&QH|)Pl`x$jQj_iA?bSAaV z)9_fb`U9nn-^-sUuCx0@fKOzrv%LJjLko5T(oh#gx1lzUHe`8Ep01ewCSfq+KO3r| zc}X8!;nYTZ4#h_KD?uv{YdWGV=1OI&fIsoGDWAs7AKGyh1`{x0RDupDAq3xbzJ+awC!;THJ5v>YIBT;K-<=1l>;&pKdN1IPx{4a_|a~L-j zTYr0O4n=w6UNm3_M|HW z7z;%-AayEA+q_KG?Z@Tb*U6ZBnm*o$@G@nK2e9UlT`ZJguM>V`%0uzZm|b7G6V9aR zyZR4DW&L9k#p!bKU&`=CNuTgJufJ=wRE(N2toXRy&8Q{a?~$EgeUBVz=?`LbjGN^x z=^U?mUS5Ot--(H5Dc@PoF%Jntjg1irP8{$0;VEWQI z)-e2l;#7@`)xC`SF;qIi)NzwSoDK)un<-aEg{p}0ZwlTVyP{MO!A|nB-sCu!40FSjsBv1~znMP{(EM+};gV z)F4M_=cS&%RD1JmIcGrb_!AxD&rWi?PY2rvKiFPs4nDhzn*A7<-4(jjs$*C(>eEHv ztc%6OMoI6J*R|?P$FgMJE5peiwfRehn&(Eji)#O*5Z0x&oNO$_F-5n?-7r$F6X~K8 zSJao$@mafNeL%iN_%K74DaT5A{`3eq`{AS(a@7Q?*bhWw*6a_*)-^4Gt4j18+@$o8R!61QxT3{{j!5(S9{TjK6<8tmTU4B>fCohRSeR#p zow*|2EM^bd-Eil4h)$5se{6QDCStpyZWU?U7+6jD=U*+<=!%$AvmEagMp>)th-ou+ zPenN%1>tg&ZV&9DR^HOQT2 zE14GXt>b9nvW?aQMrl&{p-oTkBGy2VOfKLQ_)G09nY~rn9`K><%9B|=V4SGV30-Fv zNV*)Bby9^d`C##QDBs26ZR*oFH;6)Ejl8U3IgCQ7lWwcYPF^qpj$Q~PHHy3)Q@5Z) zbqUH|(l509eX{MLnrC{E&rQpHFqenGiqcqwrF9sOlBywnI_9liFd2X%wWOd$ObUF= zF-mt)?HO{jQ*=H>7tPuTXtqjfk>w!0$8G52DFIuHlaREjD}vgDc+*el5E(`F%B zwkG+p5)sgvXp8;xNj&jOLMT?z0TGt*@tguh>eAX~55Gf5nq=M7*yOlfELGtCF$3tO zxS031;;0)pWGDXR@KMDXm=K}*lCIm%v+95gahUR>u@U#tK2=b`ic_@eE7dL zQHGZg0+Dic(kG%yiG$};7hf75w~ub@IIDL0qtxZhIF+VQ~FM3vl2B`7mklu zl3O$BQBZV6le5tkpF$(iyA`|jtY@*J$;@gUv|`dz%7y)kYD}kB$tqduXF=@k;0W2a z?)_$FYXwI)95;za1`WBA|62YzqEjw|5dTd6GS?*!D{>Q0RGzfeOvC z^Jxc00o-FAYO{;^W&VB|=a?oD!zH8hxaKU1Yo`#?4%pnMA=62id0J`<8C6Ngy!lBm zCIL^Z0JE4g8}u`CC(a;i51e*#$#Nx*Xv)lR_PNaX&ynSvDG;B7no;DyW8Vm`pc47( z5o}oaa{rQpcf#P^czlLa!!O_3w?ECZqH7^Yq3(qH{CO_EK75Pe;Q zY7jY{TtbfvvG)aO^8ludi>v}z#$>QqBsFy&Fo^+PiBAB#0~1JL7CjVSYz9raXvbrE z+K-=v!^@k@Ns`qKEQw`GlqCp%5HjJ!Cm`g(3V_ByxAQEY2#}LhyqKFV&5xhjM3^UG z4t2m2?N8@rpciE@q31D$99SSi`T*6kj(ZG7wCUlv=9OSEmcV^oAYXD`Oa+de018(K zRw*oS(HY1Ze$%_u{(669VxruCgboo4%*SelNoV)(JZAa_2;p(2R7wfsAw!YKs~61tVX~ z;Sd%=Mn&*jY~U1t8ECgd{zoWUJaLM2njl%0a3JPE|5M$5BN5*JXLhgM3BoVVE-Dn$ z)BK<%2Phesu+vii!4tWNY#NeIHZ}JJ0tB$z9k6y1ZkprtoWtyk7JAd)sL(ps3yo z@fc?q;s|z%}hk>3n7m!f}AoMkcX`dyq zrMdp}_u#W{J=1PGl+#c<-U6LYB@h#29^GBpBy;@4In%WUQfuCeIsAOhUTSiqn086b zsK)x>xn$^{QNZUXs-p%oO}z+F$N3MSM3n%ahkMJ-v$>5u+=N_BfEKUH4c|^{=fYOa znh0S{D-UpakjO$0BIg1yRTGSvf*s(QIGQ6Xg{YJj@aqvN8M;(2sEX^ zLIep;J?1B-ATLn?xf7DI0P1YEWvc*rh>F5*0o27wT$qp9r8$(p=EdpCv|QiI^7iKu zVMoNGhQMB8j-}?a_#ly~na7TLqkO6S;7uMvDzj04Y<4_rzm~q?} zT|q-H4wO}JP}McTYUDGDoz?iN`O1Fk}K^qByq~8IA&ZL z1zf3!4lxMxkqtZtZ9hPEYGqiwIb;Pdl}gcJReGN3>8aBY`Z-S*1j_eAh?w+2(lGEGXU=mp^Wmd%y{C=7GU?F<%2`g9)^I|N22#fe9_1@ zU*(ZJp$6uwqyS;oAz5ewxPN9Sks?V&8Wtaq|L_7>6Jak>Q4BIHu|by3FdszQ+VKwW zb1VPwZa~JwVUC0=5s>0VHrOzqgBP%T4yK8R$_7!gsa6+j5Ogl0khZHqm|96kN#yim zGT4+WrFe0YtqUlU!HS$oF$wM{JEokS5s>TCJ$=MTW}riWY7!h-=?Ie++gn0wA09Eo zY3C59Ihbd@r~nE!@uc(vFTgvMIFZ%x0Th}H!L;tJ!}xaw+yG{{2;T>Qx6sM~bNCJj zb!)xz=K@r~7{v1{76D8-8Aa#mAGaW~r=)Qg2LLIgxef9(4K>9mzyA?(kH z3W1}lDP7VTxwen6l7*YuBda2|53Ci{`I`_YO7$Wg+9QC#YUjc!CGiviWc3XvqPkbcIApt=I?mA7-kXg3p5NzD-KUz7{+@PZJtzN~7ckGm&DsKi zRlsKk{xKCUg=9R43f{H@ctTA)`!mTf0Y<0d^erav;#T|wRlwlD!~qakQ4Nk6kj9cu zn}V6o18>e_3^P!LJd~-^MNQdm)a0{`P~eXy&hR6#r3bs$1{l}@T;iZIDaiIx_))I8 z#%Z|p&Z%p^35j&L(>GxR*F0w%5PR4Zd&<2@)HW`-1r9?IXJGMEGoxQ~iDb#k5}RpD z9OojUxQ+u~aqnWsoeRe|Pc}FoPMW2mCatl8a@^k3OWhTni_!Q&4iC#$3!ujTxZ!%* z?B3QyHHnSkH18#S8*!e7Dx)Efi8{?0Bw9P{sKh-_MXv=)(`m=cMdt~8+%OFpV!8hX z6*ovvdr|Wmtv;gZSI4*kV7i`d6Sn|+&zd530_Q1KA8rEj_srD|7dE|GknGmWwgVQP z`kF4h#8;UgT(9qJ)V6mG ztox^XH(}d(v=6?Atc$wA+ea^34(I|CSD^`-t3=ot;WFM{0(9iPWtblPLvZH6vYoDK z))Divr8&d6IqrP|5j&<0w9^x(Is4B%B1#t`TPXTzi#^+jUly=^5JzdLkQX5Am5t(K+ofGzd{9|v zxbyeLSBXBKhVBpx2F|+!gF9zXCioVHUPy$gdBeGl_TZRppEBx@v%Dqf!pqOXkX8EN zYwi~@Ro0ID8SH~NM!T_j#;g5>wC`VFIKawh5fk$(_w*xTj190J;l7Cnd z)TJ7$P)GRjFMh}`aO~D+@QhV#7)mq1i;pnv40(@NKYB-mt%@cRuRN4RKG#c_kqb-e zzJy<+V8R11!_;N`LdZ)V%Cm+C=fiii;*-j4!E1;lePBCyYYF{3k%)gqs@-}M*}|nh zq+b5J6VM|Nt#<>s5xfdk{sxM>qj-KTMl3vQ4 zBr(VDTHI=9-yM}T$@@Hp88Iu{cVMdxC7VEGanaznK+Ar~13`bus8w6|0-OA^c@ht* z^$zV#7thotAu!U-!NcgCnSoptC+2&NBan_r4}Kw0-Q}8NetCQP?Dn015H}`@4Sa1+ z8P3AcTjEz}uMC?$sdtvPS=*z3(nIa@t-~&u{oH!Z=bTLCPVBo~&wVR;|G_lj9}l#I z-cL6D>#?b^Be==GFmEqsUtlZQZtw4d*MwT3ye+%lEE#;dA0#-w>+90BiHfeQN*A+g zg@fnQ8)fCM_ z#ra>SBFfXfJrb19|2qFT{kfO&PF3Qyz^kwaJFMbNTm5q$*X+9P&qkyeqBdKfQi%F6n~y@UOowUVGIf?#vi03#}j?x&~6a5S_34 zFRV~cM|Kis8E;(LLMlG4w|Lng(JT(5LtV?hvtV5rS^bE!EzV}3hNah((EUrtdZ=9S zsFKp28Bcb$v3r*bNCw^Z#M zQp#2guNn1z5IrF4T$;{S?A#rzGJIugBuBAP*7_+oG3=a)S%Ykm&gy!^xy8yxqHi<` z-f*>Lhw(*vbZh&>E3ZlIiVV%*Eu*Gq86%+Rjs0*X?|&JQn@TUKyU1FvnAv=J;PET+ zoT*SZ=nHu|7oqJJtvI~g-*)VqvUhcp;??<ZM%q2lMa$t%p?5B5}$&$v|8%QzNPy|``fu1q!i^Ss{g#ryE`s1D;8{n)fv+2T<4 zHE2ml|3I|jX|Y~ZUrhGeQmw^PV0&ugcgg)m4gECPoYc0d>0&TE$R=T+-1L)jk4DZa zU-uPf`EsPG;i#kJdx%iRmn34Xul>qQmimmt{>r&5gDn}k%jP$YZl3nJkCyBdX?bEr z*MS+kOs(?RRQ+vN=CZ#C-VsA}@fzDl%R>A!E~Rsvlx7*1My%IR0Sb%q5>fsyf9t^< zMlSnbY>spG6h3()T)MFdX7VGM&jbdQ3sc5iEWyax6sY6WHJHMYVv6G#KAg8cY+bzP zY+9B`kC>UMEAYW%^G02`tP9F&Z*Vb94ZeD*c_x<@IPtUy{dr0O`rHUSASH793t@JI zzE5pf;Ah2Il#6DFM8v|C!k(IC9iF98AgYt4SI5V}vLdEhX}`i0+0~kAg34BKjQ5%p z?iuqbEMvpavZs(Bh+9GW;2Vq&S=LE<9Uu!x3QC!wVH!Jt-ZI4oTh|KwHK_cUqYkHO(9qvRb#g<~lusU%h^BLG zHx@BXPB9LDzcHB~`9L|{*|@ybY=~TsZ9X}+sfL_;lRR*7nib9X$4etLjBfgw@6gaXnzE=o*BxcgM9aj@3}2omqqOoDFMopWHo5Ym zU-}-Iefvqc(&B*=-TBI*u=myu9UCTB_de$CvKC}-E0>PT22@Pa{(@>rLJ5ary z%bc6%s~`D#_s9x-h1E^PCtgPu7{OQ7Y%?u%9Y3Nsfb^I1@~YrBvYQyk#OmTzzb*S!9k5HCT3F# z!_VFRtABV#c1yfTp6|sm+{?p@$AKc4QJg*I!61_{P4TijSc~+;VwI~la&$?=?s>~u zKH($;xaAPE;BZCdHF=2W@t&xYDz&NH%tQM{+l8T5OI3agpY8P3eMfihx@zj1e#vb-d_j)^U(Dd6ROonsfm*yj7+}G-S}qw>T%e$MDi`AFDp%*>?qwBerWphEKl% z!>N3>Sa)EdaZ^$3NFAZ@MzCJ84=yNb?rG05U;YR8&DPhMXWfcQt-5@2HNAdr@d%~m9dngGkIyCC@@ba3uC+-^ zzI`Q7-s^An4$zxB9SSby%|(T(4d@Y#B|r4RBm*%>IYPe91!mG0R^Z{GDYur%RapXA zTbAxE7$)mGwfW5KUeah6bDr7>LCgEjZ`^>7@a^6NVZL>ZFjv;I&HvSeHCsyoJ?z35 zwebI={nBdqaRlvb8!jMfJRdgOo4AnYGE=9kTDuw&@x4?AqM{=jdan9UBq^u56sSr$ zDh>wvTYtAFHZ;M=Buk4J>j*#fn^^`fd{nz)9RapH|Fh`|!gGTUbc{IH$14*b@}vN( zTo;}y80WcSzpP?$a%s0a2qNid>Vnilk&k4rYH2HIJf}M~*04inG?e-c&(As$VPu7E zF^=ci7uA@_M+PESIV*1*>x_@Fd1Ab;(N?zd^|TV{)p^0o6gX*#dM}+b-vz%Rz5d>8 zY!A~OpCfkMy!{vKbG_1&*LQYBHGe;6OHst0$Qu2r8m`!PN03fkh>MWkuzcY8>YpnV zguZb!H~71)M)<#+D*YV#dX^@eb9Dslsk`IKo03d*cz8-Ri<#?Sf5T{nsjJ&-(M(pK z>#GXvb*adjc-Tn!LlmB7H!BxQ&%xsu*-~xj050@m(~jzjtQ{cMp5|g-1BfU{?qL(b znt?P3f~e=Qt+>)*QvF3Nh#Is%ooaUudEbgrsJ)Q;p<7#?ng3_H-**b)R*|JDV|KLy zd87#jxssM01IGqk z-i@s*UdW6}$&Mr8lrrGHquJ6ZxL077HyPUZqJMvgx(*GpUaNa3=qC1CgE5VLfW~WW zk~~yy4!O&41w71P+LKWjC9Aqq6~TcpM+JCQcY98^S&{-G>^l6@sqDz6LP;9jucpEU zl=(X!Y4iOOzY6NOj<`?E=MUtnekZ1-=7~fTO7uwuy6ccwU;tNbZ}lf<%su;& zgzNOkDgU76wvppbg}P^sd~2sv1Uj5m?;}ZT=t5*HWBRFvJyb)M@hsDj_P-61HyIWb z!;TYXT2O~_p`LlwOpBVvg70i$3Y_6(taBwRhi{vthxBBCr+jMIZlkeUb_WFmXiwXu z--y;JrK1ucO&>|om8jzwIdo80?_dsx=ZkeXMveeL{E0}y~x_eVN6VrR6h4r4PImFC zx<~Kd6l%;u-t}U`kyg$iB{mZD-pO0@iq~7M^5R&B_un69C4h8NSavZIpo&djkyHUP zAgA(lIr+h~O%+Yqu?p~To@*o7P-h)_gf00Sf(mzlc{g?D(8k684`1)$mQ)}3e>`L$F7zpT5$>1mY?&RXq7=!FDt9@UO{p*C zp8D6Zia&i&hFiv~1YPk&7Z&F@w`ev@}$J}sYSSfJ7Q@5gONQg2YM%G z6Ja<xWoQu zIpV5^&cXO~ks1)(Td_uYRDa8}91sn&??x;a%5%DGf(SdCLGckW4-@OM2(W+^`OJtm z&A8WwYNfazh=V{;h(@*b!I1dpEbUqOxY|wsAYcI*a_f)2wlaJZ<)Oo3Gg6AEfD!i* zi=!IK;T@_i4j0LnSiIRbvfq57?0^L7lVfd}RB%XkrD+E;e)z`OEoPX;m8tUAdldS1 z=Kvv~8(JVMp9Qax7@3VYv%lQ?$HJbzl7{0qeeJiC?H2ug44}p_0db2#4>4Xx7em|@ zX`ufzg%vHMu=@VLDJ(7(HC*t27kYUVlFz6(jQ%eQ%WzkL{I%5rT>|TYOz4H$;MvKW zIOBSH_21(%3hRTS2(1ut@c_7Dsc=B!KMKoh z#;g3>;+CFnS{evBf=QXo==%H&w)c%)+qrvy@vU6+&o^y=ZATR;C14;DzZ_w?QV_3zSD(!G|xJ0~kZYp&d6|95}>tn3=Oh*QZg z9fQOczoJ3>Iw53FXw(zOAF4~@T-2TKQ#jARz>uPUvfMm#Jt{zsN`fl7LBv$IRLiN0!L(H?gXUZR;B7d&6J`<7j3{PQMT06e9v1ns@sz zFc#EKPMR1;_}eSGq(CDO&($#>APbe!1>xj{Q)_zo#@slq8TGyPa>Jg8D@ewvR9$@& zFQi(EOYEh@4g0DEf1LU6 z$vJ`snUy_Y5W>4qD9+pe6fIJUpxqR)S)JZ@YW`@R_k-3%H}?{L=3-vJ-g%K0Ral; zy2&TRqi0o>SjZbi4qvZDBn`Bf5$nj49ptgi^(r|<$#g>1=t3jJ*tjuDw2t=JcjraT1 z?ycZVtX%wVnZ24TnN_y#T{bpd2v#X4nmr;*iZU8mS{v${vuM}sM@Jj*NltBglETfo z-U}XT0XkO|nL!Tr1FEVX9%rc@;bw}#aI;a5C4_vG# zkcM>+UaKFC{bJUDXBHW_t1IXqe8Y~->A2Y)A$9B6@S_q4Cqdl2UDnlA>7V-0i;~QO6?7n|GFsj^S zDeXwdhKke`AI&{HpZQvO91k;xSYzS{xpWDNxh3DE21)_nxKYPnI_w?tQ9nQf}jp*eIY2!&die$`?b8yxa4$FyK2M z3g-II%`T428Z@j7ZEjAP)jtv~RgwaX zO*QR>4}Lt+Il1Iw8PlGpb*{fB(9k{jN>#ZHI%EtQ)w+N9!!E}Yt$vV+CfcdQsSj7P zdm*IF9-jS3uYd+E?`GE$=+`F^yc;S~jjv7^9l$^H=jb5d+NcE%a+11M%1>C=A8dUv z`^B%~s<-*xS0L8bRcD-(H<+awC0o3F*QSIxcNG7H#V6^vpA)#)g8l?&*XAg9NL($< zmm>qEgQ~~`dJl2{6S`err1;+JN?hVc*(X@^QB_!X@WSH5`~7`GE5n=SZqJ1bfz_Ho zbY0UZq?dOzE|&Jw)m{dAHJ-p<*MJz2=kxp5KQcEylcn7Kb@%z5}{<$81 z{uRu`SzSf3FlPH3P5DuC8(F9^K^#7lvNnX*wN&z2-LK_w^q4`b1rRFzsajlHP6Uvpw**XBl@BBQKIDlF(<{S~UUKjp%Io23DsoU zJ?cI}1f9+ITL7za$@KMvD~buYMnw+CP5kI{5TG8ac+U=M!Sv!BLc1vDhA1y|vzFD*amsNJ>yLV!78Ca#^*dM0sgv64ePaXziP{Q^X)uO%ZN#p*w`?dS$o zFA(;6jRW9cx&JtKU=zx=>+CGvzIbrp!-Agv4Mg_dTq2rB4Vf_lDq=C?{DY%>^kX2z z`B-Yt4M1j_s6K#l3r0>-)1-V<8*uCt8Mqw`^!-$05>BDBkEmE-X9c@()4O~pB6)AK z0G%V{v_ts3BNvTMO!Bew6bv7a1y)We_ruCTQP;_6uJ{;aIbo7d$H*GJKaqcr(Hx8A z6Lt5vOdNNT1IdY8-nlA9is0>h)S#GpI4`HdKxTzd@cDtcD+{p`=}PUeA^?4zmgjZ} zVY-6zSvp-rJBhH$>LjC@YSZ=G52E_hzU6EXNhP?m?zt3FL^l-K1VRqt(fJgl!VgUC zOv+=j!Xpt<3gpoQ={R3lK7f`9v^qJ+VhW|ADYb`r{ zphEPA?-qca z6JWb2hy=XMUk%$wFo>bTV(`EL0G3RK9U^3(dWXCzMo4QBg|uX;7^!Cr>^XK;rbO!H zV;J`jE0I=cjdjgNUO!uAR(62!0=3QS7o#!+E(2X3;sg7&^dW;0__P!$fqMH&!nlG882 zOaPcB3Ij5aNmf^W7I#Se13NDUWH7D;7c)X*x%O9reX+BEJa`#A$hF#whYy{{Xl@1G z0}8Vej2aox0hxRdDSVdTe$a5gk5oT?3@rkoQ$?jx3Z@q?qhye|ftX26g*h^+8bGJl zqE63Z?-CIE_|O0%G#oFh3&JR^C9EEGKxqL)M%BGE)RY4-GF-MXzf7Bi zz4$gyS}XJI70DcM&3yD5YMr`gB}VbWF1h*>D0YOjLeqx~J6Vgk$VZLRWLy{U0Z@1f z!brv1QewRwQSAx|eV1G`L{bbDdI@Erte*<-pmO4J5d+Ft9ESu<($9h{#d^sX{{A-bb>=9!E}7f@>-0T_=|Fli&sjzziAq#Q{o*`8$z{RF4ZV z-y_~*N}lXXQc*5=;-*a8BlNl!SB#ydU^o(JSBI%90eZ+*_Kkp9A_5g*z!$#4A|Kl> zC9gxzle6%NcPkZZUz-W6pk9EyDtI9igPljNDXGEB95?t3dK<744EI?*GKD#Fv zXeZY~hUMhq2Uy=%BtQQb|OZ6#G-%GxM^7FhJ0GIiru8Xi=sr=Nv zz;1KkITk^rT|&H$HAvf?LA_#hJi8 zDuydSoD-ks%4~k1%yL0Y-#hdOA?qCzuvt~Q-kq(R*!5I02yGwS`>ZRRgrWYBpD3}S zNZ=ekeO|0E(Q^l0-0+bAybvKX#x(X}s<@I%H9`P#9H{8REG4FK$gqBS@(rtqkY?cF zFzlr{a2Ny+a8s%nfmL(zc){=_GF%dv{~B6ROod&4Mi5(pDzq=aIa@Y`Wr6jxC&p6mQ@tIlb zHF(|a@MZAfD1FL*)E4rG!Of4fh9lB3KnAt>QgqQCfUgAEDMpV}Dt^V|mWUWPIKqp* zt{w(2{sV`8ibQ1>C}H^*$w(ec@#Ss!RRX$$fX*i%+bF1_cc?x>NCzK120}lZ!M+ls zOR2ISPWazKq2_iugcVpy#Qma*h-8?-L`SW{SI|vxO3Sm43h+O;hTXuD0L$S_k8X#C(h~b9?V9b_pC1$+ zi&51Cq^K?U$UL?L8zLnmpUfhwBzvXg+HhXM%Nr=or`h#!iV4pZIRy0m&nQhHvO#>P zUwozN7w#GH+H=__Spa$hx+8aVhunIO5YjIv706kF27XC|&OuGl|TYAY)(F4q~I81}uXe+UX49!bFaCkh&h=kaFT%V!Mn*TLL3J>{kr4BWt3(Df{`}!sCh`BeyV@wRc;_UG7%tQqV0S7I> zYBwX212=!Go2O>q-sX+gZtF65IS8J3CR0g$S;4dm4ruA@{qYBu4hoK?+>JLf2o=mt z1i}1)Xensv($g*>XK_cu6LqpsoALzSudpDHy>6_SB1583muitm`1I93DUgZ5mx8P8 z2LqZqsP3Q9)W=zB6|-7V?N`U|!{x?0wyO@B10Tf-i^LQ@fDuuiGQt!nW+_oB% z%$bHoX?pSDGTq|{WztU_uZuHQ_^2%12V8ujwt2q+s-3Ky^7Ulm(^M%X8M6FbUPsb6 zbLkZ&<)H(B@L80f$T5ic_{ty~Ok$7LaA$s;Jhl~~P3@=6_atR0;AD%@)bkPPM z_sOnCFxy9wmV7yQ-Aib{+rYYPqN8c6PlArIApHNVF zIP`{q+1IK3Itd83qjiZf_`@lKudgZz{TFYvqGQuoU20H#LrEug)BZZ#h$YRW^ z+LaL#pilbGyCmSi4H#9H@gvJzih_|5*klm=1pfO8X)U#yg1SnZnIdE7B-kmjj0r}@ z84FV0hmDGnTmdSG_T=S0p_KCSW#7wqDb88|2kE$p?^;3btp2%#n0NF)uWOb1GubMqQ^!%!sZ?lWs$*H!cu%7zBwjib1yFTQc zxSp?vN5dM@KfhGHusgn*aairgLfrB*$HR1wzSS*73wGQ>^~BusKh9svIzh?FKA-f& zktoeE7z}tDsX0b7j9tByq_Zc%rYGSDV{~$(^#Q54>iiUZzRA04=lu|&+<%H&I{YGa zAYaqwz{Ay(KI9Y4ei%|{{$}%VZ|_^)ij~kdrFHJooiFGOmlUe9QpMA9xeiO-@s1uh zZk$)P@Q%|zAN2=reH*3^7-xvv+3Sd&EwS7Shw43zj;)rRZc;>+GI-;t_+`v_fuxXFVWc;(Zbwb%3y@T6_H0K}coiDDW4wzu-Vtd;UxA*er z-L!%YSl~Z(-_MAYwQUbS67^kXxZZXt4s6sHj zyAUF*>{qK#T;JMfqI5M=+=Ii>Qe%Vp&U(YThR6;OinQr)s!~dze(I!hM-@_9h|V5bZ;o!xzz)z z7P6KiEKBY+Nl@~sLN=>-ry)nA8YnA=f0`K{VY&A!f2 zjbAq(Rex=7d8S~p;Q7%g7uJrF&h`|Yk@RmLwFzspg@y-8e2=I-i2HR(Wn|Z{dW8dh z9+NLhzHQx5mw4lRBieo@B)8~_>e@S8@J^eznv}#8MybaFbxhUYJiF1xi+mr^j18AM4S^MZe1$Bzpze-(8~DtTzIqYoxWH46)pFAWel3fDPlV5UWUcWo(0ASdUOMpwRcg$9vz^H zlC-PFN$$)&F6|795m)19A{D0(GOJ=YPKOdQxN*imZ%gL9wye07XB_N6zwM&+O04Px zQN!N~aAqw38t~%6nHGr8+C}6UQ$snn8?kWMg{ADXw#+!q)* znd0hUxqNoFxyyka9I(>~2~KzV+|{(E9F4aW<`&SDgTLu0$vt%w-Cj?%1Api?##6?_c)*%|o^Yl562oJgTJ*WB%lkJR+ZrZZ z>(?02YSKDIbqYRY4W)050(w^9Heo2jc|1hPYqrX#M&_RvPariS5P56;uH4%T*j(z= zI`yy6WT?DOzW}1qOJJz!z;u#mxh8&oY>#n&#rp4F>V36vZ)&~F;srG&D;9LD4rm1I zhV7{-#y-~AV)ar`=^Jul>pgEh&4(P=XzP5@#vk!+N^+*;Ty%K6d#p>oj;|4Z*`v7e zoc`@!F8XV}ET>gxOe!GUu+MzI`jL6<3DnB-Z2d`TQ_Z;!%Xhh72-rf0Zb~(6~F3cm|fvZ_Z9 zXq;`1V43sg)9QGdIzt7>*-bm2B~u%;dU*`XqgDm+_AufQ&u({S^kO`5zt)CumO){V zQt(>^rN_ytnnJ>btnPj+g*vFk9b{Tv*1=qn_xw2HS`ymmH#tI$v;MlRz;<&_(mwy< z4HdqWhdIhR(}-`5(+geJg4^?vaR*<$j>5Q>fsaN0-0C#ztuiwpy}te~&C)3&$)$u7 zJPOI;$dYLc zGP^abrx_JkzlKZB_@$lu%WVz4e^dT9z@VAMXmHqQ)XRRZe5*F(M!rCH;LeCbFvHwo zhi730c&29pucv{XK(H$1(?d86Zvm@B_P=dVpK_3YYa(y$-v4iJ^WtxKx*2=a47pgk z`JXxV9>N7#Uh&l4;$nn;360soW+w>Qk^F`y&QA2DI}8aUrjD_%t-|&?8;OL6X7miS zvp31mq7~?07BZ3mxoM2@5;6_Uk=-8f8S6Y*5LnvUU`>}mBPr`1Y%N%4V)x?@{22Ah z4)gLXcjq6^>?`@Ud!H%N@k(G9)~X)nbSPq~mEp&;3(k=zkV1UT^RYX_V&-A4 zAQr()ako1xl=gnVLS zU2DP4d33%lS=aQ4Zu|-(5(F`_SG4Ix8W}@RZQWI5md9%#)J|S{_9yQ+6@Dx}FE{PV zOc*>}_GDTxSmJ({h{-3Vl^0IgO5fKNeE%O zrMO)WnJk3r?qz&p3pOk3(`kjWw{dzeYX&ippaGTT@FMMzt}N)|Zo2QvCU1Aoce!;_ zD-eGK{7?uijKkPUWl;XWqm7{D{t31*Pd==c!2$u`@PZvwG<}k-W(AeXqv8gIH%NK+GTn!-O^^O!#I#fKsHj^@}O0ib&(pjU|S z(KuHUpr{evd;rv##pAYEKVa~+C{zZ+ck){yn{yuKW$$DGz24`WcXS2jL)mg`rS1<0 zC$&;3ps%QG{#V2hz~Vu$NU}q%Fh`Hdm_wo38<+_zq+9Xi$_x=4igH>Q9~&Ak$i&)> z-_7R~mw6T>aG5hAx6Tx14Mpi7AIIM|p&B^Br4(++f1vsq*4obAtJv+wgX~Dq^tIPc z22F-?>0bCrUjb`py!OrG^3L|`J+p<0cvu1f)>dp$LWD}_+X+SN2P;rlj%pm#ri}}8 z6>8n4SVV`yUL^VldSc_n9?6nDGQ{TuhRj`Azfl9aGolz8E4mkc-RUtKIoutd%l^!g z>CU+Kdf1r;umd1i0{>i`HD}f|1$G!#Ql3+3)f^UFu7w2gIm(e8vZ6 z@F_%CuxO`7PA*BL9AK~IkI|1q1jG@bcZGfl7Hm)MNyI3S0!NEV}CXh zm^IX8v+z$02s|$To}Yy2dZmDz3 z+dCv%=h@T5!V(EAgp#`zME9f(l!U-+x*+}%M$58(3$Y-egT9BX+>*m^B#)`KU-T6i z#jOO#iJQ5`&>tD0mFedlg(lzV;To;%PXjX#)1Y=(ROUF;Fdv!BVnvDz7JlbFYQLu^ zgdRO;pOG&5mJ3w!$j+O|KITYugGU!7E>5k**YB{US_vLP<3L{nwt58O5Etr@!M0#Q zhl@g@?azA97_mzbFCsLOO-L|?y7M4D#&eklh44(W8{O#}Q zm3>iHkiX!Mo%4Wwm1NJ7 z7ov}_;lAr@KbYFEMqc+`MPCfEPEbzb3%KqDel1Y5HTZx-*!&T;Iv@QimR!f0V>gDK zY!dhDVo-mWG43YSh>eN-3sC}7&;&iq=BLu(C8DK4jib8hsD9j6z|? zi(!YUmpx=GE)_-@n>!!E^t8Y96xj4{7)x(wMfmJKr<1Qr@UfLwLjB{6YBrYlQ$ z?F-Mg1huKuTlYf7lllsthhqYapTbbDxffuwwHIK@S2;G#wRU)b10p9@Tt!u#8Z^~ zh||m05NQM`OvM%5RtMdCgMIWpN~JHXmWzB`+s}Dv1#~pWYeI@tcL(E|X2{Htq-ghnGTcvLDus-40=$+FcYM27NcP zqoLNl@LBwrIkNu@n@xRF&uPtUa#WsUwwT*#vZuY)?@K;3)Hcj4tG($-gSgJhFVE#{ zHHP|hZ;V`G%aHZD(YXX6EKGwD?{2UgCNaC0+CZfVvSpc6s2c=za?!h$z!*p7OO0tc z76fPnr49kt*pGmPu7F){vCWJdN_;{ph0p*VB=9I%Y0G=pYVlkXf7pHWbq|}(zi?@e z9erw(*AgTa$vhx1>fBLX-oc)Ke2J}5_?dh6AWf_DWQm&w#Ex}#^hIE5Gk~+H@gy-a zhhd>KXtFV52jRQ);n(m-sc>GlB}d-N&*qlp^21e_O#x4xE;C2MTpI6oB4ELwuJAZ@ zI=-Q#T$sX(m?SrSBinLG-iHG{1T0rdn92BEb;e)^irX`nWTO+N0kgU#;CvJNi%CX5 zC`e*O$L41#=0VYp@FZtd;kDq&5t8!EKuK3qm* zh$i*#RD#X!xd~_pk>N}5_p4|ay>BuuhPZO+ks2^xUUS~z>ehb>b_k(CTWUPh?b=$; zIIhSu@P@6hUqgA3U_!R#Y_8i%d*8-omrU3W#Lil3jw7#ZzlA+$RMlUYlbFZ0sQ^xOOw7+1G09yUz}IN&^cXmq7Qu2hVVPCCC3#$(4yeN`(%~C)U*0Ki@*j4dEe`JWL*dpG^5*^CMjMoXx!#xcUwL z5#Tp?uo&Ca-WQz|rGS`!o?kH`@1&Mc>BbBb5X&-jP0>7_N-48`G@@xPlvLhiDoHil z7@mq(*jl#C(%EHg7mjqN)+(ZX?@;MnD`}lt^6X{bXT1}JOGVA3L(e(_EA1XUxoZu1 z!apu=WX#R-khVXK=RCMjcevS(e&pM$%AC+eVT+zon?L*T?BxqVz}~LJNrdNEoI<6E zztlTQi*B1Zd;7%Cub)5u+$0v{z_)D>>3D6By7KwoEq-E`UYZ1(zHg2F5jodch*bI$ zoOr)HTk5jzcB+Awiv6U~dXGyJD21Hc?dwT0qwLXDHOn6#sV~wJowx0tyB;G* zeGnG=!Qa4{_Is(tCdfyf_`G+yk-0sTA9mIITn8jUR3m#_>H>Y%+2Xcx{H)*OvF3zR z&6Mv~TVlMm?B1}1Z0zQQ_plM35~ z3vSm}*yQrKn(0^hH8WC#PLQeU8aNDLJyJ*&ORhc2E8L-bdECCB2OJL`0c3bxjS&yZ5 z)aK+HmwVR>@w88J_xvI7b{e;NHU4$6_wVmNvgos~c*rrgY`{Co$HA^hH~3SRizZ+6RkqMO7&q=%?K0o& z7Mij8NHuBIz5WvZ#qUQnC0AvPg|rD!dAQ{T#TjGX&pLb1i1KL)Gy`xKcvl5_XV$S4>)iJEk)(Emn2-{*x2di1PvwbpkRgk$kX47@bgn;Lc-PuKslHHs9 zS6nR9vO6|3Hxa9?ToS5YL%dk=gii&!>)#mPbI>AyY=tUDG^^r+&xwTg}|$ccJ2^nkwg+HCi4xM?KRC_CN|q$^)T(6V7C; z7@+c3c3DvLJu=l?>Q1;f_~Y}v@;f@4EH{Y3`y>^6gu0FT4`A5}L)@p328G7;LS6Lh z-gAjA>v~p}yh>ZAn_%WOLmb!^jU1N}>$sCU{@zo&YNBy3>aqfwVj41N8iXFr#lK&2 z-@2xQ%}kf-tsmppkg{~(#xe7o!)y^)REbLw`HgymF<5TIbhcl~Zj+}qYujxSM#WyN zy@3icyBnBa!Nr*3CU}w(d8)`}2PO>M0 z46{}IHE2%|x9r*T<&t9;r@EHX4!1Oh>BrvUISi22tQdX=k9IBI*>pOhx9HYmaCKz2 zlS-A?iCs1j`)daw=VxfqF_<&`!)A9&W=hCjgYE&fhfP*ha)ptETzC9v4XM+rDAs&X z)lYq=RsMT~c`o9;=2(2Fk(L~6VoN2|W#?w8=5{zrEE-t(M~hm%7`jL>nT?|<{{}XpT5jN$+n91*-8vvzxmrYd(W;t8ui(@{WPR~(_QJY-_-Z?bEi#< ze&UX;8F0hX)bK*(Am`3^H90DVc_ekx{LLqH)uT)Ed3YvoT17IP&dAkm<~_wZ+v}+1 zM^y7(7gjEl>B{7oD13u#iawlfDAUpKXk`W{Ysf$xtr)ZMAQ#)w@7=0Ge6nzYgw%7xB*45=d_(`UQ(9MS8*%Td))(3PmCdcYwR7_j;7aAaQN4O}>`PyQrY)!Z zrX6AYD6=PlLhRrQl& zo845m9ZdJ$p)|cDB)FdV{zPRIVN`$W)Ga?g<&uS;+Lpi0!H@CPZ9krGj1opZGWvXs zGL!aGdSyZ_GDdNDAbX8Eq+;~-^Uv3c>9R*4W<4KF-`V;3!Ld!JNyEJ!#!sG~xpvx#zm{traa*B# zZB@Rjm+l#q;BkKP+s{XXO0ghkHA3tS0sUImi@i?j_a$cq4~BQQI#YgLHsDw%XNOFd z;=zw9a?LX9(2*9+UpW+H z-J6aMbC(%!JTt8@TWOKB>xKd*Qj|-Sab2zsacdXpAET6~Zbc5BZK)H6M%I&?G11giW5y#Vtg?@(4HBuJCz-3;F z%Kk*HzSRSspGke_=bo!|U1QkX{XAy>^lSB|S!au*%Q&A*QZ>lpq1IJk^eQ)6WrFKQ zpe&#D6XvK1K3%ee<>VI{8nGitQ1?sA=xi=nsg&nxPG~2`0j0`Xa)Y`N`4>oPelhF& zyUWgzy_l~=5i;nby0T8(bMNLqm?EFFajz%KUyY> zYY1U%veUhlok?xGs51p8g#>k!XO~{MoJ%w$0S@?9%wd}IhHs!eSO;D0Du2j)CLif) z9Nm<$TcrNm0Yh1dR`20KEz~^yf-$ePOSvuvYyG3;qIyNHhPxi5V{BY{{~q&X?UMOL z9c)}x33r4Bv)wtt_A7j?EmI+{3n@W+U6!k=#|yV~O}amuX+kr3pB-xyi&Dc>wI*ua zV&Gqq&fC=udI*g5za?jV*W>}|%1~Itr2ACp7PAjk;HU;UY+}71_YvT}nXiNPnU3b? zVCOxem-Dv7f7Ry2(>Fr?oIPzl43i(tKJ`!Axh=I$>bEX`wk#rf$GN=G9$h*>u&-ln zK{Q^|`;}vCK0i9+q-%EWH=KDKzf0lpa1J$O$-KE86QMAqaj9y=vC#^h49F`N*>CbB zParcDh5*&(t7qTHQt{sNoo##RN)R_Ye@9vrvK&B^%gw)3c81CJkTlYq zLvP|b{mPS6S3NhK@z?-)wPwK3@II!9N_AFg!@C(olQ5B>H_Aq%LnQn8mzT+U8r8H` zB4L8P!(C6e=tbeyPrkqzsqn={x#Of>0@8oFPHjXQl4M=po*zkltv(Lo-}UlEMa}45 zd7%N*AK<{OH-Pfm)q5!V2E+vF+EBlcmE7>b=qSU)+=_Le z?2Yz3Xq$7inRiqU1B52_Z`fqr`tFPWttAo6uB5JE>Mi)`)0N({E^8&$Wims@lJg~~ zb$mdrlh)<+Oq;%Wtbb;-W+}zhx~!_uD}G)(jv%l3u=e;x>3+6li;c;fx+K#eX=txLe3xoGbYBq0-?`|QAZ?51qP;%7_yHD-YCHt;DK$k zxl-DHob%5ufNKUI1G3wK)m;pMhXm~6X7r#0J5Oe)^kc*O4faoXG;uIXGUw=W`Yj3J z*Ezxg-BXbMZ2jf%Bz&?zktzjYEV^Xj?8CRpFfRdxP66T~1y)*%diWDpDBA;*K~fF~ zNnuHAS=*PON2FrtehDs90A~Z5lQhrAc%XY1=Ak$TtavoZ7ki!sxYB4cF7+Y-B_qu# zEZ`$0{jLQ1sZPmd9&)`|R~GL0XGE!D2A)Lll(|B&H_!tMs1p)+8wE2e!oI0Rmy?m% zV)SAfGRGY*3&qPEx9ey{7%F&xic)H)Cs^f6Y1n5BhLoHRp2vRTsa?B?g-p0RQ=#dU zP+7l&QT>U_C7>Vjv5VAPE`S)r?<)iaxKP31;vzf<43-0HN>GVX0qz?SS7n8r zqMVr)C+7BJecXT_^AH(1j9x-b)GB-gaLW?hZ+GCDFbKSC;F_XXr=(~rMz`_dw#2CE z;@y5D**zgjNqkr`AJs(;ZIZy8X{f~jR5NjRE(LLlh8(GtO-s;cMaU`vW(vQ%ijR)Ak7yF3W+i13{#kz+8bv@{ z4}{Odd{j%ylf}`-{j$FZDas15>hjDnjH8`PDE%Z+0MFxArDB{EUvsvY{Z_5)F%A2ac9OXa{oZ}%J?PwL zu|msJfY^0Np&j;?srZ9{8=eS*S|K2bh#Hj$gF2stU&t;Hx~UOyCNKQPOmZ&)Ju1nN zSr+H{UR+|4lmcBxC@o-DLzm@Vjw(P&=jBN?h?M;)zF4>`c3gmc!Kn+X(2(tIn#h@d zXBBoPUQ}4dmhvI#){6N+LNM!$z&EKHh)DAQnklFzksqHHsMim}Kwz>0+f^EBX){7* zE3OBjaa|a1H@~N1Y>0+}P=c!wBUA8lMJ9l{fD5%MedPfxjMhW?6>j5Mm(?S`tl<7P zuHM5d=|AxIM`RCq;~ov%xDw4AEpg8bT8=Vtk2JBYv?a2{nU)%^LQOL@LsK(bICGUF zD>ExCE3<`7EtC8He1E@l@45Fcki+31@7L?`d_0~psvk>n6H+|b@s-J@@#!7Ay20(j zbpBs;VyPYRmh|{b*7i7kbN-QpyV_CQ$fIv(xx*6N5Kty#UQx~~L}ZIUaHP0m7){Ga(%`?x}DrwTB9l!x|XVd2*%4u zxZ?kY3Ifzd;N>K6|E=;n_nd}z7kCTUVNyOKPXQ)NZCJ5Y7-aa}mM7|Mzz88HadK;| zNjZT#eZ5k1{2@3`W5B8enEXRLz|zM3K!Cd0i_@5H20BQLI0Qj5Nl35&euCBt4kp0h z@@FI9-CWFM26_+aa{uv0M0uGp1Ad9pq-z4iOZP>9^B_2O?1!Rj9dWA>aLo-^iVROr zD8BkWnyy8pY7%{<|AE1eHUN)7_p2BqUj@)oiIy@p{*@)!hDK*J;y*UOlVlQ+xMGwY23ZX}5A z`vU8FQHsWbJc<{t99tt32k@Q)TMo2U(iNl|x8L?8&P@U|s$UDhNH+m?M`C_iz$q@u zM6P15lJcL7bkhz*kQmt{#g0~?ZcgK>AV?o6JoFYagM`@`04@`}yRGmOpcYt66N=&@ zC`kPS{zVdWqYBcP)|j~IGH4lxmP0KmKq%0KD#t+c(32klp%lR<yz1PTxVq(g~a3{t<0g>91(&OZaXrJ%4pu$xrBdI65*5#JQ6U%9EU+Xzp)5w_jr zW_}6$e!&&zWkULieQ!;y`*gI<8UuwAM3Ub%)WQIE0Uj@jiI>8qRj6YK1UO)bRsrw7 z{FWOL?G&#;RxPI-_+ZS99;D#h%^QGDQ^hZG2yMX#Jg@CyuI`F6FqHs5(geR? zr&T$P6_JrO$~Uz-(E6RJAXi;2-cxFeYbI?g5FzQgy=4$IUnWL^v2!s0PJqX@-p1ES zk$2Upy=d&~K2#;66WP)CwSHVl0&yk*DS!VHNAIu(Zc4FnE}f46g?dlm;&7NhsJl$&<`L6!+`YH8yg zOptY2RJ8(c{3Q<%Tlm9`5%-{PGHYs@vDYb~P&xFBEA}QcAf6d1BwQ%bBEN%z6x#HUMF3S+#16ox3Sh5kL_|gd;Obzv@8IbL)@}~~wb8dXPLaO> z+fB+S^*n)Zf->&}VQKQ<|3*8qW zB>f#@ukNU*-EY&HscWCbfxE(yk>;Pp_@DE2U}0S??b3&+!S911a5@I>mW@GTGFeC{ z9rf7|*tZUGR7wCIo{pp-4@++--v!QYMswaa3$jyQ)(DR@Rh&xIKC@GY^&NRmI!sSRSLNQX8X!)JM-arD+deiwcfpP` zo`8nt>UF?3t0SEOnCsK;Wz_6711Osp$OsBIjFt$WNsd`ZJW~g}o!z<18hh6WxjUP9 zfLfyM1L$1P0QV3x)C8HhTW2+~=RIIdgufYV9mhLiQ$Ioe5lmPr<8Jx^-wAvj+kHf= zr|S^B;|rG9vOV*}kBz>*X4r1n^`VjN)cwFP4d2dauBBlM!3hB4D!2&Pdjolh(J!MS zGVqS=rx73B5Tpx4lihmO4g>&qqW+G;a%!3~^~9u5-~DxWSPS@`bRP}MjR4y7+B z5~r3Ah7TT8zefHBv%qCY=Bu`TMy4v5-F-jLI01~pjUPX$+UlpW+K5g;ajy|?<-Rug z&Ba_@d^i0YnXqV{*CZ3y$fO^@!QTias30Er(vU8%o&Q{fPp-iy@58rx0b`Ukvq650E?2{m@}EV zL;0fKzXhCW!Jg-!g=D_3=E8b})x(dgo?DEb@MoR_xm#`F(7y%#%S8=y?41h+75g_QsCHGX1U z0Kf51*Y!YgZ`5#YfwADqSZ&ZnW4z|uy0J@M_bQT$cX^I_)WUyK9XDWVdLnzhZ|X$V z%=^_2_FZr(+4H$0Q8v=S;T;iKac2};3;byHuH;jd)a3OCo;1bquzNVa2G467`Zg?| z$dY=VPbqD`+T;CXUqtQEd&%G3#U;&ou(E%l)|BUy#jqPMlm%D!n1y!B1Rm>`&XhPD zJbL)wiHOF?4Lb`k0f+Rjj$aNMJL}I5^9*R&E!$`W?Rv&2OJ&$;{#7$szOZ3(xY+XI z{!@=z;r81e6l8_kapJUdK5wEC%mOaUGz`eaDMvNB(R~WuQJE zC?9VB5OE^~Hek@gxn1O161V4hO$*!GS)g^$@l9OGi(Sow=cg1ka~!--hr&0sH_5$Q z>r$KPs^Y#`BP`oy{9LHWzvk@M^Zuac*3szlrL)H9ry6eg9+HrVVhv(NJPD=099jI$ zdLEmh3+d;n&YWI?1LTz=Xh-Ur%vh`;quA0h$GG;aaq)^pdNCUY`zmve-+0MbOBs2* znWSEQ(>FkB~gO)0wsp`ScGAqGH85_VRwh+J2ZJ+yX`Q-hUeH!qpW-b ztGYj~O%fMzl@trU{s*uFAtK#9 z9lKtqlE$IQD3Cxe${@G5extFM1*(3^aG`FMDoUKXc*MQrpZ@B%upg@otdY=`4uJ$v*F}8CW>S)z0KBNNryg56`Mt6>e7fWl9$Zd(-)e(ZOT5pP+f_{Zbf=#H?L?@y@Vlp zRTM0<#sa@fj8|$P^;%XpVyMm^ytkb2(Rg>m;oytQGS!_k7k^^D-5g$hNvA?-YI+3( zAEsyRVMe$`_M6O~Rois~$!zmOy&X&8PFs6xUh#KvtXg1n8+Zp`!{|WZ_XjHvx|7yt zT(*&DL@HmW_E`CJ;i70xnw3cm!ygj8B_ok@$w?XnwKD47@58Bb`r z+upTE*JV00eI~ljo>X&!WXG$;MrGlj`R4Ygb|9E1Ltn1w;#2i<_ilSci#qxy!v=it zW|6x{rrH_)%df46M|y1|Qqf*>Au9b7u9gzrtC5LprR&o$(%lhzKcaK?t9Fteuis&F zYu2XcUcqK74!0Z>x;4y+|CI*jN;}mu(|P7h?X)r!&5Q=?$*V(;_pTFlWHUZFD36K;eb^SL2vZNj zt>ydXH`)V&6&R#5VO^7&Qg`~Rx^imDzwtQDa)9yZv8H`w5(?yXM@!~ zQ~E;R1+NP@-J5szwlrm&lHb?f_@Kl#W`o*xg4NWc59rA;*fk_-A zQ(_il$T2KVrD_BQ!+CFZ+I(E(t?9psk@{_VZLB(1JH(;AeWHq+OK)1L|g9E4$#x!>+&r?Rmv%!?EjRrapKg9;;pqi z)+`~a?6wm-;) z^jF|_`Bk{x72?f)NzZH;ugArYbWM6XWCouch`x5y%*OfheO$}Lv4?W5MlD1<8i7(-+YioUXqs zNtbZ_jYEw^R#007_TFQIHRY$y?i-KWGUSrr=-4%Feg)Rp!h3M5&f)65KB#IzjeNrs zQCjGV?j{D+Y}KC;lx*jmPW+$GH%NQKUcfZII^4~(Ek4-iJSFU{SC&J$16~>_q*g+#%j8aP=Lh z{z6n$TZH1y%b;54I%zgmOK0?Q$O*lRPDh3AA5%YB{t7Yd>q30vgW1E2dG>u>In8|k z!${w}$gYnKc!ZC$Q@Gi!rWc~%vvHCN<;OEz?H`onKliVGlc6Ap`7qQjb8RK5|IkxXvVEi%bz2@~3Jw6>JFblpLaG=uM4gtablwlX)_)qrtm z&Y)Og!r?ba;Q_4l9qK%-n=PkxZ;mTc9=}F?2)1K||xJ9W`8hb#|DU}Gqn**eO) zu;Pnkp6h|lnZlMo=Q@qitP~N;sD{(6lv}{I2Gxu@>R9hS-abIhQ77+?1Mf+tL5@@` zOQBf33m|`1PsVK@MHm?d5N zB;Hyp?N~}bn>h*(0qNgGeu*S^*aGXV4$~~{q%RjjNDz}{UQlkl19T~^uq2CB> z+^=vJ8(Kkbqo!!|I?Cy98fqNn(01l3cG7<&-s6MPe)(hK)Za=Sl(`t<1h_t4c=O-?vd2p-@;_AQg`$r@lRTz z*31gb{mwFyl%>zK>X)G0DS^kEEY*!-n?*UKD8u*?qgDw@#s%bV@1MDM)1G;^!nXbNW9fpDT?zN#j@5=j zO0_rYOD=reNpPowi=0BaPk1#$u=3sZwQct<(7hfCy=B2?dq?yh-ZZL?pGNFbhu+V1 z$)qR*h%z~TrLDExt#uhCJFwIwxu?btMOK30PY1xAK&`h?J@Ca8`p zaLav-@>8uTqW+>r(16PA*p~^J_E}i&U_-V;^l3@UyaXz8b0=SSj-@ZD%@(q^L((S$ z8qJIN2P-@_&h)Iag=&l|B8+)3Z=>=nd!ZN!#Qsm3DfLV+aK5smA$87x zwXi_kXA8+L1>CO&t~9j5737f&`!;AFAIq3)XEjb$a0aHOqV3&+$|! zYk&g*y|Ia4+Lr~jFN3?(6{k*c$bF++YHDL2zof5q?P?E)f8&8FH8lJq6ejRb(E~)A;R-jV18| z=HzRw#>qubVval&W~QYGksN9HxO!SnIXH6S=(e$cjSJMNWXu*pbkg}-t9DpNJw3MD z&jOovyYFf^CX^Z9Zaj<`$m<=Ax$|7z_0B;h`$4+^$Dh&sa@(TQlQA)MrpAbuDMtNG`PcSrVr&Q%3xYN>OR*Z(2q-34;CJ?}x; z?E~DW7QukhtJI18UpKt^z9sYT;b-G<{y&bq`n^rS`o9PxUyv~B2QMyV5E*)vyBLhF zpp=aF^@+>7(g0o0Qd^>DK3~l!=KsxU?>snE^M6FH)!XvD4*qY#=wK#z?`<}HnFS_reWEW{_Mv8Cvr8OOm$5GrJ+*f zi+f;B+s9LRATQS&!&XZEras zIo8#ynzRUtToW$OT?j1rZGW$ggFW`4B=l*Mi{JOfEuhHt{n{&z7kyrYCh(u$-@oL0 zsr~m?LfN>?x~632tj?SF5lhIoNTyW!My>SZ#B0fC;OXEUXn51IY$4m4Mzq_ui@SI6 z&f~Q#oON4KfP#J@=@5R8Us(z)?n$820X%*BRB#;F;r!|!^_sb|2l*Y0fO&WneB!QQy`MC^tYJlL~$ z_x@AFE4u-@>4DET%=|Gsa<1)%ui86ZZL%i>h}h6An(y^G+eX^5w;;$TR{QH+eU*t9 zVNr*EI9;e*_tqEi6%KsuTpRB2n5d83-^Vt6ZtLkS zPq(2zaB6u=e&qLbw)t+6553tj{lj3S;}6UHE~4*r>Cef{^zaV>14objpt{Xv<#xfA zHo%nkF3N^}z1k2*{MNTa_X$naWmRl0%RwsUzB2ps`$CX?m=WzhEAsT%aV;n94g81| zr9W@O)n?TQrvvkOo#tyh0vrpj)h~S_n;8R@O=`_9;$)?6r#B7|<3;;@DgU$x_uRbx ze$#(;dj5)9ocpA*KhEODjK&(d_th2WPmFxnwcdQi&6jJ??m+jmAC-7fG7Opdx=YW0 zzIpm}v>|$RW5og%Uf!tG=Y(4R<%PK3`R9IutKB$9+t9eEl%IQ`Hz_{AbfEr!QPfwMjtlaHs$IW`vUROJHBj zrpL!+Ox5o5ZSRc&MXGKi1x;%=(zWf~g})BjoLw7sNw9q=Bq&LwHEx!gLF(_gWmVN< zsoG=yqGO-i>GRebis_kNtn+Sc8{X%>h3t!+ueVpso-YL!j;_^EKh9^uY+g6=zSyZN ze?s)-be}<9yY)uftIw@f7;}Vz4SP98w%y{>#OpgeOst;1UJ|{7lshY@d{^3U$sgPD zHRO^TG>PKT+Qdp<>M+R^uilQqS=_xHjyPN-Kb~$W)RfDihZ%XRDF7$5lV32Q>XL}# z@3stFueNqM)Dn06d&xBJvh6X;jgPXwmqMR;73Fdr64x9GtI|ScY0mi=vcZSh5jDR1 z8<~CTN$u31iLaHvp!wi0I^TcX3@iBzx7`g$oJ`o6yeBNbRFH82=W>bK4&k#~!_5Um znnHz?_iN6mGJYS{%P;*#PhfB?86VXayO zmpQh~d?*!jBMn*#(m#2v)B47%4fuIQf9lGza>W)yii(fl&+2uV8hheGn(L#seN2CS z<%y}zPV(bKcQ>^$-a7G)!g`#i&GQ(Q)`PrwV72>xY{*md#ro`V>}$r-##MEi1*U@< z(HgK4-?G$T!l}hBlJb9=(N4uOhUv+>BIlB}`}7kJN>pUT2~Pcg0s=SF)4^FOvgOxn zd%;DR+pYU`{{#tw^cWql#JneKxJuoNNQz(~i=k(uf$;ANJNB`($GH32nx%@7$=v|E zteIs0hn}D`hNh2OtKDSw+F$sKdts@oUQttb_Q?`^-n<|4Zs)yqla1MWzM;<6AxiJMRaqIkm*thTRtV}rAuqViNAEuQ+-+RFkd->F z)A_LNv#IlF=&sG?ebY;9?Q);c8U4wTR0T3zhqN=dPaV}5!JE1L_!Kn^yhU|v#8soMij+Up#xKIU zG)b!?v*&)3TvpuJmo4x?C}-8u#Wd6WTUp_omZks z%&y6sfhb=T%K47lcK-U>V2n@hab=khwrcBGFnhDc+;!>+U022IXqppg#Ltxyrhu*Q z+}ayI#<=ac0#TYlUjE&g&pN3_qq6{_-|)5EA# zY2rzPHa0_@|MXmNmW!dhR3<&Xj$(oJb-pzdM?jnYf~4`W0mQram)vfz!9R3!(%k;J zi~5Ut82=5FoGWfaa5ZiqdATTou%NeC=~4{ z@=uk@K@?~JRs?C4L+xblNe$+qwL`!Q-2r6SJqEhRiLTv zRYzg$(-NX{eS@V0>TkktKOhuTFG>kFqy)-QV9pRIV;t6SFjPKg zn5FPW3aA|8!V(gsDE;-nuCXN#&4BOAn7z0&9&!iF7YP}( zT=u(IiyGp@dtT$y+|}CnF_6w-o&u$o5eB)(d==hM&daAN$anCd+G+CzxRI8qRUV4( zY>w-+5yzz)*F;01GpaA>2*UfA84B=9Tv*g?y1K{nrlC@}7~IlhE{c%1m>F&Gz;+s@ z#O*&cZH9ssQgC3*8)Rsvq_~T@2=G=BEPO|R!c_($Bp1=_0R)PX=OO4y01LVplkL!X zxqzkzaRQ0Ab}uA#updha(RR3IkVv9ns>FDx#rf&vJT+M~_~-HCRPZHcZAw>UM;8+4 zcsmFL0HD8i6x?Gd{C6=c#Xspkd%rh*LtYWcas`QyjUxpVLx7@&y-C8fK!Twi_?cX6 z0SU{WMh#N%QxyCK8V!|zlra&xy~yUJ62)Uksw(-BOR9HDpoK~uSz|+A(yxoiW1V!PAn3nj4DvTndgtk zvK1lHJfz&&$D`3ji;8<}0}CM7cnZ2VcV90v^g07~VFPZs2meNlJtrlU@NjM7V?rhZ zmmse_d1gNa!JC9b$iN^PO_8;h>Mh{Lrg3vW2`wW6BYIi;kqcwYQ_a%z_Lxf(epT|R z*>kxH&~p3`>jHG45GRN2W+rZMin+dL>*O25<08}<8(c;4MVVMZ%?{g|4}@q!y4&@1 zj@CbdN889nS5h$kG|Y$!u1Sh?_Q0ju;d&XkDVjny3PrF%rAP?{v;+bPf?j|ehSbO? z1?d!^lLiz>Lkvet&FFaVU)(_&{+X1}55X@l5zZ_Trag#0i@;6Rg^&FJ&`um4LkdY4 zh!z1ps$gOShD7o0Og5lhO<1Usr$R6@dFFX>r702JghO~9iFF)XJEY9-OMgY25hQx9Yk14HCB#Sk(b z;UcQf79rnUKD3oyy>PjHU|zB4!|6hhBqV`fV<12fS~!AgrsAqckc9V`K@q;~C!th| zlCbc>=r9nbQxiAK%R#;VHpnCjOH^Q)0Su6Uz7I8P%3G2=l=@_m*FcK%aS^@~TLMch zo?*4(J6ZwaRlFShqXj%3g6jAU@GW3)W1vQY`@pO^Z34*Q+LodfUP#a&l(kn14W5IP zQOo@;(S;*Oo$D4Za205<8%)khr^rWHTD9XF;(G4k`Xk$?_>oq5XJ|%%@l?C%W+0Xl zc>X4l`WsQ5i!Bx1z~4s?GxrvPG5ag16k5i1A@1BXy1^gc$V0o_x~)V7)=uA^l`4Q# z{_fjA7PC}mG;F>=Y@TrJzHi#!-@vE6O5A)$75bWNTB(9MLB1YH9mGQ`k)q2;OMh(E zu~0E3u8|hi=7O_0o;V^!4;UiTm3CBomp70>+Vw^qEVW`*tbmsgR z+3@$!vg=xFua74Ab3_bC$m*)tWrjkvX@K9+{$vreBPAysTpUX$o5682th zIcxzxHjOS4qZ265+y4kkl0kXxH!=uRCRO;#0%jo!J*RNx%usJU_SbL1%MV2L33R1e z;ktxl6O_B-q*mxm+2>`#xqZE>XYS5Zh#xl-N8b_OQt&LuP6cf&V1REm$(2cwv68jW z1((It^?^*d9Sc86Q;^$Cct^n&N>eWAM(fMLPXRd8LBBkNa*G%)mPsy-F!RoB29nEi zc5Vd@?ZZFoA5zRKl92)*ZOA+@efl`FKj%Tf#_Nb!0G>gb*{)FZ2!in*dgS8`tfIad z{0oA@_}3(0TH5?TO1M1Ie3*uAGXq?(7+JuqyoCUl&?G-2D%6~0`QgVH*Z$l9dSA|2 z5WzV43-g4kF){Mr3*h{XvWq0lAqc`?ZoSiw&9>j+?;U360K#|R>!Ot4)*rF=XgE<0 z&VrQ3Q~ayP^ik1@=5}wJnXoF#vwqgoN#fIES}mVX$StOI!(g7ik$OqD#3z?K~Scf182 zoT@rm$-s=7DVdM~{UBi9Z^Df!px1}^m5h~GjJs=n_7{0}ND za3kcdMd5BQu35`usU_JKdX1qi5u;CgBAc<%UG(wIyHwOHw11-yahE%%!P z+bO{OAHu&R1YcC@yF|#N&3wL%+a}wLJr{#HN6S86bK5HThCIFO&yD1<2E`8}D^QD{ z$VP>4+kpw6;eFRWPp$*rQBXNg0Z6dI3wt&k-O2fFKA}cNto|>jUEG+`^wRsLV&imy znTuwe$qk=19eE3=*31aZBR$II3|l+PFoA0^5&3WZhPiDTl%UqIqNcicG{KP{%bf2c zMO_Es_f+cN>OHZK?O%y|9zijA5IZ6MH~7o^X}v@2%2gx3>S;~N5gL3D-8bG8z-b8c z2tWb`?CYl;rc}R}8@fcUJTU6(8@=aU>Pei1Btz5sl~(90RJ(6Z7P5y)2~oz6?Y;6) zhjjh$&&RxEG<>DXpkj%`PMO^Y#~wru{gU%3*^1lepq3cI#ebQ65&Gx+yd(Euz0lHLa=EK*c|YGrKkbv5d^!!qY+QSWZ!%Z+=B!1pOsI4Roll+{%gbp`tH1TI{8Q`4hk9RDb-L!gLLBNVV^3SS z73x~XkVk&6r1J1N^N(tAT8IIv=HwOr0E; zHM8Asr_8&1nx*xk4WB0rJbO~gL`_x{#$O6Xn5baK-j$0n1BjkF{xc_q3%I5{k>w8| z3|N?$?$51b7tLmD6bW=P*X^?q*v+;-t5Whg>-<(N($fL_53oY-XnKGd%c{0a>Ee%u z)0Qru^K?x{sPEiJUth#Pb?Tk>oTz!TJu0oZ+Ad<{8@w>(?wz7)H{GiZJ2>m$Ib-a4 zjOLoeee_(>PvajL*;d~t)8tIkmB#o3oV&Ia=i>GLy}#F_ZRz&F;}_$Ms0Qt+Qu)ew zCGxU)Lt6;uK>4=c>!9nCh@A})1n{)x8F{5WmX66R&-Z}U5qAUg76jNMD zdecB(O6k(ai#u`#dm?=fSA%g&pLCWk9+JD-QLrZ6j#9 zDA%>sn(OHYmjSU54wtn9kpaWFyrA&cOf!}3Zg=eW$dfOe9;r97nq~WlQ~gC?(P&&} z)nkUH!yfLs-wdZi`=7ZQ6++T3Er;%pS#ng9NC{5fuPv@mJL|r_r0?sl8!20an|Y?9 zw{KvRnxt?&aiaEEJzFXMwzI*C+$CGU8KI@#fk0V8Ic+3)z>b5J1slAgbZHCW7dFU>3WRb9Ut-je*EqOdQ{LG2XbXH-9I~QU8Agt?dUaPD zVqC&%NT7u5_sUGV5iyJ?BS9T5Nzbeqcg6`Ux>ofv5g(&xjbur)>rYx>{PH^$_jvHv z^HV7spB;!7W(f?U9q~KK6^U+QObpJ^lUi!?5%!aJY= z%b}#CW|(^immvDJ+A64-@!efT&Z%zJVcHm{*p7>^83+7JYvoDBXDx; zI$G{xm+HWXp)EN?v2c+~_72AEs%NXV^ud$Y6lH~bb2P0=boJOog*d8Hom0KXtChTU z1Ri|rkh_B4>B;hXrc)i_1HvXE4|hcqRyj<8N3Su^r!TY3i=wU=t~3hHE6ys&Bu_#yf5xGjwOli-()X7N}c( zd|PYh*MTXV)&kKm7NIHZ9bJZVg1i6=UJ+2njE}p zQk#AoD{mF75*CD<(m$%XuWV28p;4O?y_yxwdq1a#?IuVB<8~IY?ezw%!(xxMkN3H= zK=(CUcsVaShN^LM+l=eZ){5Qnn{|&hB)i&V ztdB^W+j9e!e8Z`!u^}z0Yp4U9GXwW8y{Oev9Ui%4wMqvsiz3fX!7O-3KAKi-&w9;? zCtXsKO@*2ZXO0`3RnnKuVA<;OquuIogOJoJcdz4P`A_sVAmH(#l3;x72wtmI%G(`V zsr7QPmsu9-Nz+)Apk06ZW7$^4s4b_TLq0!fcFGD0F;|z6dsLIQDP0Y2xu&@^e05se z_z1OjRWF%m;w_iXzdenFmvpKg|C4J|;i!7E&*i(LO;%Lm+X%Urd>fWQ3_G#w>m1Ie z(se=TH`J*yGtuj-^ZLut8~594(&5g>W-^Zk_Gmp4^sK*Bp3D|6t%V}rbjZpv3`+0A zlNvpVSj8x|umcYZ-ojk8L@!?QsyfH&w%qRu@E*vZxELcRso`hKw}~$^JM)Y;WazGn zgLMV`O}y!(zPr2u`}zIs;i}QJyD{0cw2gy;og)K{nLXBb9OGAd$WtHy@%jkXfx*9u z3pqpoSGjuJ<36?c6FxqSqfwFBus@X?>W6p&-Eut!d5nB9t?%B~e!HGWDA%I9%)M50 zCNGd#nj%DGSJ)(RP%q}GQ;ur9ft#_T{2&QGe)`^rTNw$-N^A})8gl0yc*aJ7Ge#7> z+F)L}m7`s7szhHHd>Eo2!2iQ380h05QBCHS!(aJ_GXt;2{*_ zIvs#r!;7ZzY>T)Pb-7v#=G@GNwA^ksiobh==RxLJaceExax)#^v;iK2RW|Fc>~h#_ zc96f1)!OcV>s(#Bi=N;}jsC0LG=Gs+)B=Bd+nQJ*pCPOcC0cMM8qI3>hbTy2EV9fC zwB=A^1&9z4Z!Q2KJ07d-c?s<`ReSX{2s;Vlmk{^74C4hLcEJnw;}`7XZ>U4;8b_Tt zaJzik@}N4xuLgb}4GJ>Xr!n|f=3Lme)N(yRV2zWv1k|TBq)hN4lMpG+8nL->HVY=q zy#I@u=?Yq0=Tty}_6`{A+^r&wNqL_|?v5lJ9pLQ%2iM==A$}f_wt8l!%6@ZDTd`v@ zEN4%9Q6dewlTs-f#hl?CeiDTsUVVsh)KdcgykDxhu+QEy|3lyw_PkrzTV9(01gXGAo9l#H1)%JW<80h zT?!{F)ni%P|9u-Ordr0JkY{gSO`Nfw{d+sgo$v0+pOqk#uawr&TsU)0RC-OFddBkv zfw|^@rL&@UUs(X4&?B#2DnJbBqTHyNb-4U1&TBG+@HKGdxXk+X_2=y7Va=;H)91L` zqr80kcu%iz&BaAOb`4)gt)frx9^bxjREqHNYs2`b9TM=@Z!V-d40#G0W%~!Ah@0$n zergTH-YO?S5(EP(&EY(5Ow`E7Zu|IWp{Yk+C2S;`v z;N?C*A9>6s!O1td9~PLi>u2DCUGQ#_ujzo;b0q z7;u;d^|us+oh`PqTlqUZ=dqe08U@&2B!9dXZ7aOwDBk)_arBt5C+_bJ<$dAh96RI$}p0BPl_p(j}U2MWw zk8svWVDDIi+y21!y@iD^)yw@d@TKteuVH7kQEmq+L>8GF-91z4VPBHj!LI z7FV*E_Wobm<)psEnJ4U;{iYQvS9cHFzwQ2l?vHl&8<${i4U(V3YU?2G%02v)xBCw+ z@`I;Abb#$iE-%C}QV%1{u5e|m6AIy3DNtO~-Jr=`~K`u@Vg{_9Ce5goFKa%`Ab_%YCPs z269}&e&Qgm)&d2AoDwS3hpHIJXrQ8z2Xkk>dK3jgxR=5Mekr|WQ|jp>x7gB|jb{08 zy^8iUz~WiqvgBAxeb=XH;VArAsfv<}#v_JP3Lp9=v@WK$!@qz^~7pGg)MB zk@$t$I=r%iTht=1u=yjM9RwW#z5$4_bD~n;AFWPzxX_!gA9DxBI<_CO-#r8R-eDmrk1b!3 zbE5qafk}wRw6~@P^NG;g9(%a#%=r(8j^ zm4@Bu6H_7m@bI9*&Tb&C`3p|bGL{|d_mPp8hkpH zUBmUrg=azY_szAWMU`l-e?Lw}MJ>Wv`=N(0-S4I@bk$(^aSq1;(AWVx7Iv+v>N6YahY8M);H32ed>x^>AY))T4f*-=Rn`MvE?g4m z?)@z|+izj*IuFwmi7EdO8KXRgc%oetYHMrgMd1Zd5UG_mlGCVCU6jf)b6}ME>kmAr z1~J|3J+;KyNOe@7&kk}?3Xx9Y$NBh^2pd;qXSVKiU2)W}7xNi!&+)@2czzH?{q+LB96{T!?`u{2 zV|jv$8T-Xa2bEVRDnG!)Eh1d}IG{&3fb}p1!f6!mb?)K$baJlzE`aAM^}Ee-X+_^R_`|)_yZ00Pf$?Xd(7X3!%7BUq~C>KR1I31&F9>#P}Q{um(1Qx#=J|>tL|_<@f32(xZokd+j9i(A#X+;fQE3LDmIjCrfu!a(0_9ssD_Z~iE2)!3^ z!2co&GUedJk>N(u#F^S~uQbC^?!+|rKr=Jb1Qpzc8_Nt=Sy|yWHN&mhKr1s_m{zv2 zx0RO3<#T_z-^b%V?hp4rIFIvyb2x|R^Z5!7_x4shXsIZ?v$}ChO2yokK3H$L#;!Fk zuX8Pj{s=LTestOK`r(A2o1T)62mWYGtUT_FdDb5P`Io`V-sBInH~M+xp{z8FUFhz2 z_bQ#bB3yUpf8E|K9AP-l{dlgmSTUK^5q{f$bpCEK-0b*f^^Z5*x%g(S>8^Wa*KaTC zS%vRi``lCRC+y1Ao_*GOsKqH%Nn+)Z^Wa3C z#h$FK9gQ8|QoHtLE`*y5o?iG8xAmpHujGPx{NpAy;WMK-9p8(xAFs;nTRfQxx4_dN zN@@6PNyUnpU4tq!bFzV(-fjlbp&j?FJLfycWQ9Si=fbnp*2b`-_|cjOtbYp6wLY|Y z-gIhn>7M3QgURQy>Bqt!TD*?)Mw>m}Q|?Z@3o0+#(M-v9)uOJ2%HSjyE9R6a`Rezq znQKWRTb;H#7AD+vpn#HCa}DN`y1&jD-R6R) z^j22hee(WP;eEgqCf4YtFJ!ADw95%^U#L>tbr%&p)2}@7j#Gt9C`qd>2is9q*WPqY zDJ_%-E@hUEDV%m6E+E`o&t9~6Oi<73e0HsWXa85FUbcC|+Sp;)H=d0TND5mfNSwc4 z`bWD!7>Z$1qc}ivRNa=FXg3Swgln{z`godl@r+%yL~s1WAW{S>fII*8iDR2+3YwiN z4BB<0T{th*6+BHDQ!%LiR_8xnK^_ou-c~~Kl2o?Cb{(dgD`%R{Qqb+sW8b)lPg;An znvF?&s``XDDJaPlajPzCQ52_IEPRGxMj3$FEY2ROSIJ$YL*m7#Jf+t++&j`DuZ@+r zo9Ha>3M6X4)~AWpYToY0q;{7HmSpH8AF={2dSOl|6MqBE$Yw1S^8Z` zu_|6(W&8}iz{+?HOJSKcNRlZ*80tz&zayNaNot z_{t~nw|utQ2_IxEKaaheDRm4qJ7sv#arC|{Dd^rQC$H~qB(tv}heS&ZU#{QoKn9;5 zlM}}3%SfFKF&Hf=l1i@3vRG2!tT<@J35K^-V`wI z6&GtaTv`&Oq9(#H_siB23o@U6B7XIDF(+yw-41DMH1`k7@&%~Gj4+iq0*0$}_N_ST zO^+c_XjgAYTwH=p`!rk!X(Wv4dL;#e(rkMyjEaif9USLv#$*SHbOPHjle99LixRgI zJ8JI~^!N#Bf8JeVa)dHs#20ia8y%C8Bz>AVWDO#MQf=D`8GAIRsj}ocTG*hFOFuc8Ze1&6pf3dhAE#4a>-;iqJ;_iBeJLc zZ0u^&ZrJIyR}XH!ll=gt0yef7CUq?G%YSuJWAQP*gfZ*vq^{8n;|k+s$T5owti@I% z%pMOlf8Bw8zHQX;=a9m#%b^W~j5sDYLub#D?jx`z2r_$o?CO9K>LaZl7JIeAPRjm4 zE=fai3KVwC{VMZ`Ee&ePe1DoDt;86MRGwXjXus8-Je9nbxa}XoMHnh}p|!z7$a2~_ zFS@0R-HhpQfw>tQmmJeuAlTGHjrc>vNw}N$Kk?%iSF*oBi9O6z(^Kx5 z*C1%YIop+^D&I(wR)_`ptoPaS(=AY}qy@J|+g{cK|B7^zn5(cUT!QQ%I%Uk-jmAYS zDc)Tl)vCYt?9Puvg?$cUPu?40P7gpV+S3>paSSuDoneZN)Zs9zCZ=w<8cZm9zevI# zsP7}(eBsB~0TrVSmUVYtJ`f-yBQ5T>4&KROK}?Sp;*z`DE=NLeTsAWY7cLLk0oxwM zC@a~HZIm_Vy^Ait{_>p_pfuBZ$f2{XB#yKc)9E^H99K9u^#i0vu%W@v%ruOtYbrm5 zG1PzDd-=1y=g!x%yiC7Q^k}k%%9U#(i*gm7wNnCN?I&h;gbGGWj5s4ZzU?m-J!kNf zuYSuU=4!aJQ#!>50_G=F4atEO?r7RBII6U7>c$ntmAWvfV=6{(5CgT__w zyk4m(D5`nFz|=5awLwNbDsW}Q1Z44WFjlG~IX zD{OH_=Kqb{EMKt^&vO6ZX!2+1lRHC=4QO#+rW`>e4a*1Yc!g_dkb1D3)M#(;X?8eI zc~(TDLRaf2*oKH>e%m#jJQ4mY!?>5dFe0fmCx?*!WN^#Od&93JQnY$c<=JcK)5fb+ zn+~r!x>(&aDhV-d5a$k>cVF6%iXcZRo=A>-XKRy>U2yPMC`=QBG%b9N>*#+~pzmyX zzf>xv$$p#AWx|3HY~!6jEPaCi-P`8tH=0aP;Sb56G^(X}k+iM)JA9>LClSK2qY2)uD(e?R7@9|p< zFNdD*Z@9vTsy`Z!3zjBNDw*w`H;bNk#DsZx-06F;1Gtnkep=Jz$Y=gYk5K>11=C-; zo{Y^Gu|WfWe+x`hcdFhU{8xDVg2MfQ-d#fk5SS4x`x;$gfBLsp3*RQqKnx=56zWT& zy+NBgVAJ5ej`E5-MRi+fmXiW@~GqRv+SRQLmnFn%?`w%U-1|w*c*F z;gFZD*e#1$dm7c0xBsdR$phiZQVQ~I%Hx;%j4R}N?b~U(g#A-cIVR_}$NwEm5WF!` zd_aCwoEdLh|D+;(-1TBj)GwC2tl?QR$3(}%C(X6gGtJ93kh$B;BlhHq55C^4?$<7_ zJ>^!KdQR<9KNe>ocEzDv?w)iryYDa=d#SK17ky!0ini?@#;2HA*KVO1oh9>+xMJ-a zmqbs!_3P7o<#d!a_BzYWAgRt@|fGc*nFZ2tNb(vLn?A9q(G7C9CH(P`z_ z`^wS;!$3}t>;)^u^E~!nr`A;`@kH~;v-*fQ%F3iT{E$9&ll0J7j@JK! zoj4EqcI%|Wvd#EE<_JdLWX+MT3=wmb49aK>)qLv?;8?w z%C8o@9$Ap`fA2sDNYdDoKfD1eFOxp9TC{!WaU*G1{BzQcLb7|KecB|}b;%G0`9ZyYp*{#~hE9JlL<3V1yJFCC>J0a%!@tzf; zs7h54`#0V7{=~;NR*b2Vy|kZlNv8{CaxMI-=!an^o_IdQr`a}bgBi3XjuP^<%@3~R zUXw+uxp|gaDF3)KUTjhl%zaoaZNj{Ux?h!NJc&87CY(HZn1jmg!^gy(R5;dk&hSi! zRt)Fy!K|GmyO8x^vhnf8hd2IHv&A*o?EFL$mL?(uW$1EPa-)V{NnZD-?FN<$o?kL= z9158P%Q`7d{;WVWM;(oJ`zPrckg#a{x5n<|kK{)C=f_|$iT55)%?HliPxKwQ8k%Ih z{2(Xj>aO7Y75VD(-D?>RHP_VDLa&{dCnZ0P9L@HzCxu<8?R35nc`U%82S1j@j8dnJ zg-Hp9=ltHA-E`Xx-Xa?t<$ZK)*%g40g-Oo$&5WgJYF*!{@L!IUu|so7bG3}&nsm3+ z$Ev%?WzX36eQL`qZW1%f7Lx5x@1KwLeAlGAe^20(P9eYT@`dNq)-e+eG|<}i8zEPaXJw->-8eGN9s&+V$zZdXp8XnS$}>x1$3 zi(Ljq5vDc+o2hE7ZIdxmu}y~Iz#S>YFVOh^o`1Ygko@KV!~5>&A%yDWetoQ)`R4H* zSbFz)IbCtQb{xzl11wX;A0-e)&0wG5+sL{nA?5SFFlPyNB5`zQj1iKoxwM_T?rdBe zS{wq{`80e=NiNLlBw8q;KV zy1SZk+rc%#Ilor0+*4eqZVK(4=7+a3ds&VSsrOe)MYv#}+TzA2n-g`U&E)0KRm^!4&B?+#`c5a$ zLh@RAnQop7&p@@Ze%I#q6F|Po7N{T#rQXHQ6}SEMvMhXB6#h=LvW+{#bln`De5CDE zR=rr5Wvc!$Zr<*Y)oTdlmtrsY`O)m%AHy0>M<5&5oogXpBJao!&mo-F*jh}Em~i+E z9@;3`-3qwb^iMv*!%WM9kPQ2yKr%r*=E@PQ%!_UM6qn8m7mdD+2}d5Z@CELAt590S z+wB$;#)XB=#wW1Xq9B7jDI_W4hkob|8h1rJm{BIm51P3u8D^rE@ks}0tpd7$1O^#)6O@|x{tN<} z`QtaH#yo43OQGxnWFqlnPb5{npcetuEbrKmAWggtRk|xm$jKOFNRxTV3?2aYO`sCb zNYv8=dB98$poT*a5)n5f6aQV7zgcl6;tF0=^y~m3mD0lcPUeWKA!qp!;2Dxi8=}b^ zu+^qQR!@RyIwh1a*VOdwQGl~WmbnY?1jshlMwSDK^P})WJmXtwTwu#-o;La^AHBdq zjDr}7pnN5vC%P?yksATnwWQPv7~P`MFp{1fTFF;(1fk(2RSlyl{yE|FmrN_MTJv|t@r znt<2+iV#&yg{%UY+BtYzF?6v&Xmh%`>KGV{u79s6#szLHEA4!%c9{n|Ak+!_)x&J( z!5;RYUJ1|~PC|eEHyto|Im_I>nSF6ufrT=nCbM?hJK zuITT@GFeabT>+fSjQTtmrKqTA^wC;88W{AG7D8dyd6KAIs9oKNK`y0e0=;O1ET)7t zb5M`@==*#)1rJRSV2*GCL^6cPABhkE)u2l8MY!p%N=PXsw;P!dfzr$`koC;F<6H)| zMXyx@KYG!#K;|?jwwVZLDJp7jU?c<>0?*`=*iq5+n|NE{+u0mrZS(?J>MK`iT~2o9 zgveolTp}S7iDv>?;dk+f`|J#nDY7IoMFhxZK73S2jG6%lF*{P`mUl9Zjm zV@WK+8f=bRZUCR=V@5#ecBk{0nPcIWS>m)jt%AJAoZ=2<)bcvk362fKVY5>&VASfd zWN?&m520Ap|v~-tvC}M;x1*=Erq)L!XBrF9Q2P}ZTY82%>0K#Jv zH`Ls8We)gC7P9Gizu-NQsm4OTMlKn4nJpszQ60eXJ5GSA4S*70YOJ8icp!{l$9*T6 zMTIGf702|V9&!-3sm&5t^nFqRUI|5Bxz<_$XxChagoZz5qBwo14ocV?QErQgHar}r zxb4wQ$!#8viRzitOb2-M54M8^P(XAb5&I) z^UTyQ__-dm)JjSg6HaAkvnY}x3kr@0{#pT|c;lBT$uoH11|FsCSQz)t5`GNCLyzYC!Jg(Im;wmu3X%ze_FRdLgxnUQFbaIDC73f72SqFUr*9Ja+9->w+PAmQ{c}qxaQ?|Xaz7dCA zydtx$lzjaSC3rgTs*LulaEVc_?#-DN*8B&PT_QHl-n+=u z-G=I{2d>T~3ZWz&CF%bTA(nQDvZyhSA`nM>;aN7Y95Sqp89hURvnX&b5v`^N7!$=* z1Q;1n=GI6|1m5!nm`wp@i#f7g4C&t8Qci|9gOH9pfQMXEasPF)Z>GViJCgOy66ZzN z8Z_ksb_H}LQ?J*<6WQ`nN<$2CNBeAlWr{umc3E(;O>pu$rv<)veFjJnvL!Vt70?fj0)YDx7*&xDD9*vQ-IWn8qHA9Oo;=9nFXXhJWI=?~ygT*{zIPRn;&9=$B+32B zJJyiW!2sk0``7`6Noylm8z0et?*jDzd~Kiw1Pvya>is@&_Z_0>&pkcYn0_XT#|@w9 znSCihKNX~lbVWVTi0K}{I0LxsJ_9bjXY~?@+k;(JMtoznD@1=I~4B<+NyW3<2~Q$wf~fLawNZY zIMOv-y+IJl4v`gwnHQvIr75f*mI#`~h7cj|6y7L?E@4CgdJxH<4NG!aR->W&n8_=poXZ&HsDxI10W#pxW>mf3#Wm&-78W?Qj$ji!@WR>2f*|I$`e+RVi+YM z=3yN05r3m`1+};X7`BwExQXp=m&hTWaoxnc;DiryB$b4+$`ki%L~@t*^y)fWsv#eq z4$^#Kjx|1!Gg>E|NLiaYbH{EA<7SPe4_TnN&Yc0u zRI%tS{)N}8&{cty#Sd`OijcX2e7IWukm%@{Fr!mH&p{26kj9VhHkX!{3o$>)?W;sI zss~zl=#x~vKGaagBO&z>XhVpv9d-o_U9lIxp6>vVMmK?Dytf#!i6JIcqO{1U`)&kJ zbX|j$P~c#(33lUPY|TDuFOx~4zR;fBJeoBs7*rOeh^G9(Tg{4}JCj5teoa(~kOm$cA^ zt@59kXCj>>20i*KQQp+W2_5S$@74I0@g!U6@3RL2i;@-D%Wlr3S7RqWQyK1y9|>P-Rh;4wDh#59nPw{f$@2H=yt{4MmLDWPif)kD+B2}~l3Y(bW%ox< z(ag3;qJwAE8c#O=`jV4`{H1fd;g}F#z4*`2ZLa81??10zH>Dj;!hL8Jx!)l#vM7=s z{9E-#5B*%LT0fN&E@Zh6jrMx6Hz0CLESbrx{iZ+YtZ1Cf%8ojfMvB%wJ!KF4ebc4Z z4tDroNmYfA`%(B4<|eo5XIs3#Zl8V<{k1FWs7WizcZ+sQtt_La`K&JW)3E5_ExH6> zqh$9%!9(w3*c8ySJas$1Q@Q1AQE?5UCaW$~yM~;KoovdQS6MM^*z8w^;c(iGeHn%OpXxgrQb{#7sHv66w#S>-ezL!h7@AZ^(AeubdB#UeS#A)aCvY%yhYx2FY3DLc~+E4%o~$ek~> z3#Y~C+@)Rn=wV!V?RqLc&cCURU=(en&EZO1gI)+1WH&Y@D;c(qAuRp z5(|G*qV1d5co4L4Qj74T#4aV<92%Eo@rNfam47S$DEwkdYx75lBF@${@RP0GIY%iXEZH+-MKI;e}$G`)C;u4 zSl>8u^*!T^>y90h3xh4lzrvYArYT+5#|4Qh6&rGu>Bf!2@Z7*XVhPwPgJ)hY&!be6-e%iFhV$Tm^y#d^Q*SRN;+DH zNPDJ+<=TmyB6qqWLD@mUtBh_|EZCmz?Lt)5VTQXjDkZxd%wHKbVnsD7{T07&?a?t5 zmFcQ1y$Ic)wvXlJqb2!=GG4zjsUPrA*>bch21gRfTJF*Ci z6VB(T%G#DB6}ML?DK_ISt`~&6?}!U2%TIw0m&B9pm0wOmC3}`0&c@})Pm=@f*+%HE zSO?iYVuMWvqhLQSTSn-@Qk=Abn(TRiIpDFw#bnqwrS^Q`C?awb>@Oh`ATnMh_-){6qDJ3Y=`eyYIa2w70F^qok!2 z|Au$yFe^zZh7wjJ`)Af>MWQ^)XeqsmD|L~-fr;oXCLm5dJ{6=C2R zxihxydBqT&)V88Wm7OTzr`+=oJF#U}#%6EyJr4%{nLQt5T&|SlY^Gg$iR@x;E4@0t zi;!HCC77huox+p4nUz7z&ZNMkG0f?9y4t9w<$FKqY3)TTT1q{V!n5DD%#(CPsYfzd z4z0yFc{Z!@${wRU$Kln7G}eFWS4to1Nd9pB^s3VC*PVRb2L2NjVp|9hz+6 z=I!{$`LaYZ{9sykgOYy~UFxxP7yUpvP<2WG=9k)kA`3d!+Q~tYIXv8TknJ=z;QtDwon{-pK=g${V z|Nr-jzCkrbY!R4r}5Iyp)Za;&@xrlRy|d(9+na#+YQzV?d0JTx{V99 z;>E67e;k&R{`H=@V{_ApWbyi8x$rpOB>as}UA0-ym9w;5Xe9qloY5cZ? zaeGp^`;*p#c`0MI@a#gN^sntxY)5^@T3%#qifppSy5VID<^iO`kq=)AZkO+@BHjAW zH0$`XDyKW9G$_%|-)7GVIq+Ks=aBjWrN<@bj5b2)j?Rud`8_q_zS)A!6Z5!@*EJ^B zqk@7oyqv!f(^f1zY``-2TgH!EoBeg9*-<0n`rivt^($pyq1~z9ij&R~UPy}8h~h&5 zQ@4VUUPpR#d;aa=*!-OpPi?^RaoJ`{!fzV}?;ZkuxB-`L^}=G^BWm9K%)U_PJ5fN6 z{AKE>$z_b}G_pVbF>YelT9(o|lS^6C+_Q)F8*yzoG&Vgtt^JS&<0=4&%-?&EYHfqP z6VB`{0gPr$Ds8E`=hM}*>?-}{A-Dgtt`jt83Fx|3`DI~JCn%EVruQlS-A%XA4X7y$ zimK7hG5*Wau3JZ2^qQ!NHyd1o##rckM@ej0p&B0#EW`3VXQ8#}B31Op7u--00Yix% z6ntg|C!w~|6>s37A-%b4pXI)AhW&Moe5Ln}j}!>6w-h>e?8RIkZt$aromQ*EcRT-; zJlLShvOvGukFIK99-O3yFhzoa@dt4@1v?m#1GZeZrID`mUt_4NkmE!)lF%aXj1*)J=(xyxHJJ~$!AMk7+=z5A8Ww;LA^?gxFmTsM@{a z)#N>Ar#1?x8=jaZzWWzex9qbx3 z5?ALpwYRhoLT42QtZT*#AQh*|qsW!QpeTujSY#v7)knSaGb|Ns zNREkQoy~M8MUlRLl98@&_*c9z<7Iv#b$Ask9Sl9(r7mX3 zMz1hlRv7i@O-`7ij?PaDU03uEoxio~CCr~t{Mh!K?R<`zAFJEQ{V$OoBLI#>=YLy$ z5IN%Z24%!vr+IP@(Aba)HADLP2%FD%(&YMO#pQ5Vml%rS+R{vesh`-)iz#bsm}mH1 zherA7c@T3;>L1kMNIMsykx^r6%W%Wxhm|nK_Th(FIO$1?)?>Y8S(A`3J~VozHQI*m zDuB3?B+S>r5ew5CTF!Y{*b;TJlI;G*$Gwg>3H>T3+bfErdeBKg&w2Sf9atOI!IFHi z0letneTD}5KAD=k&9s_oS?!k%wqJpM6St#r45MJs0KSAH$+3h$`UG=m^m|YerFo=j zrU-B7vtBKHCj+ZMLOoV;kHlI{Fzd4N8J;T=N4dGSEYGb{amy%o`=o~^hgdRNK5oaU z@0Gv=T-~SVc%SJTG&bs+$&*Syu!F4~9bZVcQB?0c_{?@7zb1Dpu)yaf?$eOhEzjII zR+r(^dre54>P3@M3m?uC`gzZpERw`=iPDKuh)7hjAz0Axg^_#-9~Y<_sZQ@@@4ju* z`)@pD&$}V9g&X>iitFVjO0bWd2Mj#J(51PAS4QCG1~Jc-%=;9^c^$8Rq~%Ai>W6h( zd7b>LiQS9#-8Rj93v?D9t|OL&Fmnuf;vz)ZZ?ZEaO|=15Fi`+?2jzy1@S=zfxUNp2 z8D;LwnBRLQ7qkMGT+e&dSGb>j|3pBKJ`3P#?kNRB(Jx>+Xk6i{h070U+OgW1hC(Oi z1N#QAr!PgI$@7W_^S=?2UwSc~++5UgmOeK(wz*R(ROWA~AvwxVXQ96cy>K0^48rB_ zI4y2ZC_Wt2v)~8+)n8)Edi1CB(GnHx!)IJ9DL(f?S-0X=z!zWMD>|F&7%z8RH;si?yA0^vpPaz8$2#}Ud8{k1nA%5};Wj~e6a z?DGNf=d)I*hIm)EX@w3-Wq=qoSoDJVn(;CrJA~3vN4~N&#Sn6Vu@26iiHhR61B_4` zh}f6Pas9$DA6Q}XQToa&Co*G1={EBR^wv}u!F;(G4LZAxDn+z*UdY}*2{9PR56V|5 zv8dJs)V0*1+v8z9vu90@yp|r3uw1(v#bblE@;ZsR){}?m8wgUj_b_6l^lPqbRIYWD zPl?6U=0$sJ>_8Nyro_MYrxL_#-*VX5IS`MZ#icd{N)s&zKfu9s93vo2eA|AtXG6n` z{I(kUi#r>6($^(8Lw@E_4m76tKgSTlmV(84j;jqMSb&(aa7>s~3?Ki%-bT%Wi8cUV zTTc~+P|fJ1TG}Mt%um|jBbf$VG~m>dVUN?aV8Rb+?a`EGSEBQq(Is{-^UjlL`|;2U zZf@~q)z=R`l;3;`nva~x$x*{jR1(Vr2;#(VeEJ!$&jH~4xq}dYm7<;3viK5aFNOnH zi`V~IRm|mQiREn9bI%rpHZeZkI}uVs0h@EBj-bH=-w+OGaKk^3Tj?_t{UkFURKjLpg_F5u$!IC})S?hb%v7Q4HwLtNdFp53YsePNpp|t??_yky73mqR^K;YyCu_3{_ z@ysSj#1Egd9iene@n_vmJc+vS?d!K+-@d0diRFvgf6NVFRpsAgI2p+j2lJ2gox89e zUP3tM&-`X!>t(8XFV3%D0rY+A*LUITGNtvreSC>;@wei5+aAk3+a$M_77c8?kEtYo zFT#I$&#bK5%&UY7&>sX+zA%~IPS?qz#O#6yXrVsP=Z}8Z(9rHQ2s_ki7`BpY;0MC= ztSbK&C`_umYJPj&%X&7GA49aaciX?^li9!T>V#WcIPo zQjy+F*2h7^c`=43D9L=+n*F6%dtBawk8sQU?CUH@L%w{8pNjPxK4%dcL4`O9A{~CO z9o)6NkV;h$X>%=Y?3G-RuKIY#nC6k4zY-?q-^@`;=27Rl zRgv5vz0`>~%HV$9woiS=vMsC~{g3FHuwZ_!{(M5>v)`G{F%vEfS2pYT#?*E{nnFu8 z0f*b0#`yI9H{)cQ{oL8%v46h}e}AH-(X?19mVS&+2|x0Fub+G5XBP0XV(J>r0xb4{ zCT&__#XiYAxlxS?Fl&H{bZUpT+m}}K)+%uXqCM;P#-($I3-~(07po0>^>ldK2q5vj zxLhZqRL(XJcJ-gDi9D=QGz|n@I&N%a#eUjieNFN&$GWNb&-2Bok_1i&4QJLC`M2Bf zYPth_OCI(u^>1I#-!ClaI&O|J`I|wC?z{V!tFT!I`(25niut`C^4%P}BFBx~oVfe< z|5sAn#S>pqi2HwIo!-}irv4ACQ?$i${L{-C6U3uSHaUoG`#TA?m-dzD1^?ezC&utd z?*6X-CB=R1lG-(4=UPQr=eFIc`zwlEiclNBD_cca=h9Z~AI$zzy!eZIuck#QUVWi2EUfjtIXIYEYJGO}MDo71e?pM)NqWo{B#KY# za5S3tT~k|O)BgQC;gEwl48tGGw=J!utE5goBdan9Z~Z(-EKlIW?OksR_0Rj{79iv< zzYKNUlNwxP@jky)CeBrM(YF6-%M#Nep)=UtSSjU5sCRh%(NdCAf%FmQmEV{QuZXM1 zoZJ7A98UWNsWDl?J-6T0MD1H!kUpRk9&w&B9zB1`5|sqW_(s?LP-o#JrojZuC5_1o zS1ft5`9H2k<@r}wcuF|}h3^_F?$vCs36si=ZmzZ47?BN(Tlm=G4;9nPXehgO&B0mL z=mkXzA`}~Ix;}@%X814njRw%sZF6q6DoKrQo&&6rHdL4S^&9uSIvpuDZl=zjgZ$%5 z)EgZzns1vlPjQgHYQ7`EE}daj9$@NdtJvdWW&62TpcfwHzB1c%BXrNEE>AjmK>7RK z^9f2f_uKaBJ(hEWEz6bdkx0_v0x}Nox%wZAX62kWsSRU7!CyxOFimB(SH`=wOeXt5 z%9Tq(HmvlPTM%}PJ%2XN#4R|()|=(;K7Ygh)%(D(2K6^_YtH|IpBRQq=H0&Tv?0|t zdf!(yUZkjg+Z0$Yc&&_8<;J{$lT zb`ON;ON_k<52IhFe+NX6S1H8>+3wM%uizfz$~1bxO4dQWc!>`eEl zzxTWJVEwt9eFxk$r%Gjl!w3I-F*&eU`4)*TwfZ{HzvlRCTTQ@;@1u9uAk!+DU8CQ| zb{+Im2u3A^I~nax{I{QbTw-kC*~#r?tjU8O+W)<-wk~D)3rb2`+c1fPz3F9Hk2%ti zq_2P1bDH)!TJkRnh01MSPG>0CaWMfEK?8SXq*zN>k<_8n`Jh+7Z7ip5CBl~`gJ1g$ zNl7hd1GFa!HY-D$!Hav$`7lYhb*`-~P14du?MWeMulxcK?YW-)C1KrKUoIkDHYr<5 zcxq+n4VIx%q48F{t*PVRRbA6O6LkBT%MJ@%ok%htD@1_%^{j}<`Rr`8JWHR}Iz>Hl zU-<}Wxt(sR>+6jVQxu9_HDD4;5|p!5;OhEBk5J!==V7)^Vd6?}OVbAb<(xbD z<=+-+_xZc9^!26F%~V=$oH>Mx7#7_ebSJUjQs@-KGSW&p-%;*b^C#IwSXG=W;1pmm zoPPyBs03bUXL_DZxXKcr!XJ=&EN|@9M*Jl%jtdHCDuI52dHUqxn(AD#i>a!TClnT^v>0s+nKl2xUkt6NsI4J8-0Uk?TTj8`_Qp7!xMq@DcS1e7 zw?Xa@QF@NI~#N!ULvS z1xL6ttSlP}b98TzuH}mYIcRYE-fj+^^(V~_X1qgu=Meh0pQNpe` zOEX8FLi!rxMla8u3zcSxqS|G)#Ubn6JtHeOj8X%UHWi^)Mk>8xqZ>^2`W%%N@^f{o zu*Lqca7A$%G`)Hi>5(zi^1Ng=HF6g6H2JMel?}u+dleJFI(g^e%2&fPVnyo-y6ro} zo~v%nz+6m+2S#B|21o0WM>Xw53-okdkKOP^B~};A13oz~IOoc4km*{VFpd&!kla72 za3AlaAAv=>{I3nZK9bj^{I(pQf?=`72;nqzMDN?}T_V5t?{%bG{xGh?hOVUv-n;&7 zeji0+$AP0gbjYm+8BWW%NopIy6Q(&PBtZ08L&YI1u<)ke=(o!1CEhjdc5U?+*(wt1 zg~Z*B@*Pw<0Y6lb)jKRV?FThss1Lk}AV+|!_F0M~d4Hgl>py7*Ea@~oXzpwYM zEN(wR{jI7rlV7ePhbmcj&>+>9M2fbl#IX>)h*e|&4h*nhPCJj5#`w0reIQKhRM&5N zk%epQd6++L=oDIDJMfp3^Y5CS#Px5ZR5fIS5C_d_yNL7=f2p|}@?1fdR^Y?}D{sl? z?>sD)pVz1^Z>5@O&=Oo=yBP*h*Cp{~s!2!LzGELNMGg5-rhntpd95pGT(e;_ID< z=l5-n02f=FOjAqW&u`hvKlx=L#0S})PMm(bJ$~XlURF(HH#;cxadTCl{Q10m4uYx$ zIhi&bEG|@DRs?jU0|k&wN@^_$?d6LUZ9}&Z;aO~$vn0HVOWArC-=TwK0D*=4Aaxr0 zB^TAfg=<2MMVuJ%SeEZ9yFp-0JxRYn5APtNJ-aSjij7=apaM2&J$kC|vqHOWgHWS1E- zvN{uNgq|0i?zjvqA;TE>)3ADEyUodaTGCH=xle7-R_mD4>&P3v`%@f&%lr(9q0`MyQtY}}AvMB$Iq>YnV>>Mis`Z*cpA_{rGL$q85 z?79&LtEHc^Ges%z(-a8V<|srR;PFon+JYQpMO(U}-FkQq{*>GVYGVTRngZkyupwM% zB`@_-T4oI=x2Xl)4uSy$pqxZT+9I2I@jGnMZu#hWBC3T9JN*k|jyLlpNwP=?5oXlI zL~j1Xyr{;hfqaa9LXrgu&0LDP1bv8%nxUNLa!}&{s+ohFd5V^pffoXSB5LX9Z{Qdi zmZ**FVZs@dlIOgI{+`Z?_QVY;UVYYx!t}AEs>KWpmd41gS#W8rf0Q!V1b>2cs+EU(l z0|O!*65?^r%=Cs|$nz~yqE%xd6{EF`pbDa9Dp6j~;`@oI4@oQ$rZ~z!%@ah40^%~I zQ0o>%J2Cbg0Go4$HM0>{VR_|zMAYFkxc5ObAXFnc6f73YSU;WWFYUIDnP=wtoIK5B z!^kZK=hrbSRJm9dBR&))CBV$LOV~ApHS^2f3pwb=HmKq9BQK~@pYfO<0tKC@?IA=Y z_I;L+2N#{XY@R2R!7jRW5pJ(wr zN@yYDe@yEW5?V+^Kjha-|H8EK;O!z*Oi`YUE5D~G4&{jvh-P^|piaNxQ>2R`xa%Vi z{g{k;;R@LKOBOP-RMs({nQ{>f)u}lkj*ryS0pxTLU8HKnDm(u0mf8P^bI-^?+kP>&vEd`SwRYC{PaU6 z>aHOB5wA#Vv0f-77lKQXh6<=9f#`^({5;Vse(0$U%*>So;QH-)epi|)p%uD7MUB)V z2i;FJD^ml^@Y_8=JGeF|E;avMIno? z2sbcCnCHW}k|(GzH~*v1)!J9Mgg?E3axQ>wH|lr|a4<6ctvRY&NqU8VzGH^==|N5L zPgI?kJ3s*5TL8n-*Y|)SRt)%cHXTO0w#Sda&e45g0#uR^59KmJJdSuNYqUd>-%S6p z0u+-a1OH%PL;%iiQ=SH$;7ca(p#=iWc>!jahj@SoCMc+CF07Pa@;bk~oP*#9sffm| zE8?X`AJY+c%vz?Hfw!9j2PRNc0O~ILw5Yaz|2A60ZVv%y-59x8i~m6{{hU*O#I}*R z&>XJlGJ&=T09>Dovh$b)5VBy{6p|#m7fBT2k!_@EAP~!i8Hu_0akzBwY7(k6$VPw> zmCEr%053u?NnjxvEh_Q~K~j9Klz1sdXoFefAsWqNONp@&)yGbyT;m;LhD zm6wvY#OphSf^6>(G0IBP9R&0#7j&Bo@W2A_zApQ-5IxH|OVlzKf&x16Xc4RB`ccZ& zANWL)dd@+79Rl)BNHEDqe0o4a4oHj)La@bz0`N^C!VgZ{8IY@M4S=op>#fekGeF2Q za7w}i&`*a?Rf4zUdvi~V;Yq!UY*Zc>BR+%yWdIXYj%ZZ=5(#;oLMf+o{xd`N36M7_ zA&<2abhXj0lc=$pn>zJ5GkEk-r~b_KPI0x;S2kBY+R!hkHDm3pvYBI%htZ!v7$FEV zT?9D)!8B4h%cVf+DqMtqdF>+X0g2^LWz@2F{(KJ{wA&Gc1)rS8fg;^xN=wy3BW_BQ zz070w%>%WdD;g9rQ8#@%MeNvpu{<{^=pqJcd)sLWc32WFvItgpAf^O~a;<@)*#*iU z_)XyCI1{yhN6YmhY1P6bkGU=G!u;+9e9lY3q-fOP4X57$i>d^v|7p|D!Xt*bXfyW_ zWNC$EG2DX!iD(0wTdVqsqWuB!SYC;AV9EP;<%s{~`2R1i-ZLPn|AE^^_SEB^6>iKC z&a|>{Z^KcJG|}8EEG;ujL_u7MnxUS;1ckhzbvC$kV?ZkO!(SAyb;k^&)qB!Aj5vAB?pxrj!_SorW6K z%6h;!I)YCU?gpBNC1VD%yzb-P%?)bk0r^ecMr#sp*bnWh5C;H=2T!q}E0L`z0r9v2 z?HYq7)V?F4q?3kFzhDq~>;xWXDnPxWJ_^$XzM>?*k#Wa`FOkn3Axa!jQm%prnLec? zX?7nG148I{M9$p}ZU9knPHaRWO2~%@xndFf`r(Dopz{)-k^Wd$V4Z`l=|^gsq0&WP zSIW6&+R;wI@rmgm#71}xB@wuf871M4eZce*&pe8hqO7D&k_Lr5zWYra{Z_ZjDmcX! z(q508*OK6D0vDsiXGNjRLnyEpNeE^g%s8d}7?f1>t)4ey~=ahZ?B1!VE|4T%(@ zDs+CQ1ps#WB%ea2%$Z6;KA@?BVcB^42V@31+R*OyD&l? z@`XH#L&o?=hC6i>IsBo9A4ai3NN=G|yyp;hRDdP_3BOIkbP=%~pu!;eB*m%>7Zz=t zh!bhcU-S8pRououoG4v?b#v;lNDtdJwur~2;R*3K0T(iY3t)B;t{JgTuE-}eJOIMD zU{O`Xh#>KYhjVy|%rvqJNs`Tx_bQpYEu6zh&0}AHa1Y7oJxNmM1TP?}XIm)4IMvr8 zC_7{y@Khg&c70H)`#@wE*V_v`qM%B6$k$n{*Q8lTCR)}25P<^KJX9G4RSF7k`!5`f zz|dYsSCb0!IqyqJ(RXeZC>!R!qS0bl?*Ple42wHHg_ta-d+0Ioc>tG0^bnn$*a^)M3rA+26K*PQdRtUR7eJ2Es zNp|5niJ}V1TfbD3h&eEsVj(i6fEKOz6-z*fGBu{eTK(&Q_(^;Qd1WY zk-Z#tKpUm;4W+wukN7YfQ~ek9dJk|f0=P*TzRN=`mSOH|1BnP^8aMHjQr3&P=St04 zgPbh7Ter{fz|Ij|q26HPd8w~_aSK;TP9V@lJ4%QJEWV6Et3LGee2u)u&A`>@BQx{Y*w4*{f;hg+T#|FSOeQy?)<4P}$z>Te~{a@Z5?lDcTg<3fH+ zNOuQ#b)eM;I#-vmW6v(%7n!?DC^xrt;NEhw%ZTR?tBc4g z6bt{qoQasIHBPyBCKgTpKFD~0>mg%0DOet5HUAH)j)uN}={|EA)5=FR5V7N240Rew zbq223)eq7Z#sI!l)w$#ii5cpZRt3rP|A42;L&LAc;ky7O5uN&M>=Rpj1thUTiUhA> z|5!?z>BS2Yh#`nFYUW& z`-&AWYPo$NvtM^h+EvIzJUr!mMO@{6#6%~Be^oqgPmI$=0{PLY-{`(M8G?`P*tqE} zZPR-bHw<6>J`P;e5q?@2Df%x+PCJRqI3oZ3-9Gl8<*zVXsFs`ly|h80d0eVZ|463=T=)GFPxS+I zUbr7AiuvSu`Y5O?{=M!Nd^dK$Ie6&((6oUsjmH}5Yb?Iw9<()BXiOg6UiopDrqc>v zQnrYNcjdrtEkAo{Uj8pbODSS&@7IQ{+aW{v(?#?wLOi@{Wk=OU%u^NLoOZAt!9->l zulh-1AdUJGNtfS=p!5moXT3Ay&UKn35h=U^Hj`)yxsQ9*MWKU5`+>(NNK(6%rq_ zBoAsHHIZe*uJl!x^P{QiYqxt>s$t|;$M4xGZSne5>Xv8VHBKY1WNQbz1#Y*0?+680NLDuVyL=~rM0 zyCO@Y4vXnXvo|Yw&(m^xP|ug(du%wSfSF^BpXWM3_9IvEx{M2>L`$R@FV`#&OHJr2 z@`zSkYRO12>hR9+4X^pAx8=KB?iY0TqmY*-oPm{4VqNclPD?rD%!La*9Im9jRE!)y zbjs;^@5@=8h>Q5rI5WNGvN%a`|L~b+rA{aHIK{x|;5Bqlefv$j$G<#nl@qV}XO$h) z6Vu35d$gT3QS1LmEqC-}^!>JajzzOpWNEYMrNHxzFxfyo*s)ySJxA;>pH`KgR*t7P zX1sr44XeHQZfmAS(uHglqmX@VCS1X8R5?=o7|T#Yr|3T!@q>jpqn;H*lidw+L6qiR zDR<~~W_d7iL8I)eQ4&lkB+>8LMZaI5pS+cr=nK?Pj{W8$BG87RI!!aEOEu8Wsm@aYHD?{nzkxj>@~l)+GaplyFkxkk zCwa|QL$MiV9UzX29~qR_Z|0xGqzuyVtKm8Q*@~KyCZ{()S?SFn|dy}L^-ETG+(g%wh)aN>c?LY z)oK6r_&wXqQq@?M*)4wm_R>SL`er z5684=vUfkK5~mTsWnXM_scl6@RmzTL_Y5x>%=bzadpbXCYtC^K50h^uz%)i%v#dsR zG?Y|xWF`a>I*wI{?a!Rh?N2YK={e|x{jfKKL-B#E5V>let(Gth>$_QV-9`HSp@kYF zcS@1sR?~=yy{d=ZG{wO+1#NJ$yf{%Xu44`jCtiy-%ed$!S;p$yrE#VL=2j!_j(72~ zRgjCY4@P^?dTVQ&tt&V4LX$W``*u&8idX)KGcKuh*uGnxyiRcQTaUQelOs)KsHH z)8QsXCxf>v>4UT-@c@N^ZM{UmaOKqf59K{7r@Y2%ldDqll5tXqBCOAZnjEj}P^77K zt}{(c+)X;nJ&At9bNd%`9h+I9VFGY=zE?c80am^(xCY&0*XZ(9!rQ7_rg48?W4Nw^ zdNP~?F=Z$QDtz{_Ul~aYn3rx-xbtpyL&ASTtOD=x8f)B!j$4|WSe6d+dVx*S`p}^I)=SoXvy!)r9BpB1PX- z2c=(O#u*V@!XX*&AqKQZhH-x-3= zPq=w(u*7hKol&(U&d180FqjNcwhnu4`Sx@A!S{!tNk49;o0r6X9_ZKLo4j4~3`2#A zeA)d{41;#M+ygSkz2T%A;-rDL;gE}bNP-QUGOhDu?Wu!|YSvS4Eu?p1v)2*`L0Xc$ zhgU5!HVV`@UIv%0Aux29tNGHnFX{Wv51HMY&pEanIw~ydHS9A;3Yx*F5%FWoZZLf@1b1*KDz%a~P zl@?ZoYH26+JN@*&$NZ0HuH$g#JE=Dbziv(Do2O^(eeJQDCNNTD5@7WDuD+Z61qWqt zZtE8*7_m1*u8W}WShSk!$5TZcZ~nrzaxIrTF8X^RDW zzNib=^LVeKxah-~sGiu?08_rUn%jI}F{puMmny#eeXADjEljr2e|fj25fwINQ_l21 zUwCw#tNNU7H?-SUSny{-H{ER;%izVKpuEqSmsY4*26&UkVIQq+^S*sRcg2Z^C}A1y zjvterK*t^1w3a*GekT2SV|(0V+BNzZ>Q{-;pRE&{&*za2BiDZ9d17Pmy&R@VG?;r} zF;uB*ZLm6L95=fev$=$uo3#qb_S{_9eM!NwJYW@LlX?R`6bvykhde%#K_p}lDf@;R zp#G7&L=W6eNeovov%thi)$HrUKkr45;Oa}<6aWvg*B%?u85(Xc*NqCfEDmff_mYL_;0y1~$9piC-pGd7T+$ zj&4xTi7#WWC$JnUN+P&utzXtY12Dfen6sa%f(q++BI9!MfsDC=2o5}ir`Ny1h$iPc zQ8Ovi%;ZfLS?n4l*eY)jWkbDn%byuASLDmj5FYsXD2<$XkR*M1J=24S^le~p&(=zr zSa}e%O*XT zIX$w>@JfSKT?4c@z-fpGL@H#lY|uB6%-}MnbU8D=0j~IK&xnP7MzT%i8uMiZJZb<7 z>PDrhA%W`j&`dg0^6JS*5JCGGl(XUj?VSw;6ec`Dl*rn8b@IV_ z(X`>JWX*%VqBo6kkjy|xHTeyohHl`J5*SYw`i+tymMa;b)=e`M7`gKb|8tHLnf8u@ zZ(Y&HQidQ-S;=K^J0RO({7D+mzB0M8#UqRA2nVG4YY7a0j+~Zv)%{JFFUvY^&yY@2 zu6l!8>Y0uge7Bd2&ubO3639r|6wO*TGt?0tLa;h6sEz^}q~k{InsWj<#y?KnOIu^4 zsj#Fsvs{z&(@4yqGHAD}{DFNr%@-}a*K7j~ODaP$HiOmsH?utE#q%B%EQA;G_59abQVX9xCaGz;DSQ&ZcXXQ*L9o01? z9LWymz`P@&pD-`#8{m;;OgYm#5db=lO#JA5&+k`LWu&{k7}T5$b)ms-CNm?Hk&`1Z z)i=n=q0Tg4Mku?M0j<{0ug@OL4kg0QZWxzZDHwt+&u(OVifTHj09{M=uEXoG6*4E( z@}ZO2ux+d}BIuJ?xJAl3PGpFyqIEOnrkq7-uP2(lqZB^tVkNjQ-9FN`(g4VT-gT?S zGhcdSwz|Bm#e3EY;P)n&vJ3DRfX{NK=beue4WC7Z)J#RC%x!+~hyjPFNF%oSc;y;H zSWaV3iFv86-p?I5;OcubwRiHGFZ1Bsp}c^KIuFJ3km3W=5X*-?;=Qi5{O&Xo;zkAR z&z!QVPF6fO(^nbY!crrVh~Ww@ovKXAT$%iI`E1 zuIg{YIL?H_o2g^}WNbKkjj6@;bD5r^M=0$mQkiF9IW&;N{DpZETLwf@n4w&kt<+bQ z1Jg~1(EgJs6+grc|E$1B=-w+>P4CXC2F(Pktb{eDGswCYz-W^$rcvSPgUnI8{9vGW zc;*svQRQ(vnAlLtPs|A}V_B^gn1tbZ&rtKJIidI~X}FwI7JP?u%sq~SLM!%*Tc6<3 z)LQSrOLvt}#y2zefHcjQG7s_h%#^XCDDXgEm`7RWgW@+|Ws7#Lyh@uB%U^|`Bp`em zpr^lNtBFAYmmCr9X`g)M+1J;jviqaS(jHX$PS+{Y1lx@MGsvxZ1pQx+xi&FTxy zw@Yt_+Mma@PlSZ%^K!6Rh&8Sj#Nf4-_Vk-=>?#rOw8RKnMUic5Z!a> z#MZQF@K4Hfv*l3pOwi71HIf3%N5D`Qr_}Q5s6^(jX`qgfd$55)bG5g0J0z0N?=yPy z-0+P~0A%|^dq~xrXfVpusXl_IYW6L(j?WZ<*nu~hdk(v8^&YcBJv^wBVI_i|Sx;AA zz#}+2P##ck{u9sk3a9g&T?#Tk2X>4|z7CB)hA>y~e~9!YEp0Vi@*e=|2i~zW9{3%$ z&!A<7NqOr`Xc5SnaqaSvaZ(!M)9E5rd;`ow0V<60MTC~Vp{~Ir*8Ho1sYh=LQDbn+ z5&!V%3QFS0%`dWH1zBp}w!9QaYKbQAv6OmA9 zuCqE5pG4P3T9}qoGAKcc-47xIPB*18D*s(ha6>SyI zPT!UjPh|$I!3y2r;f}LSzZpT4386EgBCTC5o$}nWY`XF1nS3p$<8eo3Zm?2iQiy=B7`gk>fu6URqJ#D@H zE&NpIXuW`Wkf#=ie{RXnAZO2n9?fuPE2NcsOI5+A%~+>y3wEZ>e0UNCA*JtH%dn^L zhKLA6U`EaMoY5$#aK`^zJ*m=ks??trvw2ENS_Qedm}#{J&)pvLLm6qgzxtqWhUD3+ z*HKMP`r6g6Zj*!IPG1vf`OCEf#=2R*wrRymgCOFiu=MnwpY8cURQlnoUUOS4|ADrV z>v^W{LbTa1jqc;4(U)j}F8F+y`+!T#($QPW$YX+QoF5uwk4MXvb(i!7X*3A2Van_M z@i(TQ9eqw!n9+b0uq7?iZ<;xfZyr;d)F5C6;!jp5Lp&N7fdf-FNtIg+x_75$ZF0}y z51(fhuGz|5ib1?CUCTO%TDmpHUda!? z_s8TXbB(T@7A|Ew==kJx5LF08FwIdE!779;$j+L*cltwUTFn91GH49WzLpl;C5L?8 zTAa>07B>fvP~~T z%dVW9Ld|P@6}-CO$Aj9GwF8KNUlfS!qnwMD6&3O8CF}QfSLl0^w_ncAy`1&e{Uwb+ z$)Gafn+9140%qhiL~sgCpse~$S6|P<{NRwWwXcB@L--Qy z_(ji@U+o_@%f&%x1+a%cEQ0o5r2-Dl07(xeM~*Ew z2~~`dSE-wa=AZ`~Q!m$_&~*5ldaSkOdqL{w&E@};5LB=^$l|rb>0@&_lT+ExnX;a{ zS$=~sGso3lzh(mkFvXFd($yail=W%L%%x>0aA@gB(1(NJ0#(g{y#>Dr=QlnGN1#Zg z!?eQA66}=+X=wQ^%>8Fmg#@g&d*=AZpj%P11f$G9&waLKtH>WM|FO%NoAzGr!r$En zuMZr5W4|*Gu0P%6S=OS51ZY}(j&+ule)KQGc&*91M;-(AIui|^^`5t)fA91_*ldXz zt;K~5-)YDR&>3nxd^<|!rvAjAFYgS@)uO`7J&hD?jvFb)zj8D#Z*Z!-XU>aWBQ6Mg zbL5TVzpSkuf*oi-|6@{W**gBk9=r8wz6M{nF7n?-7OtT+xMPlX{jBD25#?3;zgOXZ z-`U5VkBWcs`#B$g36Ug&_)YU4OGB58>m%`wm#lUSm&dGsKVlwf=;{cS{xwv3s5S53 zvAt54ThkuAZQEY{{++Bc@1Ehrv(roVQO&=|YY2`7O$_}%rTG3o#bSieF$c|#OfPZQ zH&pd}QS*ue$e6f^^~tyLTSlU$%N#sX?sBK>$X@2@^j)+3dVW0SaXZ=Uz2>o;?F>o5 zi-YiuHFdTX+5!(X+e{zS+r{j0Gl)rC?F+5aA9FCct5?HjVagqz9T-utaZwb0)%msE z#$ySf8yLcWS3A@t3Z8>{f17Ju$uT{oef12ufrL!K`z@M}x3|DjWA>Sj1qf9P9Swy0 zj_t5fKeb+<=SO?$;V1Q;VuO76+RQtj-}J*F4TR-r-^hAXzVqfSwLdSwhLmdZ-YI=! zSDhSgvn@aloqyw%xzi-udOPgBs}a{1Jt1YdDQ$!37%?Afn~s%sBVOloX*b`b{MBzC zf$`H(rDcom`_O}}Ql_1p5XWt?Uks5N9b3jI{kv4BMf-aF%vil6Y>RP8U5>yS*5-OP zC{Ec*-9=M1bFX2a$a$`y-JAULV25zJhHNoDVl;H%`ie=8UPlAN%}i*z&`&lS(NNFj zb#EC{WvuuDy0r}7`f`P|Q_qN=2lBMxxRdVVUyfqlAcS^L=&=j?&<`Nb_q^82kU#n& z7NWYlEqL+!0mJ91eRVRpu2ySPGI!YZL&-lEZHtjXlecF+TQ);>byi)}v>CRaH> z3oNpz(@Vs7OCb=w1sL?t?aA%!?Et?7i&jCCB-0+9z_M?2`?o~>pRUQ z8R`FOko%5UNp6iX3}|9lA7p=jbcS*)79w|iPEKgl(1kPlU@{_dgYT;Ww3qO33#v6l zIKPb;8?5k-gNv_~%sa^8fm9x;il1yK1D(2#2}|gftfaK+ur!dj=iujFt6@lGq%8MT zHJOrbxd<8;tFmsrZL5lv%dwUl7G-@1$Xo-iK~DHSb*0JbQvWhAVf&2zYv7XjNpE$9 zN|IOszu~Fnp62tT_*WHjo*0)+62xIqT}^thlj^Iz?Xz!|n!1jYiRYr?lXZkvOR~&& zx0d3o-b!#BZ}4DI%f)r&IvuY@=UT~#lG~}8FaE!#V;7O>coGB>_0NSU6;WHMD+4LL zGhl#Q)sqFNJ6Ae3SNElh8T|iE$4Us!{|kwKv6z!Xi2n3?u(e)<#K*Wl_)!pfQB6L} zTvh4+F&#T!L50l~?oiG(U-wD6@qbOnFy*izsV4a}?8iO-*L1u{Z}JZvkl4O$>i;6~ zK@VK$nYJ7Ex$`}&DC-1kh0qJC!fK7Ht`Azma^0Z?nW+z2KRmy3g$j4;X#4mAEngts zsCf7D6jyXGs!JVuIo*Epv)o=gPH6hA)0iFZn;*U|3>53`Sbuo>cz^ySmuv2pA>WtN zh4Xz!9zXo=yL+jl@RXWAepZCUyEx?hdPMs6X>s^z{vqz)bis$u?}Y1FX03rj#);%lJ$U!h5OsE z>g%p%O5G36!mko-WfHYC6utCkd>b;--21dc-4B0!D|J^aDX5}Y$s8IHi-WzC^_g2Q zyg^P^`b4{>Bb;3Ev2{}|t1UgWu`{hkw(z}7hW*{lvWIfYlMSLqeP(h)^-iF`-L0@s zrYYt6&F0PZdbv{hQ)2qwE^|Yd+F`KVxO=DH1HC18%U`{a^T4P0CgNZsU-t)avb_I3 z0XIId6`piBBwP}DEkAwX@^_l%1=OT$ko#exH4ZLm%fsB_SXc`O3bfQ!|T>>=L0`4GA^DDe*Am7J8a&zbGFLu&#bJI{?wEe>AL=_#E19# zWWFRQoO~0yOL#BXD#=P;YG`}cL&JBh-7>Ixqj?u|2a_FD-z3Vl;w`L>geLbcLvizF zj(Nosv0tk4zgNGZb@I+ND0ZBGNP4^1yH~D2 zTBg%xpSAKGJLl!p^H=%RdcIRK7WD7fafU94s0R5wu<<8CFETJPU3R|g4xnanA<-&L zN_7Y18niS0^)q$fs`000rfVo5UZ zjUbDJT{tQfC-kZ*t+E_N@bsmDUahOgQ)Y|@WJ0GbwEZPDd}!d{98#}t%BpJ6Uh7|x z-H&(qf1_8`pvFd69g|`1+J>RWhTto5$f4B>;xpZH7mD}o8}cYnyHU9Vkn$$Tf+nJ+<9wFg}+u& zLZ2BLru%H*%DaIRr9r(e;v50v$b!+Of|>45=bap90qKGxgY$-$kUMr5yvX(9FB;D% zI6FF>tT>7VZ(huPrm@8>@ z!3wYkZO*EIjZ9!$f!w zhNZ3b9@xKn_!wtlN2g=75z7PPPw18rvif!o4NYZzNxYYp{Z8v&LQboW&7#;+YUq2JHy{Dkd46C35#n4w7y&i11mdk9YG({MG!c^UQ6b8lIx*6DtuE!DSa z?bR|jIejrPW7(kZ3p+}1w@5E1~8 zo;0!i2@eK6mwOL{N@9Jm3p)SM z6b*I#p36bQdH%!)jpx`W=wel@AfQLKjd)7WwrXtulH5qf_5q`-l0_=R@26t4SSDMm zdC?OgJ!*qdibrv|vF7UXeTSgRdWD$w^Jk=5_^^D$_>w27da{4Z^gaxX!z`OrC6wR1 z)f32$#P&|ZR?X~&K&&)ux9oKCe+SIF;O5C29kd2W(R>QqFVPxbB3xtmUfM@x3l1#= z5B`aLu7qV$ZIq0(bx;YpD4Qm*@|YuB?$@hr0dfr*G86+glWSZ9~P0zu1 zU)+hiYm=;=MCdz$$`6aBEbf?Suy>VR{gg&hlS4$c=n}<{mYbFnm>o_#jG#=Trg=TU zyMGHC`c1g=7}CV{cdin<1`$6{tgKl@LKpTr2o-c6ew+$3JpU=Gp+ecB%U zXkrxz0Evl{0XSO{Ee3*0f>e@iZu3z-;lTJDwhq96)^NAUA}H4*W{yn!AYyb-$IK!# z$>^5*8I!zokaSd97SKw>G;=*+V&@5kxCsHKhKP)1TkPXP-9;_Z-RRTum{Bw7$D+vV zoVQk$6bM8Yi8y5iV3!0~NFq#h45Nm?+@_#>DB#1H=oEYsv=G}vL3iE7z9ot`6C*`7 z;1m30`DS=N@7x_b6o-R*C6Is#FJZs@7yj=)&`HKz2gNTQN>Vq(asQJT$K$$as1sC} zA4nwo_0Aw-hxws~!Psh%3b9RU`W-VYiuP|A^@R)z*ZnA z-iE~#aql9u2%G9F?yUvfq zHR3UC5q_yz=!d+Vzq^5c5SGiv4s%0CK(q>iR8j=Mr=dIEhhC$hu88P=9_~FLJ@?x; zjjH1QJ7>Gc>B=<;$Xq%`gtvlV`1L(UM8q}?)q=;ZaKwco>YO9~hXM!$5{4GyE{>QE zzGtbBBGwPF_Lye@Giws@Km;`X>^+}^)Jy0(azd#o zvXqzj2kG-p8`nlko`ut(R;AEYnxr8cX~-TYNk{~o+EG$9Ug)4GsBDE}VD|6zXh~g~~Xo3L7=6MVQxEgKX zr=Unklz>P|yqTkxieZz8+prA)%};#pJ#dT)KPHekNr8h`|Hp@5J+3^0jLTlJw%bIz6tN!Zh8F2PpWLW=kb zO&nT?8>eOOD1?b{=gK(`*>v0t>3`D<3x1&~X}gdLb*BaenVtTMF9sK0nk1vqB#{vm z>^H}N&x;!><`oAQLWB2T8w*Fy`~AJ{?fG9UO41ME0l%*S7ZGKIAw()SU&urF^Qut6 z$Q(X0TMk#>7dout^L!55K=XwJmj+K3KZ~Hlny*AR0!a}U$MH$6WVBfJRfvbU=Z3@z zMO;MPd7`BJ0NC!sA={EpNUo+pn{m^k7wMYwhOk(^=);I=CF4E;#d_-!Un%16K#_lb zNVo$K0!NNxgb|5IMLlfggma{3m>m(dF0^2mzEm_e2aeqE?&n~x395v1heQl`KMx6B zMf4Fd?OY6YMGWEruHTT@O$3hdZ`@y($hi;X^O0B9QFVgKn!Zq2GiH?NGe|21s~&c$ z!?ey}YV5GjDGdv!YN3U-sIeQS0C0ah3SciA6o7Xw+?r*9-PFmKcmJNO>`b!IUbi z_`_obuxc8b-R+ryNB4rtPX3m-9E~jzR6r6C&~y;25F|qML#W5}Dv;S6lt_`>jTb?i z=&Cv7)f}KymXrmJ5boYw5r!+U{5gOCq9b*qCW5$IuV> z#uZ;7ijR{~iE3)To&fkp;#~oDR7q;Dj`Up-F;Rgz&R16LajO@DC(+PWA}rqwb)1Ch zyoacxV0+29WzkLZ-NW!MD7a7zS|}!B>7Vhjm_muC0*MlQl(H!rr3I9V#tGcxrJ^a$ z;o}Q-SX;-KaK-2XyO`(fwqa)=+;0Ks?2Vwd*-gKH9Ucwm4JH#kyY(d~Iu~8SubXbCzkkSoK z?}l|rfD0wI=73_#p*kWmO@JEa90H3S?flJcA!E8gn1$%li3(uobN0v{fN>UhgF5>n z`nE_Q|B9IMMj*Nh;11_L_UgF%dB*1HJh@DOX?*}(-U-}(iW|eDV=1Pj!^X$i9(5$_ zJ6@4sPCO}v15YR)79a{L_8zC9Pnfa;0jLaHGUz|l5dkDdv+BK29ngdx2$v+pOi10F z!ySC2W+Dk=Ka@uOm7sCi%HyeNMC8r7`yx+s84)|lzF8D~mszJE9fcuExr%+Y?2nQi{a@qrg{62!M zbcEz!M(J;WHByC9Bkm>zRZOKGFl;oDY&2;;>UNJ^N2?;(Q=5s{chvD~{AgQ|J((yb z6dAKYuaH*aqLs$3k?#9VKnXwZ-hYT<&;(R0p;W>D8VH$B_T$0+w|NpRE#^wFqoAgt z4GD3?GpW^-aS|?bueg_RbCUW`;uZ02>fj~tSk^M!cB?KWbu9hygw1JO@N66F z8#^W2v(wfcU4cl3&@&r&2kI`{od0*bX9%MoYC=mDoi_XzxZ>6WL$CE~CUGJ^|u95IjSQ zXk&;H7hWheof7Gzaa|-#%3C0o2j53SC)Gcm=lU0e;FXh74MbPhsw%D3!#Q}|7zd+) zm7E}9+c>XfRcm6Yso*hW4kgVu3h4Y@4xPtcPC;=5<1LnAMsa}AxfkHBMbX>`EQv-m zW2>fEvutb|{tWXBpu#{^bNz4A&`dM5XaMm5kJ(|0P6^KeccBg_;VK&*jp_Bjc6&Cu z@h12i5WXLXcq|$1en--ya}vOH52LE~q3^)3M{gI!e*3WcSK=cNCyD}vTLW3=V7m7( zi&|&rCSM0>MV;Web<02&?mjy;8^(l#} z-UsiWLNwn1V(y4U0WueMU>)PG2h8+^cGMyH3n7Rq z2Ol=1zyEn%6j02AR~Fg(bz4iRev*-lo*_RzdPTmBCz^y}^CRDi7hZb}U>{P@{SGYD zSh)GS`~&SF`;ytuEK-~6FQw# z@KCdgesSH>MGJStj6ThEySQ>|&YZsDTmjYbxYCm(^{P$-c`)P=-RQ`cSN-Uldsf$@ zB`^2qQ|=$1-zqWAGI-N@`J2Xd;}16+OVd1>+?$m&tBZ|phyS}_@3zpE#?$&&v+;e% zKilt~?Z=kbBSR6@Teu3ak@H(!zwz$M23Y|mTiHTx!rs@gOZ7@e@R94cE-yToZ42wU zr~m3sTJb%-(ed}!uBN4J4JJf3xGVBz=;uyE=1sSz^$WMQl@0`3JB!PsixQHTN6JKh zrIWU@a_|k&P`mR#uMc}!1qx5R`S(<3{lG)v&fp<~W-m?R5nuUDNCO`4C*){mBFieK z)1Ijp-CD+0`?j=unF$?RPRN~%)Xa|GxuVGnE&8~l0)1jS`tuH9_fB1U+X;HUUpPuj?=PC(e<^TuXaRk9I%hzi@RGf(4AEW)FHO@M zt6|YEZbqQAf2dKpKdWs=h&#nTb2;kH^Y)h`+RAf{=;ANn%Ko#E*!(o-^$1zJt&hD5 ztsU(P`C}WRvr+H7$_9%FWQFYoLm1+B98@HWS+SI;6-LoEnX}S(F*X^3vsK4MJZ3u5IP|4}7l8_>!n`8GbgKcP+*&C)9n#8SQ2Yp zvpkY>hVX=La@w&edjDzU<>*o!LRsYP*Zs3}E-dyH3(!z}T{cict@GUJF;yPj{e@2` zL8g4Ps%$UUSV{wl``XcO(?Zw*(SG*xeC0py=bvl598>MwLecZ1h9u8dpAmcvj||K} zVuy6I#iB5y4NH-;aRG<(G_o9v?&A#_6YL2^dqt=kRt!wPw zVaHsR-N=nG9-SYe)Jf>m<~XnqxpvFcsd8-H%@j=k)nF>|Og*kxA(I-f_H+Gp9?}!{ zN32Hfrg`8qjUV}M#h6LNgl#Tzi{kaYp=#Wo!99AxDBraO#c~}-k1x9m=g!4!n_SC~ zPRx8H<5!3GqS4jFPdOCW*4jUzL1p&0)_k#BGEU+#EtbT}+&YdarYUDef?FRE0tGuL ztmy;O@|wf=y*}K#Br^#cQES{9sFPjl2vIp+IR&54dXXug*uWIcH z1$J*{6|%apvm)M}CY-i0)*iod_aB5ITBl2(jo@Z^R#-P^&-VSQxu3DOq#S0pZbz|}>ug^Pc>BA6n(A%%kp@@h&`NG-JZBSH zGUrXe9rVyeMYEI_8uzE<=Xzjit6(%%a2}xZailfSC zHDte*O$XcAn;xH>_uK{gT)sE;_`%Z)Ww_-ah z*eDHiDup=I4_6mzx2)VDif#LuS|^h@Lq$AG5qZK$LC*Gykj)6y?aGdtE-&lBJ8!Acu%WC=N1vGoxMsVYxDrLFE|bA$&OinFLXY5Q>F!bU97Kg#xmOkwYNH!BJ0BuC8`Ek0v$ znIw1qkZcEayZNJF2@irz$_7QFCGU{oFHG_LH!w1`x-|Z#9@2PAqtHJfUhPR_f##MF zINYiqwpc!yJ?UXlGLHrGlbILxs-h$I#VGdpGBm@}v->P+pTRR*2GY zUA1#|3Ia=1wDqVw@$HuV)BVC44cDd6`g|&ECg}SX<&hV6ITz0B>yRhkA0?i;yQD8xHC}hwxrxFuuJ{Y6d;UVQtJ`# zvem!6tV3|$I%Rpp4VVHw-q^QZa`p)inDbm*V9g;`^8Z_UGGj_2ykYqNs zcx$y*D_x9^xaPR!?ZBp9v>BY~>fM!R-EmrYkYM;3etUhxna&s9u_2{r+f>c#)W4w~ zmTa`u;1x^dNjti^UCdA|UCufGJw(n-&+et~Rza9XkBlf$y&a@{G*I#vE{KTx7`i2~ zWCUHt58CSw349=;eBWd?E2%&&aZ>i5Ki;FmBm`aWf@-*o6tTgHBt-H6!-~YX7Aar8 z(Q%Q!&CE0FoCVkeQr2c%dp8G6NQS7Z8r(mLZ}%$jyZn$oK=)Wfp2Y(*g@|y+O8Nu3 zNEfI!4Gy~zc}a31OLc783_pwE@OTi~V*aB(|fRjWAxAZFOglSppCS|f8U2N_Vz z5;+0f&7auMSpHCFJ&dkH1`-_#B5gqhdCJW3qe2AbwQ1fAWJUZfn`u&Lyc_ zKM=$W=o=WbVIw;@tvcWQ^K7Mg*VO??A`+&`f_i5q6Jd7Aq>xB)oGMyEEc=opBA%RC zsCf6<5Sl=;*PhPs=fEP?SoSB7cSVE%;wc+DvJ+YHlxsr&HHOG3nu_TeOdfE{lNd=i%i=Sb#jKBIkfB_bF-L^C z4-&+n?g}thO8Mvf8=*{fuTVOTTyH9j0h24m5f^*hf}Y>jY-K=G}Q18bQ9|0%fK`;Z-4Hi zd2g$ISQ^~`k#N2G&q#xA4z}Yn{3#ldddTrc*fK#g$4LNoufD%JyU6l%+S?k zRYNo1LzvWQW@s5BpdoWl8RJ$0%ufOSsto25S*@F4TXaUnkq=XDu2`arRGr%*IZW+L+Smhpmj!b~-T~HZix(1Pch4XV;@>pIPhj}QWIDm&Z z4al?0_I$692Ym>W=bVIxbg>uxkRf9Q_;ldHS=TZh%n72bjKPt?w@)Bg^2p6!-cB zxGxuatcdl07<=!pB>xBg8)e8;94W5EjWZm%8iFg#5vV1u#67Y!8*iH;OWZg^)54Kq zmZ@2(S>ni%RyZoPrKx2bo7&>b=lksvldx* zL;lozuX*!-L1AUkW6t&$@K@6?5M1AG9##H4SGfp39$C;hq}jibn0KAeXzAN={!n3G z#vYgDVAGnrpm1bQP`;oP`g^q|O~UaTe|+GPV=X2iDbbzlq+2T}ND+*bdXlo!$f+Vo zh#)v;zSxIcd&hPV3z7+Ll?} z+|2pPBsty6uMc^F6$j?;(~pqX`D`|q%SnTxT(b>eMEjbbh+K}t8VV=9fOW{*c8zWEGLza1v zN}!E28OmAyt?espeBr}c9AGCCAgJvq_jy(*p8bA?bMyph4sVAGFSQ-nP-=BAK0tLE zUl6hYIuKoIuex)K37Vlb2i8Y_ljp$KVfU3A6}>%o=WC>xDWnQn#+|LP_Mm}-oQ~zH zNIqLf^Tm}6btAgnFrZVz2MCU=kYk9@4^NcKBSL}pH!U_ zvqrA0gT8K=b-2|&tPh>WVhLncNE^Z*Ur<-JM7PR54At9QvYWy04#84cZ;hoNPn~(O zzLdIToua7_70#g5^A|(p`wk2C*i z7h<(4282syCNe;B_Gak=IDcw{k`&fLa* z7BIt30c=XD>GqekQ752yO?a`esXlSRw0!oU5YoQ7!tKm8=Cj^sK<FM*>dJwCNpVR!s#1fm$1 zAbhZoCyXDGWAW@Dw`({9%No8=PVXxCVGXpeIJopV@FN-=*vjI)pBWc>EZvj+m@~(> z9Ed-wa@yqH;`R^)92CljW&cyiz-8|{1dgO~o`2JWY=*!4((4w(vE{dx5sJ6Ad@}wQ z@gsyiQRt8j;Qs{1hd7S$0tId_Ds5J#Jl%7M#!i}(B6SA$wUn?C@ly+QL+3+uQ_`!}$WOgLE`B?$f z00;FcKBgunrK0(^~tnM1fkbfd;_b&q<3~SrkmCZDV9)}}5{7S;b5+eneY|Wo3%yQwghyYi< zxj8E9s;#_)k#;DAL~-7AYvMNppbgR6_!=Bp+C#dKoDandIYd)Ze8m1W_7+rjE;sS; zj-oSY$GbU#Z*4~REf-$#7vmL@Ke?c$U&UxXxLxzIHGsLD&kB&RlQTH} zE7*a)>Wbf`$s*kC@_k`2&-V52-5c-a_Ld}GJl5ZOEL%j!jWC+Xp#MOeEw7-BKV+QB z<6&zV!3CaV=G>+-HcQ~q*!XNA$G>+5*U6~;n-_9RUS)hdH(xW?Gyv&p@T1RX_S}9( z5jW62L*M}aVD+*Rn6tHh`bD#Z?RcdBE~__2XPakv!U-9W2Z`r`Gd$e_g;1c6^)38` zp6yEaN;}WK9Qar^c<;=~yHutk776cUjC{PjTfkm9s9DQLLgKbPHu|sX3&-Dyaqq?l zGphXe*jr6S&Vicj?Y-wdc;`v)2y)G+K$RZ1qyvxlpW;BwWp_2Fj{_r_B2V?qZBz02 zpo_F>S9+zS+gJz*C@M+(r{^BR{A0z9!f-CuC{yeHj_t_&GPeG$R|QU$QCLhQvo7f% zdGf;YpNY_qLL)wvu?+wXZ7+!$`0;tZFIk}p{M+>1y>csst2*PhHa-;=fisvt!HW7L znJ>EapEX*A^=Ce0JTkw))#~QiN-LY455;#?>nRn!hox7Kr!5>%vC1V^waDtwF2A!U zannLu?|*-O6wP3LF8H464@yF7;{zKuhI{?6oa;z_(!T%wk1NwM!x14W@FL|x)JtLL z?MgeN?$jBqu4dTbTra8T^&s_>XA{_g%<2}}AB73qp?r+;nTexmZ~S>d(n^nzg1L@_ zf!KoNSbWEL)$5Uee`i%!T%Qr$Pk;TPUS%DrAG0|iZ}Qq)t-|e7&9BF)_~;gFRB})P z3WMKwj~)g5xn)iAYPi&N)6Yn-X(Zrp-e$F%2Uvszg}6O$UY6m!%ywPcy>HHS24_@i z-}fgP7N`EVRFk9@QTx*2-YJJi#HW82E9t^3_G7qG0O_Tl1G{0$@8)`J8QHGj+v81A zvF*5Pw@&P+RthOr&C#ehRzK(SM+;6KxTKoPO z4!fp_7IfXZjO_gErOP?aCY5or`xXHDvnWE-aJKjGDzDUDIrS3c*r&bxRy|E^{Z6*(+E@8b*?Z>UDgYQ&H*7Aq)Zgg!QEfM~#RZsw?L)&_A@E&4Mkw@uj53~vB% zqb$OKZJ^F@Qf+|N95upUh@v88EWyiKcVwmJI26|1%s^T-qR3~Ayp(E98dfUrp;Nzb&X1xy_el zxI))SW)fw2e9r@?rz7dCAo687gjFw%85M&i#?THTLd!x#nx1N&eT5GOn-gXUCT93{ zuC2Ed_4n?xzN=SGymLKucgMS7okKl-$$m|^l2oj6j>_g%;j=HqRC<=W_Oq;2PmPGO zw&$*oqs;;*(|ylgxEB%~Jml*w4SW`$pgBD;b^G_f6B&q})}f81AHLl0Q!v)Mxm#832maKJP|HVk{}XeBJJom^F4rCHdItlNnrvrfyE7GQ#Q>-0RAB*8 zI`t=cd{ft8I@#2u@7(qe3wp<~_pZuJx8WlB4fUO~*k5F;%CxtZsp84xOy9|;7u%WmgY-GFU38+{1}UkWQ}&1t zQBRtHdFH#PIeII&bgVYeoMJF{_;=0!QQ$E|g9NG2U9)?hh&EV4ZTJxWf#7y)>TiAA zg))0vTd>TI9L88^)zVyM3$THPnzXzSvvJ*jFQp2i1RUWzLG8FD}~a7JIr_^W%8 z+S@Xy_cFGE%QJcP=Df6rp=4oNzF!cVKSdg{2F(=|Wz=igz5*GUv_UosM6#nyk*hkL zxA_@2L7`T6qNL(}I)_!A(v}pO_Di?s1t@H0eR%Aigm_Hlx-iCopdd^0k_6FOWA!f` zPPc&uJ&fTsLQm_8##Vr4tXVH$P>p&_$aGS(BlFn9+)314XQ{EVlsaS`zMA8*LR2&% zmj+=a_nG4zhsbSay9%N^Y`~9wy|hy*x|62w+V1fM$etluunLWCi>CFBL=s3whL>t!YQN^;o6H&p>hBNDou0_X@z+dLib+-vOgx)n zfss~>L6zxPfKF-Gczk19;qz}fu|}V@8=-v&dN(`!fsredch~wH1(gz8KalkG-A3Wb z%1Sk7h4yE*XY|iJMgK7bWNfo*FtmD`VU2~nUjW&tJ0jE$3xLx3K2fX++X7dY^8L!k zV?U9XBSFVqrQ%(d)xH&RqB{C7T~UnbmG==}=aPV}1ZA~V7%jt4=jEE0y^|bdZbKBz zW-XiTZp)TcW7O}A?Dix^?_>kUG>!KJfOkevIBzFQG$TpW8%f zU#LtNmsi=)`d`*t)R*G_#(H?jj0W#)lCFRx6A`~sX=E5YD1*vlb2Qz z!Lo&OvIp2Ie-*=`#b|Bs7TZblYY`4Tw;#9yyrJYiL%oQ9Zl*A?UGyqM0ea_qi*(C0 zOpx_^d{Fn}+K}Bj{ie9YtvV{6$46#1)}Ig7H1fp$A|{IEg32D+^`*XdxTKsPAesOE zxOe*xsf`j(2*fRlhBh(UkobaE-)0kcT6F{1+FiC#g`7jxy4c(aonbT5rUmTQn!kU) zMn3s>|GICAoT-z$6Dfb&jJpeMz-UPWOs31R@?TiG+m5)MPMh>q>vNr^vvxz>f`V+P z`?YZdX#o~iq6siyWj>b;gS{Mr+zrtHz&Q^hA8bhg{eJFIUS8xK4t0zj*hJ_@bFtIq zSY`FvmP!CkF8czQ)n0g5^1wn+hpqz}Av! zk1Fk)K#p;uYzo4>BJ?pL*QVyEU@$-mumk}9e=t!@fczhXXjPA1Aip`eht%FMT8jJsG9ij;&XUE!d|O#2 zT_5SRgHUBpga>PY5y^U0s75vX{bmxuBv)2-*_Ue`_ z8Wid6_(v>mzR~jhR>s$N8`i!@mKkid{s&E8djIV9|1u%tm(d z7d<}@7VAj~3MS4Oqtpk&z~;SHN1%!2TYZ1W`Q5tl@u^z9&bm#gaa3C;6QOrH%rUjX zm19ZCsOVREuz+q#KnRfKRM5EDT%vSL@;o;oA(2@6vHE# zUE5pJ{W14(WaS-}2eJD!{xz+n39{5Zl=rqBy{k?!>R!2U*;{>~ z(QEroabBfg6}Sl4bSyy84xan=l0}zh6>Ste>+4x;BZ@2&AG!}={KAs5tekMaP>gJX_S~ma29PfnBNnf{p8&7Eb*Y@V< zv#H)EpI)`@DY`!F8lL@YCeS%*Knyq2I~FlvP3$G^SdyKRF1e4~Zuq%fK-%Y_RP3v< zN8`>Ds-M0q)ve=Swzl&In6cAh88M^YVl3!x>g*(9q}`r(>3TlnX0iI<$;r-_-$`ku zzegn>uJw-l%DE|plTZ|4mG1XMeO|7&vXrIKHFpgWO@l0SkSP^~gLZo>t@_&Z5*iZWr^*d?qC%it{Z;6G5-x!`441sL% z4AUT*gDqgI*kh>mh6Dd>KqiVtMflvLHUV$4N~@p<67o>FlR?f(8{ZKEi1b&AHqSlU zm!hQ8U#l2Rp}WY!CP&@{Ce315p_iiD#+zC_>_Nv%zUxKCJ!~#J-a8=KtZ#SUC-70# z`JPiH1wRgI?5@FIJ-7a5Gcn_}+P|HTt$i(we+=YFNjs^4kZHg2rd{JkPB*T=c|wrf z`FA%2{wLkyi%t7*p^&Guzoi7bhJ)j!4^={VnUB6Umw9rdzK50=td-ul{`|S*sM;Xy z?lQc~b7a-cym-@5W%zJCw`GX&Y{~qLH{}E6R&|`R81&KZwq=fe7@`k5^7z))X=Uvu ztwBAnB~oyjo8luxf9bcPQVFWT^R6v>IrgUUclfM&H^9GCB509Q$9pDpl@CJLH-DaZ z^yskmf{B}5Dq_#Ba9@j3y{(M`P{>>L{_6`^5B)2;r?uBIev~ftI8`aUm1ll@WH{+( zJ0!Pg;2x0cSl_;s60)s4?=Q7?5%^U=s@ zF*Cd)AFAA3A)}_`uUSYBDEO1m*4fu?`90q2%U-P_Dnvh( zi}-7ZzIcaAf8Eg*jQly3W3892>n>0NZ2WhPC99D=OGK8%&!)!CUQ0ci_(ZMz%;Q}2 z(RZVvsIVnp3g5A(W-j!B+k(yG;{{HURzjb!i;sbkUoR?5vOB3`20Q2(gN8ac@cfO<>!PBAbs6r)AD_*$^ zJoo#uzEtrZi4&V6{L z-{(|4x4-mWfwyRn3>xnbzP>LcY|HdCTcsvGYo&AQXmH07Xh>G9La)vCWo z^xyI6msQ`l891Yo)T(ZPUcbMg^e>F>!TVu0#_BIUE*Z7j=f1uj@1L>citYNNxOmQ> z$A2mjx@@@|oH;N3^;UW~+c6n`vbQ?hD~t$%+!E!RM85ei?pN^+<&no&Xq@E4pP!#` z1)nqb=^5|rIYU_dkx5QZMi!IJvi6$|eL*%{TU0Q34<^CL5E`d^Z2%HY72`GGhZt}Tp->S zyU{N7)bxT zk`+f*V2WW-0Es@t2jtw@wveO2s~$Pl`v7Myy^?8IE|E{IUNO-d3hzKcO5|NdrLZ z0IVT0_Zk*momM7W{a&9(%C92$cz7<)cU_^jc5kIgi-)P_&?|@w@(bKC&N<&g*DSjaWdbm zECE44W-)pFz*nM?XB<{UL(i` zD%-JNZ_SloKt2SZq*63WzE7xB%x>A;xUP>9^N?4((ORK!i-UP7VraQUsh5WuB^O+8 zg{R}8GSg`z9(D>38zOL~N#$*3=p8VGtY^c`Ex;+4mi^jT2yd!1N6!$rbF!uPyJp4W z%oIQ&2aCQXKwU^~INl1WNh@d-Kr?Bu=6CFNa=}%Y>@uJgt&Ib%NNy+chBJCXf>b%! z5axv5u-+_blkr>Unmb!$_RNG_m9IO6mvL97onR3XNNqQ~LZXl^f;~yBy?U&nMFgug zhrf14|AH$|Nt7PZQ6M=~2MxA*yndc^^;uNql^m{o8%lEwIVx&$Jg!{mEo71rvl8T> zlm@4eVZP?vQ(~wr8S;dWkU!WENre~8D74U9xbIqkawy+hXw7}-M?BP19#Y1>T#7mU zwHrN4YQMA!X(yCFqzfzOss^#Br=qrpSk&BTy%9yB_SZFFt?UJqCMAgTJY*LDN^fN{ zvFE@<1S1U5C5A<&fltgMKz+zv+RBsY>p&t(R+cG(BkRZt>rcSzHzBWo?%i!ueqN$f zGvB`Vgz^a*eApbtb-HZm-9^nQnS&{y4i>`XAQyilo(O9>WW-Z4YLakSmX4ISftC|G zeee%A}V7`#KdSI>8GE3)q?F9zI0id)(fs>*J>j= z04xpxar+YtTRNSi(c5m_UE?&E=F z@P)rbK6ONu_YgMr6ly8GK(%W->3Du%*2l$|; z1t{qlER#?)qzWFJP|$Zq^wHsc_{&6MdZ4WHQ;${!N|b;!RYkP?UVXo|w*2F=Q%?ax zNQNDXl2cY5B;0_XnD1#O!}{n=gLF7+P3a}Ap;>~gYh}vHOx638Qvr=P(TFnynF+%O!*8{n0%{OZw&8b;alZQKG~AI=A5!RyJeDIQY&ooW-N8>oEK zdUXWY1~4IGij~2?N9sn!ifefEsxP|Qd>fnwKoEK%tx4V9=veNpd%nm~F-j^xR1=Wr z>F`0pfc!$e=bBOsdICm-?3M81KEU@TLR&=0CnRVq0O4nTtrURhruEDT5#1tW2OjYd zJ8Z0fKjS32<+swP?Ed%9hu2Zz$La9bXhm>a?r>GKd|R(d_to|#^bmH$It!&8hL)QL zv|QZSaubv)fR>Wsy=cYv5+zwy=_5}OVxt5uZp*Gl-T^=r(*~PYfemMK<-aH(n#!Kf zRsns>RqoY16W2U9>y#il_ZZIA;JrC0*wKr5sS4GVe;Hw}fI5H}P9 z5Y=J@00P=|X&ge7b+=?+R2?@eulhC%|Ae9Qa|aY`P(}ODQ-XeZ3aZ`jsb+I`(mrG> z4PFg^4v1w^CdFkenihc$Tvy@)c--#Xm0a!v6hgxrT>!0pZ-x%ssq(*A6kYzj5&D5t z9`bY!c1MDeO`=vrs0lRcxL6KytMTZ2)ZGYl^fslizqcwWa2ZhTh*7T>p>(v79w=RC zH9E4jaXsONy;V8L=JJ&$#GEs-Pz!ZV0*Pv!Sx=bRD^ZHaqf>a0WD-RC94D6!D;2;m z0UAH)UMj`*Ae(Aiv7MmRs;>E#2Q;{dSFnD(t>Bl^<=cxtB2-#@?rWbdV1&V|@u-2C zrRCP80Y5bDw&H8_xRu}3yY5{6@%Bvp`B$oy(k^^rd1AiULNvA!kJ}!I!m{Owjk}j_X^woJK z!y*ZU^7)S~V;)Dsw5Qigw(skEUYXk~h8@&7+b3;pmbSL=#0@g`cQ^uVECOtM`PHhm z9$37vmkc>Thi1~DWfG-A0IZlcexs_9FNU>qb&#KOl~g)?m$0}F;pQ(%x%R7LcKU5BCLzESjv2#`m*t7bSSWG`EB+0a zCOrL+`|t;>uWbyA0%ZAxUeA0~0$xe)e82T(BUoGYGZ)QlJU1!b|*LJ0i%{v`~ zl`oW;xj!Div>`v#fgf?Z4k_7vnHnRF{`-51T^GdZp7B`!FYaD>+mVki?w)5pKW0bg_$9#ouF7q5h5Q;c@l=xsTUHY5(lCQlo= z=bc%0GlmBmQxc?_(VJiIe9{{?UQI+I`Ln$Vy|u*r#+!3r&O8$SJ?mf<>Tuv`P50OTUjBLdb=RKOof!%L4C52;6=B^m@mVn?{^7@l zbTXC>4jWwB!d5p}qGYYFOWzAkmD`+e))8xI|iZTB|4%~;eUVRBV4{+M4& zdIQNe4Mp2Ab@4jM_|=BZT&Jj|1_WX44Uk)AW_3RE%R;tZ>CzulH81l@mThoi9|%og zT{b3#GG^J*wg8-4947JP?*u0<$KsRYtHJ^Mu3Ht0$|i~JIbK@(TNjege&~MtS}*m+ zzLokt(#jE?tCLwc-6QIk^IEpIJTvyX)%hz9ZCZhg&dIFizAEyv%!<=G{MzQ7#o;@Z zaXFX;TUeN$X>nY|Tg+U4jv_(FO(W>Vy#5{H9a6g+=32&TLx$#Y30MK6HSe95eKl2p-;7)R&p~2&dZ_#dxFFFk-?{ z=cr{3u4Lv);Hrh$2Td^k?ITgS#sYqGA<;4?V#A_2-0P3#xmGTVu3q%C<$wAL+C4jcroqP9nB$l z>AvZV2akQ*>l3yPIM1wbW)u6%1Bf1Mq__6v*hdbfBlkInRP(mJ)>mrCU(^m(^--3c zoNOM6f^ABZSF6U$+(~jOrChdS*{ecOfwAr)@2;BDPnGVIwQ3!Jp+k+zK!S(+p52$j zD1z@w$4(k=eAaqj8!(K1uDbxmp(k7|ueZ9S!vJS@i5a`SBgP0V{S_BUh1wb2nc_rm(6|o2NU30)(SImIy>cB*vIRY zyj2~Txr?Q{A)^5UJhZ-%sX9ByHO)Z1U2qrQs9!(}N;x`~7;3*0iaN6dW`U(qiaW#G zeN$QP?8fxk;LeGHG~dCkZ&Dtj_OB@&Ie9_%bL_}6X40!o@&@XjA*WPGW*UBoQmGJv zj4mk`neQpqhZH2B9B;5J?U5!FD$^`pE?;-I%p02qQ;ht=OU+;!Jj)<$nIIwqPrg#3 zP?bFnzXGYn))xITI9EZNxJWuJ^Es{cm0Wr|aw|jGK=x-U#>t`K!~V~DLg8J@#5N-i z_ImU~+?ZX!_ky7P?i-|%LGzIHqF?(r7_>Bu-2Y(o_&+>Lr!jqGeuO>RYRLhwf=;ARCGJeuh$FxfUSJt5&wK6OlHtx?KH& z$ff9`XnhX#QX9d|<-;}_jk)o~C9an*#K8Cn+aj5w&Jeb0HwlrRCgR$0~?%vijb<>1WM4ihiNCJ7O z{qwjhE3V{I<6;dJZXe2MoygJm{cPbccDIZ#&QFny@FvqBrZS@pVWk$47SjI;{d(nj zxtsROMAME}efbunKlFC8MwHAwUS_7WiA*SC8|e#hPf--=&vUmP{1~PijfwU(ch>+N z)4f_Yp{?`E(xZEI;3~jSqaH&w>J5NkLdPv4rjKp6u%=(dntab2Ew=K-$ z|Jd((M%#04J#38FkRBbf<2f2s6yn=2YZ^l~r++F3>38TnYV|;qo|hW~q8-OOmE4co z{D`o;rxG@Q^vX~0ri?xzq(waBlonUi@ncy}>B~gWoyi|9(@{@2T$Rjyw?Uz_J(hhF zocq0#Tk$E%yM?yi$`B&zK)yBGr0Liz)uNIE=z4V_4`Vd!b|4+tt~l22VI8lp@af+o z>iORty0KTYUB1bwJdhl`kQD9k<*#&6KJ4So;IJP`2Gj+;izJZ8pZV;}PC0Zr7ley1 zhI7{X&z}2^+k7(QFLm&>-b_3+&}wg<$KQJOyZSk&O=}}_G0{pj!l5(zD!R92aqKUJ zFwcGyRgR9?Dd}2aI$q&0hH(Cb_H?>wuE3zo$)(gOx7Iy7eFYlKmzn6n@pQe8S!b?O zkw;i=f)FSaz%f}c9G?{`1S8U&Q=l9g4vd@EDC1vUzbB95%9qSk=^MpJ?ya&{|U49w-KaQLj6dzXjpdU`3W8_1s=(N*xp3+~+|Q!v88I30zK+2oggrD-7ej;6f6xoH#Kgga)EeFKh_2 zDVwMN>N;=N$;`w6IT$8>P2SlF<%4U_#ImTueiMXPJ@LsX6}m%*7(&*d|4T!uvxJNXM* zCN-k1fhqJnj!TYaexKzUs&kgeY0XX}2(~%Nzc_|5C4-^~V3FZXYyP?1F0B-xo0KD~ ztB-JuW4Y1a;6GIJWaIMW6-etbeJ=gHHS2sSMmrL%GQrGo6tN=cU{YFL1eUWaqkrZp zP=Etd*Ni#*%Wu{=Nr?^4JlU8S$N_-vV%XASu+ydYJY%7Y%t1RelTlRLi62Ug-4iD%v15OlSu~ofi#9AVw!bB&< zdjp6AG_RXYwOyLsF4wLlUH0O3dT~0v3aQ!ug({H9HIe+n4>N`7zP?9YavW?GV)$1v zHZ7%GhS{1y1g7TiR4)y{36NBWeI3?f$wxyKl>R7eJ`QmY0!c$plswKDskwaJ40`V> zmANoOs%*})CWF>3w5!K1v#AU(A!k3KZ|oGYl3zi} zy*Z(D=CLxcdkNbW&ksoir5JW?Ub{|GG3sV{mt_F)WL8|O`;cwU%Dg8RsxPuca0r@3 zZsk@;Q!aM&#zC*4j=bTmLa=?eeH}Mr1v=KDeV7mO=Yxmm;U58_gWL^{JF{tN3`#qwK9%E$8(!*Wkmf>Oksgf#!M4{nuT{YUDcNu5UgH3wM~#1q@~E=PFm_chlU zh6Op#3(rX)S-yZGQ!*g_032ndIg_TY zj0Eyt!hZLPGGIM}t5S}+3IGO^Air*Dz1^CF*#_GVgha|* zeq8Xi1xvR_&hJv7a({9Y)b4i!0_xELW&H7m74A_9jxv&)BMLM^fcqRU#I8 zDr^a3G_=0%#CDCIfTxyIQe#2h#Jk*#*6fT7PJjsH4gmJp!L;pRcMcUBCd%G{sgJN5 zmMiis-0b#c|64Sm`#d`NOMCcMs7%Rrs0N&b10T5tQmb+5L(W(#rtzZ zn5sIEy^NYnaRUX~w{4`vS`I{7VeO`hDUS?;mSrY>W_McY{QH}kYY%rv0}RBwoW#5L z#&PWdET{@HPz3TqtF(teBB^SDT*yN^Hqoh{UWR&Cz3sZS+eeR6rpKRkb`4mY+Ez%IrXA0tK9qTj4OZ(>@glMJLlxqE zAk;Nb1g;9JzdL#c97KNR-|AD=`nZK#vUyG3fBr&pT23N#gPBLpaW%Ut>MLmo6+BFQ zRZ7)%WOApBuN-1{nKV5~OtQK+{^V#?Lzx5{094?{W*dcr{5w%i?g%FsYx@Tx#-z>OYOygBcWg3k)vi~utbaMkGC z3-(OA4B(Y;roC(^5pZw2h_(G-PBNy@wTvAV%9im*v1{NV0bA+~V0PK(Sbl;_LV-?c z>_osK>3NgJ_uR-tluxI;51{CC8rSi_6Q|dNgcOxWF2ckpZg*SKxB11xT!mmfYxf8{ z7BE0mrv{I{$fRbc@F~h*gx)5l#NXVuL?uIfM+h|%z7>x)!tY&@6|`7pHZTe=A$R1G)RP9?f@WrB4E{lV`cn?H!!uv!7-9ci zSN^N8{TL)w3`uZ;MrX8omzKq1I02n1B?GT|R^;9J5O{wT??pIAvS&X5T+U-! z?CY9W(s=>bZE`-82lw!jwwkycA!m1)fjznG2zopwck;zYcm`SFzzPu7rLJ-^)>puu zd7-?&e}@k@5HayCSevzu&x_ z!lQ@}qQVrMSLzygCd4@jd+3bQij*n@2^+vcA0B#lHf);MRVvzDN(b7cJtNd{?fAfF zFWAwiAa8A5scGzKh+;GvjLR#z_~={@4u~g!4{k5S|AQ;l_P(D7efs6Vt7NrvxJA@- z4*iLJSTdXy8*n*2Z4SOeKRtB_~l| zJWPkt@JW^XF_}j5#eWo9?;ujBcQX?Utmm^d*0QYSOWxVI`)|Yysn_)?6VF`PsG-12 zAI9H$%G{0>d_Kg^3#<~RQ;6pv2XNW!mBQW17fMOzchf->{9q(W-~48}!kzRs2`N|1 zIe^oz)AzJ}47SOJNo^f>?wRKM&+N}_1qD@qEkl3EaOpD_ z7c`l!tz~}1!{0t=2TZy*J8d51FL65f;WAL^2tQHbFrRbN`b!huI^v-`6K0t5swyS1 zDw58^HIj?Ju=4;tYpJ;~dTXL~NN?%?IL`Slu6%-Lqj3n=B;(gaH#cWq5nvSIwyb#4_3Zw{V?j_G`uVOw?X}YR<&C3m!5B$|fF0Ml zwe4(8Ig=~3J;TX)^Dz?u4s?U*Z9K+JW4`{aV7r!W2YA)S1G)=a0%S<8@MF1{S=hpU z4n;=u4pKzlK0iP>0DwL`#dvPCkN($v$0<998@I2v)STSLlL+-f%N@Q#v*!!bR)hy} z&r1Q^!%~QfWulmNiv@nJ8@slvhQM8!i?W+edb}xd?%%=RZ$3tL9t7Uk4Zm18-<|%j z(Kp9-IkGI%65*92zns?`I(P|ndFa~wwai|%4L#9^=Ql9CE}rba@#%a|)(?2Uc1F4p z@qlYg2qUPuLYy_m_ipC+g*l`y-mCq6^V1dLe;=o1j+jr@qnWQsudUuZ5sYLl^rLic zeq8L79%RWL27f$UbxeJ}HTvx4!0)}=CK>Ow-3M){{8T-EmU!MbD%wF& zCZ)O#k%Rx(RC#rGTYlw5&!Fqy-hUYr%w2!4(H7fVf917z!B4^r>1#GI4r%|~9O$=4 z%mAKRnjy^kmild;C95iW%Wr6?burQWHk}L~4d!`#+zK3t>+>i@9e^zFo^&}>9_Zuu zfJiA-O&baDv7K34DJ2ruqoHce#@~0TOEJs2jvoo%i^7#IOzj~S9+{eOok2F_SrmvS z#jaBSlC@nf^3T6NtTZg7D$=q}8BRK;n0tw7tiIO;vCj|N`B}HGec5H*_90+wlciR} zeJ_ylPO?LuOM=#B;NLIh7IF^9!xEpJjNMCa{`+Ixv|Nofif{J~fSE3AU{zLK@xM8w zO{aZPYFeiMR5In@2gY4{Ac6NRyF~4|8&f-uTM}!y(P;b?I8_1j=R~!% zLF(XvAVd_XydJ}XM~_xjNCA~TXUY{ljEQl{7B3@`_Kum*3JM1Ns&guJFvN_VCR)AH zJLssc^yP~F@MTcWmz=5z@|31_Tx(RsQ>Wk8 zgIzuiEa@AyM zBjs>$0}*5>8>@C;e-tej{5=#$bU15$*&y;x25-pl=!aLIn;*S+9RpA)xF}Kw9 zD65X!J@Oq0beNCDH~k4{^^4=h~1ow7XgykJ_`aX!vSmgFg*uF`{09&znJd_&=B>4gRw!nC)~^hMB+M+$$ScxB|%^I;42-1*oz- z%S(IvFNMtp#svb*qQ*mBOyZhh6~ieRn>hM1X(*v;lpU{mZwuFcUf99tbSs)3@v^sG zBi?*ltK7I20C_%A8kbgr9Z!Q?wOnPp__kvqxr)R(V0+1cWnL!7<|#g+FK#MYkhC>?Bw4% z#Y?5T)YAcZGa!>Fvr=TmFDF#YbX~yz;p@KNl6)Na-y?e}IC10F9ATQ8ndM3%8~fYQr|poT;UzO;@I6g-tD$!{>X>FXuYfb^Ziy0dMa6emx(p z{a2r6|0m4JeGr`JEJpAE%uZj3zRPCX$0dxVLLsiJZbc0T5BV7 zFy~!f$UO?ZbxOe0ObEnW#P=89(dtOK#WPQccxqu8i11#g$xk>n?(xpgzQ1n)<1Pp| z6S)iGu{bYx!WU!K@xKwbFf(EQo;=U(x$)0QU{mnGymjW9gtzN_4eYzw|aJ@T;IP|Jk z@Sc5!Z1?xkUas7rYwxGk_akWIt>7A5(#7jGv)mU)d}#&Ukke-@^D@iTq~a%amy zl23!Cj^L9e#;;K}s|w}g3N$zjYRQQ1dq~qe>~I zT;pNK>)mH^To&p5v4n92j~1V%(iX|n!C#kIXM@DhVf$iZuSYJCB4d~ed%}=pik(4x zUe@~KwHw0#*3Kya(}>{g9DP{QCY$s6odLWZ;;U12&OOTYcwLyZgIY zx5{Dp($Js?#Zk_F(>voBu`lD~J77T#w0h-KW*6z?nB8HNB<5Xhf^;E|v6H-(b7Iox zM)!Hk>7Gl!*_Tm99s_0O&-F#|{LfA6`Wp>K=No8#xPGANkK{uQ)i=gFf*7N3dD)Oo8X`5g16SaDuwH}h_v2{0W>%o9okEppEP1CD=eoPR z+g{_{Bsm#v?Oe3cWn0`u4haAKEVudY$ft>Kib|$}95KYXCIjgUj1Hp8yZrm3w-PSLeg$RU2b&j;scatRtPv)_WL{A*-n{9ldolzuEfnE z91W%pM(3)pb~%@f_o7FuRvbPYb*ZV#sD!hU15&>OQk60EaC^`}FZ#3d61kNDpSIB2 zNnN!7+gnMUa{Xc{nKXldQQdXP6D@wgw{CTt(`O(@!HAdE_#qWIy3$7O_3*?mL!p|K zcvT!206a!A%7zG3a`uYI__ngS+2`jH~_iXs=Q#dXq1T zndoe$kbB>07689pD(X4<+}a+b*+Tp1LD$Q)ok819$*7*4@RX|!YS)uL=zCo18p7ZP z3qkFa`zfYVV4E26?hkg}tTRO_ll>_gXt)l{QSRAJgDDM{UKY_b6TZ@>>S{+S#wbc5 zm6#o-w#4v$u%}9wURm65{s)UUK_N19XFCn;g`*!(@Umytjlqn7@%5j=k%)ME`kQB_ zXxPp`;Fm4C%UF=9W;YxP;`w%|7Pt+Q?RLjcne^o7pPr7MoHsZUB6XoM4oiZEbSiAx zXf2jJJzPYy$J1pPAF$oBoYJfUG2SL{@7Z?`jB89}dp|F}v?ir|yx#XiliME{Z2E9` zhiTW9CTELu4MJO*jG@GQ=;7}0@r2pQj~lk_1k8(wf#hGg!6SjMv*3f{&U>&>-5s>? zLR%e*t=7*@g^ZZR`Dy-%(5w^#YQ}ew3|YY; zg-#FWytje(j;6Zxr|5_8cmH(U^;wrLZ2}E%Dzk=d`{DI zrJ3NfRkf!*R2WV~RwP#=3fto{m})xxl++?^_%QE;<_neU`y&gW8{p@W9eu&rzQHKa zZhMf4ft?Z2P4%ITd{WB0&2Bk7P1w^FIbJ`K0Q3#_&;ip;O}kW*#PI#|$Lbp{9H`uX zx>G@yriG>NAu4?-(fl&@(IN?CXwiA%7|dlg#Q^WtLkguX%NVqD%3!Zn_R83Z-poNN zmPdn&INHV&G(9g{gy%aCWRYi?>lyAsFh|pTVkzOFYg~U}z|k><_>^}OHmZ1_PDhs! z{<&|6Lu>?+VZUFo4jN+BP3o%p=S4TJSR(XGPYp}ICJSB4oHM_Nr07fv)4nU#y7?cuH|N?u(%NTB{r_v#O1izv_z>CVc5_tvYO1{I_9vns}b?j7ht z+Pu8y?2OFA&Wcx3mbs(hT^^=jI`emW(q>iHZN$7)z?mfQ6-G{x&yhdU;6KB*7q<{Q z05qj#>D8_7^Oo{06P*N#Z6dBatTN*y70Pr4nG!+5jV^-@TfHQpwrSVs;RyM7+w@Y~ z12MMBysQM?2?dPn)TJqD&fG%xMDLbw?CKal5FHo)`!1>{ab;{li=_VcS2vG{up@%KmKE$DB5j-P?Ej_sytCDF71z_`%nag{GH z8-O%BN=MUfPf1f`#fnKmr(}Wu8Q#g1Nn7Za-fnC+k!veA(X4PIuyV^zc{6B!P4Rpn z=pf0CSfZ`ev?Sl;+`XhL)2a4u7prg|+dQe;Y;{_+72UNj^W z@5X9&KOpfa*dRq|`PHuI#@DR_=KH#3`9tie6ywM*3GkJdr)^}h$32I8Xh>J(3Ki~r zc0a`F_3z^&Zr$dubOsHkPa5S!8Vvuqg?lZoXlgKKG~BhLpjt~8NZ9ODQ93No9r=wf zu-3yG*WT1G0Xpc}s&-^O_0!K2w_n-@De+SzZ$RS$F}HmjkL~}OvMC1FUO4Dw_x>61 zEgPt*G-)t$1C}hXK?DBS0KV>^MeeTalD0n<4KfZ%5&R94{rL)i;ARgVWL#p)w-_f4 zGiEQ@;7q&N_Tdc?h~1>_ox{Q|<`GaI{79GSj;d0-%dt?tQTI=<9hcjsd4#40=u*MM zjXcR8x{MZ&01YyM+KmQs=OPnk=SlG?=T$Op?~;E;ar@}*qIB}c$F@#QZr4r&yRGHM zh{WzLCm9_8u=OkvuJauh_uiUB!cK@0Y7aOHjPAX2H@wA|WEJXL3Y9H|nS9Q)0gBbrJaA z`sURuAGIzl8G{eLkAY;Kw|!Y?CRm95n()TBtv6|Qf0bOhX>QI1$s7?t62^J23SWtmnYAY>;&s$T}Xp2-5U{A-v z%z2S`)N3UoQ10aW9%HgH*i2){U8?6DZ|(fx6hXI3r^i#?K=6*+Zn<;!9V39K`!yx1 zgR0t_dv&X5_FAdhXZJ+xir#-v_sBs!-Iz@yz4Qgh4$D$Iai+FCwg%zpWkHWdclOxo zMaL)$_&}oK?f#!?uYc~Acp0ympzL_sY1}x$YeZQm`spjrAi5V=ekeZuI$2q7$}82= zWcP^%oj>wIDq=N9Ym8>5WZ>vUS3(CLk?WB*5ZfA|nXs2CJn23zdEy5j{ zW&U!an}9_pwp|2i8(4gVP2$x^O2~w~{>L4^*{c{=Rd(QykpqXP%{-^8^0f#!`Tf>w9oEjmjEQl&^)Q$_^`11eUq^ph*RIKHhv zDD2}}K7a6)iVxtA@ppDODK_U1?2jqkI`M)e3E&hc%g{5VfC4`>m@V77G!95pYz;&5 z6$gqV_Q{g^B$Au=%aX*J0~{koImiF(PRa8iiC1InEV4g#WQR4!oa4*#ZM3+w-$5#7 zCBiP564PMyG~Edx(Uq=qXv(a%&lC+Ze&d&ZlcjI39ogb5+v!d8>e6&g0it`dzFD*- z-YspoS9Uim=ShmzGTxHvYLVD&<|+o6=36hW*i7`ume53Z;fjBFR6C7cx2lPZ5|iKp zF^=q!kUE1+G2|u)fIU}w^IjSEUR~JzdO5}yaWN%b(SP6Wu6?W{%Qo1AGZws zMcbT`8;>ag>WA+o96SG+tO&1zJ_rPbS%5MPsWIMv>+NQEat~VN7(fPJ4!kkv@MdSf zjU3-*?$Vr`0@$TO(O}p%CrRR9&r6-{ZlbPjZsS~JqovMf#MkBb#1dO+UFypj;d-ko zs{ZNTM;YeQ+jKDt5*BT%XJO|bZb!s-$(GEJq@7*uJ7uH?q@$KpdT0g)^c!Iwcc0)) zT}M?d#2~-=BsaTJT#^p=U(Yt(D4qtHxcGkf!9YWjrAZrznsU?9J_kY{zuwvBuhU}i z+Zqkbe0w}-Eu0#TFy%c}&3q7<>H9QQRhzrFB`nQspB;M-|98{oZSKPf??9T7vr-pcx}J z4MC}$ggu`1zfk8dDi?P}-Gcmw?m49CO6ym^`~{8~Soy_QG@j}{C@uuO340jX!?$kX zBe?+WkZ!LZ9*!MAf){`G=6|1?@4ZyBcagNtN&EFn+twvitthR3fHx9=%by*e{Pe$owtqX+(d|Vk&L95xY?x+*rW^BVD(feE zVRp(&HgbvCKNP@7dy)qBqs?lUW(oi2%O_hO*BKfY!9ESTcmiot%I9<`0)$mE01yPn z?}YWxT7BCbW~DP6gElif=udMArsPu#+GNFU)=>PU@x8oIm*Sm)eFb~+Pq>wv$1F|U z%MUwv)j9<#V<~-tS}aapUE6)#&k%<4wKSED!W0f{?qVn22k-N_Y- z@M76v$pVOwD_OX=`1H{S=hl`c9~9p_2$O+=#VOLK?wlIi77I4{fa=!Tyk^y4!PpvoS*}OnxyQ6=qDq>*w^O!Y5vBZ7&yxa? zfo0zNH^Wj zJ@|JzsCk3p7yfkj+VG)KtMg@fqt;>=uQ3~h;l!BTxk2%92l-Rd{nYLMOH4Ybt_6%&I8E1cVxy0s1=kG1|k2?nI{h3J0CYNz}iM+a}Mc&gY{ zxTZ<=HcdABv`4-j6g+*>7|@-r>~g1NSdBb;6oeYmX~k?%sG?=h5`;?aZ!5cY@B&%;A*xG2JW4i^S3GZ=v1fin~{>%fDOq#(sF^ApGWd<}YBXkeO(M_UOSn zD&2nRE;JZ_oh-J0eJXK&i%bZOFkY8UmOQ&&oV|5|22U1A`jOGCSF-G5y}%BZN9wA4{wtDRus#$L;~+ii;j>sM3mc;{#Gs~n2S;0JbzkpWdpuJd<8{b~y#{Xga8CZ78BgxDap08t z7zS!N*)1n985jxILuT7=rrL?>XVpp}thQ-wIQmNO9rrWvw^gj56Xn6w9wJIhm_Bbbn-^uxD*{~nT* z*awbTl>Omu^Uc$v>yI=!}bQ?QsBP#HiMx%vT> z#wAEF!=JL2LMexvUYGvJ*tnjNwjZyxtU4}d;3h(G^;uB~HBzX8-Z%d75&MV|e$j=;svye?^scojHEs=37s9=Gt?hl{0PxW~F%AIc~2<#o|%rl*IYsK0|CL zXhh$;{Nh0`#(RXk`16N7BdaIe!|5ukJ(6cI_bMt};(KLi{+btT=a1R!u@4+Qb#WQ) z;PE{~_0-&{PryegPeDNTgQTn7D8`+YZ@r28?BB{UDqq73-;ZHa-A&DYzrM(R&{O-O z>`4B^#fcC*8(mco>Fqgxeg*gOdO~B;)#i87*?HEi5V6acmUriPKR~+DV+4OffMYtv z3iQ`G@OQIoobC4}RePIDN7rdmni{1_;Hq5+`+iyOtYsRyimrk_yx?@_NlLW4J!7G0 zRfyg7__^DP^O5_uXbD^OgH|{6j#H0|OK8-6m{>YwtS~8a9{^E%mU)7z(Jzak-BAa( zM4PtDi@V6RcSm*F95NX3s-P&-DUKG86rFG=&%1h5xEkQ1n%#XKQ{|YZN8AGn`39xm z;_^}o3+y5%)#gaUdYTtjj3@HyIlA^lbr(*tI=#!pF>ilZye8XQ@&osPnWobNJta2K zhasT>95BFcAp$u6BIw2z+} z43O{f!Of@DvRe#GilVSqI@KyFE#p^j|LrPxE=hbxJ*58k=fQ`6&qFR++FOxn;deH5 zjP&aAXezs(f0NA{WxgUGI4l(rCFz`ZTwF63wVLx^s!y)jxEt$WNF#ubi8*Z@vZ}sQQ?=b}}_H$2;5WKb=}HH3|QwV{$CB2XkMX3WjRzHGfoa zk9^BV>)G~5KbUU0Fd9FVI}>wccDny0Y=sITdGl3p z=4I^Q!#h()Zf=R6(D|qNMt-!ez3|lqr$7FEtdrsHGVmVhz5$JvFspuuCf^4?xa4QR zlspyU(4u+od7tisSBFn~JsRS@lGzoTH)&`yy!-CX#Ql*{oj1CRDCWPXK3DiURnda> zygT=u6dYClP42%VxYZ>p%whRv@|M<(vymZ)D-%98)#L}#3ONpvF#_)!0!X7f-e*3~ zCCQtitZNZPIF>T?LHgQY8X&WK*s8Vn$mTd0B1TbAl&y(=t(p-v-edVpjrR1!_!nd> z$qyOqkWD0L>deq(zmJ|aT_P$b)+HMM`)nU{;lr00l>M9etnOG2NO$63PB*E_RD@mBwh7hbFuwE&{$ z&lI`=N6YJc2P}6uSL=(@j^rv7rJok3Fc?b1l9{k)xsuM67Am5VU&9@LxqA}n6!zZLFK8raGitJ)ZZTuSTmts(A3jaY_?p(sMYy)qHpQ`)m9 zcFBa3c-TnoR_UtK-nIj@nc<}r`zrLW`tzxuj+S26hTldt-Ew*LRFFdTTOJpqPe7jQ zH<;ADtkPzmsk&0R3tJn$a;GD|Lxo$=u&HVzggy6ljb$C{F$rs6-x?4vzh!rmaPZ7O zhp9JlEU%Ma!=HTI^CbGEUep}wq;9w3H0j)%#h-^x-bIY6KEz&|Yr7MQ@3BU!aom%t zr5ia+eOIvz&xxvcS*JEn2JEgAF2B7l>#OzXp%Kh(wM$M2XPIQ;&_Q^*{E&!$W>>Kb z8s2`r=IHh&*9?3s1+R6Zz0qd#FV;dAC?#C)A?B@RP~ai>Zo+=yF2)mdFlGMvK(X6c z&EhXDt4j6q5yZ`5?dss_pVjkg6*iy7*atVee{?&dZgbGj2$zRM%WdN2o>^pr4mK<` zX(d%bHx(P;AnDCd6mL958G}4|k)q62(TX!|J!~cAguN(gAEY3z^3elC6mSkTG>abQ z)9wpU_XQFhfkf170>z#B;)iKqcS z`Zf{OPDa#|P(liVeK#d&T7d#cIf>Od9>anQTfx|MT*GgP1ku`%imW4Ho)b}ZBBf7& zdQ48ePec}B(T~Zws2T#2 zhebUhqeMvw(R8$vjBKVN*dM8f8dwn@({Fajr!6Z#0L5L9_6OF)VA{Yh+5@MSalh_B zqPXx!K1h*;`#>PkMnx795v^EMmpOfS7746^h3h12TO@#6p`N>TIwfXZP1#*I?)7aV z;@!OABT22a_(T^UY+A8oCl18w$!I;9nyp&T(;gNT6H5(?r4 z8Pnm2GMdf+`k)^0^4bI_VRYeDz9=tISVTnR6R|Z|rU-+q;Mj&u<|pIQz`3#eHYD~n zo+6cCV+A4?15V{IM6>HyfrQHduJL~<1Vj-QGdWv$n?P+8AZ`#*PpGskGQEw0tmkAl z^0L#K;2bXMnc$L;hkiar6U_*t&nrFVqHd3+LSl;YDToRJ_M{+Rx>ZDJB8o&Nn;!dS z1YC40-a^#ICZV5TQH=tLunh^S00yiQ*?EX3lsrfZRY(%eY?GSL%YCqroGzt;gstdl zL2kD$avLUjfm~EHi=M=yFRx2f@S)r0s2TvXj)%TYs<=(Siu?{L0C9tdte(9D7sJ#H zV5V#mms(J{nt_N7Y{ zwn9tH#Wd7=X?f{r$-i@O(imS?@mrJ}QBfpXI94TL4F4N`*DoSe916tKQ zFw!nq4@LBC=QiLPT4o1!ZbP!&66HuqB$s+Agg9Bnop|l+l>AyT&SdGFy18l)Ez*-F_c=B?eM+QWDI)1{%Mk%Qg4qLoW(o zbSkpJ2?yff?tH%^=>ZjK+KtgSdZ<)gU2G=>X=HKv1HWUKjI4MHm5IPzm`(oMh|G3D zzZJdaQC=ELz{mnL@dSl1(ODm{c}q`9@?`V7AH||)H0T7BXmc-Fj{1w28X%WPzJ!eU zN_PE|zzTpCt$qmrW-|cum5)6{0fN-pPy&h02L?SZxH^74I0bQ^i^__wf6cjA=Yy=l zUhX5etM0%hL>FC&MqQhQ7vDp-L?eo#QJ?%CFZ-d=FJkY_q7oHRw*~e4QjoXCp4>*j zZd1kKxmB>%CUj@zVW|h2YfX?q0G0}L6ocFsgSdwynrG3j55$5U=)Y z6%}s|&jC)3BPvph-U_gw78!XZ+$92v4&Xo1!FmteSiOc>qU7+~L}QmpeHRBW-r_V*?HK}#wK_3H=6Uv~Pa@9~B;*2c6p#tS z)Bynfn2xx`M~mF<&lK_3(PhyvL=h47j9lfqDe;{s@q>u{O^^^(0YY<&iZU)oik?xd zP{_%=Jh=lqL_}ARFaP%dv&2Ccja?NbeqL}zAr)u@0UJ!jh7hr#9Oy~HxZb&OAs1Ex zKwKrDZqGav;pZ!ZozDiE&M(u9oUok$%s2^MEd(SfhvySe)x>fO zJmOkYS;8AQhlCy_uy?v)k0CJr@)&zp>=2dt-34p0CGpe{YiWo(5>RG7UEd}Wu>rWb zhZvd@>H)XmRvFs3q%2NY-x>>oZ0e%w0DQ#S z5(471kR$${hw0%v_{V`w1-5#g<`=2YL{`K-0eXytak+#$XN48x;N}M<*E4Snoda_? zn3);uy}$T$(P1Uu1B!_XE66@Fl0I8lxFs=0Mnr7D_=4LvDq7;sJuO$Mq{A$dvA zV}t=w;viN4V+$l6Vv)I61P6-%iG2Whl;0y@hPWN=vn>^oqWDzPb3VF8zVV(8_M1L- z;M5Yd^$l39b>xyL7=wPn!HkLyck0^(;#)+Z_=W5VP_8&|4g<`s?IixMfpCil*(U_J z;l?2z{G7)eRL?zZfEyN|_;E~t$|n#r<28?R;b92W>sfJ85a0^|TlY@
  • aBF$-wE z4Rj$6l#BERpt7(Xi;hL2 z-Q0$Tv156m&SbwPc0Cs~z2ypE;{wc1tmGMNxB)gY z0Ef3gJq94A?_!UI*=QWDrQW1~j$xKMpf|0yT8Og791bBmgUlUfnH) zkd7h-EwQokvc-40)T$DNT=)ZJ^q&;JBmznOt>08m$ySDy$H!Joemuy#Z z*Cl!&Y@-0tmAM?1C&}A{vRbE{V~xQ@+BOx7&QmSL^vhZ`kXBiu@73+nSO=GvH$6s+ z3~SaitJ{-ZO>8q|zpPkC9BgpwwJh{IeCk=_shY-9pYA3v@QVJ0iR)XYuMqB!D43t* z`MOm1Z{5u@us<~&)apCG*l(>PY{Pr@M97*Ye7_?4wYkx>=X4z_qzdm~GNpUmb?cvl z+v~|>Z?eU@qm8togX107GELZgp`N_(CaEV$bV1j!y=qet*b4|J}8?GrING1_-C zsx&m^4G6ls!mWyy|Q)4#7J?TSH2Y6Y_dxj&7%fN@rNugvxrcoco%R z3u60vT52y`yO!zn;On&zLN&BJIcn37DLU|z^7Vdzfy|k7 zgEo-e{V#WF;NpU5z+{KP(etC&Z|Z{|ic2jKIQ2vPSM>$yx_RJgiR}%FPmo^h+*Od? z_te^^DM^-r%1%!yQ1nz{^TIs9%JAbGi-}YsdCi@IK zz3T|5h4-yoD}_FjYM#?}OmBGr#rHFWbnb2GGMwTCFQO{dRxC%MS|}4b=B-s+fP-J;+N!A%g5!R`3C?oz~`oF zS=B5g!80;2y`HjL_Jd{NS78PUarUppo}XhNwKep{qShY%&|f_>ej=jC_dvv=l&nsfgd=v@60FB6ka%=UHU)LBdW&V(BVIFE+Hu z*FYYk?(`QQs!eN5S?W5vZM>uxwtQ-Qhi3En`r~1DywO*Y@XEtNKknfQ zt3^faQ(r|q>BfmdPlA{Rdxu_Z_2Nd`W1!;qpAzm?z21+9UP+6xX*yeUsTX?8o8+}e z&QUgd;YsO6ksc^-(`q5Edijk(q%r!$FkF81pJNX2Y+CAOFt88##tXbi16D4oZW7b1 zzvoJ%v+0uJ0mrl~=8(b5UDAX8z1FcbH6K1wre@Y&Yg>$cU@=Ico5(cCt11Xx?z$}G z^fKQS7G&Ckj=zw~8M>l|v6y>iai=`}D=VIeKH;Fq2fWk-j6+n&wWy-?)UC@^4@w6h zDu>SZ5h|#qtG)<*GQP(kd=1^Qr6D&u+h=yIHS;+ClWHY3O&u-9{?acdUfR@ca&0ZE z^j@%hCEs54@{b%}@j!%~uItPV0n1NRhfhfKl}iWc7f<56$kQ}~YMbJrfnNDxr}4CU zu`ItaAl6?YfIac`PDW*`0;Sw?-9PI~Y3KY9LWXkR>0} z30scoPFjugCESDBZ~n+}aaETY_UZHXT+fME?UIQZV&6=HIJo)%In4m?{S^gLUh(r% zSE)VLweVcee)S}u@#6Sv9$Amc8j2Q3pPYBz6{Yh`r$;7BhgNO0-HbHkoLdR5q2&{owCkSRX9HeM5IAr}8r%c|ogZ$cboc)TxVX3pK zF9|Sj zE&2Aj30S&R(Q^0EA|l>#B(IA*2vkZ^LpcZv)g1*=z?4#)ne>M0@!80jA|Wp|EXhv6 zdnPxa&BK|UsBwTNSW8^YQ%e)Xj(#jUQ_SS04s58AH zJH>sS5;{VaWwLsAPG`tb4uMs^;8Tt3N#!HqIYl!Ww4VQ@%95o`G+tBsc1EhfPKJFz zdW#-#;iTGG*E-nU0xSnHHeh8a8n~ zb#Dil94=0dWuBg9QPuE~Y=~=g&T%}{56d(Mfc>H&E@Kszx*&?B7JH12XY4ft7!U8D zM_JZc>N0)F$fk}55B0^PIIK|4!?0-Rnfz=WyOxgSn=Ksl`-nTG8>|CZrXS&2&%ct` zX~;`9>KPq4>JRe8SB+~t$`ln470jo)(}i)0G|yRRXSaOioMNsYz0*hX5(;hRl|LH? znXiHCa@ayYkY;oGYI*vf6d;MiI$gpFFcG)6?>^3jkmg&m|G~bl)2z7=3Kl||29;^- zC4<2ZfLh(y;!Gk-a>Xo)Qi|AsZD-_I5gD4@3_B_t70n07^C81=($A6in4UwVFi;tk_l8;lP=S5TH?bXGM;GG5)F%^LM{y< ziJ3I5MiA}*)C9awXkqgxCWH2lpP|PS^I2weSmBM#TkVV*HuE5fNr`4rL>t{kh94HvVPf%+phzS<^&QXli)IPL zx{^8{2-vLS9azj7E1K`vaNf3M*0Es?&lKxF9uD?`OFLzvw#wvt_CAcoGc`JB56E2M z2&h|Y88i|I%@~GfN}F3uJAJaCmH1xEtA(FCdAEKO=0v3j48jYQTJ#REN;b3Gc4eZ( z9?o+u7AS?gOTg3>xkxU{$A2iYHY2&iS<}w=GOpyv3^cNlp#CpAnQ&_to)LnA9uTcu z0XUU%+RhTN698ux843|y5aqNy$IG&L@_kt5b8f+oMh(|?NMW~GJ6!z>eoXwyW z3p!8#*z4cSn#hIh>A>tyM|~Y&#`v@*W}wbbH-)YNJ<&1? z4VwlDL=Lq+hzKz56alN)YXQ-cRy!v5Zls0)phu&bp3#UyTdB{)H0(HZb3EAN8bhOu z;o8A)YGkA?r(ifK7`#~gNIDLmlFSEg@1-BSZD2-bTu0gDrpuoWR|v9b2s4DZIyqJ@ zgJqQ%Kcfl{LO>E(tmYEv=khCKUV2dkXsiuWxO<(UiWsc;emj%0uVH+o+l0A4dQWZt z;TET>XB*`crdd{0n%-Duan_-z3|dDMq{&B5tA`aiE#Xb2f3y(y*kH!8VYY?tEd<^f zHnXpZu2)jhfX{rcn>{;+b;6f>4yag=({)e!w(v8f6ID-fE!?g{-F@gA(;Y_BwD;)D zWL+8`+iXB+&C|zF{(=%vB_^1h9|jpA)AauUU|?QOd?~?inmdMqQX2Q4pjt#Yu|}Qr zf&tJ+3d~~a15Z)zW0~>q9%JMbmaWSWP%Mw^0R;}*Z*XiZ;Ed1GkW&I^k~7q+gy7Q1 zEWf4Xj)nM6(@o+Oj;zoPV_8ByH@zK|$SG=;8VPc{f4XISXF6e@>`;1+LtcUtO!P@3 z#fV$p1Xiq33*@%hsC({xWF^aK}jXd3i+eMDonz%gVf8Ef2~m~Pn!@#S506|s~h z;OrrTJqrfhF#;PsE8=ii29g;wUyDrndM>38MutNFA*034W4QSXHlY(d2s<8rI zl&h>jEj~fdth3H6=SD;`!zh)>iKB&WxXr`hjA-uvNY_Tj$lEs!e9%5VYQ|^MgaEq7 zd$kik>AVgW{!o^t5TVDTbNo2PiN36(eDL%Kg9cyvvuof!H(S=JoeO-jJHN$zns#_P zcky~n*3pL_v)3W=KKD z7pU(=zj|#8Gs@-tPA!8yuhR{jN=3lB92>Z1(7ZEx(hxi9?!!EYWA>$hB!7G`0Dwrd z2M&(3>{PR|k1WFN`DX)#w1-juxmuvZH~r6 za>#D0eQR)DZ6xdz6-)*~!*yqxW|eovq=wn0QUoC-kWjz*eMG8EaKCR$zi-ew^Vg$R z>q$^B)^DXlK9QXotIM?XDA=DXy=t**xaVj8Nh z=kTMEjC0V8Gzu$l8bZ;nKlhatR>EY}9evrv%B*I`H!+KOjFH=o2Pk0SVJ(oHp?Huq zXje&div=D2g>eADiarb7SH{HtG&=6nTQkPgZ($hrPqocxyAoM7#2Veu#uYv*0uSyS z)Q%9BxJ`2EvP=DN33Vy{Sj)Q4N?L}7Gc1wAvcWTb3D>I3d?|J_3B*+2ey#c`72-bN z9(H#6!(0;vd(BAtP{)D8P;j_zYIzDfufi(3>S2Pe+2kt`etXr1DjiUSXD(6lVb>^jSGg9l$tP zHRpLb*H#Zg?8s`loW9lTcZYktu1vmz{PA>2;8SUcLp1Z~G^g9`jYz*1|H&e#eLt=* z)j#XFbs#mWfn9cEr7dyw>3-B{?Dtq9jO*HyHU=H2WgiE;J|lIiMeuFZ-7p>gk&@UK z`HlZ@ofRVbmI+qAko(;2WS~nlB$1Yuy944!01K@+>dy-^f(o)N$>2j+(UoA<84+%7 z%iPoSKtYG?2hV+TYNc(wW#=;8GqITB14S`e&q5@6jI0!@a-)dQJ=mwaIX^P-^DV^r zzx^|(sqNW+VpagZD)#3E`NJq3Qho%{JLOYt^0!{lop=GudFfqJ#u8a?m?|jvBg!4#E^FJ>n zB@>Vv)x=g&i3D~k*M zGQUi>%)(^McZfTfX-@~F9w&n{{n&Y0A2Uh)op#q$kI!h#b`P&-sgoH29km^N)=vn_ zJ^cOrG*E}iI73=&p@vPA{qqID-77lk{&@>jyONj3w4#;;YF$jsh(`+?7kDr8gJkyS zj@KYxDPz_wI0s zI<-t~j9(L@WZUh#LzLvT(8=m|s~6gbpX@#Zjmi5JF=HLYuXoSrTUBij6S5}re&rmJ z-*e{S_f!4#&#XP967bS^{~tO>PrLn zt6fdOZ25WH&v1RuhmA1{PqG)VXVK~VHpBDu9$~H*4daPD6WgcC?>ui_9vH-3_}q8w zwb@&=!^DAitCFssShwK!*5jG#lh*BqCYhIBuz>>!Mb|~!n_EfqL*|nm>VqcZ+z%Y% zC*VT^atXZLIX6m670kYd-8DeJG4|ahaF|deh0jZYXyoSKru$lcEubTGc-7C9> z4eT=2;g6Q}ZBKe#%vH~y4G*@xS^^w$7h+!^@Gn>iMz>c^OnFBlI)laYd7E9XasP}X zL+zmvzGUKY5)R@9a9o4zxDBQ+IlKT%p|!~monOfKD^)pF&L$La4*dC&+TbcAcW3Tw zoyF@~(vKBYp7mC^5N<1czeWGnE9BTKn1`J>kZ<}Nzm)ehp}y&BNDH!X$Y6Zf6m#eq z{On83=uS(F*^6l4Plq!<$7c+xIfE@ZL-?ZUU7dLK>-VSr^XlVZ#GX6ZN^DCN>eWw( zK_?S#4tYO-^wKfDtv%j5lTCe#-3OK#CPUI5fTVn>Gd-Rt<3yE5L~W0K`|{7=&f59e zRR|a2+>|uDvP>S^|8eF*J4@c$v&?=fKgJlQzcZh3Y7evhG50$zuIi4%aXa+i$ZrlH z$&OFdnl8yX>l^qJrnVF0;N!b0H|fp>G@MDg5j;?8#0#-||8AvZ-7aS@Bj;e(pwvfo zQ9)18->dIU-0%=u3y)cXVM@YPV(U-bU+{uF z^`B$k*dc{fgC3>1=w8YCu|hqID)C#5Ok-D>eP(VSV&&E_(g)_UqI;tD)o!rJ*x06h z=UWbr>p6Vd)pOrA=3@fyHM=m#Oo7q=LEU2W&Bwn#_K-!X+hVnMZsgmNp13;22NZhd zI|3@gqFa8!uAf+cB<=VzQ0giPvY9u2D|rH{-2r%|Fw12(iNdD5u|87{lXJHMuJ!-` zo}sd=G2g4iqU*J1OjwiEdkjF*ds zMcuk(d@@LFn!}zF(h;hD{+E_RK`)f6xL&Ux*9HDJt)wbTXUD&#iERAs=ZleU@`cJ% zTo2OLF`0b6)Q)#^!#ep33Pb3+ipL9;57ql8$QCKcL)3tp8Y)6{&k|duVLvHm!)!UY zUtaia+2zrIOtj~i%0-v4hLT*b@a&e$39>s6YEBn*wu&-!UsXcX7AQ_ZIFQ*INN8ka z2JgvQRpE@WP5E?g8}`=Gn3ZxvoD3?(CVJ0wFn2dq6B)2IfXQ6GqCJ~%J4v@hFKI40 zG!F~_hJisj!T?)gEz+wiN{KfW8DQCUX}U66eP$UHQAc4ltvIV%AwMpE^gxllo$rKn z0pBxM5YJ0SGc(=a= zGJpWYoUDAxCG;H5#ibAIWCPIKY0SO&u1?Ve|GY_ev2W}24}2;Gn0!|N58VVNKKNYu zv(BtA!lJ*+ddykAVq!km;Y9AqsQ0**2~47_XZ7>>Ystmk&F>4JwfxQCoYDG&`LSYt zBRORkw7U)AH4`Nu8@ebh|B(*p(o%hH0AZ79h$h0oz8|$L-PVosQrCBxpE3lgWAXy6 zdi#=1U$n3tTb4l^-I`ENpAtDtEVigq9OLb^GEoQ+Y6esf0yY-ofhYke4-TI<3n`ssEJRccdG|Vy{4Bq7OkICGDNps zI_WZT(BNdWS}R3cX9=tAXs{@Ey;;PouPjlh90iWtNn?G-_(SmxH;$UB`nyMzJ~!7n zId!@7jvIUpn50q{)D9ayoosGYn0d5ZZ5<*n`$56BW%1v8J?__Nnh&(ql{JI9Hl0jb z*K-JB0<2>WZ5I4byeL|AY|ag5BvBBdl!7pQKcDj!&t5P1$)=BV1^7V!Er$ z`)=W^T~Uo1ACFhZMj}F%qLhb)o)%^G=qL<`8}P?4M8$=cwO-p8Q(cr! z9w>+ffRy7esZwiyp69Y}zm63BeI|~UKn4Nk(Z?W)Z7Mx!8QMyz|BT7E;yFXR2fn-y z%-^cOOcyyVA#_mCf`Wbxi51L<-m{_fq?L^-*|fjP+3uV6LD{LnP6cyoEL_EUMhEz< z+<}KIuSkZ%N{JxF@0t$NN{8%R_`10{*qReyV;Oi1GobGZ~EC{MVM* z^4Db%;Ig&8FSt+i^o=g)w~w>&x*ICaUA7wR8Z$ZY-ObwDLW1-%dck z4tE+)7=YL^eVU&&cg%WxleE_1S*_-O_8zcK1_j^-aAdmHs>BgLSv4vPC+yFzQbXv~ zX_-{76+J~J6E(>FxEL3A^00+LzbsSLCx)0i1AO`rY=s*zU83(K^!@n0!+BISJ%wl< zc)2WVK-Pq1<`8Kzcj#TMYcY7#oGPIQa4{D2>wKf_T#_N%4E`1L?KB8C1~AN;Yppt- zSQid>oPO5oIT}-;@np;3nIGY~=eM20Sd!x1H&Gx~&@Iru$H;O*15Vc;I@=T1%Dp5Na zXb49dl>zkvfjV2n9izma=SzPlmzhj1R?>7lDDX7pK>*Tx|odi$y57W^afL1bu6%QSzS>XZqlZi4O*K( zgOFkO>LqU+!lO$GIu(`?39Wf3-2EE=<~UsOdsQ3aX`CfNHfT2=Q9PWgazfmVc8nnbzQR=ppkdK zDd6Qq-@jRdsPf(#i?c3`VV;)Qhn9EW;ad8wLY+IXgLo6AM#@0oo}n`zopJn~`Ud?P ztG;GK5})>w{QVtb6>nMW^YjL=`~4zC~h|!&Q=)?>11MHY(}4$wiRz=Lo5dQO(8Eb-v6C3bRO+H zq6gl_$=2F3N2H$m1b*_FzbeiJvF|q}Z@WdZc0J5*1_=SmTnOIA$l80LAYsvs!_^h` zn-DMt1Z>!fVt z6DZav5Zw;Q4=)<#UcyeudUn#E7OW;bd~M7@XsqAp)1c5z9TZNafOelI!qU{=76Ogu z4p*&4Pmjk|ho~P1j-;jZ$uHBcGWDg}Mn0^Q7#NYuQvmO?%mgK=zjQ%OqrhQM-W7t! zdfz*D7#KHjNYJku*7x=>GaU%DA{nO-){>T9Ja!+*t-h3!h--7m9mlJz=7%i=&y{ch z5|>O1#s*+yWs8#Q3ZrpZSvav*I;H0F-^%cjBqPwWX3NLDGh3 z-ZJ2VKS-76KU~Js1uV{N0j-iJ4_mD_l0a7HoE4SJk8iw^=dB~Q7;?N>w>hvCX26I_ zQ?R$(TI@WWY9!Tx`j- zmkm2NY)eCTSf)N8NX`%}vku2jwwdwzW#_-Ao#;q^eB!m8DkSDdP5FSGV8CIJ5sjmY z&yB#!=H=;kbk+M@oQYCfj2P)Y*6#FzceLH~+`}YIFX-FMF+-poMg8qfViJzx>#(|4cvd6|7mmK#4p}8Q)dgUmG{tp0{b&n z%jK2;XfO>HE~}P7)aEJd_~5M3yc@vny6~a<@_+9E$=Pe<=(N6-p&RSkJIZl8B-8<* zwLq~n##shOSXumadB0ube|j`;hMA6wZpM)xO*U)%eg`e#7_b}%UXXHDToWLf0;&_UA-d=8%^tTY=UX`I!-fE7 zB^x4oYhdW(rW?kl=d1mLLo>@#8a^1oUPkr=XmG!XE(_M z{>+W@EpzShPp*Z(ltYBHC%+vRv*cg;wfyP?o&RIW9|Ru5&mL0bzZu}jy*z#We=Ipy z+v~D-cly8$XnpYO$?jtZb_O%l*S+s{tUURDSn`R>K0RWVyzAJfJ=a4%efd`)eUYUW z>%rCNE8X?=(`}gal8A3|#rJR06GPt$l&uLSErx&G^XBARBS+ zP8$y z8l{LLcfCwk88=)TSe~#gH*^l+7{rvTKC^kA8|BuwSg1rx;8uE6{CbQTO?lRE=$^_Q zp)~I=-&H;+e(X>&?u*W=?6@D@QPn7`MopJ#v_#{jDBFGSeU^8ue5eLs{ZQjb~Zzo{yA{v9u46nZyOO7`%&R^34#QSmj8Uw_+OU2L(r2U@*iidlqv zRYo}H_kYRBv^z(Qp2o{SdB|qG+&Qx%)8~s^X_H6$ zeF>T_(Roz|_vvfwR@%#-mWgpx_!8E+_)|Tev=yq*@vZ5ni_AW9c6hYHwsrYGkX*?W zOi9%3o8hEycis)joCq^=1@8}Y9X9^`uK9YaC*uz_Njw?73C-O>RiwFsOlcjRGi6rceeB1mqoqx&t>}$c}sj)cH@P82n;E0 ztu8Rr%Dqe25qe5^%t`s=(9NS0+fko&Ep_kAN~1OL8@KlrW?p1{(D^7!+y6ytTttZQ z$IxljBq^&5)2wgysrN|Fv}^B1OSxE#{!qOC`}bo-Bey=6UyB1Z*L#=$RR7+Nlg+nW zfw?Hto7ddhjWdYYZvkUzJUyAO5Pmes0@gk!DXY-8;&G}Vq`!`^n@0YuvyXc2qib%t zWZW8k;AAbag5*eB_0=>A1(p`F^k{|gv zGN4OMPv@*?nJ%|?@IJ&OHczhu>vr~?9m3ET`;7SdSIu&p39i@-1P5Nzsq4{Q*zbAF z#eIu?#Hn;E(Xig$z11St*=o9|P`bK&VrNtf*5TY)X|Rqn{byGhH;tszU9TB(yx%x} z`k-R*lmGS(5D{&jg*r56tkNRi=XlHU!9V-H2FAD@f+z19F*=kHSZ2BZtgO!c5;c!= z7`LG6T}dI8bwtk)%xcP2_f+Rc@)j#zrQ|rBAq%|~y{5jV7o_uAbN5;@HIX-5 z>u+}5xq2frzC1k*=+J3cRgGRcm{l4re~T|-9amr`J5Yg^@cuo^OW4E=^PTpRKvt-E z46Eb1regrZ!C>LPE81^ASgL64hMlF=9QZAH^RkvbBSxaSxcET3-pT62+t)Jf!iv!s z@GKMejFPF72syb86OC(0UZii*yJdE>Ubkgf&h!F9FmvAH_q?5b4c?5nKD%_n?S>(e z#lsnvLUMM_S_X6}0Bdz?Yd72v1t}MOeEqgvi~9}hOEn;`U3hpi9hy_!5_qlf1=mky zxd~!xa1hT@xUV{Bd)%kRb>{HA)j$h8L?>HkLJ6(&RQU7Ki zli4ghxFz4Oz3)KFPlqaQ*N$iYR`V}ARjt9dcbK~O7PMw5(Vdi1GO&#el@Z4#+*|aP z+^&H=M8ozsBKGQZ91DXtF~Qg0cn&siH-6PDC^h!C{Z>nKk4xC+JoyzdmpAi}>!-AJ zYijjq`{9WfYdcR9BPvc1)3NGtMnUk zS8|AK5Nh8@uodNX5!xes|L{Y&_l>*@d%-0i@Ua}jo#}&L+#lAxZg6>rEJas44;pwq z51Z|c&`e2xq@*7+LEbX|eRgHIr7BybwYjT}NOKSCweaXAQQ-;6#mHcO)fYmJsZbu;Cv?WaD?`y|IkZ&$X04F^PYoG8;F{V8Kf{KlDsAlZH-0hEYZ6@Nq-s}C znArD0hf{b}_39(Nm(dZ+mxEX-k=_~yCqpM^JEYT@K@k@-j5=Y;&c+x6{#~usJwG8A zmJfV?jX}l6zi<^Y)Q?U4Nh-bmJ-o#jBU7c~3*Wvo9rO7E?&--id9aJCzpKoWJnb&x zAGLuVeo93Kkro%z5O03CyQp1Fiy|T_#ru9-%7axcO??6?&s&sOXtGsEGau}N|blHJhF9=_yt4w2uMfk$?^RYT_HO2r??1m%vvXcgp_2BRFLbmlsfdTqLLqH6VtEV5sX@Niy$L$kJIU16&do^IR`YoUnIex`1_cN`jzNEar+h zI*LULc&9tWpt3+*SVzH|k^iftS~DIgF_hBDO_ETRIgDd23oHRW#e;Fl;$S`U2?5oE zp-%ji2EdT*R7AZvf4wGc<<7G7_wwRXaqCcVrh7sOIY*&(bEzGqvk7ysR{rTyAtafb zkrA)eDOv(&*~m6uNRj>qIfaLJ;1R7n^y39Y6P|OQ%IxGL`!Aq6gz!eJWO_5E&>e%G z! zj5}TV{CKsiTE2CX7Pkg*Ixc4dFnM~BCtuzXXNZw=3n(3BqzEsj?h(s(P>yGpE>m#DfJyCP|Vi%%6gB`L)@%^v(e#BnhHfE~xE9(+C$G zc```|`wTn(gg^&JB0355&NX=Dru2P`xCoE9M1@1za%!mgod8rLA0b*RBvZ4@#}xO3 zU~Z0{H6A^6#4y)*6LOL-38IxU)=mN2B$L(%v3w|nmv5mgduR>95S|l*`cL@c56S5e z!}(ZDH@0m4ALJ_RJkU>k$q;FyIepZ#OS#llnCx|>ib%5x>9mUW+|;A8PQBewBun6JYsC2xJdwa&c44!zsl| zwi1whEJFM*VAuxPj^~KEVlk|plK>av?v324ch=`+{Vt2}47==0CB*86u~X^z5=jHh zG_UY620gtd{e+Jiw8oT^BoSFMt9PJBufndZU3PCqrov$LmBlZ+^DlwuFl~dNWtNM*(61<0B`{6?k_zh}SfbLm9J_aC*xR>$D)xAN` zWHHB1ZW1%yv(={cSJN%A>p(0kK-gi#dI&K&`38ep zwLumU>gqpYlBnXvk3{y|sKGYOP}>84NsE;OZ2qN$QT|9gqFg9hN1-a&b?W<}AI!lS zB*_o}RO$tUGpiFoMYx8x?IEHf@DPp>Vo{S1)a(YDp}jmXek$dc));l-W;>~!EoeDi z+wmh5dPr=SSU@~jlWfAEKUJe<$*2cB^zsqJGznS6%jad^Oaj0U*&{Cj;FW@Z5++dG zHHH{|UTeO7_wIGE&E-1v4zTu)VJ+IyzD`Q#q7~NHZw>C8*x)Eiqu;`S{RGgY0y(5m zLX#(n8jMe6^A=!L0@Uo9bjNk{T>$K!9sExShEaLFI0QMKRXa5% zJ1e*|%cYj`IkG`ujS~>Djo=Ca^>9LNjEcyjIdLas%{4Iy4A2R4AXEmDN|H<)6BFLZ zmwCz)WZonko-8C);s+9KVEVbr#V5HpKU72qcQ$mL7Fi=(xm3#@l#>H8pCs8TDNE%& z5G}xWZlUJ!_k?@|Y$AskhPfrqVv`XML~H#|dSpTB{iR+#gIFY$$|~aLOmri22yAVM z0TH)es<;aLR2GcKfP@lDYFbVda1y^jTwQ&Ml}5=xH1QZHPjQwjUho~j+L6*RIF+m9 zLWR#^`GeG655FQq;$7VrlSveaye+JcfP#0SKEP0=e1vQgN)v~UvPV`BP#>(3#Q@1j zJ~ROUjl^Oixlm{tH<|!l>6N^&Ce7oIR8)8!!s99@9|QY+6yq+Rhho2KlZX*Z*;JP9D*ugxuDn!f{KyuOC;p$ z1u4)QsgGPKNs)v!n23JBrGgKEM0`L1vAgt-v{()GpCtNfQcm`PRqBs*eO^WQra6;N4+|^fI|G9GnN=DwMRb(TxsK0MifrD z(Mp4U!RyI0NX_R&M+~>-{=JeNM{ZsI6NH=>N|`%K&Ee7QWFWAuMu=!eo9Vwj60n&iz2?#or3KOMi9ih4l-&&B!mmr za%An%@vq>25O4to{hWku#7lGju@_966D}Zc?4pVtBSDFng+nrRMQu_==t1&a>q2++XUxAmrVdT~rF|in zCKerl^mrzUy1H9M@DHPCt5;GYzSMgG`UMFoPX;vNFuVBRWNLF0;p~wjsYuQ484{9v zYUqSDeDWd2;HYdn7vg_|`XuEQ`r12vGe!~s>Ia9m63*&x_AY-!$o|QBjF*}h!Y`8% znS{z0JoMFIOrQWFB0#dYrL#;hG2DuqD$6%Q;Kjmo-yPujB3^So9zMlKrFmi6#qJh9 zs+oX%rP2aPJ3GvOh4sOZ3)?0L&nGdc2LyT#W)T%B^&a2dWk=N|>iaHKw5_pggw=Az zw}CxNRI*>dEnNx#R)I(K2w$wPNq;84{mgwUT0js5x>i)v{aVLz@bH=i1Y`$V;*a!Y zH5mXv&T0GB4w(lVUb5m*^1QrxkS2m{?CK_j5sc-7_Pj#2LBr0;l7*7IYm)Z~XBTr3 zH5gO}0Cr1&n!%yp2+=K6csU>X0FSx@K-FL+L)WBHSd2o%Iye&g`wTRi4?Ru7{M?c* zBrOAF;9MTedF9*{3Vj$u?clN}tdV2lC(T9x>RizZSORq=Sysj5d5OJ1h(S-1I+_w> zULKY`1b`gPW`FvExnhEuBp}7nf@A4=ZfnpY61)b#3XFULDSn&ks0#W8k>A7ubup^R zRABMTgEaKK0M)}o#&2FZfWur8LiYDf+NZsfrnQ{DDcd{&%_lqrjg|@cs2)O1H<>P6 zL%$*yGANQfs(4w!qc)|b*Q8+-j20e~$Awi35&z&Z&j?bw(z6gV_yio@%&!9V@w>6e z2Wu$FyG&pk$}NKKW+Xd{NB`%3>A7HLcn$T2B)`=GQB9E%3sUO&PzTC%TpMIp5#oXH zg=j(Q3uP5jEcI5z6H8yhPrkud(sTnuu8P)16eQ#%NaIdB0pb^kGJzli7EEMRw!2@h zA(3Co+W8jSb7Ob>1U{c~$6;x+@lV^43?$2YF|3dTEYzEd7no5yZvi$nBpsta^| zLSqKr2V6C;*@l4h+T=T8`fOI(z=d<>sjtH#e+PXGF(XwfM^>$yf;en%>D!neUtc(- zi{}2;f56Q5xR>^B_k8>M8;kDAld0NpcgEbS(l31Lh3*8Ox!AVxa@-HjXuyu)boEa#%5YmKX3OX z&H3JT$$Tr~7mcUsBFb_Cq&ALb>3Wq}w{EMv{9(HB03wA#k@(obd?ka!D3y&x4a6tQ z?e)!E$E}iGE?Hp1lE#TLEdwJ1m{9n~jXmELdGQCXa+hD_(iR9*$go>XxsdaN(p->( zj~s2lo&FEkpK}YtZ78z(9Zx8>v*R=ryOs#GxPs+qqOIyLNJWmfOrwlK&eaBKN4x}7 z_2~U7h@5lq^I;WlYT`$Yrpmj#+N6yH&J{*k^76GD<*N;~{P?uS;v7|#rdCEeJWkQi z?w4dmNc>gZirAX$VXe5Q7KVI`T6L3Z)U~T@)nu&#T=&xJrS>|*`|$=9+P)icwK=zo z_ln9)JrDKgM^X9Y2FF$hkY$&oiho_{>qjDg&rrF@N-Z-`yIEQ%kNf)4Om0 zZw5Z6B~M>`#%}70Dlmwe8Y;=l=f^xQ1%G_f5HfxPuZyzpr8J;SV+ORt-=2Y?thQ-7 z7sQpF!7}ULu(+zw?JC_0#+PMAY0S}vcO@Rjr{Yxn%x&G-43o`;D_UyfDM%%UjM@*iZ_T=t|#!` zoTq)P)T!Xa*6J!M#QxH+2tDp;ryNxhSy<@-RdJo0+Ey{TYASZ2q&9J9C0|xlH6Yt&zW6{Jh!IoAPX!*RBXInmFYY{sU@BU=fym;+zeZu}za+cT3(Dp}C`PCY=NUV7496U| zBrq2Sm$3LYNxXQ1yZ6+96QJ#04lhcU@W!=2rmcW|LrZzgz|GP~PKrF~jXtPM3)n+4 zKWsM$3C`1)Sdx6e5I)xQGiU8~osx9JuVJOt0`_{Uly&ZXlkvtI2W`2-K23%I}<-weqiAwUdChlFp9o89=Qc3Z}$IG-; zD5O!RjUU{eDKw%KuLXTa%8ks@-mylxXeW%6%4n|FRQo$@D|%COG)ug5gU_{FC_Wcc zxhO}i?0+v+GOXkpiHTh(>e7qhI(q6Moif$G?9@VJdAci|nqhe5v+)-S>CIP{z5>VamkVj+%Iy<@t6wN72%UL`Eb{8J&LCGcBT2&+TJ?_er+WI?UEYSDjri*ogxYr2zl9O70qI-NS8HW

    z6BCs31HaG2#w^dyyVmcVk@H!(yCc27(t;lJzjgc3#S%}|$;zn!jlvGeT@Z3Q9;saS)z8nv(?qLv>#be@HOr7T(3k%{pe z)iFS?fCEPs5h31RU+ zEBCy*K0q?9$PNFyC}KfIQ2)EgS)-igFI-geOM>AN*FB>u>4o_Ku)gNfU5D*x|M?}UZN-^&_(UJ zU~gxyM1N|ay}IUs55!0CL*$t#dG%r;+XU3S)b|FP3}6s5I@zSNG4gZ5y)hr<&h>QZ zKzz-{BwN;{DcpLM{;VNl=o_fWX-ix7BK{H4zipv=J6ip*a43{xl+UPg)`B~Y_HFwq zkx$=I?4i7OBSqeasWfSBX79D+y}~9szBDg4%ebryI`3-jx^u%lSIf?Ti?EURAj- zeVwVUu5fvM4LW^nAbOq_FXKnkRO+O(jd z47CiqGJE4X^o8B7YF|)LULUzOpW~V(BHi3bMCEyo_A4aeUn^MU)Gqz4mpUaFw7Bfp zzr=j2Qn4_od6GY&^-J_!i?F><)4~tt6daGD*sMO?F3xk0(NfbnlcL#8Lur7DJc$xt z4Z?~kMH(>*iibV$4Kk>S=}F9mtz6B~m$|Fm*&Q;~P>aGo)N|G0ZB_Y63Zz~t6Xlpx zeUg(EEV-BtJNADo33bs5s%W4ify~) zu8T1zj=0thA&@v-(S3^Zbae`(tiRT%BsYsMnavS5x0#bF^eJUJL%B?IoDNIs1MIr} zL;+srjv81&Tv)7QZV)|j4rW(-X7#5y~{faQ;e1mn5> ziC{uAvtT#NqszHq0etU2&dqd~%ci7P78`le=`lxD48zOzay~A~ZNJ?C(77w|&A_mO z>Cd%GxlG$R_;wC$E0qn)OI2GKZWdqb7?L38pziMWPL3nZ!he?Hq^venjm@4^T3pZl@(lLE zAaN9YfPy;!Pzj$KJ}?N4$FsbfA;DNExf0^O3G`lr1PGX+c$T?11-^MchYQ-5ct=VG z^GO9GUCeL{W`#BLqG}4?WkFrNUGZhMErxg1)6qu)bF=VJcRVYsQqKN5?5~<2hmxxr znwzo!-r&&Z%6v3$T_h@(KB|V<6|07CvWUUJ(=kMmbOSAPfjzU8d+|?h&WwC^7CX_O zi6f2b+R(R*ioyyWF5vPExQvLd30()y(_%=WJZhrAp;TC&To20xYKDkWX#qH^lx>L1 z!rqeYs#m_bYikS1m7%CK713&7Fz0!E*qxAGs#Son_#`N-=0iAVKmfnND1G z1YT;Rpq4CPdSKmEldN-8xZ4h#H*J>@wy+Qw^ax%f0aiGSwViO6b4{+CT)OnI0iDaq z4JCmC3FC=8zi;!yIl>1Cg#^*uXkF$q)NS+OTwwEDgO6k-?`PN;Xr4pYpwQja8#h}8mmWrk{wJB!8|U2U5S^| z9I1qX*B?FFgqk;6K^-{h24eKH_S^#a^9wd~y>Q~x?Nlt(Ynf3-y2;1_DY`he)0o68 zP(T_`p8!c!mW;sOT)L_qKxW7CCmHTgm?!&JKl8>kD}eyXTxT}-gZH%z-nV<^u3mLL zgJVW!?03M3Ys+~aEbn+QNdQe1hy@dszI^6>3i~f5FP03=D>S0R8_V!FPrZ439>z6= zaiy--@4-Sv(G;iL=IO%8f>jl0(ClQHPDHVQPhvM+_idSWYg_ zmmSk5h`x&prrQZ_cq|77Xa|17-L}RSCUb8r5nkru@05OGH`98zf}!+qC>dYsw<&2e zI+0unov$f863wxD39*U4mnS}_xCIWWgmiOo-opC__)HTnW1?96{Lf%|l*7)jkBma& z@b3Fhg52=zyk0OjyCes&$E#*=_8ma>9u-A?#=tTd)Ms{GV4ngHo&cPnoSR5ti(=+j zZIzHXVUypTQB!Ai4v zaz16}33rRP$+>=1aERD!(R}_`{`DLRq1MG>wxu>hz_uI>xzzaN(v6F|lv$yhtj~^| z=I77qUV%=zz6hr=A`Ehy8acN>qZt5yzA=5Oa%Ssy#WPJMXcA0+jxjm#giSghYR75g z!6L_i54+?hK=Uc?P;kh|?eNNWqj4ettYRB>&b`e*92Os?7vUkP%}`kASU$yed{-Yg z10n!lUS`dilR*SZ!H6a_coXcxX&9Jg?Kq=+oA<(Tm3cr2iBM*VoX8+Y15;629v@a< z&<9i@(YVj4Im$Hqoe~c0S2#b6(?>&Mhsbo6xQ!|J4A1Hz-wSxT*1te zrXQavzG{ye{nm@GQ*5hzMIqhk?wA~Wi#j*@qj2K_<;4>($YnC`X8$PKezE1ZnNkvFmr|k3inSgV00QeRy7=J0LTqv zX2?=aBtTrSM|Q43G7KVGJaVHvwLxK`sdjwP~Iq%oaHkhHlxzQ!nRkPQSb9X|S`IrV)JP#Ou!RG&-)C z;TK;SN?>UKK>>z9E1P%PdtfgTI3mYtx(OC;Ud0+qbPN9hlgeg1Q-gWXnB2qgfLpyP9o>945 zD!rP#40ad-gBH)r?ydBO4Kad0wpn~^+d6;SIELt(h^~FLo9DKd%1T^j3$W}6EF1YJ zn^hF6k-DdNjGgk{Jt=O!a+KBB*9MFI946EWG%xyv&c{ry{k@QdywzJ+BT}zp6am%tT zgszFH2uK1)a0;DOa@}qgzA=|{Va!71A-gI%BR1IyYqr$B_@KYgkk0cdT@HUR-}mdg zq|T}I^W$@2g-_BU^GOBXVjs-fSF&p*I^`urEmo)o&J@p1-#A1Yg#-v$7Bp9 z({wqqs1n5$zO-9FM#rPZW}f75p;w0xE2^jsP^A$(% zEKlKz_b4+20I3BcykJb*O2+QW@LUQb2NsiyVc@YbXRK&`mW%&xI6la>>h#m0wK} zimRE{c^NQCFY3>%)b|DkbYe3r%>8>V^-wg&re^%T@dC|~2mR~f>-sRAGAu7r`?@z> zUEF_RC=(>qZ0MR4`8QdYGm|Hs3~qvseQ!OSUUqvexdz(|J&yhBtU%UH)==$a43S~2TuJk zeer;akn=qjmnhrBtl0DSPsU1wo>zs@nSKk&$(o!auGNt)!w;Rxkk7WF+wpIzE0I3~ zJ-e>Iw2JFYe3%%+QE3b7D>U6td-C*CSHjCho6RM(qTO>XSsv%!%`f{Z=`#;%7rApG5dyd~! zxv2K@>%}|CV`s+}!K1S`!v&`yyY8-rSf()VoY{5c%kR5lDEIUBz97xJtY;&;0v(R3 zFS0lf{st7z{d_?Almq(u{)Xx`Kl}Ex*V*{mNcQtaG!+O`RX`%)m?!&StgPdQaIRMwp>osm&e!QWUq7@o9jHs*AxYthI0 zv9J!QpI*7~*nDu*yueh{1uWQ=jxT>2<)`;e(x^x0*W=w&uJyCdPaK+sxgwEwdyz>* z*E`uF)3kbFb!N5;uPkl6TWGf|Fwfi7sq^2o^;cv0%g(QEMEhE1685Upk#uxa^hH~; z?*nJE;wDX7xfQBS0WlH~y*DkpF9uR8K>s?uqO=!TU9tVo3s*_0JLmAZOK!jOm!(Fb z-MnF$6z|?}f^S%U=TGU=8|9@wnVetQ!6#R<|4X)LAKXA*@7$6rAj&Bo3=V&e=}HNo zP75fq7z4{q;yX4s9$L-e0wZm1VYClk*m-u2GFbm!Gq?xRi4FJg{mT0Yv;ns_X#1T_b)%sJ}YWjx5Z6y9$n|H$Sg&I@;S z@+@fH>habh(rj2h!5cqCDMjC5^(83X$xL}$WYJdXJb~*JmUzFbI`*FrZrJ-j4VNF= zVw%5_&=95Dh->%M7i`sgIp5kU^){&R)+&7jzoEPDTpI=W)S}yB(etGe16GLRPXhDS zhrGV0Y19;Ijpt>Wxx_d>KHc@uC`j1i_~)}}hnmA%0(ipIdDo23l&E0E&RfaXCOkyG zW(^WJqosVX{e|E_ZgP3pCKIA9pp}5s+rHs+fjw%<&qv zexz4xb@j7G&_(F(<1z)FLOSzR)%b};*_{ecS*$YwoK(P1wS>X}hYbm-^F~ag6COsf zeanmFyKQ#?mc^X(v3YyBbSoX-<-oN;5910mbo@+Ge)wsqKDI>5YZ9pXqz< z71RbVBE7T6ooec)FTEH#nvo!BC2uCi{RgmMt?IIm@=}2Yp5tk^z&jwtJL~yQ&C_?jei2~0VQGeA`Z^-L!aUJB&k<`KdChJXG+s-q? zL^55z;>V16LNZeA(K7i(L%VVo9TkS?W8>JwqOtsh{F`!KmKA+)FV`3hp9{4Zc194|K9b+38TT^|Udv`{ zKH?7Vo_Eufe0();?|iC*k`{Kv&R<@XFCG#++gJP4<0EfC7^LqR$?@z4;`U^?`5e?l z8%qqxrUruo(&O44&qc{s21BjuWTr3R-qw#byJ;+N{eM0$)FsA^sn*n0Sc9`Q{|#`h zsFDp|DN%8_>8C>G$P`_7b8m@sjI_N?%hR^_-0Rmx*GeodKux&$&roZ$-XZ(6DLBWC z>AG@^mpdhF36t?e#sfmFh8P^DxR>(yMNxI!wfO#-rwOgst#UYM6Vx<2oUJ$ono7Kj`$)2}>D zKISYRXajlDs7i17FT0&U3ZH*j3G-gCC^SO_de>Tn#WsG$ZBCrtRh`E+`&3^J&m%Xx zw4SJH8d2zXzW?eSYtEq%GHZD7JD`0}@_2G?R-k2yD@e7pV7leqw>K9^@oLRtoMW8F z`CtInEFIcw9`h_ud~hQ#qU|NRGxPkHw4UF`#CYY8K%06c_R0T}G-@io@qg&L%ebcg zKW_YE#S%u35Qfy~(O`VpMo2qCN{~?!f(!&~87o>xw~iD95fBi}k&-$T6vUuZY%meg zUHd)$kN=J9#&vhMcFx&Oe9rszd_~e7)CG71VUOj}6NBK($D8L}Mv5vQ`vX}F_;bO(kH5a?m}gOuP*N>at$yp~!?XZc)?4 z;P#i~Uhdd5r2`vSFsmxA_?YF4ePUooFt9VfJr*6$l#3S*ev!+6fR)-PcYhlL(h2Gx zpa*B~yshp3vbg4({c`w;a)9FPHcZ5Az-e?5!~3 z0a2oXfb1a9O9z9Js#h#cl-4s>qCd;?NvV&WrIQ^&6n#&oSopv!a-C&9m+n?ynZj#G zFWFmLYv_oQrhA6H@Z{XTWYaw$t34p?2#8J@BWl%`{1>RRJs{cuc?3xm}1_z zI%S)SLVo@XnIJJg_OhJj*vVvJp_MN9H0trWbk#l#)2NlK(KYGnBIDLm@6-E|ac4du z8RUawggIv<(LC3>{O#R*g^GuOButTld`R{AlVlSUlhhiSIzO^+VN&u>Ng69%FRF(iQ z83&kJLkek#=e9FIbCuU*|EUc7N*NVAc*#ovZ0B^!8)2j*qg2RriXOoO&6=2uVF%X% zZRVrpV8NS&RSG$FqDS_U>66Fio8-USOsq8X*T(@{`tSqv9XE34Noe)~ySmo?6Jff4+;lrs^-pVqOH%6B#mPv#4$w5<$V88Z0QCe1sPWsz%p2gM7-1|P)@yh%h z-$|}S-A>1>juC?? z7q+N7T>${pS!GDc=`jpJSjrKtqv??U#)Dg5En~^DbbZFI{@#)gO_SoZ=g*#P28i^7 z9ZEp+5<@g-n0Q=H5(065 z`)xmp_04{)nlyO#=p#Ur1?2G+wn-ZN0eoKsG6iH3Ef;?AsRFfDYvYE;mpRW}K}*dQN@|5E83hq)^z;hg&w)1!7)LqO#d zlG;8D)lI4A^AN1LzBYxmbQ7po#=!R?Uh0xp2hvp^X(XnT+*%!ub)>7i4XCR49ek7< z$WvA(GX4{*Nv1OWqa#lf?doR0+9-z7#kQ)lHfUiRyemPYm2qnm9S20V$1x4?i-3q?D^n|^(AbJe*7ebxWgNq!NvFre|8~#y_gvkZ&);-=ES@mD|{AqTlG?VMyJ6V z8uEC4k$a0UI6oQ9+JhY4$egEw^lqoC&|6hz(syg;2BuEQRVB(NiydoRcp?Hu)D=pH zS;9_xg-v6(#c*Iw?#|q$bBd!G(OFhSAhRkb-Fg_#>8NOod#CYN+vsMoGUB=(L!WAQ zVs3UcK&G8iBWzt4TKB6GwX0NuP_~08AxZW*?eX~*iC0w1tOIYawotqVXCE+h%^Bvm z546kX1fd?F&yUB+$&=&ZCfj7Ap@D7a3=S}$_B~w%hCSsYXpXQW>}K|@4H&eNiG3ft z`WmXh0njhg3fEWG4ogm*iF*=ROP z3-vEfsfWlF+FeuR9bSV6b>~j!+QBcl%Wfr=8mn~<^%eu4 zm^%OUVC?*!jy*Q-{qakC;Ig%XWa-|NysBd!ilw`*U3WbrMtaLwu~$3Z_q{rqaiQRw z?E*x+^hdEY-xf=R#r3OJ&6#d~%uqUHXWW>*M&7sgWzVw`$EbAJ&Nb<6vF72Ol9%EVzKsr zs$#Nn{kBaedt(&?goB0rk70t;fp*q`knSmdq@u_Yp)w%v85P4BHbnzn)jw=CtOCPz zA=c@DN}$>34>Do!k$G2yN`bNU%S!1t4l+i#&F=NEZ15-2rBU~jU0w&-IiUuHvnxN!gM&JA8+AXPHgz1)>Ba1awW+UHDDS%sYfnHC=WUYzsfdD}L z(I9)i?lHyJoNuoF)|(b54icaCIarjYtL=~3jK9`Erv4z?TO8=J3F%{wA ze97BlsZz{4*|T~+9B)H0EN_zFGd2C}iP6V?Sxn!F7LE)6xVQ3GaQ=97?an93Fmo`| zfY>L);-7-@PXYNpLBDOI0lTl)ZB*GD@$_<~{^*Mg-Yo9%q5lq^I~AvI?=yJnZ~u$d zR}k0c-_?@4r=Wo5-9)L@boDbplL&lAm5Z*dn7Riv+>z70yI&csYeIi7cECOI3q#d> zE9CNs;(pQ@MFzV{<&2vltF@&+QRvtwsPWIB15tpIr;z4*Hsu|s+SK&h3Ke%FPd`}S z-Jx*%L3A?+)o=T~ACCnE$$D6~qBUjv!}Nw?4D4eJNNTJHK0ks{$N$`zNJnS%p(>Dm-7Zm8A2R;TrDE+{>J} zB5CAKN?R@X9$`E2uUMSv(X14@~@`$98y4N&E1s51o9$2%Bk{3zXgTe7sFZ8>9=P597)G zx(Z*7eY#98M$c-3h?vSBk>e%$;!^)AYY8qAGW4F%KleX{IONFP2$=b4Tx$~O3Iz~o z`4P^AI-ZR_eP5?sN{vH%ST==+-78HJ-puqBM(w|3Eav}_KO%iKccrZS)QYA{Nw#-m z&{$ae=smpO6JEuS7U8pdaoXMNDGqwUG_3P((EM^y#0=i{Upe->q_RVi@?cWSn+fS` zE*Q8i8|3|lTFplPvaiCv4jZ|kzOO_@R8S9;jPXqV^=09D$R%jX@BG0rTkF$$5=%AW zC9TxiyS|zW#ce}rvsbjtpe;FpY)YMdqNx@lPtKSOSoXDgJ#zl~cjBfvu07(z)0kZ& zpS^bf{JhYgp&-0=lZi=b?`HZXUc8k!U+{YCSJad(u~@Ia*-l@+BmPEzoW|Mj<#f4c8+dEDZOw@7i9_CGT%3=A0mpe<;a`N z$~=Q{yd~;-=$ld!o;vL|>SdriB@<8Hn6z3#J#@$+uYpRU^akEuI{7a^d`H5+liEtx z)|TTc?KIX{vO)@Rps56>?&@&ERx`a_Vp`r2?HtXmU zUq6pwzd!Wp$-;-{+rG~eT@k#SHo}edOGduUO*@X?>j%>z{{nFBb{SVWWf7{u6ScZ! zdHvAdB;jai!BO)oYc265i4OUgMo>OFNw;loImb?AQBxNB+o2+Aym#%Tox-eDxtFN& z=BjRXQzu7@Hww%(=3^W*Zkw8Gm*6H*3M-e=B?8y_0oVN7PTa^S~~F(c&%V!8jtOn0=`aLOXBt3>m;FSqVMmYq}bQ(vwh`%R5**vvuz_g<~9c=?)hMopVmEjEG3DXQVmC2LFCt9+I^m-`|d)9xCDG-(O2NtTU+p#2m*u ztgnw&CF>1Xs3e#Up&XIvs1TKCqf0 z2dA%a%Ivj_rnQ_RmSt+N!v+7h;Snk_JnsF!4UbF$VmJqD7W;g(qwfBN|KIS)^~kOg z86KkgFhclvmGd!8+2TD(Ga|#|^219+TXH#LI!sXKRHzp`-W5a2@%y(!3O3yIxW)f^ z?2GXqD@E$IjBVxGug&C^V3FZ5(er6c*Wtu=q5jjWFK(Uq_WlmGp_P9VTt{rqPQ^{% z$&}GQwEeA-uLd6`OJN%b;U!!o@UF=4@YAuAKbm^5@2f4|Zs_xjGa>5y(~IE~hbpvO z)>!3lpBV=KNEN79#@#-=_f~J>Mb|TGEY#eu(6)xlDvIvjm-Frmv%&C!KfS-cxLj5h zp1;}swHQx2K`C`Uv-n%rgFkUe(){kTaoVxf)$)^93OBvo5{Hj{my71Pat%qU$)465 z&rX>%ciGd0Wsd5eVAZB2j$-7K7lHPq-a-fYe}$p@hIH>QWe+!xJYkG9Y^vv&KZ#z+ zvwqXGa(>UxwUrA*sBT2m7CL4%U%w|~wZN^X2;yCc?g}aN@tv2-bs_av7YC&_V>x=K zbl;R6i4R>MxfC?Nsc?Exq*_VS*4pW(V;Q-So0y%Ywg1n?I#XtUV|Ua=*79gjO{TWe zW69jc9#&4aqh9mA+^sP?j5p~NMV{&L{$2hJv{a*gF8SwR70_Y!-R0JQ{!tmFs=}oq zDR0A~r7Kt8#IDeb{xRRRKzEo7D+C9nx3rBuiwJBDr3 zV^^1??z_OBOD}{SF)E*w3pKP$`V08nx8AlHA^+k~#QSSi|H*>e-DZ`)+;cV2i!Q@2nkx$Y^ zgI(K62HzsDpqK1>g+=e*O1{^=?I15MS)?fG;BWbD+B_o_+^_N0;QONh+17^sof`2L zhra&{Pa@qrAN2mIol5$KyyBx`ii92Z?2l*H&;C_^=vWg=c^3CHzG~sue~n&2n7=}* z9maaWaMR1XOy#>n(vhEb5(gzeZ~7ked67T=@n85LM#;9#X8*UIqRsGv1fx^?|D`H_ zv%e(d{akB(I1|5^x%>OzyQ@#nc@50&TzzU+lk&?((sSVGpLOGM#b>D*$G~S448AtX6l|h^2Fj(iEis{rMN!wTL{WqU|5hvF@R_FD~zYbo<%Q*In0E!}s0U`mW=U zF!MUFsDgOVGFT|I?F)G_-hJ6qY@PnsG;_=)^3JCEdb;7X@5~!HIVgFZ(N*K8aI>AQ z<&Rm16O_I@6yWJH51eqev{UO zaZdJ}jD)tb9vY}`}|4! z^cn2gFbA`q^Cx8vJ|RAtD>S^>k;1Iic>6i}meHsuuC_Lef|CKi-SDIZZ<6Id&dKgo zO$v>y!eZ~P-|vG&p1u%K9o{}L>LzjiqyRDXxdOOvf9z*u(WHyIyUnh!0~d!csQ-thPsCWq(}cpLSGc$0>GZS7Uok*jXX%#!ak@GcVo-J|1vPEt)D?$lGC zkmC4H+0{x13Tfn(^YiXzjC5R`L6mk4nY%L-3lg4vySNzSR58;ml(#-q zQ?NIYYR9ABLQ4!)|2FrO=kqyfMKux$i&4e=b_iW`K9$myUi@dWpHn0%r_UU=4N}Lr z6_IM)x5$bv&N8#S_5iGd_X7?_?s%uU`q1V+Q*c;r}Xp$@IcA(p6PsOCTvd57L3pHf>Lx5ID;*b%p>5vCU5VKrs1lWAs0ZiKzvW#J|p zKgT_A^*#Qot!@jEPZ%?%nCl&csYE1k*`}-C8pYuwwpAOs!I~P_ZjrnS2z{!$)UETp zd_W1B5B^qL5xWp#~aQ(Xf``f7u8(`>syY6$#n*SMpgxQ+oyBDBGwcG&gMq zD953*b^mo_Xb6obFvG0}Ej5MM$e=TW7y^&&n#&rpCczZ>0g65#> zI89;4Eul}-L0uQkpKTAo?}?v=fAr@RLT!%)7TGY~-J{^Bz&wk3ae~eJ2eslG45sCJGZwkwnVzG z;!BG70sUo}$2?BLA6}%Vj32IQEtT|WH&X9usI=xw_*V2+HvaqVcM8AB6(;#eAIyqk zrepGKp-EmEfhj*b=b-VE@4=>5qYG)n2CTMBFQ+;sEk_4K-t&pe(VVPn4k>p@Z*kT@z_4SGCp9X@D@8Q~of#n`in zUT87K?ha^EqK_Q_QY$!3%s)h-h_^qL2GFF%+T}$h>F%A-BV0%s6;aJab*)PpzeNpl zMVW78<2q6l2VS5c#O7c@^1-_gV~!BuI~xv_i}K9tsAnT+Ar~#0KyT;Ah;J}EiO4!` zn#D9kCj}gWlc(bl)l`&auS_FGDTElWZvp^y0Cud~xmadMiUO}2D0;7E@-UR~6FwpE zt)-@o2?3}k0%}BXdVXE zM+X;?t&6Za8glU|4OxTqiafD)Uncti@_@hBX&(ADPAZKW7*r!;(hE@M?UFN>gJ6)NJ=A~KzFW`Te_y9ia8^@EV0QR|X16u(0NSc49-P*iA)feDE)ArEndUkoyV zlYcS6`G+u<{atRz@S>>CFz8$KBZW9b6JCl-NZ^;r&e97;{XilVKplqz_d|>1jxXRa z?{Fe%0WOOH1_R*0>C;O*%x8kcJT>8<30h>57};R3b+S~uM zx^WSJz%YR(hC=?~mUizKR+z7}0*EL2xo@U_hv6k%sYpPDem``?(aQ~w$$pKzM?`Y@ zz9TsLE2@Mj-rfQbzad~REh3JsOS;iOnl81XAhplBWYD_gQ6lsx&PO&S%sd;OPr&3; z;Dq0jdDQ69%W|Sv`ZOiWC*$Br1*r*MOi7b0UKjHigN)-sC^(OO?T{c2ya9t^|CSU5 zq}BQ)(9P&-3dl>(BR5>_AVmb>#CC9zcX4O|Jv#^{1;7AOb^*X5_QOefo`CLtDtDdA zLp;O4x1=Kh;%!u~?sfkWA=jJp7I_+n(1{9sNs+LH!95p|qZs5pib#CXL5U*K0-zfX z^LZ4C9u`j#h^MWKU*uw*YGJBz2%m-%9@Cd6xabAJ=?9CbE^dibx`e9 zm+ID7q%5ZWeu7?KzX%p>v6MGq0;cgmqA_~_R>WQhQFgo5xJg_Tjof%yO-9U$Hh&Ri6);K8rb z5La<1$^OHlJbDZLNL_pO4aDX9Tc~IM6DLr5PErHevNNL;TVpLPRcs38I zFwVV8fM?U-qwT0G1W_M4Mp1-XngHwRki~V$)%9Lrzr^=-$!)$Qw-TO9!_3{UyC*Uq zvfv(`=t~*shrHBaCv!gB(uN&vB4baMj3rY%vH6PS1F=vmxNkf+?`4YiF>SxURO ztK`k(*1C0st(|;rd6QxsL;C)mxZyaIu5hRcSln`<+n>c|$CTQnd z-M||33wpMIni4#69^3(jkIAM7_Lz@hVk!@O&?}Vcr-X|mYkA_Qxra`#!#immLsV1) z0hR)Q_iNPlp3M(%~tq2-E03?w$60Zp8>_ug!30CNdaV5Z7_Z?_C zVlc7{fC2#cbxDy3WkV6Kf8+7iM9~w6`(_H+J+voX4l1z(*YrqOV3HeXKfa51w<8>*;Oxly zYC58ycjPn%c8`l*A)*Rt@IJ!ejXpTAUrcRXQb8~-?`>oS#|`o%9p5W@6-GU ztKy=%2_bjiWcOP3AjFc)J+nYogO90$!o|tpba*>4c!-Kf;)BYDpiCaDQ>3v78b0&# zQ8l7dFY0WmjiHqQ;58@oWml5GkMRv10udvzT6!Ukm50* z>!W?O?Fh{SXDH=A3oi~rR0+9<&r%Q_i^zTvXu?MIT8jJLKot|e4Bs1P9lsN{y} z%*FJ4l!Ww42r-BnKCF-c&!>s3D%8sHsIW~@U5$+HY3dZJ?Ubj!rzmyjCH^$!*e9Ii zXJ<^X-UFD)ctZOwUr)K)m8l>S$XEb*NRjx2k^H)TF?g3`5aOvYMskxs_Y;TN z*Z8sXn@Qe&0XFTc_ijgF|7jZBb?6a(@DBAuDI&=V!}<6GzQIA%S|#++kuy|;03-2o9sQ7YK}Zxg#er0| z#oY5SUBWobja*DA4PHn`ObXzq1+bkE)W}EKD}PRkFsD~s1-%WBD{aT)P*5bMC3_wD ziFRGGLt+Jh3U1%E(@b`{1bH7R&Rj>W@FX_q5^s1C(nhWCXl2r$(Ju(Els=<{0`wYT z=(V7^s$JZJtNcesEs3Tt<723_V~3dZioF!XPe5v;A3VMOY)?M&+z&_|716kOWO@XC zi5~&#hnL|HjT8j=T-YTZvZ}o;PesZ)^HB+o(@Bi2!XX-P$nHht#5$^*izr@O0+P_8 z_`5xC2Gaim*)Q2+fcZ_t+{a;xh_mN^!#U!p*BPfmt7T{CHy=_&*NB@Z63=D}1>zpG z9q>EvZ=l@dUQk%g1k$GpW@5* zwL{La5f3rdCripfOGw|R2lqBabJ=4r*`dGwNTN%42?AK6I6Uh?B-$<7dM|P-wsnEG z6dZjaV_mYn^$VILSv(<;kL;8EBYB@El0f02MX{eH=sCjWu=9v1XQ{;)>F}%U)%U1_ zyD&@7>=4^bH+eGdaQaM4TaQ@M8}eg(qm0JX~|^5;}`jgZxST0i;=$z9Y@Hxe>j zN4!sfUI4rY*0ex2&`YAjZu{aD{md!HN4&ls*MO!sZEaEwUWoU8k$)gw|G}WpQ*+dx z3w(G94Yrs61uQo4#|SgULkX$q^Tr)ldGK>QaX%QMxjp;(V)eJZUxgTn2mDj8^dmd^ zJCtkCk3>pOPQkIU^_CX-{C|?d-;&=b5*z}ei-@{&`6uqTNgK<%q>hn8z0^P5Pz6&2PPTsSx2INKj{?ON`6~JtBAvOAij6Q%;d$&o-?$> zOmY7A{?Vla@*Tr}{s1-c|Cnx|zujpFUWfXvBLN#|<(@Q%Fy5?;wm^;-LJtp)pp~u$ zoxa=dTxJqlo_2)44PtgIDp{XGxhoYT1;d61|0SyEz70{c8|#ru?wzW%bSu`J?xTqf zL6~ah45y}MZsYC*Q^$etk|q7|&s)8;dM2N?gI*M3 z|0%$@q6kHLe92+=c-zfZUEmyOf|@QT`MH^Q^ohM z;r+O#pZ{eX!k7#&A{)06r6{EvchCxlACJTbw0b4nO$L`I{+=-OyV)9Q_IkX65hr_q z{3l`m4m+-O-xV!vc**Z5ML+BEA%)m7=QoPcCFzGNy|DAF^J)L_xlBgx))n!cz3X-; zle-m~(iE4mdfef=zb{wH-%EcZ2vb?IP=|&57p$lem;+u|}!4nOV{o(;hXC6lf8zBeT;08{_3^tB*33Vy`%Bmj=Gv z{Md%)VRvGWJ|VexGgh6^l_356@Jw}{$O*flHMt#cy>IupmI9N%*_5->H_O!f#_ivi zOVZ}>E2T%FvC-Gq9y_8-1KjeNXv$-=%sSKe{8gFmE$nLrKd4yvlS4wnko4OK_?t@+ zwaw7V*t<)P2Cjhex(jJ0E>f>AA%rA7bqTZgPcEcAu-4GX-6K*j0$iF`)k5x$ zX{$#$N@*$h6~s(n2;+L}!l3^GzUW)8azTyPR_QBh-kJH0Mt9CfT<2*Zy}qeMXU~|2 z=gEBidg-2YfrFG=;k0>m3?OmY1Mhp-rw(sW^ZL@wD>VUi5v9`(3J*uOUGA!%cN$SX zZtmr-dgi&<8#NC=R&A!nKbzVfjgqo>VRo*{4x>(s*k-N1w7Z)FH+BYvCWgD)?8qoF zed)iVaI|Yo`{ixSt{*(_lyZk6t2wM!o$(_5wW2>@9wZY;Eswacm)>pf=!zTDDyL>! za3T&DIY0_me*#$fHV-0LQaG!ACaBh0K(S-`d`W%A7}<?c!~igy(6RDMpEF^ElZh?X6aZag8d zJsb-65Y=ochT9FurklP06d9(ZIC?nMWKTFwn^nqsunW;Ck&+uGeSMQX__;u$ebnx( zQ8{jVL;=-1XKXYx`pPJ^pX0;OLWq)>Hh@TOuzZB-S3<=u#zt1u?>Fg?F|_PqZ_IBB z&DxWDLFSp|p6}QQ_;ul;thULcwp)9c*mfr|t(kTi^cFMv4U2X-bk+3Qj}a;TU!(%kxp&Ub2l`s*;ol6J7R z`PPL?+bh7st9a3->~cMaj}sAK;4D6X0TngChT8| z5sV4efP9b7^=qRIN<(ww3MDb6FTbZNuB|m3d}AVcI=4>#!U_z8OsZ@)d5_3IOPJ}F zLGZWx6>j2+g#FgNIk(nP26Nm>lJsHj-sfzu$ld{kHVVh!c8$ctO^!Kur38DfLEUACjK3q4IA4>b@2z`IO#p<-*M&TZR-m zl{~iNjT1C*;puO%+adH||fo?qZ1IS%C*$Yytb*h>z z5z<&Yu@SJF>Dp#j4_h!->1h7uksXLfY(_*Vc7Ag1)O*^)Zm1QVPNodn)>AMBSbM}?><`;hJgGTFO|-CV?c2YN7aiMmJ}J7s25#wD z^-AE8e?@U4cL`Y`A8VDSc^8@eojyz_J6U?W$hP1&p#2tb73NNxjiIpLXuEmAbgZH8 zBwk)&$Zem1dAYzOd~ycc*1bLzd`br5WWREs)H7l9dIRn6v$eQJA9k)G2;OD8(eTv}KMXZj%2GJIdsXr5CRyRh zB<+Zw@k@<72X;?@v7kXv`5sYVtP-JqQ zOFJp73r$yZ=NZp6IP$<`ek_*c+h#LGU46CoO&g0Op{s^F+=Tf&N>sC zYs&X3<0Lpq+l2S65n;RaR$$p*|hmp$cYmX%=r3T;4Pog>g^Vm zT8swZwxRJl@Kt-O?*h_oz4j&#T9Bpa6AcC`Lcf_n{jh4cS1z6cGRe!k^U64b6R0q1 zrF9_Fcu%IxZOu5>%oG7zltfl%)1JW zPl!3qK_eo_AzK;2?~xaN7yM5Ond@ee($z96bQeU~=1zuydH%zNw6&p;{A`b!#`+{^ zR2ej3juSUZxJ}4VtGtqiQ_q?~%BSZG`~BIutx%6AgV|9=W?Pk4QTVs=uu9jfhMk;6-Z}4|1IUX2+lPFl@mawIA&V3hS?m@Y#nF@ zv%IsJAF^09_J`@ng?8%09K98+oA|jkl4n2mMT%PCaTC|J#Am&(9%3PT*M`%|IPsfo zZl;DM#V-7Ld$OSZo`CJ_-xNuexv<*KB8bOPMZ6iKcpHMftro}QP}kXBnET_|K)*TY z@y&(@e=<&#N#Db1B@=2G>zo@E=B`*);5sA(zzJR~h@f9jBiedojYfcTk}3V|X|}bLAO_N|pZ1H9MBX z{$)0CJ+A$F&^>3-HV=SZ*Dt#`<)^|SY5gpl&0RLu;|%NZ-?;^;{j310JaC@v!pmh4 za?>^;;Y3IP0b;d!@wI^6Lv_!i$h`M-)k>U*9pyAHs^2{0a_hFYl~1 za4Hhe7={Ek;N*x>3x~SN_RMr^w>BX70|W5l$GPHDapE3<r;xo4=lNLFNxSF|Sq(aucG;UE~Cd8&35;AFXgRWdqRe9nh zl!}E4sW7NNpL2B7;O1{mEP?&Y6()Y#J{ITY(ZovaU-|X??=^-M4RLdba%6WN zjV_9bi~jt5CbKyyqZ4UZjv*H}2(B6!%-V|4m!BFN4`gCRP<8S7PBF93*dZ3?k$M%2 zO38Tc2GdFLx|Qq2#EKtVgfcR{3?Mm2VeVm6e7G~T9>Iy_NxWRTxXy2;{?ymnr4aA0wLi&~@?hd^36GHs0+fnV zw3$)01`WM^jy+2EW^&EG=0N@D{IY5|`-V6HF!}928P0QT&X|i`HUtZ2J1<>iy#rtK z7qKMQatt%aK$MUs_J6&UBY#*PScp=hZU~kW;SY_WzdL_D;+XT&CI~eavobV4jbsv)NpZ3CVSg$2SGGDh$w=N{d8DjsfAiX?i@4SVWvV#u(H~R(W zuTOI78Q|bWXw+K1Ytuwtde$FVNFXdDeGxjDk`pLkwzc+A3qQh?3Pl!%8r60Ro04$Fa&~N3OIFaGv)C)d_%yH-R*#t_-gP2l~f7QHgVVg%3-CkgKpP;o_0(}^Jbw5byT z^5HZmp3cd34uToL0@e&r4HFiW+5IMl71WzwlY_QS7$Yu5N~YdVi_QpIY!mrP36FEM zTA_A$hE!^f5xqQk^iX9vClm%1Qc5Ou@sUd(JrmYF8xOp`Tn+u3&i32xSVh;g4Cl03 zg!zZbCoDd5U;3|QQC6=Os+8pZMP@9t=fLMRXgC&s)2BWDaDi2Rj_Alc`?DtltfTpd zNY3XEoEU29Vp(k-#;1diUIBM9`KG@4Lk{e-akG8fK?S%nkJ-0pInp}88T*@9O6j$? z2{GCEAcea~9RM@#H{|F?$4b#~p-1`n7AkCRia`lH{CbTXF}b5h!J!OVV5ywQE>JZT zj}vfSy6M~!-776}luF{Fh&rGDzH}vLzSw|<&4D`FAkj|HCm-u7nxRo95D#22S>JWoXR-fuxu#kJi#~4^A7(X_4Z5u&mgo!0Vr<6N#^! z4jV48udkn|6d^>Zd6l>DLvHXlj5R2=33NA|8OSeV4!w-{&G83-jmePy(dYO^s0W?Z z)C-I0)3m0rvSir%snXH@(h)hFh)kbuZ6m>*S10vgR;`BTDb1ZnkKSGbxY28A0F!G} zPD6#q9T;@x*5_OS)1M28y(M~Q#<94{+R*-@fd?i3m&=%o{*^j4_$JgFAo_++RID)=n<^dU z56#`HLwIKN_>Yp?7Sn_I$+5RIXwKLPz_P^>jE?x1&c21qAG;1u$IhWI+}d9*7V`5! zPV*MT%;swvy-`;HDhjf?O-lk)vwV#+za9cb;lh?8@_#>sBAL9C=cE>}w0VTY}@!yV0%R^vVPpPaI35vqETJO+BPz7QrX0 zz}N2T*))MxDmD!LwLyw_Xpy{J#wQL7?Z@23Ov-Z#o2WYaXDBfW^u`D^Xryl>II=YBQ+;I6PliaWh_FA zQv7alzvJC7ij8ftyZ6I}Xdh!KNTIsjU^6?)|4)Q-Nffb*H1}s5n6*>t0blK#y4ANd9w)lY z$h!=Dv}rJISX2MSleaCSvDA~ddi^E$y7p4!yJrvOjT%fT49P2=(ST+qwf%IH{_*9K zt|#{=mOT3LRVQ<%zWmvWo|0M2LhOMpzgX!?Bk_F&1~Fe(oh`Kwlo&9-YE71zM*Y(d zFVucewd;6oGG;ZT+EJKv^4rL_SJp8pjYGN8ugC9s+BJ-|a?sCgL(-}uvQBDct3)q3 zmDss_J$NJS`M>yypOOc=V+4$8y#w!*Z+6=JP&F?-_S_@k)fLajj>ilagpu93q~xAS z#eM$w3fw1puC7K7&bRl?rk-pJEx06k4tYO*p(kdB5};(!ELmj{!f(&N9y{B5L%jPy zi}n#gYs}-Wu`PwGK6R$lCo0uroi^Xs9$ogn_W9c@Ro3%Kv5RBB7Oxu%Ye!i?$gDxg zY(&`LPeQ3G{vg$(ud_bCCqesup4JO=;=zPri>C$+{$Jg9&FVTmvwd;K4sB7sqsQH- zXNq#9~wJppa$xC_2`n>6Pu4dMfwe5oa?uqgtvdj1t$n zF`_J6)|fIIvo8!QSaPxpuxu}?xlgM7ClgWP z?{doM=DRoMd|OeSCKSgNgne*Z%e_8jt@3 zC6_s+2gw?6)=0@c*v)uzZrk#Cf;gS5c$z4kBT5+6yX)+mlpU6$uZ~P+6BJe43~50o zuUsYU3^ttD@83?P)%7`)ja>4PK7XJ4aOQlX?yIy z?9mbHJyG(HD4%hc`hrHznILy8v3G@w1v`&RNhB1(wHh#Nt)d?nY}aZeX9*eS9FI%; z&?!#FVN zW!}~GGT8<84^hLVBN+K?%{O>gt1F%v>el^mvktIfs#u<8@I#NIF%L~MO>#bNGegtH z2c%_d&~iH+*qJ-S3Ys=hA(LUU)tUauf^>;vER7WDe2y6wlglFm%3P-(9`0ouvXXzO5VX zqGRu};~{EcvX|f0yLcg~Qe^|yu|sltBPE zzAX?_xK*TX8ApBcDcSkyyZU0S6V=WE;Yka1tEsI=0Cv8ok%ce*4`27;)Z`jId_JU+ zN&kJFn>M-U%SmxU0|36nO9GC z$$MshT!|Y!{MO(!cVR6ao&`>z{2Al-fIa*~6{CauGO`^O`9Ki>&=>XAqIlMu)MjOz z!hG=NAL2~d&8uy@Wj3L$=o7(-eXnM@#tZOzBrs4Ga!}sjLL7Plwx2$fHuesOEnI|& z(rX~DaaJ-8l?}>Cd2UKITCa=3GWPglBY=;M?dyA6@+1C8S|yt!11La*6dpi`f2;k@ zU(vyPpg5yZaiPTf*8P10$*Ha+R4L`4@*YN}tkj`mZN)nIzO+&AwqjJI;4Lzktmw)9 zRd{wmT25tiS2{aKE4PSgnH&PuBbaAv+X3!g8A;xDxxewY*6o>sBU3hc5?N;_7h#XS zLgpgBx-*nOa?hCGJlH2D4WbrcEgoux!BNHWG1@B9&YhZMTEy(m+c`N0Qm!7m`mscj zsk1QWZtpFTft@4je7}__z7%jP-9b>gPjEZip%e>597QKDHR-@ z2Tw>?1WOg?;0V=~Ej^3wa`cmH^x zRx>?6)v2zV@h>dcUYYdhkr(p}(%a;)JSxiDq!t-&50kj$|1-V4 z22>|xFYmomnd=8qWWY#()r+T6%g+6Ndh{m9nG4xZIB4>XfB&Y+A(>tehN7TFATu9! zZ{h5cq_G_g;Y`Rmf}46Hzg@{ZN>lPg_~qZ*ThECglmmuz`0AK9dDtUm7&=nGzB6Nm zWtfZau39duxskB_fXzEZ$%-M{im{yjnGrBUcay#X$8T7n0d>Xjj+%PiF*~x0bt1=b zGt;DEg+-&9J2 zpaoz+R9MWSxcic52^M0P=>v(Rz2SrXL3yDKqlB@GYVLJ9zHj{ieEDJ~HDy7;XlTzw zFb*XF9iZdiqK>&{m?*ODMl)i`Ak*1FS${2)(K?f20U+$HNB>N|4hWwTDNmHZOpB+( zvXajX9t|HfA@5EAGn#|vO>F8deW|0KC41*N=71sT_1F7NNVp01zZ*4}ExPV?sR>6H zQ}3Z^X`#88WOo?t*&vEaZ|W5m`Hb4J+{Oq^F!CIj^%^_mWhT#B@5Iv5#D1pJ?b z^FDF@HU9sde|dD)xv{*={vY{QiGhMyMlx;ON#F3l{OkWFoK@GgJ>1W4|KEhOoV@0k z#qLMV|BG;zi{~2br|*09KZLWAdXfYA(Ekw5p~YEzO{M4m5zZaqj3c5!h{MRIS9j?k zr2KCe3bukF&c7xUm!u8Os{BVdcMWMck@JOz!=AT<)!a4R{-GRy5)`2q} z2fKe7Z`WH+-$8lyda}=UY-oTXYV_gu(u!Ca;!F19$YYnrFMBzuJQtR|pX)v$1yoH+ z{VW{bBPuXky}kZz1tKZ!vGdNKU&*&r^wLIlZ2nol*FK>TQor#InqFv zM3cKdlK$-P{sZMewW5*Y@YftlvKKXaIdwnx`7+U$ce0uD(QyCVdEb_bk%|+`WzVZm zoU_-BxvvI=|T@jC%vLZV5VosTt~dQ&;-*d!4>0xZQaht!ac?eetr1 z{njG1A@3F9I_uaAXb(+c`G{OQKb-wBQhG<=gKDCZ`8>}VS#Jf#rMR1L@8X)P9-n$U z`qAtpA8lUVqM;qw?J0Go7a}nFl^Bri9`Xl+`>e!%E}gn_mep?+4Ryl>rzCYh49vAU zOpS3yn8qmWq9!|I3xAGyx0UCA4~%dL{gJ8b8yti4T6@s)RPt)&6Rdsvryu*3yIr}N^utwC8xyhe*9*-SJtrac`>LylY zW~Fpa?mpS*_{6{A^v8MmBxEVUSN2{^0Y97*F8I1H*=pd=n(W{A%(wCzZSh6B z8-U6tQi~WgwJ!YB6fB)7Eb_xuzsPCp+qnKi{)lg?>9w z5-0y|hFYB=yNrd4po&GJ1s$tsts0>F458#kf(l!o`K(ABzl-^E2Oe*bgh0}A6r zAC&_M+#8_}rEl;jk4Tx@A4!65o2(ojnxnu!M#cUe$SO)3KX&GOzc;QaTf}Xo`r%^( zgXA6GKFn0MsuuR^A3BxHJ);%1KLWNgHvnK;`d>pGr7(z3YskP;U+{8&cd2brVQy#M zYSdxJOtvy|_HKe?WIxAss_rhbJSQOq+yE1{)^cMvwG|A(@_a*T|b6a;eji z3J+oKCdq4$!fJ-1Tg#*r$%`Qkr3;wezpkb?I`j65E27bs5sMqUk;Ixvr6%%6@l5x# z%u?H1Eep#EL4Bq4!7niGrD7H(w|E->c;!-yn@vS6^8AIN#?cBl?I>wvy6r5oB22n3qf{lM+W8ruR#33I$`FBfX#aO#+H$7 zKUc@u=4n$o?=78<%?s1NQyU=SUwEi^P1}y%DzNVxEuwz!%?&0)bM+uy*8+^+thXFq=MgRau%131%rxPh^NJ|tvP(#4t~|A*4ty8DvG zR|<1QRjQm0A%$#9t<_^Fg`NK)!sDnplL)5#^5xscZ^NJgs%M1Lnja}_5#~2C3b1qb zi; zofcENaUz~Scra4z>x!rEPXmxsfK#?>5I4RB_eXMz1Yo_{<;e-`QWWfR4{FXG`v`!( zOF)ZiGGZFift~4_Cl2*C9ZTlJ#k6q+@!S)9s#^>C*0f|7G_yn)2QE6t_<<2;8c18L zxvgw8K$gS>!M+}KwNv`}4?qlS;=~FmMM6XbV5#Y#QU-htE*5R4$jGjJ*r(7y5g%Rc zjtxmU1QJOnK{L*(+hUnygt7)ALMywz1CL^kCv8(rvTdYA2ty; zhiO&>5zYX_WrYx+N3dA#goxo>E*+k`jy(edbbBc1mtj4ll+FcVRewOcNB2(gQ6qNP zHVW$RD7p?W&c6<(($DlR)1}s+IozWUe`1*8B8QtD7LC%>$1dt2Zt)|bgK2yrlIo5H zonV`1AR6=}D+us>!l7^&^Z_L&Gl?ONsjPTlGie4HFUg?88@Z@uItG=Yg%kp$g#a)i zFS7{kUdyyE%JW>uB=R8nJpcN*oRSkK2)0shcyW{Kn3rBM zUzjV?X(nYT3beG7cmyN?Z{r~;cGw<#&?o`b#xDkE6k2p5TZCdGx>N)ZHwaP-HC8}s zWcV8UI!wY~RdHJq*o&WM;)Yt8{!gV8GlB29Qb=j3S>dr+E-GJ)!*b;>8er>bsh}Cy zoUq7wN#@Tn8GN>^eUL9^6uS5$QG4k$4~yEkflBQW1B6m-!UCsCF@=aY#tV!mLZisg z?I)okBJ`SJ=pi9gWeLil!A(+As#i-2xQNEplEoPKzjLJ^X_VMdzAHQj{B_harc95@ zd_+diucET85ezzF0b4HB>0d%g^q{hUNf|;>Hri$tBS!=U^OSxENJhvZX9!Yj(^4y| z=*M_89Uws|ONJ~+eOtwR!()C@Fd_;@Jm&w7a5i2OQ38;huz@)!`AY@BQpdNCgdDCZrS+efys3&yRH#U5jEQQWE52{6X0n$As zsvi^4*&8T7BFMLMhc6eBI-T1>Mt>$?R`KWG6Qo20^r0F6l7?kd;1}gkvskI+X{pQ? zmy?s?&kALH{lKTOwNFIc;9`H7>#G{_S5myKWy=Z3#8vpfFH9c~*+e@I@{=-XLL?H9 zuoZMW1sXF17V*J>d~o~kI9J$?8XB} zPfK$7@D3vSgHS3dL2P16y4C2P{ZZdd4idL@>W0!1guGK}>A=A(iy5)Mo!H3F3#B!k z!lPeIx9Brui;O}Qu3($3LoL>z*Lkf@(J&_i>|H*bEdB+hf{44k0~Bbi z`0FIT9Ov-5ORh)45z^wP7?{xr^1?mA(i9X>P16t?x*~}NVH4nYY|tOE7}2y;N<4OgCrPNyffUL4 zu0oPmF%>mPfe`g%8jY;wsnqu3i;!Z`T>UiUG_i9Q5cv3Ug?3SAiIMcYRjc}G85#lQ zZHyfjUV@mTDhROH+0-&&9c&eY76YGzzH6ZX5g&4n3(Ll1FW^yEr%{stDbx&1a0uQ- zM_k4u^5oh7oJS4URBb^|Ra&1k<;X0K@11N$PZLougxFUJ*f*l>9od!W+pCgZ(|FaiqDxD6|x{tl|^44~9ah`TN0}B_?QQ|f;Jrx9! z0E+O#cp*?_712yXgT!qS5hLPa5Yl2UJ4Zx@4+~G;YYe)411XS0^$8I>A?XJa=#N5r zz*MHv+?@ltIBXvJMGbmzTJnNLWO}INHt5KE;?2)ODWLh?6Wh_tth!+5!?TNn2hwkSSY}N+5Ms8_)V#Oz0_X&t}V)S06WD^B+6&;>O zz>3#34trzG#Esu442&e@Hb22vhA(BE7N5A!jYq!LLtdu&I~yYVgeddoTisM{c;;yhw-08gP zLzQD;-yDur@L<3-3DK%V&|eAFRgA?dW(yzy4r0c|tr1_G?X|X%PjBu^{ko2PI0`SH zhS%c}#$~9TtQv^<*%>nSeWJ7+5y&G39MBL&AR{>;;tMqTj z!MM{62+i}*45?QH)JY5Tk1rr~0AvpVE!@CZV?n_Hxa)7prJMetP-G{sO#dhHJ{RR| zjT+^lAU6>78dx%o`iTk@5kW76BZR}!yC?`7AFLbwaq1PMvRt$l32ByeM&4)^p26%A z-S;cKb<4&N(Y6W~@Y+scQLlyQ87v}$2e-TlPvT-j{$loVF@NY!$Mc>_u1T4;UmkqX zXlM-&dtVByMP6jVtFRm{mTm$?jS^@RtIv{0j!#cNJL|K6BcW%-PfE+BPn(#K2`u&g z+^Q;0;iq`Ds1^baJxdO5;i18%*fsuWqRF)Fftw$AC%7}%T>xm480ICTk1B%hse$sj z=oS8`wHX#*gz^1y8I*(hNh|_V#i^ClgH?DL0T#ehPwECotO6-Sre2t|7gqrF1B=p< zdic;jrfd&QjRKGi+$VWE51TZa1eSn}Ka~`>zn4{H1w2&MKJ04|5zXJkBnW|K_+d!r zlVDRU^%6E3E%gbD0Ijth*o7)vl`H`i>aJsWfS7dM-m?T)2QPSF_2>iP;Q@RM=-D&T z(=(6BmqE1)GJZEyU})vBsn_&g=>>G24=($Ye9i>Oeif9uTF>R7><2E3yUsZwf}5lp zDS)=%k%Q!iAPLFjRcIX@y-c{dM3?$NmwI(Y>fbP_c_I3%>Zdn6^gFK9p?-818BxZE zntNcax%sWV)6z+HF4Hi3M|Afpv?EjYHW#8Qm(j-OA=Vy{_af@K{g?UhF5bD$#IyLB zoStxGur+eV0Q*fHF+wuO1btrOut$t<8Dj<{P-VDuU} zCjyLMi2V8qJ0pczCZId$R$nW<)y zc0Zt@Lh$}k^aoZ=kG$G?@?-g` zN@qyjcq#Rm&BB}XXlzHYtRia2;;2w3tcr)MFpIu1;dvuJ#JXs{Ki_y{MT3jM?~K~y zYt|wao^}L#&3(W*?>s9q+56)Awz5W#-ci=Ka@zdeqxZK4ciZi*Z)IL4o0gQfl^BNK zBI~wS(72i|^eAcx)Mqs~QPi}zp6wGl|8?n}zR9lx1Dk1U_@O`lbf`K1`FZKDi|+ZT z7Pwh`3N~a{Z5B59UR8ooaHL6Bot<-0NP_g9hIF=)o?^tAjoAMxuO(UEr~DO-EBn0t zM$&6ILzRaosBzWlpR#u;`m0Pk;f z?8q%Q9$$CHB-{>mS2-f{g57?2(b?eQ;TsY$^4?p)ps6)j=(~L8>z0GubfZ(>E^os} zzRPz6Y#ik7?R^dv%_R1|A5{r({qqmwG0xxApQ-b=S<>3q(6z*Qoi;pW@u8xj*gMj5 zNyFKnblr@_)znj3AhDmILrxRO%H3cqqqr zG%Rbxp389WNSGfUbu_sPIe(Y=iD5uuPG>aByM)c?Rwj&^VCz8thPG72<0Ohr+UsiW z7b7o|IF@Z)p34gR`5b3Yj#-WtGX8e(y@8XN#rM>Y#cbS@u`7T@a++*H>hwB0QnYe{ zYi3t2rq{u5E~QKDj+1X42P}rWzA=`q{V{PYy4>@&#{_}HWXtB6&`#Co8uBTiJPWA# zhr*p((=MW5?^6(VMS4x8yMnjTMpR`~rs1+i3~^}vvYVdiA%DXyPuINkDY}Q$F0)&U z8p~P|OApLNRGiY@Fmv6xu;hg(tXtQgT{sWDjpjY0(jNrH7F<_Ut%G>c*=5p}0c)wO zzHHyl3{er(toQABQ|kGM^O(C`v)M2?H_G#9rC)FJ|J6ttd-3n(^$$GHH|cf60ojn0 z%AXoj)z7e+3G59>*|v4l-22+M>B}lLGF^V^XPyS@J#)Xkz5vtz`gcZ;HJS6aX=yT3 z{y6QkbKF(OE6-ytR9y>uXjAT&8)ooUEWmqT!fEDsZc;HNc)Z^0)n@AyDn?Y{Y8bYF zpy0uxkh#@~ZF)s^g!TpGp>>d^mNeWqC{nt3{T^f@`2vPOLdV+;E2gw?9k4*n4lcyN zf}KZ;t5=!lj@odkh!5g*+ygXLwYvn$H)Tknd_7b31D9*6cfBQcf{t7T9!-ai=IC$h}GQh{DRuSY(I!AsTkQ-?Wg{*AEkBo0cX3S4CWXv zCSvXZ>}#MEmlF8E{1Y6 zBXw!i^M?r_T+jMF4ZAhe{&p>;0RY%2uL$YA{(v6ki3*knv2EK)Qr&4#D_3Px>y9SovLVa+3M6GrgF4KI@&S=J9v5Qj?U(H#i1eN% zLXAv1LxXm>D75jJ#?^y)A!9(<%N1@K>L7!&AtUk8V=Xy^&iQx%DivN-?s@NEUO3H0 zzMfeb5^mI2X||#PPtLM6naNHEYb$TheU?V9ETDRPHSrB{F-f52{Y){|eu!l2y*XcG zNUX&?_Q*0EZpNy#epTrf3UoeTSq0)f*_c66F^LYdq8@uaAA`kE%H$%8gi`=zDLP)I0yDu;PV&6WmX7M@uco ze>zg}5r3OA`&(g6d9+hk+IVm|Su#&|nC~+JwWhBj1Gqt&wi&M0aar7UXJ%xx0BU4Z z%Q4xkY4PbV%;z6<3X)fE#;1z0EmgFbokDWv92V z${6RlI{Vjf(PI=4)=#|An$NP|Jcv3P*X{gMn7x-D`LKL0pyx`)qu51f+|DNPI09AG zez;EhM#ylfWoGzLf{rgU8l*Y^;6#1WN>!G=7To{#>%r(jr8_TwsyX=t?A+2;TdQDe zdXuodrSNo^VU|7Cvplu59_K}0WEKEmKnu_*Zy%UV(^_sssq>ZU`Ah?zd15ztLVaZ& zqF<0%raPgd>H3Hh*hFcx*tGnJh!0T!Gy2WOYLO&52(QjTOEhf{%Qm{F_pC_Mc3(G2%_j#czb<6~@ZLRrX2ccPcXs_BK}%(oa0RGqHZp0tNN(rZ40wd0wAc zDlIZAjZ_*GDzmU^8+>+bufgC2_Igmy1JHTM^V@7dPdZu5?Xo#nAdxL?uJ+rRjDdPw&^lPT^%mZqGeQlT0)yQm@UfgaK8? zB(RTR#+rA-Xi%rV9sIc}XQjdj4%B-Nc$NY7oogdhV*31HM}+M7ImqIAmV6l7Vhy#q zFl0?FHGj@dg0V#rbL`n*wfAtvco_TMeMN6N7_gC*5V`X;kKx2sF<;%uscS>An2lU2|*>5Z^l<- zDi2#h1;svIuuY+MDsLop8j_T(z@*?V@8(G1jIMqBFY{8=5kpas=5OV4^V`GM!R`1# z!*yU_3kji(40LD=RL&9xfbEGg2E2@PVutoKoV70NIDLyydZ#@%(`1}=WSYI%m6NQP zb(AO>ybkj6*clKc8#C=pQ<6Qh4lUCxI0dedzRi=byOtgYX07{uD5XVDMYhQEgmcf1sF0R)kqy^&Z0WI6jrfNb1=^c(^jYAg-H~WAtW2{(l z4Mw-xsDK_BV_C#GZZEP63N+r?)p{_4b-a~*={@vv2*2m_HJ07^#5t{lvoM32YY}#s zZVE||1dQnBm+W};h>6uO>&bGPC|IN-h+4KXB%tyHgq!p%94x7e@#(Eg(TBI9n=$=%lvTIUnaJ0{ne z+O>7X$=Jl{M)q2V1?XLSzNf1fc4eJK;~QNqHcX@J*%fUqwYTy}jmyV4upcpCcb-#Q zP){;3tE0O<$-sL-QSu}%?=Y>SM3Xbjgqm*d%3r@{T{)4q0gcD=(iU}@27X7US(NGR z#7j`38|Pt4eH8r`vjQ9}Wafq5@SPqDCrdFaK--9%&x{fyAI|d&vcxo5ub{n$70bhB z8P}7ckwFl#ZXIa=vGu(Dm+_bu4-V!+M5UhE-R78Nwf(&w;=2N{^JItXMNiki|!zg_b>v;DhU!L!Qu}xW=JL7kj(eXD2}f0C?HMoVl)lFwN8UlNuP%P;)Yz=3qG=&rV&Bc^OdmsrVD}E7XaA9iNO?7!+J(&ts!TWuR%SwTj;3-2K92mvfNvqD^{7rla)FhIY(hqedOUw zt=>%XR7gvRh!Zb4)a@4P&H3gwJ7AHO#CK>T4~wfIsca}Qyf9&P*AI)nKH*55uGEnh zNT|xQfjiqp!R(j4=$tA@8~|#4lI=xf_EMnU70i=e^$vLJ<5$JeCDboSyf>t4vPWJP z3f*rI_#=~X*q^!6ufT5w?2Cm21VKW^lqa8fI=yDpNM9)WvGB|@3#8VFR^W5^Qw zv+-Tr3iPH7iWtrAw6_-TL`+ zpYDt9WqS6q5`);YceIl&nV<0N1uisybgpzf_>C2$K*sI71**^FHlioGxZ>GjE+k}* z6;;7i+>zVP=p)OhlX-cvw1-=ed5U43O*yqi4_Pg^}4(4;-oCuidvK#sR=t8u*>@}ia{e+U4 z02%^#HogPncD(u@UFc|K6SV?59%nI{&a* zk002aXSEf?7*IgHD<6{FIn8&Je$vzvYFw%ct*6<9b_pZjd=`35Zg(0zp&vG#Aj zdf}U3wl%EtbvdZQE2U_i%?+BlJyeS(y#u2Tgb=`@Fmp(#6#EgWBu7AN#^?Pu;jY(@5hu;%hfDZKoNID|IK4Yuk5Arp7hU z6u~xV@t=_V!0lptDYkK3B#T(>0DJOUHkGqdoKCN1K~|5{+NY6Y3maMMJqOcj+0xa}J3%)O6H?`#aZGPsHg9G7@_cQ2rPdz=#B=Qp zEU)5JSdQ|o-z%QUo@hOL1?0WL+~e^rtit{sZ@XeHG?r}W#&aURv3bTWxyv`RYouY1 ze&3*F{U#_J;TS;JP&D;;7a{8?uitkUr}7oZYgWxqW3T9nd|}u+WADE)2GgLU!9Cmb z3chV#41NgJij942AsOy;{JuDze`!?~*URfG#7X)lav3? zYvKC(rPd!5KEVqxdUnsXNXOi79Cj(?`FG;+1oCl?LE6UL=H2m3M=r=-2o9WHQhAN~ zba>GnrnZ{Kp4&UVY1q=1$;PdDrkY8UQfgmv6R4fW#B zf3+IY6U~x8t*mK}6(m00Y&+&Rbs<0X_U6m4n2Ec#>JQpAmA?L$f7vFt#|P+7*EnZ= zP@R?-S2jo`lwEN1R<@}VO@yoN_n9fHBG=fxABx{+7Efw3N4g&>ENQoEcCEbrIpS8b z+CA30m8&W@Z@#=9-RFT0;RRO^D!mkB)OLvk{z(OogMYofdGxX1!1cJ37e)%6YAmy~~2(hqL3 zI7d2L5<8J@-6%3XChePgS>fvAS-X_m$GC=$3I8f>?f89B?dgg{RLiVU#H01P@*BH8 zPhRyKw|Z3;9Bcgm;Nqngf3?g_syt2B*FHb>`<$()UF=z(PO{3kygT8aZJ6_yA;r;@ zaeERewR6rd>NVv?CAoG6IN?-z7?f{y)UEMx==)Rw+V)lAw@I7)&BrYD@;r+NPJHaQ z3Cnq=%f7(-p9VdxX9xicPUSk$IJ9eRlA~-;!r; z&nW?uRuge?*~Zx!y^7hoP`8CTXKFXvrfJi{$Ewk<9^I_I#xjUkcy&^prSQsn$|h%X z5WcHE@GAx{DlN|2HZ{-5HxX3;CoL<3ABAXJ^u$+tyeU7acT$*r`b#8sv-O@%`3}n| z+d^qMDa+s}Ik$5eH*xE8Dt){6D)j z*C9*$xrZHmBJL*R5_i3%F?T!mi%^;SLFFc2-R9H2O(wjd zX@9qw@gB<7O&?o(lq%|V_OhrR_z-WJQ+jH~q{V}AU*k~u`yZqK6sg!e&lO)tgMH7K zd+7Fz=_>dwrO0~Yel6qN)Sk!$eDkT+6Jyp#iA9fb0b!jFGEosa|Ar49dHl?2)}uRb z8;06$?%R6qrFoRBZ@teohov8r7H6lOC!FqnlJPc-rmsPd(}~GZgooEJbWf?TRs4A? z^V{Qs&72)PA-F5W|Gvg4%CCoCqtDFT-zETK>}}85e=FQJ)4zluOb$pKKP5bWXKqfl z%xULuaM&VWI+6I*lOUDQanj>uZ-pmbTDDr6|Ds`*+44(yL z-^ysU@~B;ZAjitDD9qxx-__s-&@oLz$-gNA`$Bk|^EYWF7VU)eVWzeMiQ`5{SU`B7 zA~C#@VU^y4YRjKV()BGPPUV5@ifuKx(5{pDp4f)awgyRSOGroXJ6D;QT1IFQax+kf}5Id)RGCL4B?Es6q1VnA%5<84xVgvPm1( z(38k>lo(N6;fHn)%HuqAKk$a_&bjIxqN$6Q&PZyW zjg-GmQ#SI}%*mzI$>hv2)cc=QAAmD!oTSD zkPJoQA$e<~dIRH{Hl+uq8H2 zJ-FCxYY&txrq|k2_vP{7B8v|7MM47L+f*nqEDygxP2Y+o$`>X8`#*Tdm**s z)EC*yBq}K6TkzBGRie*YR+M3NleJvww@j5sK^J6&*PZlJfTv@=a{wfN^g-}Jx$v=Z z;5Gy#Ka;C1(~g|Zd}3VGWTC+0xtf`E`6vBwOO8T~n#C<30z8sr7;*bF7Rg4E(rA_9 z)1wxgwcHT?5U#2MjCapet{ekPd40R;xz%a4VB@3Ty>MUcIRLtUht;;1ic?lCMQHgX zrq`)C#o)Exr!;BEt%O%!B7d)AAhUEdgXd}*I3`_|@Kfu4(6EgBE%^YQY`2WRFq_{N z;RmsdI?-H|2kIa2XmV-Kg*qP28-8q$FVa5*4e zoNbm;qGPplx#*wl_uM?D{y11rMb2nIgZ7R!n_FBYUyARN5Nb#eNeUmx*};^9-O2EK zHYR?{7hM-%$sI)Gf`ecx|{>0 z2v$W96SJ>b2Dm}6s0JYJVip{Tu~{#1yX|c=_YvMdy_w9H8rTkeSJ;rIpS$y!yA8Tn z`CfzG(+!|vjb%>BX5bTx13i^^v$b?ZJUF1Y(>UQ$$zkueFfs+{JN7CocvefP1bjcG zqzDzTiEqvRF;-d2L-tNTq(1ryZ8mWYJ~$gGNBujjqKX9o0mOcMEz$pCchT7_{i|A? z_a7bXH*Y#^SZMv4lNj}lef1xvu&KH?c<|h!#P?26Xbak;sq;~C+B+jRnloZ7H%H-YJ-qL7+YlX@b z*9BX(+H4RM?4(-hEG?d33a=>o7pPiuXgDlq8}4--vLE>K8lZmE=H>EmE0+b}REjMS z@tCkHTAqKeX5zrE&k;Wc-lVI)9(CQie%ER1p(VY$@hXZ=fLJQd*r93)!NWKd>CAh% zfw5O^f=jZL@@?d2uO;%{NDmMFW!#|)I;j!zSeO2}uxk7q!d@Nl17fr3tSd&A1$1E4 zfh|(l=A9bU6drwC@Z5wh+n=FTnrW`+zsnkWfIqa44+pWqIGVE=0Q80>ay^&t4v8GX zMGeXam4+xzbwWUe!uct>#tO0EyyxWN50YeWNazz`(euknO|{DEl^|D=qT_?^AKrGK zGC&nXw6`WS6FlHe(jW7lG|}v-^}_}`3!`hG>KA3fE-W(EV-a?iS8~Y&WMq&D0?;K; z#F?uL$7^f#j@Rked9{TLfC8ct3aD=~>~y{Iq8met3E0(7l*Vc95+W5FCM*)!@2nS` z=FeXXbcMN^2bdu`dvPWi=*`Sao4(r1GPXFf;T*BJwXp5%+nq^u)-m-qr{ECq zAf8X{XM)T(2W5JvWb7m`s{rXKt$}_Cqs3QXt?_SSFd<6Ba6>UVmTGrJjdZG!(Eapn zbJ?eUL_(GzVry4Bkna@r)@J;G%T68F>Rez2Q7tdie2itgn5kkb&XJ0sdj9M>PzpV>9du5K z(er80t?HQ$R^Y@OF+09{_t(j0R~HNLFrFwPDF~t>sk6v-K61Lzj2U5;;mZP#na~H9 z%p0i1XzEnc;e>+*$zX7zs#TD#(dMubZg=7H`_W(CHUsv#>cH{z%&ed3@Z;8YdcTY?8tPWi*-sK z{ON82z!}F}Tq8+fQUr(!{x;M-hf4OlA8uBQKztk^jh%mUHiqH8Vgm(0HtA37T9@=<=2!WaK?=#1NtrrIjt3J41+!|g|0?w`jA#)V7e5e(6pN5@;y1Fp_ z1z*OMB(Ec@IF?}!$iBo|w%OrgI!(16HEi5>rLk_b>MP6Udpu!wP+G7kJ*JD;q~XO)vQ4`xMvR3$(J!1V}EjC6Je+!%P^VsY}D>n(B3qVvQL{i zU>EAsvYX(_*lUw1XB|L4$*yYr*N0l$2()mSDyS2aM#oJ>>6b_N6qU-dvICo{{rr=zPw3$mpP$%v*T4C^`!7s=&$jq zjDU57y0_v=aYj1QQq6yF=ew&Jxv0|3wD*PDN|w-$3HuL48X(dMU*$y(f3iM6JKtg? zC5}O^YWdRo>kapD_c4Y1x5^6`^%~5_Ciw4NMg0A2<6m%A^6={i(a<8bI}Vdik#5L_ zBaSiez6b*xL`Ur$Hy=C@b=BBBtX}2{K0798jMb0*T3?S)55AoKZu9lqU5wLq zE{b%vGz$vNH#xGRMRF?Dd*`%2iZqQ=UXCLdx$B+8Vq8r8p2W0EY+wp@@2fm`ShPxb zOU?4hcoE|fVyKtt)RhcYt{!$T{Y2_<#<_|?s~%?afKmBK zkIi3VyjXN>h#~mF_$A*(J+wpP+9PQR-4}W#l!(!N}>W@_fSA@J$fw zwvO;ko9`b;#lAS#+tBB`$b&YlIX8tpy81de63m-B3L4hc5zqBYw8u|*RuEik;9d#k zJ)Y$=t->ZrKlh^!v+uCrre~~MTk39$#cI10Sh6O!j)zL?Z@<2Z!`&;##*Li1?xw)Y z>BCk52bI4+l|8K49??}+b=|q{FQAFIZ~v*PTgdQ18`py+lRP5f-VRwom~m{!DVOb{ zg^=0(*A&1#I~MtjddX<>A2^OBnC2GZRCfGz*_z3sj5y=2eGZvCTf=z&_v7?ST9Wq$ zt=VEgAl>2jK>Jl;-$~b6n9q*S#3l{b+oAWLIBdMXh4vxO15?+9^CP5u+gHHOC_9pP z6H5<~e{N#a{mKEGk*^-4X4BOf!w&IIwQ~=OPQ`7z4~j`iepu9~sQ2UNys&WjN6&up z`*W_&>TCZOSN|E+#Qp|+zahPn2{jZk^dd-T3N{ith!_MVAZ|jFszd}gRzez~8mgcu zp(%oU_t8!b#9Pf z$@sp1^jqofs=a?+aR>=dGb_Gn=T-KlV@6qYew)lRVO6SjH|1!dv4be^qCGG%^Ur~h z^O^c|zG}`3dYijj<#~nB{T<`uO!+N#JA>jrb4IHCoC?>Qk#Du+qseE*9zw?j5o5zJ zq|T?mAmdZ6^#%-H`+l2Z`+{|7%&^9vul-$>xV#mm!&)u04P#PxOl;ejI>x9sD`u9j zJ4+`#{{nMEBxUYP#=e8N6g9Wo8D(r3(t!;PiuAu2hRS{YE_)7o4cK`UAF6lfm#!D< zpFLELe@&ylt+fHq=xhB=zmu~ahrY$z1&A7+1t08H|17oG7&b}j@fk5blN)s@@u}~( zFYC?!zCpEqjD>EEyAOc zE>J;wm5lk3?Y>TV$SdB|*b}CGxB4`zzf3c{h6$8FD;jcSJ{9zarwo*Rzn@isH*eM8 z$Ce+oygtVZYd^kSvVUnLpLm1%kL06~%o*RBRhDbM3}svwof@mubYuWJk6J>juH16U zdZb_Hb&C=*^>Ogx-Tj7i|AQBI{!M4C))cV}-(O{UW(94ypXc}|7S^}U{>t&wmh{W) z;1?69wsZTq``cbWuoMN?uC7XozqUrEqP+EpVtwh;a@#}0q0$|-D}H@S4my9yBE}Gl z8&PdO@@lG2Rr}(L5AWU2#Om?*=*^6ym+dp_8fN_9aklTP(q5JNe?r=KN^N53>(a>D z%@bXUSW%2rgKs&1{(KOm*VRn##ou3Nvu94LWn%0-yHzJ|r#yQU^G`e9bZ|Eg<;C{8 z(zG?LR{heJTyUuB;#B4wI74(_A$-+znqJ_1f$abG>oJI6`pja#!R5QH!_)xsm3VZ| zo}mre#XO^MdLQhdIeAhl%pB|<&`VV8Vf!11^*0|~f9#}sCj?1Y%cWG41(s3ZdJ>6| zmT(bOP}D_vTxfB}(EmT;O40MjF}}*|h{jYmj|JkcWti?bdCSV5H9XB6_?v>@ z|NX-@T+#F3u0=cCiU{DN&Cu3BaegMbmpmfrH-PVwq+W`|ed^IZS@z?fw?-E|Q8`fZ z+{G6(VvN@4qNfe^3!Xb4r55};?MMJ~ZZ%D1Kh1iGSPPCSE8TCS7SxhH8&|r;z1uTr zhPHX{5A5C$t)oN>Z9j(R8h;3*rQS*&@=}BE_nfB0irS84S%>nL-E_OjgR80FyCFPW zGZ*mDsr~cmN8fc^ASdLUPs_#l4<}y0e6Mw?-_MC)c510Az571>A%-h^HPRP*bPueV zDEzt8g@5#$_Ub&DAV&36h7xP!2HYa~FZ0xIC|YSp==q>CN4{PGB94IxK{LAe6+fLv zT*oRsE+58Cyemz~{`(dejp!_yzTU_n!fI0%He}9?Qc{6%yjYmKHo0cl zQ0cZMWTR(p`=R$9A*0<_7>+X2kMWg*bU)&oLX zyj?=bC{z;`iF5#SQ)BN)PSC0MdVf`NLZjVoAEK^#gHn%dx7`{Oq>kZ+2>~^WRZ4M96rf}69x!Qu*FQ?6)bG_dyZJ--$kvLkuRJb7^75R8uPaY zD`Z?A`=Is-pnXQ5l%i@G31nuH9-Z(|L43-#6_6k>3IKuZ;J2qLWyt@vW*qKzG->e; z5WzsTEE1bQOlFbz&KZAJiXT$&ehPtzZ0yue zDzYN`?Xm8t1SRzd7!<506OIn#nJyp>v#`*}BSLBsSa_yvM;$lIsUWUksc6Z|RpnqBSc)*rty5r5Gm>&?aci&Pcbx~iyhPu8q9HE8@kT7HnSeZh z3{-qrE;-1^l!e{udLhWo3d$}qBpZSgQu6lvfniJkIwN$78Ny&n>%)*_`N)*}H`%+b8jcP_W2DwCC6IkY8ck0d$B4{v{ z0Jy_!?!g}!eKV=sDgizPNPr*{0OT*v=vV-mAV#7VkoYBH5k)*g;|axBB|`$wDk;^% zU*=?G#*?xdNfU|!83Wf$E17LX&r?WKZ#5p$2uwE>+Zk492_lmU#ueCmQq>O<)z3Qh zA2>uLiHHbH_&u*#%i0IeB8(=ur$<(!LXa&S%pn$jh=vEZCa=2&2pI{}VnW&*-BAfaX-0u@%s& zq^bgjIdo@@EEixz2ZrRRxJp*JHlWTe5hoS3AKwwy{0mo=Ms)1R19QDE6rz$!ghkdv z7fy#6q8b+t(dgCcSxtnG_tI_(5FLgCIbst_bGPl8Gth%LgDt$B;RF_Qjo(V zzEBvz7C_hG!T<5Kq899ee#kUAC-kSB)I-F3HEWs-=rIvW1x5-%Hc0W|>+k~#+-=a2 zVpJmSu&ENgLnCzFN<2X9miWD*cBpT3l(AZAhWKZjtzwlnH5uudD_ zBE3BICa#W#mn*U#nE@?t@%$6`*z>@T+$*q}E5yLsNg95^3)d)>;z_E#z-eEV{PLNW zC(X$9oj~C*K0>Cpo&;Z4qt23|mVRK?Wgqios^;sE7RZp#B4AcWotY40U!rgKOWl4m z$?*p1@(xsq8S1*U0hC93;_)&Fx?0-k5W)#n;CcbvEeJM>1H&4^ALU+(V)I<(y<*Nv*h|8A=Ge0BoB)8vPUB zOT}$oM|z_mQo(B^9upvjS?|-^DNZSoVt*e3Udaf35H_bKLifG{8-k{uz>i7^vr@oh zinP$tZO|<|D?_fg^O8CPuMuj^hXKboiDq`5N2RDh7raRmx|@+yLA?pz$7QpyC*-_* z8Nx=|1)W7HLAFpqyrdxZQ1Ek{KBX9w&)7HSBCMj~dYrMB8F}qu+`usYIs|9Du67=U zU)WLk7)d&m)TpI%8(UO3MkVAg;fH`u^{f{BPQr)_?hwPn`ZX(*ihi;aCl{;YX9>Mh zg!RITOyz=ApqTW4i5meI%g~Egh5``A5LQ7v_n~`5WZVtOu}HX?c^9c}G&5_UhY}bQ z3#z12FiyV#EjrpK#vdIh81e z74pO75;RAS8Ia;GGq9^4W7J)e`ao;*R2Cv{;B#JKau+a8Js%NBxDL`G`^XF_64cfj z0NexF8P#Uos_qV@V#S0VB2a;8lj1Ut0IG^YB}B!H3OF+2ZK;4Q%flvG*WO6?X!anT z162hr#t$UVHx=-jh+OuVQ=o}u6+1L>X0WFz z*hVU@MS^RD;1zzry&1ghH;`~~03Qf`eF*L4g@G3c`M!4;h8Lzeoc5V9xC&w?BfVUT zo18fVG~?DqTI4JfpV>d^Wbh|ujzU$~fNb2Bf@_i?UF9hF5`yt%#iOsA*T2#Ze+f4e z4>_?L-&M%ei}dS&vCjkQ9|DmXgTT3PAc<0?9f_XwKT;({q$~2n*9w;&p#nDmWioUN zgD^(HR#E_C7T~)Fu>)iz6%)!C;xZeUQBqX%0dX`Fo2kWVp_H`&c>H2%)TL8>z_re| z_8Zf}t`MFP1ubv_^dGsy4X^yps{yDLRk> zz-87gMG5QO zdEzsEKYHL0J`qUbv}4Ba6CuG_36-^+! zRUTh@HfaMq-35TiqQVl;JcQ|#;>$S?Izcp8_OR6)H@Q4|R)Q{JVAq|)byM*p0AY+a z1s#7Rr*-_?Q-o8h+TKqFi9sI0XT);(c&C99oNsdo5Q*s1Q|~31=1m6yWuI zLr_c`sOph4}kc9fqmd_x7o~SmjcG->@j&lIxD$q z?mkCt*15I|`0EV}T|*t^^ePpo0%?hdmfBGo?&%p^fdpNpsMJ1%ZH<3P~m3f!v=ds<|%8WwjmIhYpl{@V(C zz77udsg*wY=-&fCcHum>i10Uza9>&oB7@qIcQypVPp8A1{t}(o@Jt5yZ9VpcQ~yax z{R*}Fun3Lm0F#4Cp4#{sjB2nUbyv{OlUV0mv)xuvUzL_ByMF2WostQ0gBD)~~ zV(haYo(w@2eh0kSd=y;>9sfvO1tiI`;?5j9{=0;fMj$e}9Q9XFiLR#D8u*TNV@1;}b9vX8j`Z-bazbx8!IT(4fGq zZ$uYxu%KeN!yh*!jq3*Yg;2qb2)LP3SEs!2eeaKQkG)uN8W;^Niq`HFuO@9(s<+B8 zxpGv1)LSWqiy_CK0}1h8}eDki`%m|wBF&3wm!^i|(mfHKGPklDExG%kW*;8DSd?6!b? zSkC=1DzS}F9^2Knm`A2Z!wUZ7em}Rll5e7I7XEeXSbbK(-#-V9-@d31to69`DoMlRxy&Y3rJAPp14&kiZm5y-mXnWV4^+3+c}b_c`^Vd2PYDTz*GkH4 zA_l@;p4^VSjJI@a$g6PN{~CXF|G!I95~INIwT@)O@NG+_QupDo<|S4`U}O09v>izr zEceX0w49c?>Ms@{*xi+1ddsfv`}B9}_X$<9`DRX{?aCJUQulwDbI#|tFGT22k=N`- z^)qJ{OClcqw{Oko7g5}2e+4jVmGa21JFdfjm%NNZo-by1m(Hyktk0aOVBfU;`1@@S zUil7M81ZA({HYXlF_d2;)D^+%^K}QYsb{TxDl*j;U?hL43POuvv~&(MD1Hy}{}1V_&TH?iQVWl70SqKFZS@wXNb#Zjw~IY|msFqwi-{ z$xKe{>M;?Kx4P>4JYcTVX;Af34jDaMwe4=yCUZ{B-W3PY#c_JU)WE)5#z?HK;V!US=J>zp5OK)Z72w+Gho8ZaVsEN%=<1eac@IAq8KsWkj+gYeysL+49%_y!)OR zgH>ru&g+%3T$}jtVxM8I3AJ|7$dvk{g5R+5@A+toO!Z6brOaX%^eLupQN38BWLn$v zsB&Kx#&U7yWwo8X5>@PDWcQ&s>*A-O+Ywl0OZn$;qj~lBA?70W$L2a!1eb4*_gD?@k&d+3=Wu(}n?jfU2 zPjna?d~Tf9GTW|W5u>8n4jEV;4kqlLt5>Q9%$%ZktU*Mv-B&C)i#EQrE7;DCQcFg= zk-i-e1G#aSR>oE#RRbQRkw{T{x{^LAlZcN->phFt=N@SU_B^$AD0wA}Orvk)bFxg5 zAbsYYF#FKuTJ`jKfcKt?_K6uXTH%7Ga$C-1^1CV3jeTaNsl~_sz;FUIPp_Yiv;#a; z3&}oK`sHP@qJF(6RDbHGS!@{9U%PQ0Mt@_k9yg?-iq{pHV!jA}q@_|`yFGUGU%>TV z{J8R6QYhWA;%rt%KGkW&->E07aM`fF+!YrUtJSWWCgS?Rh6b|AD`?eATLUr@!|aWm z+y%56oU@_VZ(v(NqV+57b|nX}zMosM(^y*>kB$jI_-cyL?<;$i%#SUcZxPW!gC z$Uk?j*i&w3Xny|$&I|m3Ruze7lX<=?J;b|!7`5Aqfk|<9P6WJ8wMm4u(qEIev7^>U z*$B5;gxX@tx=oUpFuh@_oKTkKc1YfDf5wmyl#40*;85a-gRYM@F(yAC7qwZp7ToE= zWFop_H}ZZE{HxT-<7hKiOmS8O-CC%pynA}Rb0#bh7G9DdrGuAS$Q`+ZznD=Jd%`pyTrMuZTf=H zGyrvl&jAk(#5uHFPR^c;I;{dopY9Ap=yW89Vz620&_%+Rli_0AEabD|I}u2xp))Mr zk*O|Sju#^vSN}nQfFWKOP^;xa7nsJ|i9>_;Qd&LV)8Eb?PoaTpLl?JYyn zW35R0&rZhH>GqO+Y+`C23ebZW&966vt*TRPjC3c}F>S3^d~ADAj}$05sC7}Z{3%*@ z-!Z4bjp34TJ@tX+=8(?APkwVw3tN0(IC$3h6yBi~~{}aNlRli&@ zq-}r|;dR_JwDr+#RYe6X$Cou2m*=kYRE?*mo}J6O-AJ(vfyJay_UaF=^yrrEdWu#1 zW`(YDiNv=^qQGMuq(ka#uJ3%QTZQ8wP|%sUtTh*&(qW>XDiVLYZf!SF`o@t~_FUUI zM*sF|l$~Mz4veu$)jQE0hv9Q230>ya&Ld;4TCWS&6Jl1pp6Mg`EkDkx$iRA%;TulV zw^*7-Ydh>tj{Qa{NE^Li|Fz=I+TAJ@w(y#e8{2%IOk73iU#Nemlj~+<0V62=>-`** z&Y$KQ!wvn1H?KJ89q$?)L!4!l~VPSP+?uJ`BNvp}b5YQ?enCu6c#?ME#ssImV zvB$Mr3S*B%siiv~-~07b)wDbg_x4ZyTd=u_5P9lWIX^uDY|BVtD|z-)zhb=Xmagty zABovKxm{`y_qwDjPRn>|Zjti~6YQLz`SxMIE4LZHo5s_ErmP=5L(dO=>PI>p@2L6j zH{xqjJ&-1b(xq(i;=Krbl-%OvW0u;x5DSYDG%9gk5=SZw1Bb22vdl?Dl?1U_dc0-T zjgpM^Ob85af_%nOXNI9ue`hyC;I}Hct_oqq4g4P}A@V^budylWYxPIw|FSRUpdf}; zl5mj9oh<3kLuL46?{Qvni7v8mhFYnda+sAlo=1Y%T_}_H#yMwN;*bX16jW$xP9v-2 z*6KlpnS&|@7U-)w#789010%coU3FLmzs~pMPm8Y1j_ypK zE^Y=TO(NV8jGkKLhc5~gL85*cGHOu3T&x;qYRY8mN2w_1Bsle?h5<86lgwR+FIzpx zUA@TN$jpnF$8(uJb*beg;4&Cm22ZZS>%A^sHP1cH=NdYLHq)j#50QJY$i1puz`6yRaGR~sy^Za!bp&rN;JwiNs5%4YJaTV_Fh+q0 zZ4`t8f>?#soG!AJwt_E`jriPVv4rvQ1AJyf_kMvbvmZIm`>(|-*+buj-USBLnoaE|D`FrBKvnt&99ZjtH;+r%( z9(w&-2n<f(Ua17za7P&9dKucRer5Mj5zp=N`rKhu~Of168%xlnjn z6qqd-4~i)c>~=eL-C`KpKAykdijpEi?$<;6TU13(=0pyvg;1@q@BEgS{j1mlTlbY* zF;WF4&74FAk@fQq>!(psCqH^8hnJ?&uI~Fk@Y_6PPcvQh$q0{{%^HNNt(&HI}vk@`8JZQJ5SX!+(niX0~Sa`LBP@Rk5kYhLRF`)-3E<6d9hDxBq)>Y1B_SPI(F7~EY{~;qI*a901qF|6~%m!6D)JH}0 zEqzhd_;CuTa>)hTElyX$s$!VJSdq}Ww|p;6(#Fj`pje6ZL}8uKVMb^Te~O2tx5}&# z<*@1zcGa%%(`JM`TVCH@y8!szA)bW>#4dk}2cQCOIC=3KxlgksQ(V1t5E&pT_G7O2 z*=LYfvDM3&=Rii6Zk+Ong?V1e-xr$a%UO}k4iZiCh>=JZTM$YXhSv-HMB0p4t$Td_ zu!?3Jvoda85<_j+zR|ScZrPgIbJC8L$ur2rL1ZEtb+T%EYVlQBBP?(xG+wH;cXCL* z)c1;K(>@D{p1YzDbJs9I}m`;#7BVFXjKs$vJ9S!N6orZP2Ra<5i8qLq|YLsVfn zP2dF)4)v(Vq-OU&DH*gDq54BE+lbUn%rqPc9+ufj%gABr4b+Wl3LQvbNHZJJ*+YVG zpRtp3Lq4VY$!w&{-F~a}=-(LRE@`=P`=RN$Mg9g)^iOMaIT~B~Y~>nB>l)t8|HYPm zv}jJN_ZR%^q3uh~+6}t=s#T%_MMWGH$&W(vH#WFJUFHh zWWrG6LQ*=B;m^+W2TJ8_@*39H} zNpPJqmmoGG=iuo~7E%e-r6p$|PZ^6oewvQ@t&_e8r=aX6GbtUdV;RC9Elv({UWg@NsI#H3}P>fMma zwvfgt_5F=VT1JxZR1EVR#07{Sq&uOlgu!vXFDYT?<>MCO%6e{m-sww%F%IvP!Q1eYk3Vt{ z{^-(J#*LZLko}TX`;+N$88GvVCtR@4V|pYlm>)$J9sB$C(o*&+G!%ZgWNoBPfmg?C zLs6szksmqVc=?9hiO`DOl^_$k-*5TjlOJm>;y=$h_l%|caM}p3ys4_+EKt zNM|z#LFkX^@<5ALn<)*2t7lfFH&u1yoc4S)36}7Ig&=y@ROndwCqege^E%S z)VlO{OY{5ka~qBJQs2cf0?kr4Tb@7^FLHIWE3?o-zxb^-7xLp30_|-PO6Q#VtU~RDM;H(CypthM|$acMH!HT{E81J!H0$ z{`BE6>z#S}X+b05K^hXWuY?VdW}mWz{U7*R4Zd<@qhaK-Vd^L)CAI1S;qznacjPfY zw;|e7%PXmT@qbItK{q$YX|Q-=lc;$fj*B}1-30==2+@A0-TQoee*rFAP6ofHM366d z>BU6}WiEI0H+t)5_!Mlc6s~r$eI^}BxV~~zz?1k_$Png&xg&qADgJJSF#LHkzhfZ| zB9=Yh$QMuYFAKJD;3?8@n}?M_uCvCjXcY{qm)evPuWy-&=M4Y?lyUi!Z0U6_@p zU@c|!t1TrdY~hC2@UX@VuFrlGnC|99c&D@MpEc;?pMUz2tLtB}O9p@Z!rnp+9oUnp zuK`h~=!y0RJm6=jkChEojw1aVKl=@FC4+)y{^zHov74D(UEKZE9Hffnt~=u_(a(Kh z0K#)dxNT(y*LLyZ*4Xb??UQn<6a0jZ2B+Gy^NY+yJ6}{+SRpVMU~44Bky)n)8-;Fx z{OuKs-rgb`pNNvUaylAoccwjSp10N~=UKV zRPQJI&mpgdqb(M>`|k@9d{~I`g-j6`;PBg;7cwWgn;=cfhud@m;_wXRA$7Ib_?>9= z)rWIG-){}ULk{b->!IV>$Ovlw>!-vuF)tdm%=XB~J4HZoP4Vt(cqbnDK139MLU=p4&*B(9J}xTX}4!Sw2xYq&=S*jyi5{4QK5KQzHvg!K5gkgJ-5A2)uPlb z3np)GE$BSonlNF}S4SSP+v5B=VStTk_=~F)pWI%s@f>3Rj`T36#3#}%L5V*uhMs=D zcdtYLyOol)=+_qS=MpOhd1udDvJWmlH?Z1!O0qo+>93>Yv;KB3{oH-`cAvmJ=&G-C zbmb_NrqeR%7s|Tyyr{I=RU7uvx+Mj^PW3o5LHT!!I^2)@HN9SW&>eqY=qun zumrTq3^W5rm%{^}gr>{B5be5(=AO7t!GCTx4Qz{<&KcL|xhX;*Vl&~F0 z2U^nK=z9g5&fRr<5m{0YIE^+bux>Xoz8kT6+QZaM$@<&+k07Zs)ORJhENaL#m$Mk? zW_-QY+wxvKKga0AK4GL6VV!ei^~bHQ6oRo=aQhx^F*CoIejwO{cPZR!_tw}eb#j^T!%_~ zd~Lc#{3N%izpZy$Tq66D-3E7mGd`m9H(qJRndnCHQRF4HaFr8!`rz|v)JOu133+~{*?ke7PCEyp>lHZasV64SQ1 z$WP5JvZ2$;>_t~6D@fvUJ?xTZ^=pD-V;?lXS&6<5y`znOw~%dAE&GCV*s-FmJYdcC zuDb!xE|!TeqwO}ocIdsBh@l+LIK_x&<$pPDXBRb5a=J5r>7EthefOsu-^bQ9PR8~o zK~$71i06v3(w6+&YXtf>CIO7ZM`~qqx4e+}$ddP~GdEl;?JH-Tk2xQou#B^*P0N?x z+5O~O-P-oO1%cxgDPQkWlh|KIRyRwh?!=M}e-QN!;kgtlX3qmcz?k3xLH;BrsK8Nf zU4nllt+O`hpb7S8h-uC9X9tZl7fAezH9YwhpNYQmcBeYiyugjQkzz}`_#(a z<`kc&Tlv7}O-BtOWf6)mScIGLv%$@$M8h0Qp25@L+{}-)TJ7MRn15DxCM!x!xOnHP zMqgLv#aV)_e@QgZvvI;O29QBdmK`X*!KIk2t)_{Mx)7DBy14{@_+9mW^Zt9{dn(@G zE+*@myc$iR-UCkW@5ML`3+KqhPR0E|zn7X3AL;p|uPe{L++F&2IZCUFN_lBfBI{uY zd|xP#+B@qA2_~?3FXO1BTjM8x0&vwr51;5cnXrFw#A264ukI~{VD*FYPncJqU#)UZPI4c~5SQkgdBiYpE3;OgG*q{F^+0{m_5}aQ z#sSCrS$x#8k#;k!-*sJJjyBZoU=`Zi}Y==^Ilinh$b z8aswwgO?FMu&#@~Iz=RKtcVpm$HLW{7WsznU#W$^Pi?R{`YsNtAfn*iwKryJz4W=x zq2csOubdvW=QFvXaQ86ssp60Wf!TVV{->UnZa+Smpq@zmpSM@#f_rdfk_BJ!y5gC# zFbdepYD*?ZgS;tn>3&V51X*Rplu zM@3&Ch#-sASDQQ zs6?%q>LKkI*EQ{ab4s^n!2SRo7r=%Z&HE3g-)}BtKTXuVM{8XDxfOd&`p&v$v}PN+ z73mkNVraL1m)n{P%nIluaMdc<8QQt$ODCFFJJ}w(8^zH+LMN6t3Wgljic;cXYM%2K zw;<_xY=Nfn*%j!rmYQkX#R;=r~z+l*36O^R4`_=@(+ zf8WjIcSioaF*6)+Y8sqkb?<=cYCp+YEn)DDz8*i1u7qmb;$U%G6P}iu`Cgv_pW*dm zu~Sbyowb*{TK`NSyjZYuOO!LKoa*-6~K zt>{;S)6p~P;-!#QkeXw2F;D-Qp4XR*8+`hs>t6GM#g?D~ydc&P?6)jSYj=<2|0!-> zZGBpj!5sf?62(KyABwe`y3-u)WbLkEK=G>b`Ah%b(rFBp6`9;?KiH#7levQX)_;EA ziQLUX^*l#CdZw|X#w&ORidQk;(7R6N?&i2lds)`rtfD_b=f^()L#R%Tf%WesmTfbx zRU&fNpppUno&zA3%#Lm^M)6$Gjg0A z(oEi?v#Vg6Ec|gn&)|2~-(5QiT{3JJ2U*cW(-D*;z(Oau`s_(HtEegYGeaXI>qjqR zHn^`Y?Xij(a)r2WZ4`FIp58H|Wp~8wT%<>#K8k44hfR|`SkeE#`s^ZCol<3!yXD2* zmri@5Ki!2o#`mqWz^pj}D@k^D_V0C^+@Y!!ZT_ZO->VzwqPa~%kb}zdwo?9@e7=zc zvUVWK^{+AQq$gYmGIdt#ccPRZyxrJJ;0o)*F`rQ0JbLIeQo>;U1!;< zA7*J@=0R_aJHNpl`g&aR#YZX-$rZ4*K(EQ9tf{*pt^C}h4JvE#@I}=My_s^KOJI@=dH?jGnVd9 zt$;MySO|AF+Whl+l`4drXdx0d8g=S=NzRJSSmdgm&N*w5cQw8R@&8l1{m=6ofk4no zh!UgkBb9XX(CSv_*1d_s>SIU3qaE z^!yC`JEXI{hmKSJse0&38t^~vpXEPw{^hVQ4-jy#x61R*l%%R|Ib=T1a}79ASovzO z%rbDti17S0OFU)Iv%dZ%#s2dP*_5izimr}@mgeKDB5tMoYQ2%yZN6!Jv-A6h$=0M7 zV>fU7{BNc=Pq}jIt*)i7^ADOL?%e`CKgFw&>aDkL{rSE4^}~yMw{I(ZuKh8WM27k= zOcGTu1v5B1=?m_vq=#!HM??D#@cBqW%?u5nD3EweY{__`c@Hyp%1sYDVYnlRW-$)j zE3+^<+O@HMmK%L^QVs+SI!7OMvez)m4%f_@$;Fd?8W#}z*LaYQ|8ejDe0FH|XRovG zb0_Vz9*Pm;_K@@fp<6Jq`&W0)Gf3Xf3nx!N_byE51YKC%S{4u+S$|S>0dp=hv~7Ia-hqc`yr`5A@o(7r8 zsXifd>jQ`4#y2kvJ=CH*`2jam9*>beqki7nuibs3 z-sC>8c5Bh+fd_9t(E{=G^-pzu*NbCdS#}5_9UZ~wfEL-3m)>~WYIeClsT|+q?!04< zI5g(`I(k=A^~x90y()=X_b&Kk2gF|cG`^Se^0#+Ks?7AzyZ<&V>kWST+suCuJBQMm z+jiotq9fBpdSnjDlNtk!Yb zSST%eJ}46x&)AADPy`k@jf1Z(o_;Gs|GdGCdH-`GjXt~#~Mw{ zYCSD@j!M;__JwO=i;H%L>x}CT|1uY&k456h7toN6qUKdG<6fbXTK(7V-c%98xVMO; zVc@;WK*7TK6^j6rPPKF4WnAE5ok#KhehYRHWkbgx%B9cPc$>ZJF2KZ#pE3BBt)OVr z)fUNLcovMnvU3;95Sl$O)ysg$YabUDlrs_@u%+Vsdd*L@(7GtypyX={CW{~6`p6K5 zxU-J09kkyLdZzC|=YKqDb3=jHvv>bKS87?|1@9ZCZnL?48{+13X=BY+i)Ao{#s7`}@_~YUj%!{i(qN|NOTmfLc$}|HU8`Y!fP_ z-9*{Uy~0O+8HE$uRO=fVC8-~LuFe{J4s-;bsKuVOUqR_xx0b(J{Ef0S5%=@QlKTAA z1hwmB2wq#wull4zS)5~(mcmSITbfm$WbrQW(}Tw2*h_d=O(eKm8Z@zM)#BSd%o$m^ z0U|ezREf6twF?H;B;T`sPCkB`BFU=Knwo{>J9;1_7(Uvgtz;tUZj<`?hTy6*MdT5~0Pz|N}E zqO4OWwq8!B#Ad)K)P>`LEGT(ovL9UAjE^E4>x_xK?8_tbL%+=)n4U;X9^%odoc0SW z@yV)Mh#+u9=@wzFT3Ko_&szWfIi{IGv zOvon#--3+6Oh@PHp41i3X`b%YJ>5Xb;+^;t3;12~D6Lksmwmvhys+h0>QZvQ0Xdun z3)<~|4 zOW&IxW;WUGE~rgpK1CPTk~b${f+P#x!#>kcml=^;0Q6~sJ;t+xtD}_uv=3gD5C}4WM@3iG9Cf#?8Pl8(S82URFzVR~ zM1Q!=*jw`A^bZXfRIUCJoU&o$ZH_pISWem7T)FT$b1q6P(|Ny5@Kbbz&$MQB$8Wms z_(AT5SI?p6g^pFt`4Ju9zM#cyqaQM)x?e#W7qz@o)+ty!TKfQ2gnWu<$&dAq)~VO@ zF*j2|H6`|mE3Wh$NAj~1xE2UHMSNJv0-2pi$`0U`7Vazr16=@RvP{IjOmr3x?7V(!|9hQ* z&4nP{V>mHc93gm)r@-B3XZ|>wG!7ho$iX(uU@PS4qnvnkLpR|Mq`fnGxE2#KGNFi|Rm zNd=)(oZ7%brz;iz5>$|9oWe%R2;)?IwH#5$*`Et?bu4r)2b=!r5E$*m490AU&xG4$ z!?Jkeb`TGZ^mGXB1`9hP=fM`jhd|p)M(AbWCLsLdWN%d9LHIZdY)O)xu*Gk2(^SHJ zN%%bl?%+?NP?6CDiL&tlu2ZqR?WkLCfXnm10cSlp3j$}jCs7f+8Egv`R|g?n_)aYF z#P#|1kA!GQ(hE~BJwbGO3`Y@`pU!(on6anlsSLkU3% z5XRR6LvND6>FL!OhYJv-t&1F^W(11?XGzef*$EA@nEhEQ?;H_PUyjvn$M(|j$1s=x z0G9VE6nuPaQ=kUFgLx08QHGbz9K1}8@)^QhU5ieqpi&@V1Cu~H2h$`jxBy@>DYzFL zg7hb@fQtU_1ot{nh*XIJ`<*6nu3C4lfgO5O86WX(H%81Md?jl$q!!t&NDdV<9YXlb z0DeeSlV9yhrfqAKVUEhf`@m*GhPk1@m2t2`)TsLm)k#`W^??*Q7008dE5*o22*~vT z=n4RmjX6WXot;7R zu~Lo#Ypo&xSE&RJ`GrK>x?0=D!pk9q%T(OE>%h-{GfOaPq6)$^4X-_g5sS|g4SBig zl1=n_jLHRYjgBG2xb}-lgaRdIV7)3;zsObJ$iPn(uc08C$q^uLc|!p3EE2uKW* z$1yXKHksQLq+#OIh;(mLPJYtC_Qzkd@07JogklR z`9eGW8PZyVMQHUIUCuI7zk00!L`&s3kW70eC*1t4ZyXAgqtLCa;3C_In^H`(1m8j{ zsQ<7d4uQWe!?h~_j6D^K=KwkrN-1W*HtE&v6Nv5X;2L`@bpViXQ=nNVVgAY8oD=yc zfDRMjB(_7_pD;)xfQ`%}aoBYhZpe)6|C>a6E_E6fUHnawve68Yih45~@{3e0$G@Ti za_U)l3GuaY^<8YUTfAy)y2vrQSQW}yQj}`@I zh=AJSD+lXW96lpMssAReolwHaAZQi<<(}Ki2KVcc3MuNK2z^|JRfzElI%eJwNXMO4 zKrn|hq7&`03egTrVW#1eTj<^CE=Gis6J*k#!n6T=*&l&!A$f)he2}X=k`jg#zbO7w z?qcP1B*D$#ah4-F)bPj>CPry(<&P7)&zH4MnLawC3WA0?rxPN zlqw(v3VLZ|A7!1kaxxI!fI?h#h&c;ER*CTE7BRkw2S5m~LWa6VC)}W;(|q8j93=!; zka3_)>TQJ#KfxhPK!~5@q{$`H4;lUr8YJsWQD}h>$fZJv)k@jNpLHuNWs{Aw>Yb7ILFrhPvvBucGcOgy0)viG4Io#suz_ z6kjMx))zxnI7%8+fGQ_ZWw0a>X}X#OQh%u31epJ21qZWt2s4VovD**V6=a+dA8v-= z&j9$0gMeLorlO1Nv5qh<2P-qexveWIUlN{k2`^{_riSGHoN6d8W1^vqhJVf`_Da!5Aoyo=d?6K+ zBqxDBPvIpbX!p}9*0sYsFM;X4h<4?x9j@m|OaSGOgo{m7#|s(& zPHxUH?U_av;hE&&IEygMm1+79(5<4mESOm{yxAX_BfZ?mB3}JNa=idF6%q2Kus8i0 zJl7FJ3&0qTZl>Y}=^gOyM>Z_fBh2+CY1OB9#W0ul-S+q&33!eN{*fcvwnf*C4kH4H z6GduQM_*pPl12Hw7pQr`*aE%{Lu3HB>!KYMK$wUgpCZ84v#}4@aep0&Z$QGq`$MWEB_tI0R>M z4ygKzA7-6jMVwlZMQGcW%hw<_nyW?1Va5|)54sa}_~JiureRh+u-$`NFUPUJQ7-bG zOr19dpY5x454X{Z*RWnX0k~-~@w)~|Uz_xu4NM*ezSBsrr2^u8s`G@$9#&_{?wK7_ z6h~U72t&nq0vR$?&AWztF*;d}{5Vd&{21YXC}emC#y1Sh>B3nrlCE)*AIn>(C-8+d z%x)?|L4&TM0@_^QF68|ZZKC1}3BC)c0ItO&1x~jyAWJi^HJR=iy=8tn_*K zi@gU8(@Mvk%qRHEk;zol9uaOFINKD_11EPQx(Rphex9Y{>*W}(NE_M=H+3o8VTE8J zkzjt9_r81bH|eAd1G>UhRP1Tw9oy4U{a)nK5TtWw`W4B&YH8gCDz1|y4G>PjO3FX_ z0xMt7A)4oss6?10pt}k9N(1hQ4^@Eys%&9vd^o}sIH``?V}3|e5Y-~bYn=kFNQ1vu z<8F!YzgJ5S9+dt;{p_M=MOJ>2?9`v46Qi``Qf&XuxisAq2Io)QZ;5Aru&0GLz#Sk zWACm~`ILL{%Jqlq9CoRfuVLRE2&?qfv#9LgZv5e9e)eu=ANRg>Q0aZmQ&dIP;_Fp5N;!iGX z+^uc)EYaU^Cv()Z#`dn~C3^nN1yu2o&IwF0`$wrKDD2G%YE!xe2k*+ly*%8Z+GZKw$zwyv=FuT;^5L^r~GpfyQfg(lBpN>*!5UYe^1h+#qRG z*t=?9lhQejSl*&XRp31|Q#Y_NVBpxEE=+uFa`s|;MdpV6UplN6E@#WT4UW&O3b6wr zMi-?2zyp^gD=EbduO(K$O;aFg;Cce^z6E}KDO+(hhSuK2ldhD2wcH)7npx`@>B zqbz!0`T43owauz6J^5Q~OqeRp%T~RGPWR;cKJG|ZY>8*-qCo59+NC(nXwf3SDxBqV zPZg{JV;>YGgsxSK6I&rfnbc*W+D=dwC{uaQ?Ke>W8mkBVGLmhOLpI$U2iJfYq^$7GLg-9C&YdyJB+_Wcqd9 zU3!Vs;_AeW!YJ}mHo?ubra?I{A?x$$_&VM1t9%=e%pOZ*oi8Mcde>Pmi4-L+x>oHA z@r7%b9jEbYx@ONPyLUqSOEWo(Mz406^7_lHGw1l0asGKO^q##9vwpFr!z=QrhMOYB zvRz-XQ2Zq&AYHT1yk6J%foO+9bExX}M2)~08-4tQ~plttJpm#;c@BDdw! zBtbtcn&d_~d3m91opq^zz~;i^Q-hoA2cigl=sVV)Rhr41-W9D9rjY0^7D7nrkKf~{;38-Oe_Y_`B%w*hH}tJ3a5#yNwBOe7 zjnV6nY5Fvz7_83GC9g zd?PbinVhd(NhT(QKhn1k@)WfD`#3cwtX4K*_$r!n!)dS;huCFn+P9$26SDW~JzYC^ZS%1IOBfeUWdMR8K>ImqX}84>O$@q=wI8|JpOoB-)RMUmX7f* zOkrE<9V;7fl9P)aH%^(jGz7czhf3mk67^itA$RasVrF+n+b zE6rsIb>QR01wFOa0o-0kz3GjQkvods4s3UsavhbzD2KRw%TgCY`5tC&^RuiFQNS|YHNAqc$2-J3N2)#0>nfDfMS_R8It9d4~&SigNRljADF7^y^ zyY};Rck6?b>>vaEo(}|f$$pb_0TLJDN*%0cet=*dpg*P%s^nh|J{~{YLt8gK>KxNm z!r`4SbodhZJl*_SI0d}s0pCxoG&AKl^lC+>TCX>YzLEJUT61sRKxzw_pomD;$luc5 zvv${a^5Ph5rBupn6F^=}s41Nq_x|oN`@ZmWu(}q1+{ZjGD{$Vgj$Bm5I|UieUB6)M z9synq0Hdh*ABEfMhLLF&6?;<*&JdH0DOu6ud^4slE*1hGNi8W2E00z_Ab+arJ%|5f z0^d}#Z;*YLielhCHb`svlT)GyON~n&`c&W_3$L3v;v{vTr*J zvams2byl4~xvRIXi5vZo-oZ~_a=~f6rdd5rqhL>T^Gl5+&-jMTO1(NZw&D54AM|Fo zopVh+NKU&3tZZuNyM8Q-V4qQEkKO2Ds|r`ns04@P=Y-Olnu18QLe;=e2(?usmM#py zwCWq+RBL7GH%b0h4aLBkuB@VX-`ZKftFr37r*!|gT|WihD>?aO@bn>yRe@tYT%&Q+ zlS?*f;}j3;F&Q7Dj3Aa+!41@e^_P04Y_FirqX$lAo)N}0Aht~K+!t~%zhR686F&}o zA^MbC2rpBdlPS#>N})y~w8;c?ow)Jm{+zWmr&FD#3*B({1^CIR+IS)8aPc=w^$B-d z*Mbx8-;R#ZyI${yZ8&yH>Qm&tQogoroWq zj{NXJsQRJkH3yX%f~2*#7Yp@hA^cAeho{+sa5+Npdhg1l5OWb*ZSMrAf5GG`Co?Cq zw8d(pN@}yy==YD1aT4BKr%=`n4t=Pvb-`yUb!L|cD`0RpF3(HCJKtavB<6=Z>TMCh z)^jVpIY)My0ryG`?V>az$M})-bIA@(gc8GD1E-gUOE?Y4P!TdfyF4?Ym86MqdWQC# z-Qd~|vucMmS{nwK8qWK>&pURlhvw`agsvBz_7j5L!9U86`06=)wg?jko*p~kH{El& z_&$4`ryvns{y^sD+%4DyQMcnj-9%j~<3f)9QKLfPYWxj@=gn9ATih3Tp<-2wCG^Uz zsJ(K&Spv~GEPGuQKa7TK@?uy`7AhiWJbij!!2r~F7Utkf*v|py|9Dhvt_ ziAuC4sfJBG!ZP4L8(8o^03Q?u9eXrS)`&8>{V8Zvs!2Ki7;s>>TizHl5q#l3UD$aBnZ!9l3dQ?~ zHS?-?UTnAz8r~3nEK?5Ur=KoJ&sScotV$|b1L<#~33f}7aTFwJ7!k@v#8U-P((54m z*c;}Acfj32YW2j{*j zjO#$&ZjIdc;_m!NnPHs6#s}2?ebvII(7Jh5?1tkdBSMBqys^FcexAs+ElVqnm8;k% zLf$=&h!zQ6zYy+nElQ>2`ca^t&It9zChr%8!{VD^)cV;ULd%A%4N`&CjarkX+|)5- zP&(0X3|8@`*Jr(|CfMJ~PVAf&!~??)lO;(LG0v!=rA<=H>UKo8HP400+#l@?e952|WSkR$3f@a%+@%3B4oVt&9F zqH%w~#of^L9ApxRHj0g?Z$!2ygoy)!-QGIT{U#&E*HS3g?tjO){mfIWJ^83T56N&~ z43$2*SBg%R3%t-!dL4Q-4W4qw`bpBIypT(`?;#?_V5>zBc1^;QXYUk`)nmJn(V#ac zf%`P@Be<8g`lI8a=05I$8aqg*I~2aL<|g)G<0UFER1@D0QKuz~!r zljvYKpKUxAKcO|X2dID|Kkx4f>2!R5p6}do`(l<)oCO~dX5cC0cgx|PvRhtgeyrs5 zrrDgGe^J(+;aQWIJ^b@IN=NNk@IdiHhwYL>Sui&dX1f>>;&369#t#!67t@@WRyt9! z$B$O&Bm(8c3S=S}Idp023?k!XAWc@bYqr5{_@cF8k)k#4L`(v2^8o)w(t7QDVH!Pm zCxw^y4QcMqui1 zpo1!e&(giW5prz|UJD0A9E!@?tRm2J3|+WS;;Spo3#&gOAH@j3ZcWiINRb{DJud*W zlF*3~An6WaW!L#*@S>B5#z_#c(+R9XhJwWs8s4{gr2~c6FNMcba)~v3cP=l6g{e0~ zL{{-P(-B8|je+YVKC3K~GLkuFlYkB}NE3_|p_4rYpH0bkJ{P|HT=+5E^#v=}zk#xp|6@kMeVp?@F-e}t2oCt|r(*L+f7$Zt(-C2d$!r>oU%#ExfLW9w5 z)>gRrGV@DoPdK$XQcSJ%Ph2(7I7R77EXLWxor|yQ&sVvUYbn$ zh8V2l`*BYm>Oamj!{;U7`4m(5J|tCJkodgY^mg28C#`?Es!zH0NwXm$S}x7z){zES z2t@im)jV@C>($f@;g}0uBtBuiwxZYVdEbAZiS0)Wj^G zM|eo#^oF-1wnZn|IUCa7YK1?x%Mv7LJ}!bHXOHpr2E`@MYujiPhECkbYL>A`I6aGH*n~|{{{hA5c^TN;@nV4mRBEyV4 z;XZs#EL*U5N^}vO>tNy&UXgqtR1U3KS?DFW9dhaZ6F2i5K^Nh3e>#TvOc2h2GpL_Q zjeM7d5jS%FdM-R@;9d6!GKtdYH}sF@@*DOnj5aYj6HGoe^`JOI#b1_#j{Y*EW9jC2 zBB=`g%J=FzvlH%{U!`#P)OP6Cn?mO*M3}>U=ePaeDiJi#6n<59`zeH^JZz??yjb#4 zkts|`t4g`K?{)Ly$B}`sYd^}IODZbv=O?i)5w6rEQ%n)36WWqFr^TO|E6%1+1kMYn z`e&bt(viMmrj5s5(?9m12|SktK2RzMH8$F6CnBD>u_*-MNfB&cucvXjTjOg^t!G=Z zTE2FhGf3Ukv3Qx7J-X_awne#JW~-yAV@HIHy%S&vzS88V(4;;4P!l3xT9~2H7`l*c z>3qwW0u7TRXF6XWk?e44;%yE6ZbE!xzp030jQS;XYkn{ITY`SM(>q~|d|+7c-p2>i zq3e9)sPk8qf|99SG(r6W%8%Psz!vz?c&AVDQh9>Xbt-N&_*gq`bHkjtJx;MU0G-)g z=1%APfnD_i_3W#La#oUu;L`f^{IGXjwH)$~wn6Q=4O=fqr_HMVyC9MoB4bZS^9KZ9 zGPVsipAKi&ey}J%ZLhlFSAivWem@Z!A-&saCkUshY^N99v=sGqroePR(X6iR_)0!7 zDJU&PR(yE4lZ&kP z4E^S1@6UN^r%ztg{%C?g6uqqRM#j%-b~&eaokloRiKQg0?&>YI6PVKY{gYEOt)Zx( zfoR<_q~W)`kLIYv_6X^mu*U=uD&y~H+a`XPe?V8j=JGA5&%XT4RjgV7Hr9|Q0)n=kLd`mP zR<7G8R90LHZDmdN*sIw8PtWg;diC-~t*7r#n@0}SNBs%eRnx(rti6;4Jv*%#)N3jpAW}6tNhm=|JZ38ZMTcjYLVO_(qtqi zok#4g{1j=|I({ng`PHJDmt6;L?Rq=2QJvzT_`wNtD~M`SB#&#}opRr)X%i=tZ0zOb zJz7QE+GK9tyCr(1TO}>8G01z|Ir?Vs?v}cQO($(5JI%v;k<;&9s48AQ`TWN|5^Wp2 z^f4M;W)?9d`(~^D<(bIL-rha5^}}mP(%99#_8)0qBSSH7MZUJZDncl^p91 zBE=lpilV|GT$cZhK9)nb`P{=)6}K7>^DT(CFPScRTV630tkjZT>rLxTRG5Sf%*`hG z=4BNJe<+=Q?fOU-`pzc7zxAA*Om)TmQ$rxuXC1RKM!f`|);jCZ7XIXpv!+EK##HLi zT4ay2SetJMDtVeYeQZ}BL+(NUl_l6q{zyUO!S36QYTcSKDYr1kjGLr2a-?<++dAJ& z3V-bHFm1#0b9^lYUAfKPst9V!QW^fJR*m5{kLX&uuLDa1N6vV;)O+7`w-xiA^Ue>e z<7?kmW0ZqPR!?OT1^nkd>strYBFXF?^%MwL`?UrQ0T~Id zHh%WC)VIk@mW?&eV)OuyU@L`h&sVADcObCc<=;OuScl5qw<|GX@^v5AO&fTAUCy!f zd>ynmKJ@h=kB!!C=8t4{!|9sC59T$hPqZt{e-}A64Mb@&sv*{;ZGBFGl{QtQlUO_M z@-)_>PqnSTnD$z8t>>D(;65A#LTil|Ealv_3u9=MJey92d8zpWe_5(NA+9)!hmaR< z#mXmIc%#ZLC2sh=XKws<-ummlC{%`L_?YAboq4b&u60>9r?dZ2;BlPpZ~V4xRCnVUj?6I zU@LA>!O$Jni8piUpLR1I|OYSH;->lM8|mCmY->>YA?? z`7)xE3(cR2#07QXyQJZIDf;@Y*jb3;}|Mxh{pTZI9}x z_&crg(82#kga6ShiDxv=hV<%CH`lDPvMwnwpM3|F0yugNF=v5iv(0tYK1ZR^siik+ zEUSXZs-bOKgGigheIa)jxKZRrymXuzHUZHCi!tykqP zj2zJ@(HQ-tw=yxPHlP}`PzV6GzXDpbFdZ#Ausdcgho2}p- z#8^_i=pwM)#TwLaoq+bX5gOLV90x>r#jPZcRmQ@EM%yf3Q&PPVpcH)fZM zff0C%klSIEw<`S&I;YCbq6%D{r+8~ULO=9s*(^Y9s>|(MQG4UmBn}6I?ld}B%G8f8 z-kqMK4B9}p6)oFikbgr6DZbGzN!hdl%L zmhC7`-*ug!)T>!MogYqNXp-{xlq<-@5WFk7d9ujOY4wa%;PvsEzy{c17K(mQk8&ec zaq0T;G2tqQNhd9n9)qMBTw?Nj-ItR@uXQ#UV`GY5C+S&j!wl}%5fYc8(94H} zhI?uX*025g(qfoILz1r)B`dw&9xk+B@$>7|zuPCSI5gUKdFdtNr`4Mhn3akwD1k*q z9+36w+@;>h{Nx!M3CRg5!)+|WKZ{jyx!{o;bi&Q=`t(nKM}`5yEVv`zJp;TNRWNIE zttYzl)+ss$4-$XtTCfr9_G6a#q8q#LFrwZ5->%6$dEpCCEy(ki*S|CHYzQ=0CGVwX zT~?}4ynBDrxXRjt#>bgomzO<9W``? zyr02-ySV0v&dtxK#rgyZlpC$5?vsqp2v_18SEJ_rX0tcLd!Ke}4O?P7adc5jWceL{6CufPPaq`2|Qb-<5o*{9r<)kaakj*9v>G2u28 zD%B}se~b%|nr%-XW2D2LHh9_2=GowTU1_Hg2YJXbs;17iHO`iYiC3fKk7jhC;W(ypQ?@YC&h%LVSIsCm5p$ z8%nR`K==O9=dP*BjF4Y z1Q<{m0{qfZ&N44 zxOGtSBRq4=N0kufa3x`#XZExk%P?54Tq%{V9s)H-M_%)VjWW9rq$#Ps;i@d?tVT?! zy{K3tFJ~U;3pWS^`B&8!ZzC+3Q1@;!J_}56@LHhzs6Rx4DwN z-F*g5=EBCL)b<{mLW12A)Tk@#Q@BEj;-Gee97{gjZM@XGX4XUH+p$AT#^#-+5mT|r z$SLPB2tmv>{Bef)0@3|~za!dJ!#mD%L)>r7x!uJE5C^(?A=FOFaFQ~feu7>?C{;A9 zV4!u?7jfa~cOX~mHxG8ZSuxe9i2ba0SRUOF-p?4%eJUET?(0!ao_6L;?+(`5y{_-j zw%9{o;%h%zFStE(()FGzjpmhTbzdBlL-Buk2o7T#@UtsaPu_rF zol42ahHLs`Z9!k}q7vL(0Y6llpe-;i+weZc{5(V2BTS$$IIzRXu(SKUNmj6i>HsMn zR-BzxY}cnM8FB8CI``4hzOH}DOKM~d+n2IUw6n@xO|;jUoci*f;0hr?pr&uOFr=`S zgS~b@ucoi733#8L3Q0pgUW@Ow6qzJiGRagUMi&H*?^!NaTMC)B`2?l%r0(C&pFd^V zc$nvSF~{j5!?DWse5Glf_Xl<3F)|)iuhtEyDiJt652_GW?b&w+k{Z=6H0ykHW)3i3 zyti|LS&c#i%I|<5nIKM7k9lAU@Be1*ZVR@CVkv}rp}lxVBb2Kos$+`!?PxG7S@uTG zi1Mh^^^JnQe`#g@acGzX)lGSCz~s&XW*x|jQuny_O97s8m7 zEOWn*ep|iD)s|Be5d^aVML#6Hn|Kk#*kg>$L&hlPc+!6JKDD+1vR;i|ms`EDrqM-+ zQn|+9%*6+X6E?Z@T1$J#=>h5cvKoq*`TGl7{wA+1pF|$}^k9RJiEXWUa-N9!8&4Zz%U8#&YMae1wFswXm}MD0sg=54KyNsleuHxx`F7Y%qZ(m zJq8Y02!q7vb)UzHmXl#x5U>S3);qSuSjS_mUUm%*bzRx_(K%HLt)69|cTMiHd}r-e zs*j+r6j$bVXRQGHZC5Uo$(z|{`SGfyKBBUtvW|(Dp6qP;{L0exSTg&u<(K)UuWF+o zmYd|nukbm`Ih{4%j{DLf|Fd$zGw#wYG(a;4N3y3ZGNH9os9-51b2rb+4n9x!U}l zO{;_mrtcl`WF$+S80P3xaN?OnMn#ZSMRPOcK?a0O?N8~fkyh?kW*%D>ky{dqcv zoN>t%AG$a)tQrpZI5d~iKTn<$r~P(&@;V#ZY||eh>Byz>C^Pf0B{@h@!%V|?(YpEB>1|uO79M6gt0fwQ-NKlNN+ew43}s- zKHDF@<77*(T>(q&pB3{tduI>>vda&q9Q&1b?xc(*%XL4`Rg>v9Ib zG&*=zB~X5Sl)PwK(d{FI6UgOZP!ho5RBwvG?uH zE|OXgbo^vI+>n8>sS?h~DJ0L;7Pc;y?+`yn-7R01-6=g=koJV}O#XAsr#Vlqwk2WX z{CL97=6-4Nod`A3KVE}z{d?Y>+zj|p6?n-j?$*azaZHlN!esE3`CsKzdS4s@#|;NQ zPM3T1+gH2|ZgTW*sBmIUp2%H(q`aVMDwAa#km^H={myr z@YF=^hIh^cwaOgAwm_TU(f5HH4hIP9SF@sS4?Wx<|2ec(T}*>_f4Y1~H%s#eROqn! zVw9&}6`_+}OGgTd!y_rj@AlMQ70Mxp)SO;K&|m@!Kpyo9i@ELE-k~=-xHA$0tH*{Y zLs~>T5AJw){HiT{D$f9W^?J>;qT0Rbp$1~tw+n=)JoK8ky8e38*P-LZG@hYoO5 zTSA2sf$5SyXRH~HCDEhQjPTtxTQ+Y=nBLqsaBYo^weU#YXpbCOq0NnFth`ru>ZS-` z25rc!ty86RLaKuDzu}l$>&&`Q0!sGes>Ed9AkI^f#Ww4`8uttXS&lvpFG{I5k_=f= zmkT6hbN-L=`n z)^OJGd%llQ=u>GpxFej<63`vDy{65IP&V@z(qoqL`s>`_iY^sQQ!M!EU+T(Y_vfNzzdB5BhaBf{Ix z^^=7$>|ct`#|xK?Hw*{4NwS)a_A?BVlnS!g*_2L>Tb#nGz(1&#oWp{fLN651P*1zA znAhlLm&7G{Zr6O2e%o4X1^yA3qd7F&m#4_WFuIN!WQuZ3_RSp$K=&!PiQL#*s-K0{ z?Ne4HFik#XC|`asHte@}g}LtIGjrdm^D^P>wUvaTczW+65KXi7CXaa=*Am4m2EmSY zO!e2K3U)UlUlElb+xNpj_SQ`DtMvBGSDUGO=x&y!{)9M#UdnAxuz2mp$1}mlCEz=* z>h3%jX}4i5#{yjX$LuGLQ_pgHwSG_J?>!o$UM=grwA?M2wPb20-@gwT$&JrZRR!7< zV!qk&orP6I{nrZGZJYLCLL_{g4k}dsLg`KW=V8RlnUmGCs&DM}^zIch{CRrHSpGvx*6L)p}omcBe-*aJ`o;x`mLu0DU^c zXIQSW;|I{ESKYbn3xO*`P&_V`yx;*}CqII4ig}}eKpON`g%&GdKog6p@bRb-hU525 zJZ?Z(l!E7xwC!h4LztT~PCfrOr%wa?x1*l7Qk?6mzDo_VJvJ@`-V^k`cW|3Dc&1^- zO-WR#6=Z13AtTZH&o$v`Vsr&HV@QO*!on_|1ICYL{R(CSQkSbks*+=Yk}XEJSmfaS7p>oYYOjjs>S;enyEPyOf7f z2{m8{;(7;x$`NJV0*K#Pz=D_vx59>=Rf3Y0DDs24?JLGu8vl%uV$!wpDo`y(KLUu#E`A}+gvTrxjtkW; z+g#NBUqDz-$G-w~xH$>&txRxsBJJV3*jp1RuUN#7a{f0tf1dqc7dHbCbMB}fef=N7XO?I%*cq)IsO*i(z9%A1G~z0B#=W#X3%jW2&zw<0(HT+C`7nN`zyWM z@nBYWWLL_-q7dlr75oD?J{{U^wA5wLDVqUvwr;g%PusfB>$2TVeI(dZCv-n%=5D9>LDLPIrAxI}u zH)bW)EaF?~{LjrQkrEV$cMSr>&hsbWlY}uK#N{z%@QT4!F)E*%_00y?%>q9+f`%~%JBfwv8-9#HI-)AsyECi8Bofr$U-(IYDB)uEa4h*W|_h`6G8P$&-RV%J^P6B2p2#=*0XRgMJ-5RLxngIqtns|o= zf>4{ZVnmc-F|vi!2OjkxPKmLRl7Im=z72wIkjIf`g1aa1uK;2T3v)n(5pz%+0CR`~ z1*=Y2Rui-vV#q;qCQt`~%XuR7e~z3C`;!K@3z^vdziS;XrT*9K*TABr|is+^?H zQ3CxtXw*%G9J^aef=}LD<^WStbOm<@=6F?I<++cmfmS)^Bz-6EDyvU&EdP4R$?*pK zPzg%61Eo}pYd)`FCyvu9Qfdg#0RkA{dHGWn97N`0biEW`y92P^0Zh^e35G%N?oOCX z!68ZBZF)D>AD1uvr;?4?Bcd{Y8f!PB;6F6oztLk^SSb|?wZd#=AJh-UbWC8?7f2c0 z+!rk3%?b2TDgOCHYAzlA?jK+k9oYL1Ft-)>@()nR&M)KqhdLgb$AC=OOcSP7UHH3uQ5_Zsr8|11HL;xHcNNtdybi`R3|g%?Kws^o$ZB zLVlr)g^>ZIZ?sN~QXRsI_)v-zAzb{}`JK{-xaL7z7U|w%?yJVls&iVVAN3>I`E7FC z1v#o(ikX;6lCn27aB+_n0B&4b+sp1(h@grID98t{65U7YK8Rkr&n~>GklZ#nAMO1U zbL2M(_lI=lYP5TJX$}|bYzMSvNH$+htLlh@*9?<&38Soz7jnW&s=BlIx(yo!2J$E@ zZkE+U$C8kfMBv7WNj5$fqDh6j1j;aNVzB(>Ssw)6OADa>jnM8|-G9!$ln_5kPCR6t zGzBkIes0O2rnS*}3@X2ph`EU2|S_13f0rGIr?>kZ6hA93W^^i$eb3l_JFmV;@zaj(HjO~Ak!E8=N8e^}sI#wy|d?eyQ zvpP7sguw}HjttWx3-EHdh%I^gQPl6@zX}!Q?*Tzp{yVl}2av%+mN0Ekmm#hNAq9m* zSQKewf=h{FgeuLzc8}wB=Ml+lHXp)pi=g@gR?7~*IWBhiAE0e%>)^hZ zdYw{e4dLoGHR4~={`H*;@`3>;{0Ozp_!zJ+0{9>$w6MU-cQ}W3>QgRoQ=0VQXlO0i z|LPf5HFum9HA9=rZ&i^O1K@wJ#W2>wZHcNJ2=Y9*aWO$~+W|ZWzM`@SUR8uXYO0RC zGN}!TZ#uKT6Fc;tV6M~nScEC#px285Z5ogS(zs$w9u+t&CmozXIxdhJWbqen;9p6q z6aSK?se~Z4z3`h+Pp$+s&4jhGaA4`!HnG1_f?_JJ)!}tt;hQsd*nidSo&gi^!u5dj zD)PRFPo0*nAE<)QB0>cf3;L2L9myXggm0;J9!bCprT$hC&VN5}^;Je!5#}%xfbPUH zm#ZyH?9y)(xhflbQ!gX zx=#!)4peb5_TjgzZtW&0b+a##W$c#<+I7!mveWAVH2H_J|0g-nT3`XpK?ph0OtLTe z3qX1=BUH0DpeEJ*Xz1F8yWr8?@$2@4ZUA2;{)8Zd_lWSUpI~rs(s=lvj(>f+zrlzY z)npbbmcD5OLP)&yhSXdQY2H|A?w9;ZvUpT-?-n1kas!XzU)!7fqEzFz{p_j}w3JT} z?~ufinmm%Tfv-#7!xOyi%BL39<9tv1kOTjIoZ+0fx>*rE_IM{gt^-CXsbl#E^&T z;5_ad^<-`(<5d@!D6EX>m~uj8W{}u!O4gRo-KCF(Gcw zV1s92C{isjd~vl#baZH}LOH}cltFT6*&{qV`h@%A!gzfs*)F+l61!o`!S`|1X8K7( zHP;Lp$#ytJhuLNF)AMfR(1W4%n!`-rgq1r#IDi^eJ@EE)WKwT^h|%g=WYq!N`64d_N-4t-yR(kR}H@9lSr8->S zWOV31X?^oXe+|zc=3$HJ_X7(S9H6`Q2+~*Qu4bHQ-;?m1;Ao^Xz&6DsC4-L$&Og(S zJY*2xh;35}i*HCMGPIzz>v1B;(M{=G$CAtLKLtZLVkW5_PUB%qCt`^1_O2 z)Nqfx7O?izW%*vxts(%ca<7MZDe$!u6}oiUS#5P$O6PxmEa(}Jb=@vFCflol{taYm zHvcVnscu$cpDdzwu)ln7g9uVMh?6E0$qY}wbEA=Y>B292S=D<~8*YpsL*=`q;&&d? zgq2{|zg=!to+lPG)g)D~hcHPRg8R%kO1S33#+}K`*mrudP2IcnzhhxehC?!zCtqyE zt%^(bH)jhrYxdo1g!w*H$AmE+**tV8`q8lh%VdpCzKgmOfm1)7q*i3RvsJ@?Z5$Ps zzMR%$USvn`(0sy!n6oswi)q7{OR#0*Q;P^gSD16u5M-~_G|Vd?D&b9`v!i-s0i`7+ zBPxx78CaIF9*>OC+7^Ag(_KI*Zc=#LUXov2Ruu9*PX2Q+&E&X90|D7(Z*!_dSvVC+ zaM%7%OJv%q)3?OqRHRxkmtuCJ+S&3e(y1dKYPrK{ApXT0?GyZQv&MIWMo+D{kk%ef zR9Q=Y+isGKH=NkjBy4((O{&q-nKe+4PVd14(yOYKSIxqN&d-A5Eic~)Q+MGV7etz^|LpQrpD_V|~HmbW|-f6&E zk{`=*HCyPf0_rs(4+Re^x@K8uHK2?)07+pBYV!L3Vy!kXZaRfi2QK4=;DzlfvIW); z%iW`0OA-#r(TF#)_rF5~v+|{NO}kNprL~7+oG$F+&I0|j~+;F$GR|7HT!?mz~8W<*yTCkyy39{=} zI8D$eu$feaohXGd)2j6QUxg{SUd>9DtIdL-uj;6kyH_`NMDw05D}&WMAf>0AJ^QsJ z?UY{eW(Uo_S4r*LVMY?Dr&4RP^996);zh%_n2Ji$Jq8`_QhxA4RKXA{;x6eXG(tAk z7vjY{Ith0G?~Z@I;Cw+_ZHh$OTQ^i3BkXb9Xm-Uuk}h`BdUtM&3_C7e9yN4bL;VBZ zO~-JtFg(n{VwFTw%4w}K{;q}b6789miZbh2i;@U7n2=4bE$JKAQ1*%GZe=YN5eWI7 z+1m;PCVzuLunc*A+4V$k`MIxB%l?rnqy^`EV+!i;7=$@VkFF*)b|KE5kpC133D#XgSX{TjeXjfY z@1coZ(BCNe^JgBJP69rbTQwrP*)HWLcE2mwT#&n?o$Xw=3xvyZdf6B}wufi}4;azf zEw5tfJQ?{qr!aQSdyIBcs_A^pA`$IOft6Axs&>ki& z7AMi=vR5`oWd_!6Qy!|X5YxB)qLd{wE6>mS}Ce3$s&9{Fw(Mel1=(va84fPh|Q zarmra0TXPLS?T>DWrnUCC|Hu{Q9Wtkyu^%5L+xIG2f zL%HgMJJi-S<;#8fYFtoW{_R}!?OuX#7z)PxfwHA-j~t_?&q11{k-sps_)W3IO`5IW zU04mpRVdf-K}H>@q)n;^2F&dP`;UVx62vHgeRFBx04z9l96q3~VDIbLn8GK1wXQC|(zAFdv-4SkQqAp;`R5 zN+GWxjAt!T1_6p73=Ar7x))@$(~f1FH&U$&!!bL~cb1dJLWtxWC zlgmD7=R34#?i?+d&$X_jr}7}FOnK3HS}M$yp}Uu}4T`;)wrrD50+w}WQ31`DuknLJnN}5E7dx@p@MU`;}kW5L;6xh+aJ)$Z^a3+Qxn zFSow)Buz6?3N#Pd8*sOdPb2CAb3}?9aMUzRn;?O%XYS4NY$uzp)(L)1*-(Y(40 zqBs;^7N`wSdaVQKr9iPmYjvghtj>(CIHLjs0@Q;^a#`em*r9{g@;P52LD;7ZQoaLc zFm|fN0O|JS}!$-<%~zUn@Omh3)oY}eq+ zDe%2AdIPqo4o8h47^aS+7!Sb0jwsk=j=ZNYANgp?CkEEVhhkX{05z$k-BP=gE-R_m zB$c3n91*K2AP!bXz(Tas2gNF2sXR(rCG0-OHg4`Qy&dxP7`3~jDm5ohul}}4j;y`| z-ns4|d33OxFok|cOJ`Fp`$VxAkhf5KWJ`Gcg&dvpOtNaXgf%DfxXJEjAy|-KkC)y@ z!VrG^Ao=-i@8GI>c_1#2iUGO(2B-9)>i!m{;6Y>f3mRO?8>^9y-66t|p#jd7PApD+ z3eFxKOcDy{BtQ34(}3B~=}p>_ZUJEq=#Hj-kroOrAb&I!yxm6;_D<)3L>450P@WmR z+ioqtZR&xbe^<#M>h&VH7QlxB33&qH`}eM0Q<<<2rch5*(SF`MT{r(=J2eEiS1WsB zuWb>LPYq<{Pn6J8Ls*M*VbYH{xy0EkVtB<&jr`McsV^CU9FPwHWbM8`@?1|ydz+50 zTWUKk;DFR5mKwwFuc1HT@&{*RV4EnY?~jfDuM|> zaGD>#@_0t1Vh1E)^O>u=>AExS=o+V{{~mQO{?vd`VL<)4wQZlFG>!#qN2lF$LslKmhv@93~`IkGiXY zZjcr2lwtBiD{OrR@~GkhZI0~9r3A9Uv658{Sg(s#FhE}6b$KvI@>KyHVvK?wCDODg z#v4z?Ja4>9ZqV`GDG(AMJW*|o&3az22FcHP$;4wrI7Z*)u3y+ZK2zjY&3oxz^b)0$l^D-rc#yisiLXDn6<|T(d@%3Q#%dkC)(<2+ zcf$X-P@w(&3XLca+8gexE&g%h&N~VT;Qfeb@Q0Sb6>e)Q(%?|!J80}(3ndw%{i}lp z*^u8;th9upqcQUw$4^Cfv>1SzSrU1b5B0@?1rZq9`O6UZaWQ5`!lcD#_A!7mp{Nm2 zkje*Jkd73%d*9mzGb@S~g!w)0$G*q;pM2<_o)*sTKTjbm+^U&-%T>hiATRY^`lF<)97#7`k^k@KAj9iEa<{FkuI(OT0)YEKrz) z`A>zj4Q?f!3_$fJLLZpvJgT@EDO0T-paPx`^~eRsZ0 zp8j7!*$SqC-W8(M2D=KQWoU47>7rJfF(0JterLiCBOt*TsvRaD&07@@+L|JMIcg2F z%%g{WzkWS0xuCtT>xvxF$Fxl?(Cai#$10EVr&ay4Gg5R(vtGyy{SO zWL7tY6-HP!6uPj<28>jeQwmNq!_YT?55mDjz`Quqt4UUz7K7^VUQk7FmI!tV=rafI z({D(`Q`FqOZ4SaDs#4oGP)})eV7kdlKCJ(-q%MHszqIkiVz#fQTkB?J0ttM(6A0se zU(6($sQipp5%(4cB>y8Tb<4j^()sFNZR<4!4oSFFK+FV*K;VTRrg?@s zbHD_5g#RoZm4bzMCs0i3000J{?{=ct@TYJ0_tW+#ye&v_xJIgDhOExiQ-f3F$NDRUMb1v+hjq$tChpO!rWON*?dg>xuxt^Ri3$v5VT-N^;w-=%*o56Sd^l`IV^ zmDwueKMU-#XmM2tBAL7%jIgp(*1XGY1H(Df`ReM zqX1Zn03trK7eCDo>}UNO)<(a)n>-KmYq9zi!Ljk(316Q}pS-K*64iwvKto0g7eG7b zZX5|H0SEvsU5VecAJ^IZ_x0oYHyu1XIbX`?_tEz07SC$al*x)!E&#IQOOXCB-*?>N z$Umpb2QQ2hUK4gM(NO9>iNj|m80D=R_n87$KU>DL#v2LOeiG9*ei`$)K4oHilKI#r z!H8FETUeueyjiMXK=S))$;+Ok#pKS|TV+cX20nhz%Pi7f;(8Wt96+p!O$Lni#6SD# zVYT(?W$%CAJ{wuR;Xb%Fsq05!xY5<>7~Pk%v?j|H1cxfFJ2WDCYo&AbOc(#`<8NBO zr5hjJ`TJPJ?&UwHUsoUB1&BqxEgq{oC0l5p+{N7aLYHy3f2N0H&BS=e-_PkXgIeJWB=rD{hpW}?+!b$0)I`iSKk``mculb_V z8+{sQ?S79p=a@OPKE*xxd+vd3hIQmH&g}2zy#0}wA%%>347E8z% zS-1I$pjD*9GscOGa*gAQ0N+g=NT z0jGoXuk>#WT#A?rkVaL_dSCPM?BT_TJG{k4i(#yD+I6o^d+sypl`&$AfO`z3y`2SY z*Rqo`r=Ou6?h;I0ppxj#CpEJJfA$RaZAhi|35uO~dxyGA#k5ZvTBFI99rDIQV8w?T zfbbd92llL)ZWl>|1dg-_5P1qaCV%8q!}*)f1GdJ5qqv@|DJji!6PlL>O&=h8OirXf zFnM5m%wI(0{|!iw{Qm&bSh3Nf|4({`F5B$A4P9w@P>qeAtn;|m_NZ3FNGzFg?c$RQ zII`Go&*ROLxw2U4pRhwibZLXbr%a6>3>Rzs50F-yy%}q8msOMm13Ol#R6qaPT}>3*-klLyH6JD8!c1H}ujk{ST$|RAHCmniJW-u_ zVl{hOcHltA`wJwFU?1(!s~e)|#Jh!$-@5WW?56J5DdIO2p2iN0O?d z^z~zdvw{>PJZpYwJ7tx6F7NW}5ClhN_$Pp;r9zc9Hm*oe^>@kKu%UEb9c=3x>9S98 z_~_5w-!dzCMz%IeHriyi`bt>;I`gtq%#hBFr==K|&gbF*8xegw*OL2`#Z82ZdSxMQaSPAVcS(Z2w}h!!j2#d7x6Ul zKVOm0SJmHX6TH6YOmVeZ^0oRQ(57P9`gz zesq;Gc>e9lQatE%S)1zD1<`kc{7SNVm3V=|v&pnIZAn9L<4Kq6Ly~2>?aK}$N981y z-}1GY|B2uuL|USRyFGA)B&?d(hSzKc?&h8TvFIq73jWUIlM6ukwBK z=B-CcKN7SJ9U_@Jive+UPUFsHTQDCMQRsxTJQVOJQ?`AyjNo^S!qm#``WL;e#wXCR zLnq7{cf+1!F_oMf^Q5K`h7+`YznpfM8@^EYfK*qw@<_GlJQ=5L!pIX&#xJaalx_eZ zQVU;gSC7eg;Tf1HSPVuW+=#g23nA>khC5&QPO6YYG5iZK;J%|DIvi(k=uR98r03*- z-73oEH>nQs-Aub`1jT+`i-?H!70WNrsCu{|qgbmLvv5BOc~9Qi`_nKbh`N{$%vr7% zLpK+Qpz_d8vM0yqa8H`e^C}v#^jGvlTmX&a`Q9N=kC^p_FQI5ik!HEm_C}?nqmj;X z=KyQ&`!t{Ao?1L-F|9m5*n!ry%7o*M0*s8dBz$b0RIdw%m7wzClRM;#0zO3B27^p#|i9Nr1RwukxB)7-JcN6L^y{*wIZ@KO5&k>XrdlLX_ogdW0=W}2L*^VTEL zSND%ZuprH>Ht(NXs$fyf=X<7nE9^t4+|#+46LGzwB2GslYSBpTmeQ%$OevWb>$OBt8r0bq8Rn>I?X9Q_7#(eD*nv@G>S_Z;(x*p|)f2I{4{C9M}H zD}Z*jZ+5ut+dBJ6zeSt{bHyTkY4+X~m)}=DOnZHv3JO;uP3i_|HC=52z1WTtDhes9?`<76@OVTK!o^Nu$i=cDo zoKzHiAEs#khdSC$#tIT=ikT9PUj%VPbXTkHsII54Z(WF^ zKr)8L_)O`N&yI5t?9a0!ht zoez!=t6;Pmfr*%jKx5(_1*B;h8O^df_c*^MU!A^)O!OX}g=9l467m?ngbHaA!O(S* zLrZNU%!~>5cX4gRutaq^o753|Slx6mDTq_0+lIrd73SQbbhRJ$1{!r2=l10&2-pxa zmSjm@Ks2TfP1SmSyTGNIuXcnutT28N<_wOl6Bf@Lf0sJ+wy`E34dpw0e+cXmn`v_iQ2`)jwo8(`;cq3G0haH(pn<7pm}wD zLZ5h8C4V0}c<$Beo+~33E(X${0$(f^t>06QX+(V4qai;*7&B!p7RS4j6c7tI?+NCECJXV-PLikla-3nwV*baQBnx3b?Hf!GLCzXCX=u9EiO{s0McD{4 z=Y&Vk;(vL?KU7Ujsb*Jl6oG%E0khG6LU`tg2T<4$8}*D7{)QF}bRdSB zqj@ffYq-2Ys@M?su`KjA`l_>G&@ z*OAOtT*908VyzrsVbq~@Ovv&gS~_*;yD!azdeI^Gg}jICO)BQ6S+Z>07puE*t7`y z50U}M>EA4zpGg@(hgG{E2jh_on-U|u&_evdF)XS^xY}J$P51v|p-fjsLs1iZb5kJHmSZM zr(+`lXp(40kE4&OFgl7{!=Z%*5V;!6GklVYV=-785rai2u#k~ZWIsAf)EBj;iehoZ zYP3-cSn*4^;81AfWq}qWQ5CYV1_3Uf8+ixs;lYLVhH4I!yeTp7P7p22ZsQ=n5YVry zkZnAK0s$SgjtuHRXZNCchfoF#^b9HdDOw1>o-4spBqHP5I8aI}(=ytU06;bGf#-2zGaKUg&~lsUBtwLg`?=hI7k{%$fF@H z;2>Pi!8banF)sWW`#8c4wT45n@M1JP;$VgGWwBi0BCBXj4uar8t;7tfLh0*x3?ueFw15EaK9+Y z!0z4nZ{X9+>?)pE=&r<L6?6xHRIEIsT85hCA%&5W$5Xx!g_Rv*t8^pVDKA{U05yX}wr)bq zzDanRfaBha%?OcHfCNPHqA)aZ6mO}Y4i*KP`;v6R*-&BW=eaYAFp1u)E29BZ$7`cI zIPiqciz6g4Vauos3M1hU3i15KDO491c9Jb7z(X@RFxzbjC=m_kiFl_$&v2oPO^GvD z^#6!!Hc~<|tZnn?Epzl84zgWLp7>E4^k=|DrXDJmSd_CBAOL9kr-5>W*(T0aN)q~-yUa@>^6-zc zG%mO(4Iva8?&7hJtA7zGrEQyo7fG*y`_wuvR`Rhm`&mnRj+SWv?5HIAqg}y*Fv=PAhB_T{lS#Urz z-J-^uQZfQJr0ppD9!UM`aYz6MeiIMP*o=DmQ-Zu1JOF@IjKUuPP;aoplN(lsN4?~U zRjR`M(EVq<(4|LEFK`myxe@}N#P+5HvKU>A3l!3;jdSOlUC@QX9jBFuCMI(CY{a|y zlcLipUGE2!)v6z(Q7v+}L`BYsmfa8#FZ*?)7Pv?ep8~%z1DDH4`b^<9 z^4nuop*FNc5*O0LLy|1uLU|zr50@Sln?~34;9zV(RR;%_j^~26L`wgNe-WsncK|~r zuejjIe()mfMyzkuCPH5i%>^8OsY3|w6T8Mi>~GB*bejYYj=+DT9%Aru@CPNz)c#d4=$8ZRU-9#Z}K9DJ6E7*Gv4i3K0!!Y`o_D&~j_ z0OYeYcp6^psx9IKu3`#5j_e)>4@sO2L%+ZW0wv+qQ$nu;;V};vlKb6+Q28J5DpFHD zvsu0iu|0GAoi@7N7H$7hau!=7%uDqc4kOZU1rL-tiWmh6gq96ym;WaCB;LDe6ZI<* z9W3O{u`|J!#D%U7v=@!X>O>I#2Z+wtR)NZZjRZ7OA3eNpP(YO66D2+r9;o784-|za z<017(SzRyvooEBsiG}dGr)e z|KTzk? zqRo8;97rYr9Kk_7n?en(i9gsp`dl(^Ph$k*H-yB62T;>8uo+-|u?sxPM0L=#`@(JP z&>kXqs~!!xjjlk84HCUyLsGkoTPK*l&6^n@hhw4+#L5-1p3Q#lc2w);(R0iSVE6f| z+mh!PsF!%uya2l_Q+8LtS+MVZbypv8jyLnzeL*@;d~Or&qUtXiDd{u?z0O2D;dX&d zuDR%<3H)X1y(M3w-q-7(%gN%OxokeS<)X=&qDdr5Vq^?_|N4YSa zHqq$RaZvY^gf05HD*B=-G9Cvn=E6JBo!Q|iQTVe}yg1V88b}0jVITVL$N$<$@GHC< zg0|@wDX>%LkvB>u7n0DUj}~u)qK7Pn8d|H&;wx3jnV*N@*SNtmqy^ETFSr!+Mxn43 z1t%<_3we)ODIZ2Q5oWGw9Bz%DI7IrKDsT&Ii}y}~uS+#X#&v^7F<~3?sJ6>%j^~d^ z3L3+bu^DJurfVfQxehJNb=j$iud1RdNmM;mbnfZzV8gcpRq#D7=pwTRxCq^!4Wa(% zFG6=+9YmdY6omOw7q}u8XopU=LjO6=^st6~v_g+|z`Cax)4MPngkEWA_|U4yOb+fSJziZv6(TG1N=)U>5Uu|&ZO*gm@dc{jpY z?GzNHJp&KTA%)PmrO&_5%ZmsP>NcrHRN1!F*dRK~9z8S#<**Tevaa(Msjqi-JJYfC z1G%3T`ki1`!*1BSG--}xrHRSt)@S@{`g!&Icp0pta^z6T++82Jy>SnvoMjxd%_5>~ zGyLECG}xWq0ok-Zw8!@E#72*OdTYU!KQbx>E;!)dxqqJ1e+-J(bSc}B%$`^Tx@spq zuiKV`EMklk1WExvp2#?+dftvDe}FwVjJT6wz$uAZ9znf}?sbeMM@I zEq_yGBzKiFyA9X!>d57~Mv+U6Gm8av1x%1Cp!`pG6xa2! z)^fs`bckZx;I>X(ZqBU^^DOal=+is8J zwPjlG#FnSGRuE2Y>tKTM9Wk;#Z8^iZ3zNja9x_jNxg@wHGH&k{b78dF@?82;5B8~R z(i*C_{V(o5W;OI~JbqJut(Nl8m)=MhFVxu`eIrd&tf7gJj|xsQS$)vZ313z5VY8xM z8q`_swa8BTnpjeo-&*YoT*;EIl^=ddJMVde(DkO?wByQ^J&<6!hoV|0n- zW86p8>ryuU)xqMO?;HnrI<$t|bGI*+dlqN6y*h~Ph?NS=3)xbUmB?`_HAXVxWD~@8 z#1*5G=BZV#$Mx>NXc&`s<56hfPIJmkx{i{|{u(U-Cc%A~=FxmQL#IBZXZFNJ-O{P% zs*nstImIORv3D2sX#ADh%%uDmI^N&8?eyFX1^>jm(hH)EHtx@>-{$sp#7SY9e-s-X z#6?FhBYACYQtA+$O%If z>ENH-uPYa%PJS#gKCIcMATLoK_qMI2wzVSIx#nJFMjcopWM9pd$=%7nv9VQ=Ez@ze zUG)ckTT<#8{49=zSvP&DW$P|UG$#uZ6(UI8BaDWpnfa`=)hlA!s#{ld5A6 zuTxs2NkTJPtfWU$JQcSj2J4>;tvGbypjm<-qYQ`Hjn1d$GMR7!Qxx7!0-Ml>j$y2U z^5Q)Oxijl3d07Ga$R7E4rI3fjG#e>II^_HNe3Lj)SQp8hs*?WxlbnlG%M%3#8tteScoLc*ztF_Dpcv)oE_YYCacgCe@Tvv-}{D^*1`q*$L zIY&TPc35DQ>2)kCmcSebazw#iYf*B~&>jalk#{5b>AC)W`DQuJS{Jy{%3re}+WI1N z^Og@V6RUBsO0aQ?*;2ZI>uf%@g=}Ex*g+$uL<2<_p8PUNXbn()kjbq1{0^CndA)YH z=K&d~p~Tf}GTg}%s~3r;JO3>(#BNdLZ2aRQ#$B-G-NwmZLF|`=G3Do~1s&W*@sn%9 zYr}h^WM<}p<-ZfjaVCtwwJ7@1vG?aD6)w+SAKUHkdEWxCIBpmoDI?%hWj+W`$+fdO z!KD11F1MQlpFql6FsMLVVF>R2aS>rn7?K#^o*Pe|+4p4bnS-ZVNxJ)Tw9*enJueG} z$KZF>I90OzR1{?I-{`#FAENSUNvd_L0mtR%^HGBI#w5dKx$Esz1EgeeBoCtYpwMjf5t<5!WIt=^gT<6 zt32RD`zCSRyIK6(5~FHnUW@JSBzFh@$>&NM*didh`%6ys$?3?_;8UWzE&wQ~9ba

    E%kr*eGs-N1NKeMUXn76}Z1fWVxuV`OaG*wBkvqjm2&2nC$XdQ7@KgHYa$h%vJ7bY%xnX6x(nwBF)cVbXIY?m#uQ)m}{ z3&N?LOg{P5rB!oTZr2Hka*wg4TBd|z=u7xH7O2E$JU`|-OVY~v^-?uIUG~+)h~|PU z>=3|7Li^7rhjH|~;&(a6Z#vVJ!j2Sn*+t9tr;W3z+zxC+r@M zV(Yhxuq53L7~AVAHDu%DbsNbz zu)s&+97( zbPF6L&ir+TN<3xMY-%d#=(((0sdSljkQGZXF0%puBycJ%ZfQ4nEQyj-gNG&>zF5%s z*YDE6FG~{S7ZbAiTu3WlKXLXx{kZGb;`_}R+r}OtlP5*bNAl~~v{9)w&fhG}^ zE5At{Orvg(fp=lzj)F0=JKm9b=FSFMPTiRpE8c;oom zL$4MUM3O)(4M=Fmkak}AXWrExQLtqWXz3Ps?wZbV-V`vNu(dALxpZ%K$?Nwl1*{iEecaMagMCJ z=|FKe#A3nz2ySf_Ei8NVA6(RD{63jAQ}ZPCx(b!EuljO81TKp7`z{4mFfx4AQwbVR0Fqu^v?PFoRXJ<) z(%Lyl{M4?oMaIo_)dmFh1=R%Z}Sq?sSu8u(iAA<06Z;3eOijV;Tu+&!-7w|x;=5St(N%cxvk3agn}&k0be$CK@YxhynIsQ(s67-8Vqt9 zK28CEoTdBPgi>=BP_>dv5^sC7=Z>bNikiKatd zPSaE#`JRgwYyQY^z*18%x`}hh6nB~f2eiJCpJI!DjG_4OLG8<+N8k1&O+ATBXaH>k zS8AO-Dr)pxrZ8Mkxf)I2G38w9O#d%KikN;&c?%L`#YWk|bnzfkDDCAdMlx4lJqjrG znxQA8z;WR6uE9O0o{_VBi-oF#m2?PaS`G;v>Qn*R(uv%nq%252_VUVJ$X*xvUI$nL zlV*0Z&Y|y$vGA9ku4Sh#*^bze%Lm=aheVcxg;2E18gLRjVsqWe?}wqO%Tyaq1oa2{ z9uB#5%gfpTO6=aBwM468iQ4{y>Tp2sGHB11;7^3T2NoEpH@#{LgGhR7X9vI-zOy1V zWQN(^|TYp_QFn##PA%YClJ16^Z4 zj(&niql2(qf8KY3da!a#R;RJ_+&+3)TD@%}P35#5CfvN! zi|$IlIqN}pYivp&(GsVGA8)F!5F#GW-=liyF_!r)hkP^B;lERabD=Lw4$#3?`Ic)y z#q;1eE2D}}!oLF9@NMqTDNmjw9~pgCgaNay$7@w-b*S;+L6`!YIs_hTS+Bg{4)NH1 z#jX6g^#ghe=3YIWruEEra2!$r61((6@`Vem+Y=%T{0OTD#*8tWO=_~cvfdI!5T*;p zk;q0?Wwor(8<|KMMrfe*;ajiggw!3FBVs`Uy0Ab#!hi>6B6p3()e38dzt(P~iJZP* zNa~N^y{O-;@%ocLaiDrnR$efy;EJ=tqto{q=BnL?%BWu%StTznOg+wT6-&{*5<-0a z^fmlbAaU+>S$#Xm>K!P7ubjdyn!HYN0EBWYAYObb?=%_Q8Jd?}vzqxPn)+sKMZ}_= z?7;y=ao(03yGM3c=`rU>QMx&LcWeUkjXe+npm|`QQ(%7eXst^nk6U3EHW%NNB}6TogCh7- zf@Wgt9QC}jm=}w>=~ay0QM7J|?mz;B(Chyw)2zB+(rdv1dMX#>7UfecOtJt#@6?~# zZJ+~mUlg-O4aV~|(34;2v`Stn(rluddF^Pzg5Kxi$=_6BJJm12tnVW{YSXvgUE(R5 zW`b-B&+5Iq1QHfE>ON6Y&M<^85G=?vV74Su*8S+83i$RU6q9QwWW?gEq7sLwT9d^^*gSkH=JV+!ti#n!VR zP6^0~BNS5NVW8gOL3w?R)KUUZd;-|v0RY)yMsls3wH+UE=imWlyEZVd&MF=#{|Nb? z9kB-T##8i9Iut)n=x|;I;DlT4hZE=4Egkj#hf?dRQZIqnWwdfWtM?QTF`X>DrcZD&53-Kgh}3Lt>3S)>olh)Xzf5ZrE-aJt8z@XHuABsC!4+}FLiNYNa!*NgyWMn?%IP6ZhDxJa$x}ET)rI^ zjW79zbNLf}>Mraz2X3AKnFC-6KoxVg;*ExLcD=K!dqphi2oqta)|AA~Gfoze|FQD+OizBtv5yw$7?Bp+pQQc?M>k_90 zXFhG-y><$fc#>zEIl2$lHs|?dZu?o#8G886>U;Q*0IEPB-=7A<4i2XBKu``T`Sq#e z_hGsKpil?=e&9?o-(HydBPN*DR=cDh8Vo$Vdn!Wg{YAm=o4H%6B=NL-n|ZJeke<8T z$@slxJaRYJr43srr4{L@do=2whOlhySd3B2_t%4l-hx!&j24R}|3`*>9@QOcEJx)Kq1iSTQrX(jo+8F56$I#{^b zVYqIdl`&lPaMoVb_5IV!M}F;jGnn)1>nCfT3Pq#xRC;KTxWZ+D$B`?k>rt7W%SJ(^ z&J(8Y&+o>|r~6z=fECVDf_whn64jzFB%^aHO{agEf1DEn(pORxm)=rjzmJGPCF^g* zUNihuW25P{+b(A(Q%{tB=yLpmg=5R-@{mynw&LM`)vfzVFc$W4{zj->iZDUO+te>R zc7OR_e<_gAF+u&pe^RGc-^U9E%|g7O-B8aFMOC^?On_J*fO zKQe9`;l4SgR%o?k4=m48KLym?JP18GV|u{)!`yPYUfW+&1h)Qi;DLBSdtA6%J@^_l zK_|AGf-?9^zUPgK8!j>H(aoQ-2e7lWs)CdHTYV9mc=!Rqvs3<$EmXEwHB4R}UoK}l zJB~~_N#9||96(7)KL`{_>({w(`uDbu^Z!-YoBu=k`2W9S_T4r1-PqR{OSY65yDZH_ zmMDWPNrkj8#=d7nQmF=!w9TNhw9FuD7*bIxgNnA-h>DUq*X#ZHe81;&Zs+zr=RcUA zu9>-CkLUfqzS+7a`&A+osVngrmBM;(?Vqw`Ez5**^l|Yp&V02r0}Y_a{@mKccCt+r++<(Ln8M8*Z4){!MKB|RaPE{&Ji2>M1n;0+G# z*Ybup4=CoYBcx;30T6PK^WC?Y49`hX%H8F0;O|Z7B?y;m}?w@W6-aIzSn&FH|D?tTjzP+kNBVp%ae!V?{R4SJV5Q zF0C&1Iq@K+J~891azj=(_&h2E2JqLt&NF$`vJ*y~f*6mO!U*hj@6XY#fh3vdPRa(& z)-zQFn;hsVl8n>do%|nLG^KB`*dMPBY})X3qq>y0bLE#3Ax>SlndS5R#U{svF7qNg z?+(Ssj*Fe|CLNbXydUp$zUh~`@n>_!<&D4ITvG@B=jb~gv|=|vAZQ6hf>HD2as(M@ zS>v!?ZdGRvptHHsGbxf};GG^Y*~_cxDJHw*t9dnE?JG6(Z?HyZ_4NPWqi;JWcjfQJ zu|xkg`fjdg zd)W5l^LW#qcS8@`fBiGnSs>Be@(3J#&po>lKK$t6pI_pcfh$`cKl=M;dGYhR;m409 z5(u%}jRp71d@haJtHn-7*whOFMson2#ITF2az-nZFlZjZ2Sqt>EjzZm86iL`*Kkc1 zo~|OFxh>zY96eJg$&F)!YU~O|0YX#}mF6#Aj>-=Y<7F1PY@Y+~8cdCLoso)nt)lJ# z4-!b8&MTVffTfWzd%KMtvtn2I?hohV>aKsdkZ^Avv|@J~eXLA*vHRmC(#f>glN#TQ zCS=?kkNTGzowQ^dR&qzOu4Jz)4TB$zQL$B`D#iv$+wVBQ8_P_Y`dS+8#`bX>7==&FIw3fc&OJ?d%(xLxxinKC;VRgaEJmMFqAA0 zu+@BzPc(%%oohC8HpV&n8y#F1epPnB)mM;4^ShEFi zZ{NE*qsk0*ubZo5x4x;3M9yD^r$MtfaZqbsJ?xnbT;wh+{)43! zO_J$(&UTjwZStvaxSH2-B>*aamJMEi#};1b`$yU8c(&~tqab7)7wxd)=nmfAd&MRtVw#F1_@ zWH4Zt7^Ma`Lb*(d9$t0EZQA6qul?eN7tBidcUD-1#AUjx|tzCJ&V=@ zJ(F?-)Tv=sQprT ze1@Ltb8@zJc_KnKO(e};?lHT{BOdMTRF`=6I5npc3Ip3A$i4*m$HMn6DZ7b7epxDl-jFQAg9tlFN6O>+Zii{9;#3K18~MF>ip-g+!qT*G z|0dMe*w+n+2M^63?NsT2V7GBa(NE4G^sTcoE?^0>o8xZZz{vOFN-4lc(w(=n5Z6{M zlwWjK(}vDZq>0D0D$gPnF7XO8o^KZ9P zlUrwS-eMu^HapAICjtwL+@?;U^`>?W-<}oKDltiUwmuAUHKZ#qRx5`V7IbQ6JljZa zBq#NVGx64J2W(9%Eh86#%bn_U$~2u#Yo6A8Y1eIGC>pNNbvfTDi#|?>oS5EwPphlb z{Rg~pD4wOz_ z;66jlmaQaX!^b+3pNp5}`dR6SRTnAN_|>NC2XaD$(m-WgZFf4OU^9G1Hp4JUGg7Ol z`jfBxIKNxpazR?2{fex)oO2V=A)V)cVj6c;&DZYj=Sz=lwTyhb-zhc@W>$0>R#s%0 za~RkJ%qNdIlc@{02|!rIg?T3ag1B zLa;#+(VW^9**2EjhNw6esZ)Wq1=2y?u-)B{D&<(o?ma6WX30q;Rg&mhaz8tEC z1r>xdp+L0|Q^U7rT3KBpoAQ_mKbNEn$bc)jkZ`@jvu@B zX#6^XXAq3!3C~%{aw7y$;t^j9`bI5#P~}%j4xPIX%zFUmei7=X;FUQ5D6wv$o5G|J z`^i8e1UJqi;=9wwE%t+|$kQ_$8`(GknJ@vz6B2LH|Bq2(qlXHMl zK4vvrCe86wxMRa4QJ{E6{2wY1W48w$u?NFAX*hx|kFmMI#(xUf@G&4+ygqO&2QawL3J(Op zy;`cB+yaN#(&c(v?0Q!$Jp_q7WeBVU0q+ff4_rd|R6?Ld9Et(YpyS&3hoNbhV~ak* z#2uHIm{N-Ka|Y=B4U*82OC84lL^9vo_{<1#kXVG}6fjE#cl3J@BiL&cR2l`?H;bvf z%Q6xb!x-34{=n0?Xxzf#4m)6+ocPQ(0h}w&P>Ou37(%9l#Ghaw2?9=45SMj z822nOhakXwi<3+ASNXFQ=%oS%LO_!b_aP%oen`hoorf-*$5rJRmDoW?P(O8|HPgzV z5#>5Rc59Xp4;_{HOa?v+iS0}@kBi%Pbj$stv9PqgqhwT2De$cVaZV1u&{=^KReaGx z9b#XAlMau0U4n_A!F)tA|KBAP!UDNRoQ#o(N-VTc`S$i#jP6o>}@dGiD&jF-~xmMvVJd& zJ*@+rCkLl4$?na-Zc&gKpTe6XJyX0cqeV2!dEooeb05gq3bEzz)CC#Q6#*CF$K{|F zO!t#<8)qXr?g15?8dpKt{ROEPD;$^r{>mPh?7QSEK!%f1t(?o6X@uS%MGrACNM5z< zNVSQGI77i)q2L4%!l`)x|AIb8$4%V>Jm{!*y?E{lP%&k+NII-Wu0n~RR6gQhB2p16 zzlV>E7NUg|{3!ndNwVN(?q40YndDOeFxzBaL(uPP>SYDYm)XP{6g|QM>f|CG(*S&~ zkahnpef^W_J`X^8MLK}K6PARmR<2ccz^nM50ceD&AB>>H9b#orlAGMJEvB>qXbJ%~ z&Xev=5T8-dH>kKSemy4Qz(-qba|hr}F>B@Az<`-e57`VGgnNHkAg|$i5(}+$V=D#N z%0hg7bvrB(1=$VUeI*xYOZa9_8e!Vx(^31m<@lt4)%C!K#GAb;J~|^eh0NVK3Zxa3 zw2dOsw;N!vFltr=+AH8mh%9G2@InUh!$I}1So$y-$)CL>AtSFG1^W3l!X@SptML}!c07B{5zxOKv z5yw^}bNv_sJG$jvlk4w9M><{THmq@7D7P|SmXK2PZ*4_aKvbX?X ziY>L}N#*6TE$052`qfUH&sB!0qdRLe4uz0E{7P7%h)*y=>gP=d^BRv*+v z{x11aoR*JRxZ^heVnN8jugvDV_JmaCx>v^#b>hd1Pc_f!T8%*nd{)x+FQlti2?CwW ztrq9c@{MiP6h4syk3YqLZ3ye83Yf&_`q6gcXZpWN?YVp)TI}2fI1zVf5~8-h+=U%t z;}>RjXuTl`7P|u?Fw=Po-zSJ4*x50k@SE0;p+>4Bqw!uM;20#cPuQ};BlNMi)e1+p zN2ASrWYj;&zg~F}9YKtIPONsr3B-8iqMIE{1a=$X$3eTi-vpU?v#;FeKqWcj%kAbHlfipYiFzkQ*O!myR1{Py88q$f5uZ8S11dZyFa_3La+wLndA% z3na!#aZ#b~CJ`bWGCZ$Z#I4K3)KPF!u9|;L4*V# zrD_NA2D5I0`9gK!T`vhd;=*fOC7fQx9H&>0F}JssB8biEL>4)jVg}xi-P&_9qXy9fgIddz|; zD={y7Q1#Trth9h&SRsIyAoc_IvJZyrF?=vXf-||3O^}a-5kd`_gJ;0Askm1D%T~!> zRr`6sY2QiM2w`%HruZOhf_e)o1>Q=O|B!;<=&)!Gy6Y<;C-y$Zf;dUXJWd8&AedGT zP6em-?xv4VSF*7pF;s3|Zxcbt9t%U^>Vz14l+6HnGhqa!vM9a3u**+H15SZ#$$^R{ z(9OaepO$_USbu{w@f$XtH#bqJC6acSp@KE>HArmR+g==)cS7(62I&1>4(T#N==a;5IU@Z zWI{h|ef^yI6_w`AquwU);P1}jHg8nCcnhdWWR)|~sbti;12c!KP^A=Xpd!iYu{wkT zQ5Pdl(&I+NKQTNkdo;sL8|7aywKoFK7cad%&`%)wCD1c1AAiA&JloAfA}2J}DTqWN zx*kHv2_jxyBfO$xU4YwY(>Q1n{J7ZZ+0+HSeF`T*KRff68mURL>Tbx8N_vG385VcC z6V8fZhNt-%`VCJ?{}`QJAW0$oAD7MT`5{kQ&6F%4%~pTSNJ;t8QQ1uFPGZq81bt_} zeC5a0jE5nu#S7XISEtowU;aZ%5RP@2%fut3AQtc;GNbS5UzZ9>M5BYG+|UP&sB$&* zcX6@Cbz8u(?r2m%~!=wN~Y(@{8z7q5PEDMQ?>TFK3kZt|fiE@@Us}*DCX$%TdyqM_9Yc zL+}Y)SK0mB#jf(C8c06#>2;w-=IFwQE3<1BU{7wdk)C3M&2Ni3#X#NUhuX!~>)_NB zj7)WGvJv7eGYpfhvhR0wwrhXmc_XWh&Yy5z7M+`ue60GCIcRV9hU|+O^`Me_f5-J~ zFSFejKKN|xGd{4z33f47&)p!{D=$(qe>=-N1Twf}$9^EAd88M)BeD?@icWy+3$^5{_` z_l(ND|C63~=_nrV_>O-0~0$}Vq171J>Te8SJ?7xmqD-lVdfjl#pYvPpi%yEotOB)m0!Y=H&oxyk1T7cY8W z(U3nH`3a=w_gfI+g|AbcJ(8u9J3xB=swvE9s|HBVJDyBmB7pS#w_Ei)ke)BF-~B}x zGIu(ODVeel2=!CxyAh(Ugx?^i$)wBkXZ*>Oz}Ob2V&t z*HCx`p?w|2qjZ@+B=NdN!_G9aom2J&o?h^-emH%Ii$gceRpir22-WzU4M2p$7C5+ zd)2O5VfFVM!RfV3oi6jCNS2|wZNBa{ih<*oUGWA?VZp344X^d`pu^o4W?p^xjC{2< zv+Hl==&oP7NFKV!&saeTGX>QAo(gyVLsW)q6-)PGSn z4>*-pd}%DWuTW;H38o35_$4}SJ~_-fdwDYR-dkJ^1AJzuZO$am(cg>Ph^ zQ&WZWQ>UkP^&zQoWe=qJoa(FpM zcs+&>Z8bn8*wfWe9CRja$xo1QebQcGJRHyhP0etRpFxVivVP=q<# z{1GkyGvi3x$TodqQjInp_ul_Dp&kz}vKpp>uP!8Tr$MK_tDER;&Jp`^wVL=9zn{w5 z?*L17D^}gqavJ-OZ>M6>oXcaDGj4l8H9mn3??)PHD2(jQK=r+IYSt>)trP_u7l-<$ z+Z1?}RpCl=clzRMWQg&4F^!b%6u=H35xZ3D!9l$QQqpl{5}&a3+2r^k=!K*Su~GP3 zhEdEy;noub6$zaKl~~+ME`-UqgA+ALMC_O9#cAY}m+K*(^(C|KLcK zcD}kr=5q0$zc3}qvb%i@h_;oSrJe0(oa$QenxnI}g%_usvPIZWgA3phBFt1S0vlzQ zpVp4=A<~2s*5?}`4p$s1YDse3-G%O2|IzR zcTUs4q~n6Eb;dZ|PS$NBdnr+e?MzVNcE6vaKesR zo5Ag}te_R`UyV}VE6Aool*#760hwbJwbXbKHg0w}=PB29;gBM6OQuNkBOId(m$Co* z#90CRJa-iyITBa#W?)5SK&k5ER9BL11!p78TD; z*XBpdJi#^0Q)2smSEhkkj3>%=40d=|M_fDS-FQP9u`r^V*s|Pc6arJx7jJJ(Bk zZ|sy*olaUho8*<(vA>#HxsEU5?8WR!y^OL+=cmhxJKi{zM>r(=MahL0A;$JCNE<6< zO2I|xN^r~Umus*?Z*;oN;lE1aJeO|9-9mftEC_MT&SNh=7g(Q4%X=4=TgYv4r96@< z&S;s@e4*#w)ocQ2`nt!4m&}~%0DpY321$wIJ17nox#7&G@};W1f4K~-%c_?Ac~-{s zmp{cwwX0xAFM}#WBQ0Vw6>8^P4d@~)e{W_Q>0aD^otq`Q={l;T^o1SVlA`#oYNB16 zP(xpkwX%!wv!w(-_9Hg=JljoajqSE0ctSDMI#aD4Rg{!a zBbUL4XJ9PTGvlhk`$x1L$jS4pZ57a3iEfmbjk}qQfk!`b&n;{vB*ei~@3K2d=@2Ep zk00q0I@^BJswiV_+nsluCzrJ9V$-?C+ENr2mClu!TdPqS1B?^z(+InjV2PK=DXccV zf`Hrz>85c6`CdQ9bL?4pg=((R+EiZ9xsHQdd--Va!u(h&i@dU&;{@+0&JCWHR?*E~ zj@NQ2QnNdy=zG^)srOvM>U5=dp0l#tuRJDyjQntur)>%?GB0G84fBYA`HNHV?fg}h zSqXgKk2O+Za9QLHx*a?H5jQ9Fi!&)>d{Tvctjn+E3;~rjZ;XCONH&|+bfxCv)=H$0 z?SjXbLo)x#jgMw;?^1@|tbZY!ATC^kseVZq7(2C4xOp66Bv~F*M1ReX<+x}_C-vk! zv?$PFSLp0vsr%IP3d1>(GAtoXEph8K;vi189SB>v$IYo-(@}^$eoto>f(u`RDM;u~ zs5iMOSxYtK)$zlw@fLTsD8Y8#rPm)Zv2-ffTJ~8%fJ~_wAv~a_A=d-F^8J)MUaQV` z7J8SRXU%|pSC5l>PJ80l7%;ySol9ndF4ed6Y?IleWW%>MYGEV3-qz=2TP8Im(dV@a z5>LP?Ih)$BYZmFpO}aGw3_KtI9oe6AGdK{cA+D2woBim+Fp z+D}u??*uQiF>lDR$@(WG)Dtifah^jM$T)%0GC}g>68IG3C?eP_)V?dzd1if3qODX1 zlF8X=n}O|(0>n`ByFte#Y^(&pO2{zKg#u%wF7>4R{YgZoVZhV-Isl&@<#ii^<3Zw4 zylnsp*VE$zt4dVXIu4CEni7G@rlZ^dm=+(FPsbWB;tYBL^*{hLYv>yQeZPQqE)Cm7 zn6}2{ZIk&_C8x9%x!P#~tvYNUu2fr>vVfQUu#i}tv|vK*lh74HLL z@(E3S@c1=CCmk@g19EkNCh8$5FD<+gndS*FsdTtNn++j68VeMq;BGHUf4&b~y1)C9 zJ}{V=SwXdv@N=D(q~DUaK7)92Y}TLmCsngHpw^=Yv#`&mJXC1}{xkZY6h%!N>7W1R z>~QUT{5Xr1FrE!1o%jJm)2Z4A41xR834}CEv^8L2D6_u?(1_D`(_4Zi9fi}=Ph-(3%UKLP~x0vUjPDy3}VSw51s6+t4n zx&ekS17D2?^5*2eLIOaf{E3dsCga+<_*aIcZxo_1v6Ns@@&tyDm;h>oCEdY#BXOiB z;?#{oz>I|mqagntME(V7I2m}8j47s*>}&z>pYiRC4R2gF01@8ZWWo?D^oMK=idPI3 z9fS+Yo{>E!_*qIv&sUt6pNHUDW^hB|^U_kWGkm;i2yo;D;;R*@nu6#FHq;~|BPqz# z5Fko;;j)b#RD?|m$tCcRiF~AB3D?K6XpxU83vnV?13oJW;Re)@k68&L#1DMTo5fT@ z+Sw7r;Tee-7fLO}@Zbq#++F$>=><&lgh6wsl+&_wBuLo-Qf_-j;LrreLI2Wudtf}uVM|^H{yMO+Pwo??JYS4y0`NkBjgvYF(&j}- zWMkrCToU{s*$$5)eG9pm&eQq6BE3Ey_<6AO4YcUb1SuuT1MHe6DU%%A5a1vDVSqKt zk0uy(-aO0xfbr_7+a?}WhL9RJ6 zeM&NQD*3mxr&!vy^eeSPPe;YI)ZkWN zx3N+IQ%3*R%~<__Un0W)c|3`M+1O-ohz!K?&$UbD&q*k#ljoz_`){ZTE;H#j6&Sgw z_b%SQH%!djJk?d)$ERc&qZ*m`utT>HBL(yl;x`VF7A8-on8GPL zkd(Y-=OHI2y{w=Az67rdx@mL=y?|&08e~d5D*otb8_UK}fEp7ZCJ|9v(6({&ePk#} z`>Laa+n{A(Gk$kaYnkirqVX8#{837T+e}Jemt_`!e9<7!R^In~Go6AwNh7;JZ)nOVa&O zrqdk=Db(Du{G3)++sl}G_o?_@%3m<{5BvZ0VHM^;2GdgS>MWy+9b6j*i_@uRYCzy z_Vm?x_a+9gkvuO53Zx`q^!mcy%VZ3$LsY1y@6NMrv!#_ zn`ElTDs5;>8Y>7-+Ec4|l8ZEj4(ss{Ax-iWQMR}PwU;A0NgVHyTx`v+)>RDbC17ryZ@?)0K(tuYV{WQe%8@Wa*vvzix~0D zC*mbR3je%;K)eOK9e7z0M*1knHLK(48bgg-vkr`E<-LS;7R{Nk9!TZ$_TEWblF2bAGR!;fM~7H<3ac zuPEG@(u7~|Cxoqgg^mzldEoahp>_~}nRZnD!Pkhv66fA7p;zb+=PZeX;hBUTXW8ax zDWMJt5yCz$5D;FmEFUo)Qe^Q-M*tz>&5nvubQ&wb1h6xlgjry=^yM{jieEwSl>ja? z=Jl>J!?$cgX(9#Afb09nJb$XVwh@?Q_Z<}ao-G7amukrho)Xq2qz%CNiK!N2ZZG2N zfu~3TGL=*Q)(dz;CaCd;sa&gdD2? zCb~)`z?(0*1TNjIb{v(=xpvqY=eG~oIYwyWBI>af(T+0mMEL|q68{oVN3pj2O3KHh zoNx3hM_|va%)S-lr+UCQNuLg<9|d?=4+`SQSKmKAB0S^srjboUhB7hgGDkPdoZAEh zV*Q6$#a7GG$h`(&rc|KQhXh|!FtKilaNZ_u4-TrCBDA1=C08Y{ES6%boCPA2SNG^I znn9fvYSqf>@Q{8fZyWwNFe4;nufc}i0yBOxKBsT#Gf=7AxgEl# zxxr)6=J98X&=S1NAV6ngerm{!IU;sIrk9B_U9H~_GM0!^KUFO3-@i4e;o_alrn{zo zytgh^=D~TlHG&cm^vQM3O=TNmkk)xw&sZvq<9&6T5s92n>`l8Aogj zTZT0fP`r^Ea>D;Lc*o;)W!rhHR;Clg(=a&1`i ziQ6fofwT>zFFbRHyTXe~W{<`{< zHi4=dS2X9yAQCQJ{?{YZ^xYT#;6m-}dO$ZgY=h31CmH-eisWlj6_CvKGJU3_7MwvpJkk%m_;&{V#uoSQ3|e(#^}jP{!=rLZn15%` zN>$|Wp-THtX`yhly?zgm?KkYYwddWb4c6cc+Cy4$J#GUCa*NH8=TCz(=*NoYkFRV= z{pMz{qx$8$;dgs}u0fD-0Y2X`aZ_owysW8oyv^KH2H*~YT)DtF5eRbYMcMxc_w{rE zr5ki#Tfc~#DY64W?rF!Lb2G(Mq|q$fRbe;izSh4Eg4_>hU3|9K{QrX7QwW}$VnQRP z_HfeWm5ePGBO$TpY24aLYT`E|{cxyT-4)KRL)$Vh=Ms&9@H>BHch@iv$t!{&_jhgj zg+rfqvomGn8a%?wej_*%mgxC`E6(F?92Qd2A9thqMf~SmEgu>_-+u7()8{*Uq{$a< zm%^Se2@M(rx;4>;?U6>3!tcd~u#jp`ox64eH6}GoXQ2j*`n_1MHSY6_sStY=ZCs!G zy`XhNzcbJ#v5w3&>f_^djU|TAUgLqe*E6Pf6C1l#PCnJ96gSUq#p&-)u;^{aeXJKd zHQ&^}r6&j|tm$Y*U*($Ar+nc(k@Oby8~4FaeD7%nbP67d?xfocIwcv5^_jgsH&MkOKhoVrZzMs5U zyiRSO_SfY%w*7kNb}Mx%*0NkRB|o{@+P$&3Q0`z#wfGA2%@@s4adu>wGi;tEl9sSC zS2WJJq@B=FuyXX)c>zIDd?GLtBeF?hqplHq{m7GZ-BJ08c0SBVnaM;?Mbs!Ulo~HLB^5%cIrJ6udpAi_Zc5@Zl-6k3=VfM@8uR1E(IXfej-DD?aARLEiePzn>5dxui&NnzC=eHMYnLG` z409&nG(JP&N`0Is!rA}M+}(A3rukakhxC=vyI_~q1=L5>XI5%A8_5w!3(AGYO{*|a zmhzsuEA+xii2_{K(NtC)osKZ_tRnBBf7#9WLyA?(P{%M`tEqQ?E}HP{b4p%Vv z@2iAL>W{cQV&#WGbX0$IqkF&hyh}~dd3SX3aNq6&GmR%Zm7z($oGz~x2OB&fUpuzs z6f?xGFwjqa3~|`VBYn;?nnFy!G1V_j+ES_}RnY9&J!t0_kinlH@%iFwQ(uDL4#$^_ z*qw*QQ{6oSrWKnvdXbPLloT*+iNi)xRgV9f*!{ox!O%YOJ z{hN;RPjoIhbgB7^6p(H{7Xh#h`ecIFikWk2d!uc0NAEyRy>N^IpcXrQe_BESh?H0w zB9s~-MHujqTsE$cvRRVoV=R9_HAYPsi5Y&Gh^auB#K& zxN9)*_neC9T;K)+02L?0;B07PCZI|(x^xV;ftM*cWQbT^nuZItHjV1lK5Af;ch7-& zVC$37Y}t}@L+uoPWDX$62{P0=wVY!plZ&V2rq7YH>w&x@xwyt$bd)H!FpkWQ14@nirH<7njM~#`6q4b>yW6^S#@^q79A2HDoCIn778ha%Brjm9@ rF6%y8yYyT^`*Hzasj$PYuq(K*`$%DLMPYw%@}rhQ1sMPW+3k_5Qb literal 0 HcmV?d00001 diff --git a/media/gym/pusht_diffusion.gif b/media/gym/pusht_diffusion.gif new file mode 100644 index 0000000000000000000000000000000000000000..2c012904876bd8131e88653578b4ad7aaa2fdb4a GIT binary patch literal 189800 zcmeFYXH-*Rw>6pu2{oZgC-kB~5TqvrLKo>>RGJ6~0@9m=UZjK~ptR77pfu?yO`3F2 zQ2{|Z0)l{mlw96(zVAKd-gC!0#{GG}XY3z)jJg=Kif*eVXAPo9Q2yIGCAfqT5|b8^R1lI{{3J0q zH1}g@VHe&m6rWy!{}de-@Hs3pE379eTqZm`r6N47B)qsKyrMgzpdhlMGb+6?>e*CO z_RHv$yy*1T(b=zJGG51I*TfVw#uT;1)aJ#ErpCT_6~Fy7{@3M`__UxdA*UfBuQnmS zF@g9dp`an5urZ;qC84+@p`<No&$pN^)US za!FJ2bT)z5NFcTlidzV!jVT2!DcvP0+bO9!&r^x5sReIRYY)qG<562pVhtjP~Sb>z{1_| zZm4PUyt%8d`F(fm`-wKIyY26X--#J_vT=2;b#|?EcdvAHue|SB+~`^9>scA>wT$bZ zTo`=lIY=5B%6mP`sX9C|GCVRla(N~e#?F?F|O0o z)1N+l`uzFxOu&CvGn_JiL|o3zr1|5w#tE8U0q#U zTU#e>ZdBK9Q8R9zo$c%&{k}Lo2#!3wYk#=Dd3bX62d(vobb7SAcT7fca(4E&x&80o zzo)60rJc7$?x0pq2MmMZ-ez^WBJ$! zN=}`I@`)m?G|@Xl4HZ+RgI~Azj}m9<9$3`7%niMH`T4a?Pdw+%#;Py%PE(b4f_$IX zxI=s}##dgynrrjl-<f!uw zOa0my5%-kqR%^q?6md=6i~7V;DG_A!~R!7^>uZ5ncq)fMS|DP*MQ!nq0y$uQ28ft0E*MIjm zV-jV*Edmx6ql*h~I3^Lj)&n_(ERx$t@6*h6!(c1YLb{QgE&mBv@aK3P9q~Oec)Thmn z^Z3&Vd#>+l1$$oLA4~T9C*-Xune>z{PLJ?hl@AKzzYaPTJ;qR0WT)y?I+kR-h;uHr zdo(1HnfE0AetDshwo8S6Ui@Zi<*Pu4m#=6^6c4MEM|FNCHO{}Vf7LoP@bI-7eIQ?r z&xOvl_&%(TDAZ)ey_=ri#FuJ8xF=f&>~j zWdc*E=6xS6y7(e%J|G((&kO<4UM`O)0_Q+8m|eit6pr z+2VW4TozON@@RNz5B=3>*0ry$76(_{GSL_xJXiqNMX-m)*C`)38EXrq;_Ycij@H2? z0~3zz$%EC5dz}C+211YI#qfSz8x84YGUjxAX-pDGjl_a!P)GoPyy5!6v;i2s(=F0; z9SES|Sipl3Y93e+gb}Cz(Se<%zT`BWWUK90T-s6n2Z2Axo(IZf*qe*MHc83yla z1)=EXv}6d&z^zX3%KE-^M?ufe{hf}oB!JMZWvSp*I(~fcc2kde?fbF%eOe{}YzMI0 zeUoqkBwIGnM-TbAFAdP1>MCF=sdqcSP2YZvfj}2#(Sdz(tBXkv$H+O%d%4 zn+F0AAP;^7HyQucU}nG4up{%?&p$ zR%znVdQ(jj4Z-`6s5wEh6K$>SPfk#KPPY5X*6L^4Poec{t>@a0?NBkW z+bbmO_1#Y0Nw3vjm(XVA3yxNy4lD0rnI*;=?m7iff3?Sc-Y^Wrr>lH*fV0-_jVl}< zls$ss#2O3Q>-U6;fGfg^IA`N5nbAC&xqb<09&*XEgR-kDLK`_c$YRQa=PIt7W6Uno z9NP_L=I0xnJBaD{_$lml)3U?KuIX%yp|xIXj7f#d$A-H%UY_?-X#DD;^-)V@{<#Y^ z_tY_>+jy1jdic`eo6hvpznY#RFQH0bd1feA4s?%?qj>wq%?C@FYWyCK1J*X+D`J0M z(J>eahfc(zNX=ahr6pB&&g-=TukAg_b90U582a?>$Dh}a#y2^s)LK_3m)__LJiL1@ z`LXiVVYB&1w=v4z>1tK;n0@>5Wbc?ng;`)**{vO6VJ{-ERn}oLBvsom{w~o-Iw$Zw z@nPoAva!ksWryf(7Fs$=F0n^XrLR8BK5OH$b?I&d{@Gv=w)#?`Tf{0I6!YY?cY#Eo zQI+ED-Kz(y#&Z#M+RjIrW(YTVG?&Om7XQ*|l=}38N);Qbgi=Xw`N>I$EqkZ}uNN zSD4MK&-+YjURUqsbm;_g?%Kjbkr0-gGmx?ki;&ood)AB+H`M$Mt;l;fgBx9ubX5x! zAu~N(u&@|3z5psF>?KttXk=h%sqsid!kI4x$THhW9YAQ{FiVV4#@oX9Sbzc!o@u`_ zs0J(^d$9C*%%YIpR2+C9GmK{gUG;aypNM152?puRNZ*Pq9n*WNWGOqlh`?w8>4vec zrrbdvy$2##AJv3kEnjMx>ppx|%1nEw88})-11>TKLx&|K;v&2pz zOG1QQ{bT#{cE8{Ff$(vG=hIkRIg(6n1~+)?t&7wyfLv8L=7ZH}CBELtl}y%KEu6R!_a~duM4s<1 z2DmYIKm?D)Y=@e;QN!oy55Px7%(njE_Wma^6jFf@Nfr?2xJN+ngFMwd1OGLJ+Sz%d@s zztcv)Iv*dDg%o}cS;SMd`QDjX3DiY`t}j6P`n(oPgE$t*+zp_={*c>Z?bXS|43x3<8S;1{On(r5tZY$$n&VEqMXgsczOI$10rLivUvjufSGr#wb@ z(qGaK#w%<$_{_l^6tE_)O9wpJW9Ku+Y|cfW+~T z0AhgBk?&OkNE;8M7l?sr*&Z3dAFf8R^*Y_TA)$1%2es>K?36$*UA#@!_rs#*iOiU*4!!82Kb3^FD| z;NVibgm>PuCoAEa(Q#*t@;WjgXDxp#Y%+%Eit|XGnMoX5v3f5Yr#l()U6!2D-}>Q4 zv$-1e8Z1Z#4+$YgKkft{IFT)CKyTN8Q3Q}t4b|;P_^(|vHBziOQ7}>*7QmDhSG)ut zIR?qukQ-&WXF|!vYe1@4sI0}~+lUnDU08PC%`2=)e*G~OO@Yl!u-&yF^%Y88NB5Xx zk4#yJWDUs7BmFS}IwT0;Bie_`L>7SvU%W%t{H?Jplp_M^<~1PMagY1Y-TjH_k_%uX zKUY2HCpMj6UIf@s17V_(S@#+uEDY$|HehrXP=t0-q7o<+CE4$*uyx7<_6~H1q@WLlb$X z2FvV>FE%UXk(>e6VJO3eVkK#NdtLxoi{L7I?D3nVm25czMSi!Cp z6Ubl+y%~F(e;_%b{$`~INOl(@u$F$}OB8JZ8Tu1p@ve_+$dcqi$(_`xCwWNvf)987!ebd|D1q#zJVYR-P$b^fiI^us0FA^ss;U+>Pe|dS zotRtAK5iJ(eKcc!e>a6MLuMBe2_Q}iLsbFb+!*qZUFd`H;>eR?kBvgFjk_1k*I49v zEFAAxZ<;rjShE+=hdkb`OnX5TZ^=XL z!lqD&8KI=T3dv7l_chIOKa@Lut8kF=0LSY1Yb}8I0aWP)G<6PtoU1->7>tD zx-t~HOT=&H0{xX-s?jt&EHTRJ;ezGn73$@$c0mHpFC6jUl~S718ocTTWfL1%3roKE zHqn7VhQYrysi38$%nu@2@e~M#3pCRZEg_+z?WP@EW8# z;h}Ny#2=#2578iT4>A_=+QZ0aLO<+G-slIP5bO4`9|%`>KX*5k1-~L%G<4;!AgLs8 zKb_TpKKNQEkVz(s1(|nRT72LpZnAGH*sGB#H%ON9EmTIzKH@|A<;q|ohO||k)#AI5 z*-v$kJpyifG^Jtv*e09a+1_|(KqVNFCccy@fh^Yl;G$&%<|j0Es?#Hss0!0fCr20LYT{1lv1%ZKbvo^f-M)))#8cZ&B7se zYuSfp=Kw|wBuxyspgK%0*OOCTY)J@SAGk0kKz z+)5ls9D?i&B!Plh5y;n`2lx`mWC#`1X&u-)_|z^;3J<~opqkFb!hY3DKRIv-a8o6a za3|P`NFLV;)(C!+7vIqq#D7~2u1*a$^B|Ahg{BI6N*Z{o40B)<5C;bDlQzMrlzEF9 zIbsVG8zdbbsT^LFL0U3hkgN@vhe!YEYS(udCvFRFYTb<^zKz5}AN~bRb>iXseK+aT zHy0??u&G)LUdm?yZr3;xe!@pk6euKU{3g_9;ob9_&-+B*V}BD1mf>Fm$)s$+C=XB- z(W3B_!(X&J8SxO;34VC?zKo;GrS7Kc38lFQStgNoOqUZ^1#db7p%9RCl(%8RkcrWU z6%_Su+Th}Z6t5D+DUVL2jkJ6Gb4o5Ve|ge{GP{havyYVijl;?B3kAD)Z3jflDDig~(;d5MYnY+v)M zz7`O2E$G&@5SnYDb63NvuSSGijkFi(Zobi4xR~Zv{5Sh%O5&;;v&Ah z_Djy(m%Q^YM9!~;)vQY4Uli4@#HD<#?D$$W_x08J*P87s31OVyk<=dmG!p=t){bxO zbKl;cf9vF&?MBb`-kI$SnH|WT9qO1Jo}2B-{WiW!J-Ex9W=K1@%Q%xe_qAhgc5ZH7 z{d`V~hkAlYE8GCz-lbX3o!{)3-IiKI<{QevL{ou~`KOx_bbHD%X_jgW$N{jIA1;5P;L!Rv z%V|%qZVv#YXZ!6yWs z{-FKG^HcpPjw5jg>$OE|ubm77_xa5l)}e3nNF)21E?96sEeDp+k<|s#w%y1ToVhM6FA8Ll zPO1i|*u$tPgJ=35}eU-&2EAaYxS%U0m9=~kNegps1 zO?I*seR(*e2R^h|*Z&R}K!}E;k6{_eTe{lPW0-1PWG9fsgIfeb5GczC_P@P`(eD9B zyl}C>5)BxrJ3gemS2JU5O>fA2|0*{mtymUr<1uVtq^CWDK7u?;lP4Y2Q{MRL(5R1g zE0CVaA~C*6&Rre{kBJWKF6n#i8?MeON?H2q8*UdDl^1SLPr=1p|E8@M$8lBOwsv^Y zlZ38qP8%yD25yd)6Q684W4Z>G;01T?Z;r{oj9j(atSHO)D{}qh*lWz|4$b{!>7S6R zt~Do+<1vL3h$3z6+fJ!_);{uA%=D%&iiC>K)YQ|Jef}~Pw|-0kqA#e?d@PkYS6Z>GPg$v&7;HNQjk z5eWQ`(*J+KgcU#rpzvQY!En*jkI3)-cN^BzrYD+7O0az(rJyevq8JaUFf7(i=I73{ z-arYcWeDAQ6#2!oU^tx1IjNoX_i{%7_Sc5g;8fv2!10-gsSezEq)9y%IN-}zC6k#drUBEp_RiASG@0h@gqzbZ5q6!!YVs6-Mb$9wu zL%rAd0zm8vgV7??oCtVqZQE%#b9>Y4*$5Dn4I2&M>2?4xG~B-^lW?62-9IZ~Lw*H1 zPtxf~Ss*vW(IY+^6MULc63$RsMx^ka*3OvFgPqn-{Yklv6mJAH%kex-5ikf>I*H+J ztJBYl&+2^G&JPHY2MAYg*gd^_2Q9eE{RBO}EAT;a!qRA9sl0izZA^-{;gg99)o-E2 z!b>!u#%;kk%>Hy#YBy($|1-ew^^QI*$=M47JqW@^skJj|kW+&rM zcI)*pJ%ROA61&qIl^R)#0p?0GpN!$AyKHi^ww;%=x}zPKsn^`Sf1ldjdC_{4M!Ck>m(Wf1b85E@(Ic{l ztG-Ju;acsMWAJjhW(n2%E4B*JBWTZ2I|NIa-4Wg0Nvl&^VG2x^UoBpu65BoQp>3f& zS$G{lB3SAxR7Y2hQ;WW1$TdJ|nt1#>CanFo4?o+)i2a#yxU!r)^Zx}CQ~d`28x#Ln zO|VG0%nsBR^(X(Y)r4xWuNV^u~z%i1mETKmF|)LT>~x8y9@DO zoPPprWFSx&VkRjVkB9gi>?D%BweVz@lR{5x1=1F?R&F3UFqoM;{I^IimM+DBxlPRS~vmx7L;tf1VD$ zkNJ(?gXnef~9TPPZB_5ZO^`UZT5 zXS|xj@+z17YWpP!_S?a96iXX8TE$}#I4QU6@d{dWZXb2--+Eq=M2 z)2=VQl}hVw4NH&Kn>KCVnj< zmr7@(*->l6>x#zlaPrmMbE#e`U^tBWngPr|?aj172vyB00JI~Fivb3tlR^VTTS!rPr8~dj6JTMP{&-~dwF_aoW6dlHj%d=A_qd%-r||@V<`MN<>1# zdf{!i)~(h0A^E);zH*(BNpP~nNmaex+tZz&qjG1zzrB|JBP=g*^KP{dt6#xiscTAG zSw&mcr^16trQ+KWKb7~rmBy3@_HZ<{rjtvx{duDevlcg^6R2xf6UZ%wz6-1|U{<%J zT$LqB&n`voui5=EDA_I1u_8J*!URgFT3TgKF8E+vpQ<={;^hIuo`oruLsCb>ajIVL z2h-|Ha^5o5NAG!u5Gq+D{v~`A1H1sd0Fi&-$8h0$5N;V3exThPGJT>vD_7CgcDokAG++a5-T=(}>$L z*lsOE7`cFjz-W0<2!n-))><6<*A>f+dth=H5*v$s4(!VGjoZ8&R;-~wIu3v@*6Ml$ zfTv-bA(#L@yWGY13%Dhf<8 z)OmRh=r73ui4QzEvjEHw;%E~4T7}emFtZ>-7uWz8Bb2OEnvu!*g zcY;k#!WbMvn9$U5repH!>CTSNe>N|TDmdg>uF4qz|)t zM)edwvL?&z*gS_PB#6IwP&8N}q9-STKG8QM)m%;ze>!_A%5w9-MbgAT%1ZRs@RWhR z;mLlo@@ZC@{U|1Om5(-SwS5z=C>}OAu4`5zH>R{oFxJ0;GGh={l%Y|qdZ_*;qeA}3 zB+dH95v(<>frrART>h^`HoUQJXL?)pdvvyIUj1sQa)>gNGU?(4M=QYxAQ-VRWPsz-C?(3hLUw?!Ep>k_U{wy4w03d|1h*?ostOTyQ2@%92 z#|DMEfHcC@m|3 z=_;sNuPK64%6>9BBSA_Jn!5ZOo^sJ_g3#?9v4<;IIK~Mm>s&;v$XgZi-BP~L4M>*X zn(>NPJZac)#JEx(tY+^t+mE4tv0Slp-8fcFOkJAZ&?CBCFgOvzTXDBAht0)n%74q5 z;OJcw7r0X9-O6D(lEsUPlD%VwLKWw^WmbcK6z8?Q7Jhb5mx)mOQKh7=19(D3sh3Xh zMyFiz&HY&hS0~IIpTUEczHUdw#5$)`)s|P!;q?b+_CM<(8)+{kmzL8;Uw>qKx{dvs zTJ*E-u*NIBc}exfR^48CkXzf=7hbQL_6I(QH|myrO_Cm{V$g4Qd2qTeqbT)}kxyy_`|G+AUB;{gE6(Po~RJ%Uvl5 zy6CEbq`3~iql1v;)+=k%Pz$c={hz z=q4Fci5*|z36FT2NaD0GSf6{Bf8{95REP%{*-w9_aC{pZ-de)b^@q{`2n5~Dc;WFF z4^WMSg5yt4|LWhn6LPS+ee(t}?4kRRmb}-wA3$*AAdp?nNtO$(3rOJGjn z?<+R|bc74=lqTyXF?}HYn~9X(-ydx^7$=t(?ObZ~hJ&6_<>KfUdN*w({SRpMZk|N2 zVa!X1Xfvb4qV9Rq#fdnEXXaMElo!58L%Iu6I3!_O{_Mkxj<8>a08U57vR7q?n0GoN0ue=T2MA_w~J zFwBV9A0({KdricH8=Wb9K3FWPe@`>x>b=P{OTF9j&o7IU-Lme7UTC$bX*ssQpf(pL zY36#_ZQo`t|A4V{GIioX+y^bXv6F>rk>aF|)0&0uC@>2W<%Ggh$_F0oZd_HIsKk1C zl1m$ux`KtEv}`boT^`}?bYoVl+!${aFvZUA8}bSMkHYP6QW_arE#n{x>fbHjwg6#Z z7>T@hPjjpgLpVBnmWD-!Lq29RA!CtOurRj^$b4R`gkK9eg#XOb)Z`#l4AKu<;_rW$gqh)3=?FY+u(Jg3RGH0tQ1kCT zSKePfOwk5!*IyDU0T*R+a@NBJqDIwp!p%F>(y^Lv>*5S=qXu0%(M_)Z@3u znN8JBVJ2|p>E)uYa%8LEVnrOYTv9Ryw6E_LT+mCaNV??76fHC7`_G=Q)W@S&v!>>h z&F@dcSedxM(|c~yY$oh(%Nak%Q#W|Af8FwX`W-kM!WBL>NWLGT82qeA;?duS@D>w z;^!&jYUlkNH1AC8YrN(RijwG7w z3;J-DAz9(nL6b*ic>B^~p|B|&i;*6RgrmJi-XzN~8n7TCFq61WAVj!^;fdwo^k=2* z1HNP>yCFVW(fVO}BC-(n!;vAHIGKzNabvR6A*9$Rq01oaqjIxk!cG{H#{(yP)0d^> zgycc*WXv+bUjNz?+84=>ft3~_g*y%maK%%s27}_(aN1~Ad0}9ZY*VgRlJxx~l4T;g z_=z_IhB)*r>r$cG>!E9BHAcg?V{w7^b|r?(`Ye!y%A>Uk9W<}m@sF> z2#3*9`(d|jtgwr5m+kV^hM_mcc17Cf2eDY!#rj9rw*S1>)6lu^IgTb(vAZe$9j|x4 zZCJanr*OQAtLZws`w^tlf@QZ+0B;8|so3nIR4G5^sNTX{Ec8tEK??TZFsWf1ZRL_e zR|K0EqPv=sv>RJB46!uqq1fLU-XB-H;+A?zqKnBB5Q@Dqs;QhRMz+V&k)RIql3D~c zNo{VLpOmoB@QET!?8X#ncxk~@;%v!V#r%5<G5{Row~;1C#;mcI&+XaO$}QA zB5wRIQKR~AxM@0P|M#8HKVry;0!#?a|BfNk&Ds1HukW8u$IW!ay=W87UwOmXa$cLW z|2c+im~xydh;}ikm_{KIGD@3dPglE?$e@VfsLJaZ&!?^B1)6RZt(Be5 z7zxLr7&3v9WbgfkBQC$P5c7NP^b61{p%=Akmzk-9x-jI>5iK7gU>gCu2_j*<-dO_MsHAN!Nf*D**^v16J$fXc&p}jt9$Y+VN3D>4l*qFVP0e@$T=~+k~yKof2L+F9?<4^JixhDxr zACybp5p4`G|11Y_t9psB!a;G&tOgEjXYWtP7tR-2yF8_q^b-7qGTb4G zhFABx*Cc6q4^Ay*4Zfjza29Zg1sxp>C<}Y&#!SO}I^Oi(zIQ%AC5-= z{~I)V{xdWPNKEiQq47VMfRB*^fnu_+V*ia&{yQ`#ieTKLoRtj~#zeg$)yU@h3QUMm z_G)l*@?G=5t<{OP7ffroK&SKVZ);c^ZtHubxrTw^Usd+6%|O6^VCOop*Tbj|45C`n9|nn z8u#N_d7DL7fcN+n#kQ1&_sYCyJ;>XuS!wfuOs#8J2*AK_G)zCGp&yGO81(Q@v`blg zlH@x9ehmRoE@#PTH7KWb!y=T?=$N2NlkDV`D?GqM1O#E2kt*_$8_^3|5345nS)Zo2 z3^1wWAk;9MWL|gxQ!ncS5Mx94sPf(UqY17ctR$I2!{shiZmHS6yx^o6CtNU}u#{L> zHdCK`|EO4PfXj8YXrnYouyRBB1?7t|(KY;`eu?1TMwxVmoKB+b>$fDAb-5EHZsg^q zwjWcNoQe2UA@W7CpV3(9_W)xO@~La!%iSdyWl`*$Z%?N6nM&1Zm)t|aJW!Po$<*ru%AZAdLl_#Nx<@|*l)c>O>W0s4^{5a!V=#a6sBL~>|F~E+2Lu9a0XqLN4*cVO3)PR?1E~LXzr~+mi;MpUdYlZuqXSQ|k1p@GEGs`f zIy-N>GFki~lh*Bgs?2@ytusk=rw3YJrXP0AGJ}u4`1w$fP^jofi?XC_RAb}zl%L3Z zYTml(lkEQbpYKa-=#o5(oEQ`x`R*cGJiCWwLoarG(1TJ{b78lBP1Es_Ga~3@hl?k| z!(rE|A77cjbFIdCUeQRd84$7dog0PIvld-*=l-0L&?Do6`|}}|3G@35S6}vqnO!Yo zVm}7%y`F!IG`GlJ5eegT{9Vl29D`tC6c+ZJ7dn!8)E@>?f4itQ(uK}4w6HCGRO*#~ zt3Q%7aZnOP%iRMX>f(b^C$O7my+7aiy*H!9YBMnKL#Tj5A;7{GOo2ga+zau6gvT<9 z_Tts=!v=Z!xgIEa_E4v{*N=q>$ji)M5$QxicrLVsq4cty9_sSLp3N!tK^+B}FY6=9&Ms`z~at2fQ(>u@DPb%a~YU`@+frzaMurF(*-sBAc0VXC~+LjxxuPd z#^Gy22ZlbW!NHA;F61YSmvf^dSZTGjG?^s_48pnI3}4E%3=Kvn7W=GJm2xv-Qbk@| zBn;R?r7iqeOW5&8gi9rD%4&Lw~~)@h)n|NeCkq&m?D#+a1;4iq%b?k;Ti6^2fq z*a)>8N8-p+&KSs5_RAfrRqS^KGz3}CaA1}oxoNh%z$X(hXHa78j!Kwa+eJhyR)KbJPS}#eB?&?OEpW~0Ic!~qTrcI-;DP~8d&s8y09nhP zenq~ngAnrwCP-8DnPc&cUG_0}1SY&i=;O%!0gR>V$iWBL&!B57ES&%I`|k0*Pf zXlD%ZX504@|H_}SPp6D&-BfayaT=Ts6@Mf`L@Nct`zY4-LqnOMprPgsk$GdKQ|iNR z8q1m^0;}wq7ns!nIT22ISNb}o;#Q7J3eLhfyLB_+q4!hlMR2MrwO-b`!F})^S=wo+^cU(q{$90a_Ff zr8cJY&I)L>O%{Pygv0qQdOM5N_z`5<+!#~}=n8chI@2qbfn;41&NEYh)cy-)$w7uA zJ9)XNT)!!gt|gmA+5jk=0L)NSnAtda080wRN8%ocG8GuBA`RneG*ILsE`~$Dgd^0j zvCdmPQsy{Hr3Jbc2sIH1jm1J(#sMJ20?WZTf>QFgVkkgA{B@CTCgOL@HN*t@VMGzz z;4b7%v+7mBcIfVoE!-uch&~*FMe+f{%xLR?cM^W=qUe*NYIYc;#=97Hk!{-ak?`P! z8Ra}A&n-3xwn4FrZ<$ZPYoMC#WFUr2hB#zq#Q=)1#?np~Bol^Hd3m(WuMhWtr2u=} zZ#f3;2lj%+7u_tC+R%-&5%vu-zlqFi0f5xcz9JZ2V!dg zMj?1}$xguR-_ywC7ibD$hG5PCY$StjchYL}18FfN41(-@aS@3JH)K(c6-)TAelgfr zJ&42%>+3bLIdcE?FpOX5qSi+M=`2)eeNB2eCmnzgy{}^rb!-4xGnz_wzhWa6!jaMT z8mx2vdJzk5xxd1~;KL#v(ijJ{%>s~uNTBsZegtt@i0YVb;-AqXnbuENapS#8TEA_m zyqZN+R(E5rFFQjzgri`0Z6vc_Xw{@kM=)vNelt!Yj zbteL3YCv4enF#5F0&SM-QREjVc?gYxPEsE!|U8pGcK0_5I%Nsd*x~(KFjbef9|EPgtnJsA2L} z`0`cyFEI)z$q4qX>ou+C{SVCvAoeDQkkfT)so-4@PcaW1o@*S?|1(x3n3pn1SRL_u zF-a}Gn~t;_&SYXh`KYsm>(mBX#g|HNnPWqNTj)_QJB^Vdx~ltEi5h`IDA3Mfh?lpF zQi(Q^-!&FT2v|{mJdjNG6iC7Aq$0W=(Cvxq<=!OrQh@ejl$HJ!uv0Q0vZ6fuZfl zy=-*o2sOJ5H=4VcKk-3jt|)DSpc)_R{S3KgZ6M0mZM6q-XcPzw6u$0>2=B}LO0$yq zd$O>bXOiFOV2jjVP9ub+_Q%RtAY88>Oz$!d(uFy2NvNO{#U(+yLj^U`v6q-sgU=@O zx2+I+Nk6Nw60#9bHVb3IQ_pOore4QJqM!G3jtpC%lz`+?7JbVduTyM_ezB@yL23Z< zcj~sHpDCVI#+g(R7+r$i#!PmZ6a~ zurd$IrwbI0HRRr%PpgctTH6wx}k_yS||+Vg=qU6q)H&ed0g!Q@JFoESEKlz zNZNqe%He5~vEl_-xnl}jGye=N`ZjagZX!?4OdLNQy@#RdWf5e`#naRMOHtN4fM9?* zK<~e*OXz>7OEv#rdDv(gq05MpA#Yz4CoVpxJa(Z!2&q|V9e~Pt8%lM!y?^P>VKU^* zx!CUS=V3xOqdSV8UoSI^^SNlDF#fQD4t=E;{99B1-b9fFXOd@qTJAf0mGEJfMt5!< zf_c4Nbx-5yq}3ab&SuYu*s6jDwm*!s-?)84`2g-?fnW+AULo;`eLoqo?>VlSqDK5t z5mfx%zqeGb+tas&?4vL;n|?0^8N{5BU3?y6+)@(a&+V3u`U zT!*IXPmQT7OdL-5lPm3ix#az`!f=SXa{G*6o{tkbHrID;SlG^4`C~4ZhAI$>%=D-Q zzeiC8T6`kY9+x`qmK+b8)$ye++#Ii83_kcsr%iFS6Q#yQM=8CiEU35MOCvF}ON|zP zdu)*41L*3aRK#ZSB|pYeAX#KP5xtUZY!oT%ev!a<3h^pbFRLDxgB|y!`U6uBc9sdK zxwm_23D=b)A`rm{qtZymi$yhR4y`U)MP}23QWe)Y9&&3;6|z^khevwR!%>L`M?U5Qp)j)rvOKcpC$1aq>$PnoA=smmQ<M+g2hCC8st`M46EtY)_jFNkHI>r*7KfDM1^Q_GbD4QtTtqGY_WXAB%IcyVwh`ct; z4VS69yh!-&>}sD_&fj!HH78E4Nx`kNsbdNUhx{$Pi?5?V;aoY z3-!~}#lkfYn^_exk$nhMtg{9y8sa&E+3P%-Sfh-S3Hhbj+GSdQaX{Zo$@ha!KurtA z5Ba|sd-sQy|M>rVr*>+`&aKn7&WhIgTsx$bbdnTd9aX&PAc|wpl}0U<1+kaq2TeXk#`>vR3``49HfUiatye!txxCK)q>Fg%Si`Q*o55=8am zp83DO*0~8K9Nme^)ACl2g&y=n>PcrD2j?RKS}GIu7Ib-}d4mypgZq8{wzC#fVptqg ze$hu~fS4=d8vl-jCiO{?;6!xMDI#aGKf)zqmXAseuGH_wl3$Jnc?xh1_HzS88i+b$ zRWJl>l3s^Zov+Z-T7#Ji!&;?QC3>!pDh)M0W9)W*T$40`9o9e~d_#MUH|2tXoJ5bJ z1qJmKfU9OeTw+U0!!Au!=EQJ7`UX+}k_ZeFo^jLN+3Wj}R;oRwK%`Tu7)n-&Nf#07 z!#qepaG(_4^ud4&q}4BIy1S;BKyW(C#t6Uy6)H?!>l8su^8I}-SD+CK0~QFU?xGn* zo)3#*piLGNbvn&{Q}~`k9%M9Qo?7rzidrdlw6kKdPlW*<%lnnrlI-kZZ@WD%XpdX>v>Y@w$+&wMc z(SOGIRGnaW4;*SLe^A#|ogRkflvuY)vG4M&ou0}7Aj+E4IO#b*6DkX$19ovOpQMc@ zR%f(@ZP)S*hO4NSb|#bB4pJbgQMdbKqY||~4rn#ij7*IK1AZo4h(7tN9~i?iofRxw zk4(aEdGHxwI`)=EbvwFwDA~}12r^_|kQd=Nn2&W}oj^&&T4JZskACau>W}^DNfRdD zf^^wo({1iZVTxRs_uYM>_ zDw&yn>}#+aWFk7(3?)H~qLih(aUV>-D|_5F14;x#KbtFj6~H=*#?H7SXCUH>d%RBo zP%c%$HwyYJg0sM;HRC7bmc81MR8A1Y#l>;9#~n`N@IKaH_eP2cZB*!ru)6k(;y^zf zlLe*{+hk9+KnRM6h=LW%{RVq1))OHVi)ab7ZU}LOiis$-5`WF_(o}zw5a(&=W3$|f zyDTeuJ_xCz!j@aqauGNM&_D=))bz8`W9y6;#6c@B!ATShXT73mEn6|n4H4oozob~NKrqKR(A!RYrHge z%!dJsKaxrVO@Ry=SccN_N!O5z8;x*@*aG5J7yHEb*#>_`zXb0(S^3XQxE;gPnRIB` z?x3pEI_7Y{(N3&JM=xoN1-as?c^0pQJ@OiW;R?7WjS{$>JstV=2uEkZajLKogeq&J zlf#AOdr+Yqc3AM$TdM@i`M4AhoXi45NV@)a(zahwr&n_3AFo~#x_}s0Z9pf$ge$qp3J-50(DBooNbO-V2 zV_54cmX>p~=TEIe8+RqpArUr-D5eBu9q3C+E&XX3uG|{$_jE?9yGy6UdDv6uz1By7 z)iZZ;^=^?K%t86K!FeK!UGvuVd)7)^pv%*8^Zh23ED)zy)VsW2WLTDg3VIi%myVMm z2b6o?U%b5004JmDCqf249W1qJsGL|I&ee@&)m{F&-n^+j&~4EX+vLC5yeuPdl}z%k z{%SHZl4Y;@_MHjykCQ>InGZxkhcOYrG?EH$ zaUt!*QN4sH{VFz;=0OF<(#6pILf8hYD3|Y$)GlQCY}ShDycHeMK1}Eq35;$5a}R`O z4$=J$@NUi6ej=Hf#nmSJF>v5$N9<}FJn#u>9Sd|ZYC~|OWi_tAwY3;KZkrc?a9|n2 z8n`w}NMx)>Ivnp;hdD(7QJ$?`2MWqFz-KmLYSaQ*0djCg`z`SCK<<>9gd?*u`o-8M z=LB+h?fxvpS4Y0I`5I|3gpy{=;|pf3NXqVJ)`_ z)Rp(L1^R)-;Fbnjm5t}|gy(}#rTZ4xo_L{wzwrq_fO^^2CDHFV89c{Oj0cmDe7SBDLI7Cq6=pV*C_KS19Y3Ivxt z-D~^u1;ogv{6v^l-~xqV(c8K&|M|z|zt$2*DeN!7<8sDoQ@ZVynwRt2KPMexnmtQ| zKvrU%b}lY7YfT-x)p)>vFT^f3O3TDX{eRhc0z;xWuekg2;aax`UaBu+i0>s)P(tdv zhGUOU44kr-@dwKP@gZ+^&%?b^-2kRl%6#|2j}?%{-rSp4-eJV-x5klIvYgrg$tAc` zoaxWAFaz_17M;SceeWYp5*IrYEG(sw48srOv!`h}y=*AfdGQ*KgCxWR5%b2H`-~3Q zI2mG7adh||SgHU@NQ2V?oc$i?*C*$NJ?Zry-tH-Ju5 zfJ@ar+n;_$DcmJeodvYH!TaWVb)z^W=a_idYd~sFE6-DM^=C z!OX(5h!3`^rmsbu0DovX=--2@>d;O}Xxma^I8@b*vk{5m^%{SBAN%z{Xr=)*4+r_i z>*umKI{UMi$xqzOSB>_gDJ&YCfIa-1ujjg;Txq^TK*IUXXFbH6aTpU8H^2{PE;DdU z0rVQ}SkzWqaakXSe5=bPAT9id+bhv(#n^kIjrV=PXSMA@Bl$#DAOgXNW0x2=Jd~Z# za|vGc+5gO9^>W6yeHvRm-i47l*o-O1GYmsyZxGf_Ayiv{@UrO>gkRqun_IvWGYD8~ zomtcH)=0XA?Dp>`Ce)?LQaD3I`&QoOW(PCn&Jk_;lhO;-kl3#Na+Hc#1wHNYwG?Wa z)36Qn?~{_DV}3EQdslf3+dIat^*P5y0#tg>gg7@gEJ&eU_`uaJ^28{O{uIzeY0AlX3$U z*2&zd%x-PfB_`PFWa<~~v2MhMRUW5n#f(m#@C(lLoEmGvtQRoF{?4Bve*zDfm_^C? zyl(@R<_U>`rhDiO#h81Vv^tz~y5;a*=an^Dp_WlY99){XWJdsVOj(Jd*UkTPp?xW}psdedrXw@dB zU8pZ)ojRgNMoP>m=#;<=n|_zYs%pYLnAvJ8T`O2_-p9Pq&-W`|}gLz|Ka3z22|x6E;G3*QC}M*@*IV*Em9<&G372PkR*u1(j_-PBfE9r* zhNeT*i$*idEtQ3EgK)JmGQ%}_mmcJrlvo)X1^|H4SuWbtN1I$ymlL}9l0cUd%C=0T z`ShVwF|^7&9;iW~vh~8>UgFJ>G&{^;p8Y`VdSbE(3Qh%Ma4I&ON(8~wOH47PkJ{DK zM(l+iqisNewvx3!L(HI=1n&<>N}Je7&3zV#S&X7ezC& z+7tkcPd!gHma>2`Y~y2PrAs0*?w^_@2%Xq9bbLK7A^szxV-25p-2iQbV~2h2`eZD3 z=81iK5UTM=bLaCM%iNa_UL1L-d?s}SRU(1CI)dEd{DMLFQdV*A)X4pdc~ppn;)(qr!)nP+py$u$d~nr8?*(*f zZllNwC=Z+=1p}4=lE*ZATgJ9@hRzY=Vz)37a*a*%W)l``*#<)(K9~iOvPFA|8f53j zE|gRngZ>M~GFiald3>d&cC@N&y%x=Ife3R|d$m#)>cxpnTBPIqsQ2lO9!R6kv( zo>*L`k;rCaR$Il7jWOC6F~#w9s2owJ*+T`7h#NOtY6{Xz_QAb8p4=Ouc(m{Pr;5T> zFEdHSkBiC6w`P`u^?r+be2Aal3R0?^c|@}D02Pu%sJ`o;-RmO^DGkC;+#8B}a47@5 zb$8sIC(pLKI?2Z?y$M&zoyP)OHg$2eeduMI(!T1eWQ?4I`q+GrPNH5FJjSB_wJL<0dW@dj@oX@F7pov_eSYrzbRp# za2+A-wgsENvrBEV*f6bx1C{q-W}ia?%s#etQS>I#O72_G{;*0`!W`j#qE}vfiP<5~ z@HuZr#L(x=Ye&&*^DYJjSa;d!oG&spD{@JO`iyd)I|snMY)%raD>;pi0ATv)5nFiD z*=Go?4>K=LepL>VoqZ0Pb_}z-_N993EM-|J63DhYuioijPVc=Fw5jZo^s?cX)HgN` zcRzUefeAZ(N~w*f4kHh=hqq3@BFUG&-w0|q*SXI}J(r;@#9dcra~?b`3S8j-=6l^p zv72i;NvQWfq@q5RLn-hbRwMTpE4KZ)g_p{r!~OV{v83NBh<2*;w1)1JH&!o~Ch^Wf zjnmIGPO*?e7P69}A!;B6NFZ`K;|jgt^L6YyC7i<4n66R_MOF@Vi}qpCI-<|T9^3fV zjXhH^2d49(VraFcRi-#2g#z*1VpAPt`Nb7Yqd*FzMrS)L%x*#%M4z4s9lQv4r4w~m zE9zUSVLFaigInhp%R^+Z7SkbWwdo@w-I)rM>aNSSEUxa>c_s!=n@8oaOf&Q#En>`O zXbDEPNqmTFkz2xKg58v;@L9~EcO^UGuuD>;HB)0Ng&5U=np0xFM%om@)57X7mHtA| z2B{s5#n;ozC^Nt}{)Cg2Af0ZE-a5|F{A};mf}K*-40U&1I(|ur?(SM~J{=$5pyxM# zK;luR_rEhQBLN&hJRti2D>k*4E%LE%{vYO8xT&*DM;(nXD3ciKu3~7z&9AS0%gJjl zxTJr2{Ad++d2{E;hiePYO~b{EPrU5TrY=Op z$LSA@U#)gBFIC4#R81F*Z)qJjexm2er{ShVknOiaY6r^HhZFX)C$@2enDKS&*o)o( zO+!23f}=Js`0k;9RE?L+^KI%KmStX2Ry_ze^^ZtPc=5h@=bAplGf%5l9fckwC5$wv zu?gW}?UtX-W$}a`-4Az=4+qb7gczmU8``SS@fxmhd{9VDgv>+b`S z@m22C6G+cqjQP5C9v{uz0{HDsLfT}hA)SYMSjC0*p+e^%!LRnF<+D-|L>Ay&y$yN1(Rk9{j&*&ZgVdrn}a;}}!JG=F9uXHqa# zrGY7ZD($lQArUkj;w0)L@D9Dofo;@>*&hfk6I3qBk`k>+3#kaXtZ&@*j%T=QG1#7- zlm7e-#w&}c5uW#RM7t!pe0IR7TrDin-G3cnC)AGc7r1RohK2(NG5 z6|2nOYSyHr9xqFhZ=<7Z6v2U}nwycPSkUu%9=v+t+8=t|g{czq!GPsl)cW+&yjj?z zK|a-M@eEh{=W$XO>frq|btR1j4Fi8r=%y%x-NcDtD4|WkHT?IvW|eV~2Nx?nr=jfs zN7GFr+oWvvYrKv%`?~kdcejZ9n)>FNfL){ zWKtkbJ3p<({u;w1NkF*2)5OzUeV0ug_vVi^kbt*)s`7{L2_WYn?!p+|4~pe>q!f(# zAHHtyb&kn4b^t=gHT>p;E}G`LpraxMvRf8anq0%R-qsat@nO939|{M&tck4uRB`!| zE~GMlk^gHu1!N$m!vE0T8JBwsT}0zZavLOK69Su&V6LkhECoP?07L`Fc-746k0T!D z{z54-C9ad;aZKnu2duH9%FK_?s!H)h8fJ^A(N=>~;;UprpAip!|K^CH!RY{4ItxO; z{pYJX>fMgCn5ALWPgIRqc$3dH0W?(x(Ed0I^E4%K>;+-FG{(7lJH_0)(`QV6^#*A} zvH`FFB1k2e23(+4ls5*2!EVKQUJ-JfFC}8S=1$Z6wiFw+OQ8dl9>4y&%8W57bOX-D z716?X76@@OZ5e)JgOG3!01&4JN7Pm+&|ZuKdXdg(X^BtHku@?8y^rgx)*wk)1;q)- z&5POPMpeK@=!Z`2aAoN}Ma;Qc4?qG*iG?k+0<F~T=}!iyR;=lweq=q0@*#bK7LC+UZ;iX)zvQ!eXc$`prrW3$jUB z+|*7znUckD{~W0q1G3r@Gr$N#9VCc9YS7vOe3V-c#h$^CZk!B6N3$Satu*whX`Xj? zbL{S^k!M>!=Urvrja@Zrz7161v@+keOuLo{@25=pjHGILTR)-p1Or*O)S_)?l5zXv z^KC`GUy91T&z%c~wcIfdDWxTL4Vr!Pg1vH z66#o#J#DXr1YrFR2GxQ34VI-?-;{%}O8X}$4kv#b ze!Y9wJ996U6y@NEon2Gxou6BslO0^|i5A&bdLy?V^BhLDfxb4tReJzN`K2pq14! zk9Mc|+4Il1-Ws8KlYxW!w#Mo5$mXr4clONBtz7hSnUOZJaVDS+pa$BS5d(Ohx_#5w zt(~9VUD9sE)KgiZt#LANpQ-b*7{G-G+fR>mF?6eR&AT5N`C4T*w2gP6OuY6>#Wr<4 zPj3hWv}%`m2f0a0)7mqNy3}w}FO{-pTqY~4k2?AO!}fx&N67&pF`dkffd{ERpkGAQ zxR~5$lz`5SI6XRT=Dllv@z=laioqxYx)cZ692tJx+O7tN2wPUrdMY4s^k znybc?U1mHSC!r{(rVb2?-bU_@$U)?ZX`cr>D+(Wp96L3&j;m!2AU0$sPf?^!{BMx39hP!=7j~Pe5HKpmd;vn-Z-XQYP5^YWG@oMErJU*!;wf#oS(V zm5+Bo&af5F+O$YC3&F1Rb2{kno8wY%u!ESxH#bB<_}5duErXe<8>wKFMFQzxZ`K#? zKqst(9c;o%QGk$MOkj^$75z8%*uL~SE@pYZGQ@KU@O!`yQ?_u}K+C)%7-4gXMaME1 zNt4F8kvwa{1~{8y*e_|%Ib0f2+`HDbTnx@mPiVbZoE9hJYC7P?4|v%z3Yo;j#WMoa z!pnfmhM6;&gCnsDrZehjp*gPeb>K|NCTf!qbcWfW!Yg0ovq(IQNv76;2EmF>2oY* zsEr4Xuqnbaw@=fYCFI~onD7vCH9^(>y%}#hh0SHXLMJFIjXaiRt^$Gao20157;Mtq zo%(+<AFBNTvQ$hUie3lzF1-0$^u)pq-g@G%}Mropf~}BGph}^`jO7y0y6#Bh4cljf&fn< z5aB8SqIQWjT$I}|J=%f`94ar3l3E?}BE{^w4W2sKX?Dp2h}mgrTWX+$!uEpj+a($n zUzSx-S~zek8D^pH0SWV*Ux;~t_a%27{S(<^9?mR|IuuQOHwnbY;&>5Fox0}v=Jtqm zobxOZ-lOdCcJoyE{u(=D{C2?-b@#lGn%W5sNVggYeh%{@0$~&bnf8&oM>%oh8o?B6 z`u@Wpvbfw_^BdpIqKd0VZ(!%;-7Dr7Ry%Y|K*IA=$%Di;BLl=v*6|*{Q?nqW!qQVP zbu%zfiJ<0nnJJa(F<}4;ic(is^QjKgj@a(JL&ODTkmo6NS1a-%@v0F=lSu^8`?p$| zRrOi61or1nBx<^gWG*?kD+|ldAUIhpFcHUw0+^u72Gds7--M}BwEz{LyRLqR8i^H% zmdG9|$*MXhfdpTlei4u8=rA0OIx)~277lYun>A$ zy*hCMpfm%xPncPp5Et%Et_l3#t`Gh$I@kQuiCwEl0BEUs-N;hjri|lt zyL8FbDN-qn%1Dja7*#p{;6cfzZGjOoIX?~qNeT9lSz9D-UJTT~j)Ttv^@xalkT?z^ ze$2W{0G?Ytap}9%@&}S$xi2ya>XY>~t1Q^cOC*DNM0S8`SG@oeiCv@$sX#Mv;-aa= ziX*;2gdnS&;1J&JY}M_Kqa8ujjMH!O_+65dkeNq87s;afzFKz4mewo!G}Yp^LIxM_%+S`QqN<-R3c9{jF5Uja?eVL5 zzCG$_T*zg$0iMp#|B0Kn7WF&ZKiT)sJf>0^mm-9gxCHDIJ3A#UPXmB$DC>r~Nxkn^ z4ok^QVnC)OvWTlzfROoY#9d1kv?}kY_#d`jTGVio0}g_EN3lr99e!JMD?0F#Q%Lz+ zpLJ5?XQ_^(0JlU;bO%6Jw9vDpp1A4wXDc22dsog=vDLVU6^EeD=nyvw2$Z<$4-R`{ zm`0q=5)ywY6~p%-4M-qBVs9cLk4 zk#RMAzMZyB;&l8YsS~!jgqM!Hujhh(0b`Vp3gF`_=bTDw1h~-@?f+Hu{hx-6`k&Fa z+KoK-^^ISl=6?jJBl+&WIc3JB|JL5vNlVXPG)9>;0)4dy>*7@f`D-F+s&`1My{%w2y1u3 z;kcCtvi4|rw}y{;C5{ojrYyl|w3UnPi#d$d%NoHKUS9Itvgfx~rQ1A~POlafg{$_b zxXY(cda?06;_-koZ4C8GTZW7B_4+^!)R$%2bMWDLhdim#K`-|r1eyO&;57yXbq*ja{8MsP4 zLiwvMbnaH~4u;BR?~ipAPY&xjbqQY^7T}U_q|+f$hYd*2cgvTLk8!a@R}yG+q}zg6 zgQT|51Z)jFs08gWWp$c*&T|3lJF_qu;h=XcKrcM|nqoyL9tJ|p@O`mi&l%VpNPpN?(9%LXZ zMU04ir)CZPggYo5F5FHbexR2bsjhXZdaIyX?jsa*pwx3}T}+7MbhPu)b|n_&K}=Me zhglXqxfvoywKJA5ViUOefx0PQ4j@}KGHO-hgJQMPff?36RfA_s3&qQ#vhmPhgi|Za zRx71H)Xua(G|R)e3namAOAQ_)2KG;6!3ehoKqop@I38r0k?&=5E{#ayq0Rf1!7fYv z;3Gztjzo6Cou-vM!vdF(?JHZCs#ahf1e8vT{&ujbMAh}9#MZJ4*Xi$0jOsSy$wO^c zMlNMTwS1%$2CiE9@bGmPjhrB2yki{*=B1Q4Tz-f74KofO1AvhZ#CGgDA#$XpKnvS! zVQK^pvm-EP0G)7}&rrYrQv3JEesSLeUKv%16kwQBo1|0kk>y4_As^?Yyqgt1Ji%y8 zdX*k(cWp%Q@9T#wu5LP3_2NGn$L`kln2GN+?{D?6e)_xjq-#)O!jFh(b#wJ5*0z<( z9n6>--yM{r0CsEpEOJ4}{VrTr@45c?=*bHGm~*r_tJK49SLBL4u}tc(TR|ytcrZ#G z4ENN}{#-jagSa&wXc0En_zM?1x8Y~d1|l0g`=+Ble4SR{j}n93C)`1Mm?NVJ&(j=6 z&Qs57J3ufNC`P5%cgpEQf%^+)zaj0EY~Aj|P`act4GByzyFqPU^%o3_@8#-7s*g-8 zFwB3iDqUBS%^@hLtP~=*dnBgmry&HJyD*AQVsVNLF30j%TwFLnvz#fko*(7AsR<1d zPl(!SFrKR#QQqOG@5kg*J8|0;oCyR;b3b>;RHEb{{VcdP83O;fY|dRnilCK1#;>-) zHIOp%)#LTXznM3DrQ?X@Sq~UjnoQ8&-XopcKqf=fZl1Uf8!MHe0UkX2Ibg=hMgBB1 zl6HlOTb9>BrcaDx<9EtYg$-)dM_l|_*CBRW*p&ZIqQs~lpjXkJ7-rfR8lq*vf7{lf zc}W6unX4l1!#zQ(eMj;F3F;%U1YzfR%hn6StJEKkPXb}+DJgV|Vv>@53`&^}gSZpB zTt;LJ3t~&9yEz9wB?uGP=N`k)hT3mdtUh=hhTSXY;7+B1&u`?Jwn(iEeXLav*+ddl zw~HU*_APk0cKEO=pYPA4flO-?kB2}EQ2_w%p;zC@&9y+Sg@S*b`sKQJ2~B~hkL1FB z2L19PhW;fx$UyES$avVPcO)H*ZP2WXn2!*<4gb z&f=wYh9MdBcTs(Y3jho+c%rUQU6c}r}?sv}=EE#uj>~;cX@a z2k*csT%8KcnVX>Y0Pwiuin=YF3&oEWP%Zm)R)gp(MQ$+yncr)yU*tbCazF*HUtNQAU@DnmiUr zhn0;~o?3YQ6Z+L(d2q+>g?iI>%pgY0&Z;0G6`qj})>q?CyGQ@L#trbjm&TO`?j#$3 z!3BAb$|{JS!5yz#ID{Dm-d+sm@KUsX=G{4;ZhUArAQG?Xivv52P zh|Zh_nKVXzvu$NRivk38z5=55h&qk0CXbxixk6ax!U$X+3_er06Kd0Eq%O05#ScYc z^OzrIFm-!qzbE*HGg8zRkNUB@nBs8iL{|`wKfLENXT0*J9n7{!(sI?vm^gUexKQU8*YHi~8-1=o4c~O=3-i0kR-?U7kKQLP3EK^Q zx`J%4$gqe=VFGH%Uc8Be_@uYEUQ#v6itbJlgxU14qFujGQI&L3>!c0 z0J}bMex9{*{$})_tUNaWG=mtHudshM;`~VNaXgj-jmmPMIOkKLFTmh|7^l%@ii-$m z{{&?LprtC*B^E1NCD!u?cfURlgvZV(5o)1GCxZ2(opQj%+Et7(7qGPwR7pYO9NiNP z65m^EoF#77-&tbPjQt&njREtv$Kf0C4mOkjTTih}4c0{d4^MHK%k+-_y9#M~X-!bM z^dBvCIvv+@Fvu|pQ=Bx9JsnbLwB~~S^x$d{C8=ZaWn%>K;b9NU=&@Vh!%s5KOn*MJ z+xgreFK;QTeeyecn7Vsxu`{n#J2@CJ2qbn3D_i7$z|XWf=~Xm{1@12%;+Qt6o9lS7kA=f)x#PmjrvHJjMLRefBhxW%)?=|rl4S` z`Qo(>G@UhzHOYhU0XE95B=!O;Ld)`!vI9-74>nk6zQs&_OaKRP^_0Ut3&fNYE1?8 z_F#uJ<$#ro7%IjF-=UB)ELYAxT^96SSHJXlxbwEEW9_A`c!n(=c3jeH9r4@us( z9HNybS5@`&egDbk>uFzAkNHHm)gLVX)4F;jq=;M-Lp&fq%Rw$To`)Fl%9mdaP1m`o zamq%Z=rkYXb(;8o<>|c$teQz+ARVPyjJ|>e8tiU>*`rQ4S&&t{>_u18%fw}WyUUT+ zxLJ&6K3e(9ziRc_1?l}-$^~O8rQfdl&$pc%-qBJU*;${G#kMp_Z#e$>J#L)TW~fpU zm!sUumA$+EjIDd(`$vsvZ;Etsg0J!gMRooG92NRs0%A9e%KQ^>+@et`Jc0#8wKP}e z*G?5JWj#P_mlQwlqXi%mh>MsZzMlw)pi8T%+nE}6s9^Q=sbc?NuzM{alI5HaBB`EI zV9@9R;?6ze=vV+3@ez*RN$>QRs>zueaN*X{gwS{6*w|VYe5Z#TsjuZlnUO-()xvjD zIfbpLL%Dm(pYTWuxX)%9~AXod?hH2CM%t9Tcv!Pa3F#9kG-}dI z+$@rd{aSaFBm2RI0wO1*ebVBH*MUe=8pr~*m6-biq-6nax06g5IKJpHPs;+^_~jCj zb1$_6alE2e?v4kIs(IdDktUS z_bN+Th~Aob;TyP8gK2;xv?(FR3MNFI#+g68f!#OSZ!s_Ku?VK{LK|^dhDg>H?paeO z{&x1G3tT_d5p1TGRCEIlI)KR)Wh8qqv<;{a^ni@F$r`pdOlUrZ-r6?l& zyo<>YYmqGQ$#~4uyK`p#b3jz>uScBVY&bce=M`3uJ!hqJL73aSt398i-GDxEarp5h zs>NhoKNGfvdV#9enZ&8#=-v^ucgwGs7_WxxY7uWZrOONUVQtweyo*5IMA2Rr1X&oeBb8g{!X@ozp$s6kzvpaBX3` z-VJo#vJ8xuP=tiA`i1=+`%7_@F)E}}Ua_k;3XXIU1JnnS;7HlpuI?u!vy^Gt&$c7I~io8pE{&7-px54zR6|xS<2@U-QY0Ye0&$6Xv z_4p_eWS}Pn`AK36UEIoU;6pu6$w3zRZb#ZoIuN1F*s$_Wlhq0y7^eXIS6oFK0Id3D zPyIq3xh2d^pr`X*77TNF*@#ONoLnKt_v+mXF5O;lM0ezA$zT#>l~bbr9_;TEnvDjokivgGV$A58t; z6Vpe+Z=bzbh1oT>I2kf@3lOsBlx<`Os;u`n`I7KQcw4gZISJouB&xFI=tecrRW3#3 zoCaIxYi^6<8qYBKV}nLWRUD)`qN*Z)Y%DM3+oKoHO{0s_&Ed5hI}I14FnR+UcP^A` zJ*RdhrO9URsM}V-BJw3IlUn8m9ft3ydlF5W&|7=Gs+VVDPE^O*(8m|4i?CO^qpX8x z&0>vSP~ZZog$CNcXu-U!A@On<%Bze?1+%Nak-$sEpa3Dr zPl1HyZ}kkyx-rSlp~BO|>VyK~%38aQg4&*3^iDr>9RM65rR)X3iXdP|iOW%i3$>Va zQJ3Bx3uRIq9dOJ2B9Y-BN@&}9;7$!!iX%l~c9f|3f`a4hF4oLWho_lmB!|8N=A|s) zzA6!w3WqUZ>_0a6c^Zii_1hN5$7LHZn)%EAcg4kUzyUzm|KBPM$dC9x#YLBO-tF`q2+-Bb{p=6dl1>6zjbPI zgi;6J^m}G9A-v*mvcC6=UMB?JLLg@Bj$kE13HkOeOtd*AvCMO(ADkE-r14|Gq><$m zf(E?;jPdu%t9p*$ec2r3l)U?OXkzV3?O49?1RSTDf_I`-wZIf1EvZ!lOABL={0hSZ zj?of{PY#=g#no}(=Iv50R<$kaeNZ|o8)Uclr(sm&6@1LQ%?FG@!3g&T92aHcml#M; z^(G!N&LqxqbpOn#lF!qwY3T$vg6`G{$mNu%&N`c}2VA`@A^ebW@58DfwM3KlpVEG? zFmU;x#q3i!xr^F~W)NphOfOtHK4V(c3oJQ$Ns&7sa;kgVePuI+O+?wWiMhK|8h}^Y z`X0{qnC-3gR?EPIs0x40VlplyejgCRF|V=Wolj3MwI?h-WcS=pO?TvB9Llpex-CuI zYI;&TdsBO~IuAxsaO2~K<9N{aHsV2emSLO+34(I&$3ZMR)2pBNY0#SbOrCFJyl~*NSD@WVBDodwKz?Pp7UOQThK~-m#@~_Hsv@l*0+P!^Jsjcy{bE3 zp<Sj7qrqY1*%x2mCq(5{N-2ac^GB z`G;5J#>Z5{YDS5u4#fqpln_#hro*E5D!rmg{}1q4j`rRZle^R}5h-7A-iurgm4eC+ z^IXWffi2wH8JuPuP^tzua9>u5=a3w}Ujq`wkjjveMDQ1nL>NUWlfBFKs&05}roN(u zUJtv=XW9oBfw@01-z$xz2$aS$3?gN`vOrn7(adwRrvLyZC2V7ZJjeZ2(H;`S6#&$S z+My>`__@GokW*PgzwNzRdwl3oX`|q7t)ZJmYITX{u{C3H`WET5&F9H*(^edpn9lHu z@#*tfBx!1?)5oIGdVh?sXcl$NS_}_Du~jT;t*gB3 z)>b{F`jSgr4MW$#Akj>e@9El9hw||NS}I8w9mgZhPt$nUG@bKYqDrZA{g3FNGU@D#wky|dhixCgOPIH~QW`w! zM~`>f_sXHelecch|C5^MbTVU90Zmh;(@KOOJ82K?-SkS5jS_&2sn7>a$ zruu@&E5cR)H>0h_)Qs|9cT^3U6M-vI~(^gPIxK}pjrcfnW^#Dmy}S%87{)WC7~ zh08N%C)J!yEFQ~KsVh`K4J*l8@?OJ!$_lE6OYKt`-ANP>EYmJG^iPpJN9O)4ahfTd zaws|m(6tHLQM77ft(>c6VL;!NY|RJaK^PL8?WFfA)#tq-_+wV&>D)r>(GEJ#V&)l3 zxDxIkDFc5|w3H<-roxSxz~ZcTsktr3OuDI>j~GXapfx4FA{lB`aKOn8GXM>#K{t@u zQa0VZ>15XdV`e&ATk0zI2}?w(Jmz(5@EW*$u;H#<%}23BmWPmQG9%?PlD=1dKTLO`BGZ%@RR#g!);w@SL9ZbZQWcNvbuf~~*x=kK&dSu}`E<^6uIqcg&-1;m z^Zg6p2QEJM=f3av>vo0u$$bCZKk z!`qOSz(58aT7l~Sjc&p+t7AP3G0=@lR8B1RzI&|AjMp{@)k_x5@ie2pO`B?zy;2|N zRcdSdKNES*fXLeevb%FG~`NOP3RYw%~_s|nH(z#Z1!|(Wbz&X+=R}BVACUrd%kQb#PhEFEjXF5D1TPgT zXTWyk9NiXCWvlOR;%D^#+mW$O{?>zvEv5)&Vs(ONIM@oiO5Kp?c=752)q@GYe~f+K zIuM}mUA!G&N&u&e;PzfA{-8p1$e z``hyBJ+zp-tjtsR;oB<-=SVMwLcH$=>hB-h8Ql)oAK`Juy-Ev(2q`2JjAB%Gs{lSP zx9DPsYC6RY&)L#LYWesNfuna~#yZ4l!4$wTXokGf>tO;<5v1@G7>$0O<`;8!l zEW92DA6UKAVg2F-a5oD8!81|;*RRtyYKfhSo&x7W$%YwVC+3ciem>K$CYV1HQsXF*1A-mPxwKv0ZdU8Ote)+#SB9gGDRD%mfpQ2yIw=-XAf|3<=BUBwJO=|a6^AelK!{Bi2*CRpqJY*Xo^ic zDzpyx1;}EL&7SiOE)vTp20YyQO-zQfxd_sg~@kRs9L$BXD*w zF+;&7yDQYWunLpFM zNne+o^q%K*h(s}V8f>vxkis`;{z6E`PUM)7u@435MPteHS`l9B!gAXnVfn09$@MJ9 zTQ*_^_pXA3Xfw7S5k(q$g96CqkNd^MyCKBjAd$-0LUg=ps#f)3CFTbtb*dg6Isy`+ zVpKXiymj7Kj=^o3+a~OyAo4Se6Or6v33zIz8ixV<2t)p`X+R?ZQIJIUBMi|5Z@-O% z5@iIi*ILPuiC{qs`X?du3RI?-EG6)XNL`CA*z?bW#8gOT)Isda@khPuz>v1+uKs4_ z7(bXQM(|LERKvJ_3gVyUJX@#WQFx+J0K0>5HXMh{7(V5=oyrCi>rjaiSz(H=@oCZ) zK}S;R364L;_yys)VM1!Kc1d-D$jGhOgv8#y>sv#jO1)%Qgp7)6Aqk?);3_>Hnzs7e zmaAn^F45O~B`nmqEjd5;!i7=+bZ8RBf<7kr5b0y(IF62tTh?Ez4s;0fWk<#o2-Daz ztX?4Qg+WLbpH;)Qbla|8TEjOSalrU<(zC$Ft1V>O`cIyBDJ&f(1l-B7CaI?q=(RWQ zBU9HBe2Xe=f|aI9J79^w`&nxg5o4H*4hd2F3>SQPfC$Eg&2ojAOkp+92Xnb{_jFpu zIj_P1;|pv-Q+OdhQj3cUCBv=y*KWIpWV`7#79?QWV$bh9N_qSftn8m(&-q(J&weY_ z&tDisO4(*f(P*rod6rpyNu(3qQTt58A)%H=O`BHQL+K5T=6cKBep&bXg0g^m9A?sB zhzz~6f_yL-|DF2LL-sVC1!E*n8)zlHyuY1(;ca7JqKnvvy`fPzY$U0wj!}Yd zCjbFTU}A3RUcI}Tg}!tpy*c$Rbst>FmhNa)NkD*L903%Y3_*}V($)`K<$hG61M46c z1NP%jkyAy;Y|(@G!#HFX2nrN2VK_WUoTQhSxhd*&g?2+8s!U*mQYE@4_!2+5GoelM zAYn33NtoISX^Ngip0&F=`h+4|yAfHYQXRDn+ZlWDRncC-$U+6L zb27bUHar$@g_NG-$`o_YO2y)JqfU@P0(kTv0oW2FX6CTs7~kRLz3SgtVaJ)MBltAQ zLs*f69bhrzf^ljK>6aUbr3Dsc&`%AbvKgH2pAE_@ocfVn9Q<%KKKKyA8ngw4_-M`nxenpxaeu zI5CbUn6-w!{KCu&FUox{I(I@zV8oD*KQbT$(IMk+Pa+zY&>!8H5n4|B-s$|A*B3FF)@JwZ7aw{n)PmHuO4apRmJIv=*{*z9%i-XS-s0@v9{> zzFj?6)|1wG0kbSSOmuJ_NUV4kY+G1#Mjy0F|updv48ld#yJ?Rb&DIlUNY8sFtpzY+H>CtqCI zu8B>V6vC>}dS@1wb!;nb%V;IC_GXf60Wv|&g;?eLe;ZNy{MHp1)*A>K(@Cu~R*V-t zsM9*Elpw5_xb-GeTrZgBwDVI-#gK=Y>Wl+Ei0ju{ynZHa zkRqH7zE##qPNV~1?W!&Dd|T{nBWf2vi^(AyDvNdJ<;~34AGw#u9zz&!u{tjMaR5V5 zRqqi-k;aQk)jDJOkG9WQ8<3BCS_aDxeJ}+PR$(s{h!`)Cp<=YH!$Jy4>qCy&d=m}q zHDfktkJl$`nv_*m$Tzh46ZT6ezV;Env-;Am;m6#|UK~PK7JR`8i?hfj!!3QnjWE93 zy|KQgTvALG!X%ergWQGD=)eHQ9AUXIU=ScXh7Hw5S`;@9Sagau4VYhm4k@zLXX@G! zh9+ZBDOxK*_$o2u`@P+#Oa!=+Q`dai*5CYfA@?oTcy^iLmx8_ zCx^v|PLy(YQSGrVQDVDw2ycw2b5bWa-XGOm=e7L)-@L#&7nyYp3EAxZcl$4>nV zY05!-sbD+`H z+^U7tF@z7u6&^{bUqxBgwo17{(DS%E}Do~re9ervYB6BP%)m?IGAME#_jIRkdZSgdV|61&pjS zg#HYfu~Au~obnk%9Jq25$GXf!jfU!`tz*y3EoEAPq#e%IeitM9D6XbO2?7ip$@4^E z)3jL26b9>r?Yh@GtO4>oXoW<;x>)Rr7TkDgBR^gCjXo3oKr~{n0z%$K4JB-BfgBU$ z(}lerix(v|O`N0zD76}37bMC}Y}O(+9oZ$4Z7 z1Hh|mJ)mK#x3`R;OSmLYKsS-eY1%H(yCc`V96VeTl?}4=ecHrVT3u5)V?sJU9ojoL zE~Mtx+qljI+hmXdq01_U7@nmk2tO~q^9FI|jgaY{2+Y-hwo_7@@2&GQgoz`);S)_% z=bbB}C!7EEz{_09g45-DTh9`|-SV2!Z6@qGRs()?xEg$M-yOw01`Uanv1TbN>;6{6 z*QT2XKBbbrJaV}zILkGJ@1Qnbd#hyd7Z(VBtt*2OzC zX$|U!p0~vEp$uiuOP^N8XtXK0-s@!Bfmbz9Ex2E0R+D}%7z1ch=8t*6tMuF*Lf}l0sLOZEJC;=QtKoZjm+A)~3*dEu`Hb1xHc?6qy zk>KOW?$WFtLkXJz)?QYtfEbzKwO-*Pq|!*<4jppE!+y-p@W-j>7f!O~m7M9M+J@!%@!r){!T zk8kUWgOL&(@}=-x5EQt8*|*&#AjM`~04J5Jmcg|Yk7gKF$9nsyq)CFWhK4j(4DL_R zhl;rgL_((?s{A=<6~IX2^aRnJK1vcQfvZ>(+rBUAaru$SGf)c-uJ8V;1O1Sn*OQZU z+dU9jsj+Ok#8$Z`pV-UM$#k4F55gj-R_+$_FMj+O6xGZxn;RNJ`)mcGQx(Pg=lx5REZ3Hy6zxTG<;;D>-0&u z@7uWthIK)xge8_z6)#IYOCB-fBdE8|%(IcO5&H=H_OpGjpAPyddao};x|y7@>q^ie zHxN^ou6yE8w%(WJEXSZkr^z4pPkLYLVVxrx3TpY-{@98-ZaFv9X1g7tG*{P-e5Ph* zR((}8g2a-nty_Q8$i?{x+&gGb1>;Hyp5bguv04%o*9?Mck%VTB>l}X`b6;YY5?Ch9 zjfLH^g_2XRqH)opovSKttJ`N2>6fr+(k&n>ttG4~y$cyb=i-(?mX;&#Ue9wffd0xg zZSAb*%+kY3e|e`@rzvObF&iKs19$PsGBhylHPtG*YsRdD{{4Is4+$wfEJVfldLX2Gjjacfpf?jTgT^dwBdq{HHYPP}!4%&+v~u z)uwz{fj?(Ae|vm=;LHEA<#)1i*&}Ur3bkYAp5C*V()*8!1iM8rlAI&M)bef@nbaVG zuj0sJ#V2n3jzQc^V#HO_X;-1hnd3^K@gHgRhXjv^6>52BUBMSB+ao1*2G20s?A+Z_ z5YNw`)ZBV!F9)^z^Cee>-2Xg2!T&3_10$uX?0R=;{e(?N_J%qQux)I+&+%Ou(GY|) zuKb<#`j-8mCAg0(YJPciS;&QnKcuL9Lg6(`+&Qr=O+t2^18hy@E~S!{i>tq)j7~jDV-VxVS$55h*?QxsWIRq8#Kl$@3W=&zlSOUknpg)cdRyAFqyvLNm(aM%RwfK! z0Yi{RqYN&}f+pY~bs*~xS~hVlsETY{QS zFvD+E7o%D*?WDq^3LWGkI0wQNFGZwv-SnnU6nF}Lo&bEUrYII_@FNd;#|t0SDLYbL zn3-qXGj``8;U}{LR`#O;?IyATc?H+SGdu5xatcEq##H}_yckkM{DGhtG`g~(eX9eH zb!p75r?8Y)#TQ*`qf#}uds#oo;Cmum@zcaBi|vrHpmc7XorNx?t{23TJT+fP>Jltu za^ZFJD$CtH=l@w#xE4K6*u+`IFLH@dD{*VpT z_sv5yKBZeJ1=k{sJHT54W9QVfIBy+RX&IN4$_SxPzpe-v5fV9tE3#1x{@A#<%@PfQ z(DxYFhTaFYlHe9$m_k0Xf0*Z zk9E6}YZ`-!VX$H$nc;Ev%sA_l;|$yg6MaSUuEZijzw~bfy0v;>qCoo&ciD_miO|b=>xR7r}VyfZo#{TJC~Qcei~o9cp^89&NSy) zBubs%F1(@rmu1fr2aDQ~;k~pe1-l$t2xq+HwQl9l4a$^Zwt4v^0>`hdrZOA` z^p~uFDAWe3)(nGtfw;2c_AnBlpw7*>y!E(w^}bt2QUmCk2)_=>l4@!_p;j#rQ=|_c zt1FiVay)din?~JV7KZM0QT7;#g|BppfL)ZMbTng9swc!=9cZ^6Uxj*C+nDs?9ZiSJ z@=vt52BY6bnkht(sk`ghb8y6Tg$I6 zJg&?&%RR5}qAVb!!cMoI!S)7#-&_z0|N1uH=oPSsCqlw7wc6XA3)5b!9zDgx^t$!s zN4j5D-rV6C;Q-YrdQ&hwApkEn)xRM-sclwJ#)5AlxM%ASm9A(!w-6XdI@L4=1Ot_6J-fb`HR@1lx*T-?BL|_VwUirwr zov|(!M9H-9D!z3{h#e)df{<&KhS@zNN5-49lk-BPbFv18zWPcnG#H&a^Rq{&=^}Pm z&G1R8M1|(t6mVXNH>&3C$0UfJdhexBV1z||xi~ic{*JW~VO0SA&^WcGM2~9wfSdEW z_y8?M^i~2-IBeSY2^L31E627C^3Tni}SY`DdlJYZ=#Kx|i znhk^OtR^&kQMOaOwgd)V2>3FUZW-nn21p9%=^oiFg?R5=jkA>kK|@n=In-MQMI#pn+B_0qEY~Uy!n%ySd~3#R5w2*S4E}=mSI?2 zzetmTC~nh)AH7A<4b@YDSLlM`c@g60m@y?M#KYdbZPMC1ZE4=tVj_bM6<2z-;qqWePZ7Ib|I% z7FGJ_YNYjW4T!|XM z3oSf(ruG^aC;!@<9bh<*T-do$3V=w53R+gVhO`omE#NQhElHg^NfTbYwY>H9)xMn+ zk1)+&mtFJX>na|6y^v+v8&u#~Yon<6D`-P{<>jv%T*ccDx3*Nr*Dm@I@gNZ44^&VP z#0P2re=gMR0i6XVgZ=*B?w9}nK6LoM>#9Rn&A=ZPv|f5By}Ix_u%YtAa=*ewgtwX9 zpT)`NWQ*wSSkEY>KBfbIOlzh}bnu)S#H9nUxO!76pkfO2H#;bo4|U)W_UAPBpZ?u@ z$^MAw<;&)7-_vfzdXD?1#_^LDWG_sA@f)kHx)Tw9ZH&8?yRmuWrHf~m3rll&+5>Nu z0G1S3@I7%i3{Y2h*Bl==&A$HTk@@MyE%yrBgU?zDH*})gPG!RT-#m;|FDJ7V_@`J| z>(+K$EWu;#xZm9Lt)R9T)u(3KUfvCx&E@4!a^wt)NPKA@*RLMTn=XqY@zs9`?|-Q1 zF6$k{pVkS~^Dk_$Je8oVmWAgq)FjmL2%TKO+A$ucv5-3xm(ihu?wz?>cU#7Dv>Sqb za->zGcvlftallX)F_#2JsBEdU=kQy|HmSO!fH2V=iGpA)mhc_oRJ=f@xSiEJ3#-WeWPjxiFnpw~9PtUKCf<62Y`*JEmeQC8-PnhoVpb5G_aF zVmT@$!qS8llLp7s6vAPIRITj}&x>Rak3TjA7NdAOHdRJLL(HqPkSOgx2q?Rl?jc9T zq>)F{)fG9uHMaC&QoHIDE@!6LJD1;TE9+NU=Af9ew%m31QU1qS>*qNJUATy9;LyPe zFQ;1DaBXO|aj=KLZqh^D7LqgOM5P;{cJ2vj97d!^JovO7`}X!%pvKTVzALQ*<_(x( zkEZs{az%_yULAWP{F4bqS`|;ApL*0Beu4b+38|| z>J}i(jE`b#n};1lv=yntQSBtxYie#?H4N>Bb~!=$V@)QupSr|>e*UXg!M=%sF5^;N zJqJ4V^3AJN<4k?U6l9FU70&?;;Q_0G?=eqxzk)i4giB7&krO>c!iv0FZV8GVX;dJ} zxGphRqsEDF?q~h2qwK*tHa`kLm;EL*^T0#lCRcaYguf666PD3pdy&Bt)+at;4qrHd zmZ33;?5NZfZ|IoQ0m>#9(QQ*aWK?N0ia#+L|8?i)XGj?%mE6Q7L9wJto)Y#$5LF?w zLj)3Fx;zti*}4xJeL`dqt$vz8Jo^4RS`;x!XY)a`J7mHvmfIzH7B})d;8Ne5p|Z_Tx<|t6M;a375W^i%w5tzuKxl`9DWXqOjUga*B?Du@C_8I? zwgPvs1SQ`>V;gAs4~QLbIJ01@P@hWdTcTy`21gdoth6EV2fFp0SF$+H`)WbLMwan0 z1wplyZu>5R4IjMTdzILx8m0c~z{ex*yFUf19VA1U8XozAD&S}RWGX9aMMx(xRo64A z;I#UjP;m1%{jRXy!1lEBBQ4*oyBREc`Qq-gO*z&x6!>#NaYCF7*!WK~wP$GoYC-ZP zx`*=ng?|+u{DqV2UfWM4_BMumA?_wypC1TI@8ft=ztF^di%xyvAo~ociXCB)P&%sk zKDJu4i9M8hbXbT5p0JkQVQ>IiR04YmOt3M)2V_E&g8gUr{LtvOVnq6=+iH~2i%L7H z)5{h9OzgS(;9k(*wqg|-O{*Eo{@eO=OC#=L*l)DDJ>gsU zM-#(I(7Ta+QP>hWF;LN-cA$1tT4{aB8QXG5X`$NjWcA5+Mb*H~|#d?>GEiS*F6`jQIMmlreVufX zi}5~Zzyg96M|r503mvNGTS25{(MKMkjdIwJT0o9&K-w=#2j~~Wt%7>aZE#0S8ve`^ z0Vz9thiLbT0LTrV0Gv}9_1;U2rw028y8ZKJF2Mn(h2F*&R9s?^jauPijv&a#$X3Y7 zu@I8lZ9%MekUc?)MW)SA`&i=BSLloI|*(_{{L=yd#h&w(pyT65{W<7o1Rk z@pj`a0TDNyY5tdsPOEEI7JUj+?!`;7Nm1fP)}SK^j1YIY;hEk?4}&Oui|lQog)F^ zj*Ja{FsiehxpkMEmU5Jie;=Mp&2um<4J;jq$; zct^vTpw%|KXU=`yUh))H{PF;I(u}|Iydb<@&PdnkH_h=j`&n#)wn8PMK498Lf?O-i?c_g-vm7Bq;2c(`B7H#wd&%;(u6K(g@x{KMr|iHw z>)E((%Ksx)#~z@YuuD7i-vhf!yVxC`h&V{Yc_-i$6jAy6_?H*D zIY;tnG$e!xr z`Bd7ZZ+~(u*a_6Oz<;&Of7P^I+gMw8bJK|a@fm-#Ta|jgwzb@?Wc*W@C+A()+MKST zTy@lkl!u5ft7^m7rw2HEg3VfJQ)y|nXV;e6)Sz|j{M6s8YMa-N-bqexn8=vPzif86 zi~Q4(y?A4HyZ=j%{;mBQI|f~5!sDtR|NQ=LaTp=|*nH;n=ig)e)!%#GT)ug%BduO? zZ{zbAyS-T$N@_>;=F0Su(t}(_lq6pe#$(7PF865F603Qsa6RBjg05MmnSM)a6p25q z(U9$jf;Sy7_io{(i36RNWFHk^F8(DpD_(WOHWaoAKA= z-(^wh7#sgFR*|_jp%afw^?4oYFgZJDyCN`t0kgDY=UNmA>= zUs(H?U~h_3k?vtAt;ukfh*1Y%9_?(!t0S%Qmu#->f_3Ng-(@3+!j6{% z0mA}7h*0I0AC0^EA;vxy+r-IS7DB7lHE6rRO*iLlhhO&`eUNta2}aJiw@2!MP=Idg zgK_0FhlkUO`|=;pKRAMUq^!QV;ITL)fA^{I*zJ3X&`6`j$9%9qyS1b2d(d+gi)CRs zgpU7@)*rWQ7nRx)=Igtl%MqA+kM&v>xi4F35OkdKa@s4>!#`<~G~m*y{`ORhCZ)(j zPW$EK@t_7SF^A3oo7{iuV-l;jw{d|A$GSEmnqPw4M z`$k>u)yKNJ7(uM})=hBno?WsJQGyFF2n7i222UV#p!r|~X>@Ske9jP472W%RLhm1Fu5QwSElb8X%A_RWVIX(*lHrGj(L@9q$>zupF3huvV? z8c+hVAC?Ak{(6X*&nN#riEv#nYq`na8fsY$wdn6jlkhrz+Vs_<^1m@$M%XXPX4ZxG z>yuhFC2pI=6SfH3!9qtx?$pL@^3ZkAtA_2gdnxNlpT(br@h5tJi#0sIKflNrlP}m{ zOKYzGiNGgTD{22)7QH*tY1H(RBcv~bZUvs^Gq07rH(oq*Lw#q0vw0IcsORkeeoH5< zacmmE*q)tB@Q9iH_weeJ{#yGWB|t6k*>yMmNZO_Uns8oc%%I~jV}f?0W7tzO&p%tf zqOEC;Q`m{mHTB$2yA799mZCBwHHUIs{tRL=)H^jUMXS>-dP0ZCAYyhySx~}+{O^@Q z6C3E+?-7R;D;!hd{j3a-ekr_J)fXyqYZ{TfYmMA&-I@J@4sP^cvIpHFEf4+EXH1GoSz_PO!U8cjf(XeST$aSo*NyuR$Sm z8AGKXb#~ghoE#w{2!yI8|D#pFo5ub38p3HeHg31ey;Yb<)DlEu7_d?)aFrz)40A&! zXgd_)1Yd>@UCQM0GmNCr016Jr1HslFJQN0zVO4GCdy6Wom<#*mBc8xI1rlL*JW8H^pC30>VM2u{K==4?jovF{U<8jVV3=RGrS2!)$qd|>V~6&fzZz-? zAqbiK3|xCJHW&grb?3$_(6-QdE>s{OSsdQKrE!WeH zEAMEfSMQX35?)ano4Q&G#HpQJkmS zOUeLyr0fmIdrqd$iI}?slj--sw}kJw7K)DlsZe~wwo@gR<((ky&>1h!EGdd9IMFhp zxZsmu20-2_Cqs0`XK9%d=Oq*9=A-u&ADTA2_GD^4)(9LDZn@}ktgJh(|3hfzGpzjC zxax}0!0i(+LY0@Ip0K`7b-#L^(sC!+95( zcFJ;yJ}0gdC{%y%C0q~fSNK1(J)A&!AS%fB|EVET*2NV4yXyeH16o{D+eGMJzgyTz zqI=gcL08r`C)gw!-(9Hg`DJtZIOlRP$@aX2devV1+4w_q+Ut6g&yuuGAQYUM=z~`` zisrQBum_!PZ2YhfNGjHNcG`UL&y$;PuY2F)Pdz>LFh<_xveYT5+Q)-^SIyBCftQG{ zN@`;kdS*92dhlM6_;av+xO=&0rs?PEfa?3WLUEP7SMV{a-D(HoPt2Odb)(7$j6SE` z(wAFmJN5I|ke{XJghlPejuu(x#5>OuynUB=(T4>Q63WEuiSD-P2pxtqDZE2=SGjT4 z-b*`5qYS?nXEcxx9_2=r+zA zQ=*qf3&~J}KYT%%Z9)8_)G>r9mAiH0IYu9OFT6drw<;^Fo_FkU*!hWg;}UtZE~Xt7 z0_&K(&JgOUlymn=5|Z^YAz)C(9T+8e`yc$2WNmA^lRoLZXNC7h-J3k+in^+Spw%sv zvoK?m*_${%Y$J?vZ<~M4Q4x%4=*sZ2V5Ui$@Bm{+$4+Qg#M__Jp<36feAZ~L8X{_5 zQ<64dUXVrVP&`Fa#T1|BFgva3iR(aDdISVP>SuB8!uCjY1T@mPK>Rn`VXQS15xcGi}9EYZD3gJvGOZBt;y{?e1n?`yLx<9#k% z0V*~-yZIn4$^;pme%H$C?@HQ3&?ix@|$z+glIN<_GIpE-HC;?P=11$sY6Kn%B;zeua#2zKioLi$o7SAGv5H(c%lUCC~qu0C=eZrjWg<~gm#5} zG#7=d#M2>C2^xYjIrdQM?1H~B&EcSwa<|9%23>Dz8)k-+K@LJ5W+N||jp)8i86DKx z?A~MAH3UR20p#9cq}PZa~WUlJtcrL##27yrX&>l4l6Dv_63Q~mW2NN zR-nF|X-3R|hBoxzrymK7bcB}P$IVN=H~7;*@w)zmz;pNGGc+`rx%M#j`-GpMD>Hz z^1zlCTz32S;ku98IS_I=-PY=(BKqzOwH){s|t4q8nWWyilAIGnWvCfe<<0qe5N zLdM>8Hy}$?coDvads6H2BI}|g)lBB-(pl|eCN6c+c)MtEcz2Uc% z_@cLR!OYeX50=tAEgicAYC*ia{h;@;+Uy|_gd0eRn9md0-w9C~$#pb}l>PDxk{&SUQv~*`o8- z?GV(Kt*cN)o7@kG43ioAT`_~eO(6{=(#@Q>`=(zotdg&5RXra9FU(L@O2Sb|HV_2B z^<94?04XJFEwzbi%BxyLKhWmP91YWXG64~SfgsBN;w>P-qJjiYwu!oz6sh}WcZs`k zW~{M~UJc7+f?>evBG47$C;qgS0WmPntf#5a`_}Vth}K}x5MN!-n$AQX!H_}sG8hmX z=(`he!dR3zN-!RuIt%*^-35X?=waMJSDeJ%dC=6X^>+?Zc|ZaFvN|KEyu|Y}1L?U0 zzHpNa-(^1Dk03Li{l2r9;$tQtIha96v5*+c0STXl*=Q$Y&t`0b#p-<=Yq|(oIesnU z@-zW3j?6%G(?1UH=&_n3=;CBpQh)f}ndYOq?2^VUB`srW{muXedUS$4m*8}tP+mgE z2f;dh(#<{gu9Zs%;O)ILjFp#;?w(;Ox`)TQ|FRK{YzE6rvomz%&g6Ldw99wPI9fr6 zpcI+$aan5+Xop+=DgWd9c2%kMEBzLY8L^bE>V9FG)mPw;^8;-qvlG=gerS(jf~6NktOlojkb@ z<^fAMtBe=8$WlD#C}h19lz-hBNH*DaW+#;bi{E`QduaUh2mDTnZO)L=dbJ}NC=AV+ zYySzH>arMVlRVkF8Z;i+?QB^z@H-K!_kJv_cYQYKWW-X1;*<%0o;x53_&+PR$(hz! zc1vsW!H)B8=y5#iSDj^)@R{u{jAxtZC|nVTUt)(4_+?@@!vLXMfpYf7k$^^|O`R*hJ5wj)&1Sg%XnfC7j7r|J70x z`|{qGjW-8UH-Gd!xp{A9pn|{kVzq1d>+`bTKL{_91`alA-3>0$x_R%`^K|}NpZw2( zzCG7G1m8W1{WaDC4BKD9M5lKX5BR=PjrZNd=_}nK{_O9C-M#%8t6ObmWh~)bY30d4 z_=@`N9hUqr_?W}G&ZTCN;l4N%S0zev^?~g@r?6k2oh}YF`2bcsd!Aqs+)5@~prY`B zrFLeORQ<5~@nAu*Sd1YzE!@z4pZ7$%xD9=2?PBayuhh=Hi8K7c!b5flB~1n?C}w7` z&sfJ%BzSj0V8q*-%k|HwlY(ONF+dL)m(o=KSvJjQxkJ*Vw(c@axte`V#o54S&}zN6 zVk}}~bQ(w5+)X_DPfW3K>QyE@rBj$x;j>{3CREh08<1qmxly(!`J{?|2WL1@!d;;% z!_5cnPJ9Ko05T*>%#~{8oWz!O#}j@?W``($29PsASOxXEYhb(A)a9wv+e?ZMiZ4>u zTYv$1TUa#!53S1Tl%;peC?ZwZQ8p-V|F#^hu3=V{x7-(&?>;_F-_7mzAJ4rht~_0_ zYaZj+Z`P--P=v&&>pY%F>b9r4R;_JS!vB zcEn8)PHd^G(eA6R*z0}pPsP_veybjEufs8UOa2&+$dGb{MRO0QYJP{_wkppi>^Z(O z!B+O;vCRUx2-t9@LK3?$L)Htw48<1MSItYl9J%??>OyZFSJAcS2u5zLCa9|;tx^Ek z2FMbgvbGle=4xiw%dk`0Z7=J$U@mzEZa$iRs!TNpEpDLgM40)1Ep$g0&V%Nd%Q;_y$VD? z8n2T&#J4U{gcJfM+GZaFkGd^H)a>WKl`s!Otma4!JkZ8P#NU?zp#tc7$l)xb_m6T#wUpJZc9kC7 z=5nolgUfUXY0kIGZRw+UAVchBeGPvvVlYC^9I-nz5)B6m3$C=NcJV|SO9p8dZI=iZ zN2HLf>O>(%t;07r~tB&!4m_~-evUz(fWKzZbqrg6sI?DHLE3MU| z!32XMLXu1>@l`z<^+H9_E~v+{XGqki`;Zu=xgAN3daQ-3U}@ayxv|CVU?naH0dv#y zJu;H08@shzI$jYqZx&$k>@NPLq{@q|^m^>*IBDaX=N8zAt^zihXxT4c1p^B*j4|*2 zrglVX6yMpAu!29L**70kBy)fb^6NhgQ)H7;cPqN6eA)NXeAhDYecoJjB{OaFIt(!f z<`6pMG8K5L5N`C|W!yqFJ5KPmYJPE2C}W3~-r7LESNgS)$Lgl{d3ZWh@T$W8Nu)pf z>V*UpT+-gtX}>1XiA{s8ns;N|meNiRR#2S-X7wCHhf_FA_UpAU7ndq$c7y<{-RUgp{C-RX;=MyNxGnAHDj{JE%WY?+8vi?U}>C;XfYt?qgQ(@&XGcd2txj+ zXZ06+++^6WT2>ae0(%fZI#|e7+Q8SK#&|1hH5Xt9f?dop2J;MP&64BKxKBQN{_q6D7UsNN zF`vhMe>HED)WcKGW@^`RglX~maK76g0d+S+zMZSCO zq2Ng_Zjx@V3b>3N(Dd%k^lZJ;AlAI*MT~PGQ2Qmo5fc9!3PyQp+W_Uazig7gdT|8J z?BZWqR&|p(U{TrAS{&%v+U_xL3 z`hniq*09yr0a$xBRMypROEXdn0^BW3qcPx#xj6ot{~|+#fYeLkF}1Rvx^G4oZl+oq zq*>!5UDXN<-g4z(BTY@le+vZS7`SzrpUEdz8bYiH2hWtIDs}!vTaOR`B$e>a;xSQZ zvpkqz`b%KPAfmo0`_r~eC!FV`xvv8(`>w93_0GRGHCF)$$l6(0KlG2%awIR5@8h}4#URDPqctE9&gSIa&P%E$fnS-v3~_1)$B zV^CSb>iZOrS4nIxj`=W-^S2j7=2sxd4_q@FHZJ9Hrk0m5`WKbRz!dLAaC&v7mBgXz zKc5}2-bhU5by*a|P%rk_y*`+=aP~wpfRy+fWn|s(wSLM8jTId z?asT3MAX_o{&@b3ZO$Rl*b%PGZFU#V$_nScz=~9!Wn}Cx`4KZ4_GERz*g8C?wutdR zsqRpL9L(|ml7pEnU9-x-s5lij|6>%0f2R3o9S0Z%!prf{-LDUK<&=s3edE)h3J?hn zJiZdX^u;>GAU2~TZ1wt1X8hbt?nrFlK>GGf`iAt{K~5QR@z3hb<8xLOMvDsRbMBf? z_nfP`bvbPR5!XALBdFq+`^)ylQ}${TR;XT&Vm$wb|GjzKulIoztD6^8@giHx+v(+N zFT;iB4*d3JTz0)mZHh%t>yVzEFcPbO-nr=h_YVqoOamvOTGDKVv~lnJ9~EI2*_}4W zWFELfU>w^_Kz3D_&3P4hy!wzxAog9ej9FSMRO!lbPlUN%*7h+0|l+v5A}?rW>q})-pv9gE(iarWTr0u)&F;&wwx*J zYQf|p)U)bR5rN4BH~f<=?m1g!luwcMoVFey1m>B8rxvlwV~W56PY_C{(v53f04OOJ zlZ!V7*gFmpON=NjOHf4-o3+5?MBpGz%yM)I4JSc$Uy?pnpSzIcTjDcr_j_LD72J%@ z?6O}h16T&fkBvdmdVr~d^{Q)EJrI%(pQ56%9r?cCvBm+S{-|50!!Ueu>N39;o+)Xo z9d`44Lze2>eLI=nf@v4BQ_zlM%k$N2yvN0-Bo0%N@`^qfuS41{)AZZ0{Y zEtQQX(fX7T9+VKd`*(qC@yDePBHoNPC;hqV#scfjQQLx>#k=<-;6|;0LB+Na3{pyB z2MOLF^+wrXyq(*7^xqwNf_7DT8vg=m#Bk4$jjKh-0L3AIX?6F@l8uOR$5O$ykHso) zZx-9fzJM#Y{({QTuGDv3`gZ9uz`!s4$AwSc(JpD{FE&uB{HG#MyVie{AFQ@~W|^#5Y)&EKJX+`s?XH^aHe1P-kfgDsQ7S}KdYR2uVuX@Z zWJ#q$DwST1U8Rgtsid(Lr6P)uxv$=z`-ji*y}v)a$A2($IIiYA_Up{glnJPCX?W#Jrtfyt&EnnAWHpI-r)uz?h*T^ogqxH#^6d8%WpsP9Vylks5gPJ0KJIxMd z1sjeYZ;h_h`B?$S8uX0zQ878Nx}fQJ=Fo=Zp@@z44@C8Cc;k26HdnjpI=Fhjv+ohs zQPM1g@ODO-aAQ$wBhsq`shauV&rXpn>?pKW%s#Hbh(tcv#Oq(duY+;6exa(Ovs^y& zGE`?k^7yx!Csuh-&ARgBZG|V)$0f+$kNQY4&8^rF9_}z~x8A*|ZkOx*_o5>9*;*L1 zyUKc0h3fTrJYNZfKl-A)T)q`SFh&(|!E;1?V#Qi+R)+w*Hq?`m@^`zbTnClp zBB*L1ih<8l7aGyNvi_D`gpzWBw6*wp^Lg{9kY2x+m0G>*3?o#6Oy1w&h3?c0(9WS~ zQ{6G>Yuhqk3|)M>C*q6F{y6kNIGL}>q01vwdKAn#Iyog1y76(3wA{D?3+eN7RtDfT zj(Quj*%HrHVj8GFFF7)eY z0dCh!D@tc}-RiG9C+YFLs7gm0Ml_k=k?LmN`9$SxG}MDBDyN-)k-0Wij{t0koL?>H zKjqEbt6dylkT{Yll4@FR5V1q=4FWGK^VPb;TB7a`Tf_ zB76Ie#eAI?5g0#DmU&k}zI+@T1YPuiQ+R6QOLsfQkG9DP9iQ}Sv*j%W9rVcvum37jYa{oLs@3m{aAJMi;t`F?)L8TIgqm0)??^<$IZ4n?@U7*h6E(A z*ZG`a!`d|;VWnaMKqtcg=U6@N9bXaNnsY zD=`OBX;&@`1oG(}hIWxkHx7uhz08=Q`yGWVU)W5kZf6Z-58=b1QgfFPq#Ckv(@}09 zjtvHA2cv?CV5^39t+`snLpu@*$l-%s)CGi(um8K%)&C4!VgLJRC_pKhhS~e+{?EYmA1IVkCp)Y; z|NOrvNPuY4tFh|QiA9~&cL%>zZOmByh)x>&Slw}C;nzq}^R-tG?QAWUj(_UA@a%|| z+$*$3!yCQesY#Viqe2s}w1t&oN2|)Ns))Dq>L-4GuW&sKJsr9;d;f=rZu&`Ld;-6x zIzl?|b#5VnU2;ox^P~jQg~kz$Sop1hSI*o`uTZ{hkz-?UH656$-Uu!M6O(Otd~v|% zjWu@rIm36M_9HII>=^9O9Io$zbG*wJPQt}Zj8g75W609!k(PgrEIH7rimg4$Spt}N7^y)vcd?~^_Si<6ra6QI4WlduZe6f-^ljFEjUkZ)f!;JOxG9WJuhyf#pnz6->blh(x;vtc<;Py|*G5pqi5HpHr8`>jd)b zd4e_zNE{<|I3*DoI5ROtqz2hiwRx*awNS_9bXh!8-Lj1srD1h1yGxZhBVou{h5OppVrz{?&7NLU{t`GY`9biMG{Bsl&CG9DyKPuUiA;vqce| z@|0|MR@u|q!p~Pcr*ev2Uw9{Gp!6nztx%ui!c=Ku6&+xO3f7eY?$PiBtl=CA)&KGO&$Tbs&_hO|ifnIq0!%9tu~=|(S1<32 z>-qCGQ999Fz+Sm78{du(o)4IApq~sGu&qgJ6=JknfNYWvsRE&$glcMhGXDqKwTqP< z?^fRpF^Q&*Bmt516KNxEh^1>%fOTI&`2521&982}ZP+4tv(w#8L@EA3q8V3q!a-5qIu-FyfClC>zupJ(H0mYvT<><3NQcc zPhWl7T|)M-R}+x^vZ9ztlx}7C1nBs-NSThwrotD8WNdwRk`!Gfr>{2yLJ*lK-dESP z*a|n*MCpbaw^%7fpu2bHCc7>FU5zI2#jmf^sQP z^LE7x4AC6!MA8^>V@NB0rrz0}N=KQ6w92iH2#mNq>j8c~?Y5oBrSu&tisLs+6gK z5dt|=NZE#2AqfDo+okeVdnwl>v69%(S{`ZxfhGb%r!o!#TTGl%kI~ z_#N&m+HjTjBhQ1~kc0MW$H&BHxI7&zzI+U69g+a=ukS`XO}F3jp}FS^4a_E*Awcmt z%Tl!p$8K&#M>piBG+|68-gr>+z;YV^WO<_?{A;OykBGLLXx0dMhXoK+9VFBX%6nt@ zy8P6t-MSORt~J@B63ws??KN+Jc2~SipsNGJ#fV?&+1N6I-JYFu`<-PQZG~n;LocBD zyGjmnHwZbch^X90U098~WyET&MUvE=wB|Tr5QJVEYM=u_Lm8@psh@JfE_h$mDdb0# zAx2uUb$gT5KLWpLu2$$QejgYR<*h3ZCKH1$2XH(-Ny4d!WfiEa-@!kEl`QSnQ#DpC1~-` z<|suW)}9C^4%1JG701`#GT^&D$`NXc*m+LNQ=yH|b4kj{jqp~eVvwI8CW%#bAY%X% z!G`Ms$#w=2ymes&|5SDz-e^sV(ZGIbiVnARPISJ?=i_0w*EZrj@dkEY%0o4f-GBwa zWIr6@`Jp&!-_yNUTn%}h7A<&kG#-LB?l)?RPPqw^V_?hT2PCBx2qR+Gm}6r2RcbIY zW8y2IzRA!SplQ0Fxg2!_fY+ib9zfn$Dk~MBOnP764pRRnhuG=OkW|R|f!xi5=<*Rs z9YW|o*X3KbMKEY!%=3Do(+@BZ2Ci&@4x6G=*_q!JV8{GQ+8oTS^3s}^x*xU4!tEDv zJxkB>qxq4_7fB~J&o^uT%tnq2sjut2D-o0#@QK@(qKy~%-7cy@VOeR4m+R^?5;>OS z=kcSK3(d0s;ov8nI`ita!HtAySNbxp#0_|>d6orN_2Yv5Ku7n1yUdzqW& zlxZ_NQ=0X`^1w6%3xFqr7Rb@RP6n|kk*=63`PzK~-4!-KcWT9(?E^**E@+db6#AX* z@w+6^C|R6=ijhLJd&C*;YexsWYuaEe@Rzjua)?ScsL6~C_8tOgo~X;TZ)t>QUAs}y z>;swkqWpxC<)Kf{vH*c z()me2It6v^Js$F#Krf+Vf&kWm0YiPb+`a1oT`pIRs{0t_PGMZnJ-H2{ts#@!A&S#0 zPBEV+ut+KjzntM4Qo(2(g-a@x=A{SH{$d&G$Rr+Ic{CTh-`;(6R-vh*QcG4Mlm`q_ z3fKtLdf;2KZ=Fkny$36Bxr1;Zfkl0$--UTRHcY@N|GBL5!Z-sbbpq~xEpHUXT#1ap zO9zo)ZwEbYpV+crM1@)G^Y_rMmSDW6(>iHLrw^Kd>B;6n$Sv&|SH<^0hKs3@s^$m- zrd0SiO?$!uh=Jb$0^RL8rq4VeK+6zpzy@t;-uJm^SmX5_eO2eRTsQ*H#VhND%m+Q# zq%gje1aj3qnSH>lu?k0?`}gwGl*Ez@_>-nR|B~zzj#@i+@Ny4K>p!-?{PpMAx2Jy$ zeoaXEvAVE5%Bb~{&!5Mxdqk7YvYe`D;nnBq?^Of2|6R%d?|`)l^#3zp{ojq&-(+{^ zark@o(Em_3El1nc8mq)d7KopZaGqDWrq2Z!hP_!=<&xfe{p;KvTyobMB^xwZbO9EIA@%>w78l&XiK$nCBh|L&A_ zRa8ZK4H3Xyx}Jt!S_wN*BW2R|;5Hv)=b z<`d;pxD95PYezRYB}6@Qp`D-4&#=Webn7OK0|fOLfH)*?0GL_I?S77nDt;)zsc8RQ@i$nTqWkQY_{K*Kf_Gb2NT*?i-;yYiKEb*jlI)Elvwy*{GptAlf zufkV7P^_Nt;|7QCGr$b8$96Z~Wnp?e-?oj~M#q@Ywsq;I76oc(M{~(6yb-XPD~b)h zTf@+QUuf#|jxq|z8&ruZRby;aPsYCZco+zC{auqyELHXe5DKc4TmJ)qH;D&96+Gi2 zG-72PUkEx!B?WHLMw2uZ`-cjLO_>HyZvvyy5FuN~+p`s%$D~Gdan=fiNbOiI9fq|q zr=!igqm8c9jr*0%od!|D9_?d)rz}b?unh|m)3d9|t+`085PWNy!qY|QTBhqC+2%T0 zWcCPPCd$ULR7az=%=E9(ZM}SGaAl zT}2}VLNvA)xuktZlm(ns75lk3l=Cv+Kx-;|1{Z_fEsQHT?;`u91l5U;AjgPXu{yIk zH##yhIrh&^V^4Od0YgYG#%l)~&^v}iP*JUd?LLy@M{NWu!ID-vAP=UYhooAyK^5a> zAR+Ux>^ORks|%nnjHAnA=(B+auw2yDfv@TM)MqZ zlcpKIDgbiNn`TDGiS9h$v9<*JX%Pu}J!(|4PH206z}rz=vUijsYqIcE>I~Ip>q*M0 zeHWHZ5q7Ir;X>nE@AC&CK!&0S1QKhU(WJ245#!90!ywy&K>96AS0vi2CeZ9tYG< z#}4_Ejjo*!7#^_7DcYlW)COv_Ehba5MU44eo+U;o6%4~#OQq;2e-H7o%(sP?@l$dZ z50qXCdJ^E4JsQx4CBHjity^{xO_$>-kPRi3e$m^r`-BM)A}Ip5+l}!yvmyUbn8|e% z;7xI7L+z7ZlK6qOTMnZ`gp)?7f_o9jpFD7#;E$ ziE;C>Br&+yNHdDiSg2TPL0?*zt2`)0$17)F17s=2i*$?=5p2FPo0lHDpsTr@t9$7; zZd-DzLTz>@K`{cJiFtB&eXN`fyI!a*3~o8X1q4R)<6DShD&sS+cUZqW70^UOnstzs zYecx+k~WP&QdX={*_$0#q6n5^db=^_s{D=i_DK@b0Rv|j)>T<_qZn8N&ksw6CG7(t zoeq-`d9qhT1GC=~20mf|_U2-@WsRHbU_>6*Ht_z0sfT>HxL-3-60}*$$g1{M*z1Qj z>s;Cv^=|Z-4;d`Og}dzFUy~}}E{p*MdpbF^|I~hUx%$--R*EpRbiM+oV0*>dgii*6 zLH|i}ZH@E_BE!M<{(IY%SL$P3{UR~`6#lx}2=p$Jbl~q2YLupMupX-GqthZ-H^Q(%^j1RQG1+d4}rPaQDiST9Cs_w;1lzVkJ2 z-+m`une_JUU~>LZ1$UV*s8zwL}t zcQs$1uQmb&r7=UEPut@(w05DA8<^o836$i2JnthT;$EGFVmiv+u$#*T>&}zIiBHM&6N)?MfH?x6{>e;9eN?|E{m%b=$Lm zd*T1|<`#h7+@R#czlXG#8(KcyD5E5=e%ndS#$D(+J-;IFG+X=T-=c;2DgD78)jda- zS9kir#uYP%yq<`PbGKupB+LZ$^B12+de9Axn z>bmMVTe;E5p7YMBGesF>KFTa{b+zH0fkZwmho)Om&l5^q9Yp;lU;)(P>h}AeSL8N- zdUmcI>*XT=GkeZB=aZj2+Sm>7DXp)k_1naF6Z6cBzEyhcSIp65ua+0+i<&>X>?|9i zwbD17WM;3v>`#--JdF2t>svH};b!?)g2!YI&=^mwifM_>QkJoINgt#epEOzcwMuEN zSW2(-yOlzrN<@sq1sv5L?b1gn?|tr${0hX_qGsPSMPKg#YQS7+yXy|vk9=Z;@w#IU zStHO>^4n643etB`3nJv#P<~_r0UKxl(4JF*VGmZg6Es#PA^@Xu#|#c%BZLOJul=Lk zr*A#P&WzIfitKW=6id}_CTIgb=Cxi0m-cwU7_aQj5F0B^}N3+@$1Mae*S z3sPb@faN8)C{oF%ke`D;57{I;TzDaPz)yoH99r{SWQSk>$j0ugpwIc5`+#Y{v^SK6 zSckGwE!Fx%M`?tjcx~9z-oVXsZk%PpZ2Z{t)cBYI8IIH+0$ke%RtSov+ZHJT`C$8F zfp@NjAH%yWPXg1>nSt3%!yTy=jC($lS%&Fq6K*J?ofv=CY+}eJ?%ySyCMDZ!U|`bB z299+It2&BMWmmaFgU5y>+vbL60S z5)*4D+%!=utdfC|1dB-;+T8ZgGTu`LyXZ;eaYMcVUTIQ?ylniBqRw4D8McG2tHFmE)8~-v5%0HMcfYp1~BKU0*~-`w!cU{D%fU7 zi2`fIx+TTviPW^Ri;>z&=Vx&WRqug~*)}}n3@u5#D$!+6(%SUrn;i>?vRW}1mzKK& zud_8!pR68sRjy2-NJ=!pJ`M8eaQ7*#fmLKT;~C zJyGF}J1-h$(rpYUu*#w4aTU0uA}Hc!JXCSu+X0pSJo!{EJ!2k>rVx2%zY^AOT!orU za645(#rpO(@tMm`?i*}>WGf9x3zO2Ms;B0J$GkS|Scu=?#cn_m%ekmsJrJCy#Lcee zx$aw_(lDLK5X>Oa>&nl$9@}|~qX*Ar)9D@Ipt@gMqU`|t<9?Ay)+#J-4b2*V!5nPF zxjy5fs^d4l)M1yBEM3!jE+l(KxHb(Zm6XuSd2SaYmZsP%50^YwfJb}Z8Sopv(U>{Xxwd9Y?xMa1 zJzJ4jb=dW_2&9_!_)5^+q^1^UBp2ntRDy1})udBX;iSP=nMyqk5I+%(VOOGbzu-cM zO4ve`p6!6r#3bx{mP`D{82U|I7N(-+*V%S0)drNOteh{>D-n9U4SLNJb*NZNz^-3C zP>#UrNNf*Z_oE_1#aN~IfkpPi8Y0Yud#9hy~Jmti_^O zq_|H}ASkd*0zR0g(XMg$)BRqgTGv{-Onx&XqipZ-V?G9LYFFd4oL~)L)xWez4jVjq^3?W%DY-p?bs{ik?+nW*HzJo!Y}e?r?=&x}$kpqMRJ}<1)vzlfJH6*t z8$9pH=InUBvhV~p$)2gRBF!+d=fBe}2bM_eDFjOlMtP>()5dcH>!WnOzVK)=3sCea zAi)nk;p+lUQrli0_Be>w{OC_U#uEfl$Og4(11Cv#TgRekVK**&<5urBM6MQu_?Wc8 zF{}crK};zy{zNM{5h#gDGJv_09NgIK2#5QlA z|9fZ;ta9z$EZdM-+&cMIHRcib1%5k1cJ zNO@2Han%Fh&X;g0$5(&KX;L(Wiz*J!33B-0a)@F25eQ&YkL=f;c2R%j^Vwe^ar%$) z;cyxlMB>5>NU&?QNFL$Cz&XIEopvd+pr9_=i&Lp{V*TM`-y=9_KyK;>8|n1ee{AmX z@pBVfvVDfy6k4T=FK3&b_a8{dXO-RQ`2Nhx$Kd+m(T&t@qQ1*K<&@=AaP(rbJnFxI zA-Vqth7|b!Oh_S;|2rY2{!LWjzdMwDx}n#VPeOiMPKi}~khd_O5oS^_{4mBk24DIM zSH0nsJz@A=R$m`h&mzYAVoqZDzh@n`CdR445I73M4|Zk%dx4qnb>Lfzuq{)SnkdD_ zCh#Te(^o&fZ!i6+-yKU2o1x74D(G1Ixxpf;pM7vS`tB`%XyJO_aZNVrWpR`mj;N)7 zU2M8wStPdNuleRQwV^|veB>8CddTQRv8MI)FvlumznC12C)etRjPl`{=pDp zEVJ-0(MpQCowpY3+e!&gbch2=z0zcC9FdFVDxeKk?~#5C1}j{U@vi&Xop)yM%QXhq zK671okJS4#c}$pR)TjIS&0IJ3q>5RQxJMg!glF#Ax3YO7d+W7{{5VUzf0wS()a_1% zwXhykT4cvUpYv&(pDd29cn2{lDa1;64AS53 z<7Q=8-S0%c4Jc&+I}9O7GD~|Gy_6*MEwCS%du>zLLJ=sjODaM<*)#Ecd}Gm=S^<2! z$p^-AYSKh8Cjs3q#}pGZG}LBIL@H*zQi0j-VJ6O(aH2?3?DX=G7si$v;m$FL6m}`q zZYOWtu{bnlxH0te&AyoXAS;G^=*ngjcjZtp6#b94?7+$6S&=#YwfYTn8}-9W4hvLw z*-w3974fZL7>3nc-j4a+*e|R~Q(~qjkT=T4nACA$8b|HXC)HaX&``hwqVV}8q60u9 zm%$W0Z-qxo+itWTK0?q*=h8dmEUC}2p>vZ_LpPNgCf&7@n|VFt*)}e;ggnCQQf)!6 zmk(t<_M$LLo3m!LQ^Z#R^)+CYCU5$u$wQqv*%@5i^E9X62#-k2Chm)F6Qb6MDS-N> z4nR8EX2-+LrgHC{>Q#JNIe9N-i0W>j-XVq_^Ep$7)Yko3kagAF_jX_D`F$;tR^^|i8C#oGEJcc<)|GxU6qK_vDl zXb1gUq5yT2kNN{;epTgXy+6TLoW>7&*sMFDF2QjZ^gVR}H87#Mja@g4v9 zWO!ndnUlh3OFa)g=WN`UAzVT2TC#(^C07YCWxW{_4x*xs%I zJ9$I1TuS&JA`OvG#3hGCB38$YbQjBCJprJYwnXq<^TPvozjde>Wt->*s+F!y0uwI* zJj^{Vz)fac@Z`XA<{$_Dk`q+y=J%#-|V!zJG34i`kY_(A*M-a2|DrT zTUMiS?yuWljI;R5k!#NBCF^c~4ki*GU3y#{f#cx69(+B^LxxGACq27u#{6wxX`7UK2o@(#WCcRw5E z+@rBYA-0fx$Y-cucLskRNu@n$Gqk%4uLpTmxxIguiSmHy$?+D=>&rz#0hiwYuAXXdvPE zbmjYC5?u%=0K7!{YB!q`nme_52m>x?7kT=K^LTlBQRQjtS~|Xwu5h4dtZO)%3k^LF z@GSU7Pk-I0&_g{6uc0PG!Jxf!cTNE8#iXl^Aj;v3a)oz%VIy zL*Auw&0jAptKQV#a0o!E9(i$JhkW5JH2@0vF9shbaCi#<{{BC@yRhuP$tKkIuY&&^ z-eBKk zPn|pu=&AFjs7ZBF;z(u5!}MF!FC8oU6?a-3@y6L$Aa50`SQ_sQn6J4xeSG0$$~jvo zg3x^r{kVeZ(U^_pw!y9_0gb{je4&x-gW7ijT8%x^Oqwr_kdvtfs1CBaxt$;9X%&NZoQR%G= zUOuQt4Z>{Kjp>?Lh&6M>I`M@Fd9@R`mn^ z5G#R7jGxE3rcZO<;E%qXO$x$%*Lm-`o_{>?d=2-+`2vKZ{U8m$aiN$q z>hc+&1fgAkFp+1X=oV9s+M_3NF)wzA*|u!I=!G$(Rv>iNP64^|PH&rhCW5@)FK7+H z2IB zu=u%3%)@}dy>3b)H+}8zQv!fy8oL!)W5BDJ(toNvQII1Cv3=~i4+hD`=+D%5Mv>0M zbOq|AU3})Uh&rymxAB30+26?t{(zbL>ZH08Fs+&Y94dO#*?pIsshQk7i_r4|l1nwiWQ&En_L(9YR6b~Y_8o>1J%Suosp!utW90g&JUP>FRp|u; zo``&z7foa0V#W)Q>ayH=h$3}!xW6t$k^aVNdV21e(>&=xpigPjS0;wVr6bh&H3e>8 zlI7mkxpB(r@0DzODLGp>Cm$C%4076F)#iG>9vZQAc`W(0th}joyqm5%IVOzUrc!4k zsQJFJ^QNz*wM2Vs63m3jQGH==c6o%mo86=HY~~g*n}q82dvq&&G~c7P2lE*$rD;GB z<-kE|-$f`ysaf=CWCU%uh%{fFHL2kks9SNtxYR;C6+enL0WM)eKV!2;-$?ym1gf$) zki}Jwn?6pXRsOb!{)=!+Vt&O!(wU(XZUIqf%n=KzC68DOJC zETAPv5-5pB4db@vgyzi}X+>A~eTmT3xXt2wr0z5FY++zJ+8*;!*&B;GvOExNPRP4@ zC_Vf}CAo}DP5W-kxP%dx02tJu7P$lUNPy>_#B!?-_^+Mowpqc;VDqFGHcnhHI;`TU z{^tW6>U0(Tx(VM)OFkV+FmwXai^?dl-4RKfe5pF_Fe=aJ-c1s=PIPuR2F9@q;mNQ3 z$lIklzIoXgxyFwIP=Q7eRwM>&tUzmJAkmO2ts==O`Vs2ejIRV_vnKnozGYH)W>V*# z4rak=H`WE$yREX!rTmybAL0K@TV1Pg4j~OCq$tAHvTC=Mr|`x;MMNlT&!Hxq>@+gQmV1q znzgPd0v}WR0u}kD@x85qiAF@1Zy6|<*OP$p1IlyeJOwi@8&Ncaym~n0HJtvM9y}9w z_?ah)K_maic=00w{wicbhueScK*h#G~W#{Y6;a}x%9L=}t5}#x33yON{ z1Yff`N}HGplEd^LKXo$Yu`}=Up7(cXHod@VD3${VPuTKuM}Tt?Nc^85xX7a+;NUkW zoqmXB5nbN;W1I4dG|SD}5d)a-(jM?YFncNJ&~=D|UUJ|2=TNKoA)b1r-LAk6zQ*tj z;>v>x>`uTZ{4L&t!mq&YX$n;zo`F*Vwt}jrjRqaX4yREM*!zcjZ>b#>{n+$2X}{(5dS3K>!u(7ha!J-=W~=5*e#QA zu@zS|*scdyRLl%6g3$2@liHCyRG?I9Zl4Na(DJwzn;v%i$2qL}3)H9pDsr%0_aisc z&6kb=5Su`uFg`5!Em%QTn*@VVz%>3ON71SfEL<1;+`vU|f3Y2@woBk3Y z(gDB&7{z;Xq@C?wpu8LeAg=A}AmBiJ}C&~jf~ zI*pTZD`iK)x@?t}OKBIgI>vMz>vRa8>9|A@R2#a0n9vskh%wp=&gXMYm(1~5%lex6 zwXJ&Pt;Po=mAU}n4+Nud!9)`Bv!t6T_hE#;3e|YSUFXuPu8Eg8NJjE0&%sa<5TZU897Yug~*;|o4 z_zQ~RrAfH4?n15i<>vPLb!~{&YcIdMWI6WuEN<%1P%3VRgPwkB3(!s;d3esg(6DnM z?|F`iZ`#(mr0)sNfgQTD~PRvH4iZcBFB z?vyPS?;b*#|IQs?AWK|00|OJ0U5~Kj?!4#iOE-X=I`{RdBsWN=$dxmWQa!+(`J3wf7tjr$IK^ZO}jO?yWtD1;P+Mnipv4y}dxj z=g74GIc6lURe+&sDfYNV*xNkz$Nau?Dt(o8zzuI(;xBdQjMGuLbOgE-;9{CnCLifmb#Hq@RxTczAAvg)vR5KVV$t7$dYcj_J}oA1`~9m2@D-2bJ#x9QJRW!W*)_X$~sJAg7BKBkV9rOwKxJhHLz zq9&vh(18__Lj_LnYmAqrbL z|CGB6%OX0_tntr%PHo6*$}SdvqTomy4*mYghmU6O((JGi87Co6$?0v_KOd2g4ATV? zYWvNXC(SNuwyA5ZJ4F~I`ECqt*ZAn+nmNzId)fz>__^bbrs9nDq1!O~@TF5K<2V_S zKUr6gq#BEOIR6XksU(QDabAL2*dv$HME<{rB%};|1}5CEy}gId!+4Ll%2uVq^fIvu zCx^V@;|MMY#X+U|;h6SnLZy0$DkT+M@{bY=_NWzOMJuZ*N>$W@gAukZWcm#IKaI@S_ zZ#|u5@wo1vio5_2934$5MiLHHC60ZDUC9 zuAf$vk0rJ#9B*^owp6K19pjO44nkr!DCgfsQRlZ-Sx1VPk22;~t?TDz84a-!7ecnk z0+1xVLEs7p+G*ShaPskxeX2G+E>Y{{U9;Ih`Qq54n2Wcr#ZO_ZC$}ln&pg!xg6hXA zOBlNY6w`qh0_Gr8J)WXcRK2sp{!RCq06ff~>Qi3TTb?{ijL8l0%gNF(`el3w5)#*U zR)cqCFF(G@dipsj|8N^7#zCokt%1R3u3IjfRCqM{r2d*i3hP^Ewg{wjQ%W<$A!N;q zESR;yi)NVF+UKU6!;cW5o;X`T9Ad6oU8URKy=9lH9Bnm9 zg7loVS4j3sP}op?^EqJD#nr!$4ZlUMyChrMs9%4$dkst|JY;BsJ3?ZaM_Of@m9t@e z^`+ZBd^X+lyOOv|nSs2znFMHli8;h9CsIMSGMjH0Wc_9Dh;lHcmxg?CCOrAZ5nHQqdk z4UO8Vo4CGr{r3AvWABQGvJ-H-Ul9uXU)|ZfJo8-9Wot0v&TH*jj)w!H^MNp=w+;Hn zi2KY_IA87SeQjQl<i3@-Ml z)`LKZdal+$yYA0gk4@%ZZj_>a%391bFn{g4G%-Z3`8C8G7%gBRu3nO0 zQ?MY>E3e;6FLlea-4rO<51bQ1Yg22GcABv0n1y2uWj^W_3EO)7A93X)`?X#+e7tbC zd%;7?gE#7SZTgbdJofO;b$4oStHQ_J;Fn?A3>^ma%U0Q)SHBmLjotny4wgX8YPCGtG~N-H^O2NrspP}T2riD@ zel80HL7=#BH6W5yBn8p+#b8J|$f2Z+V;mKty563xJG8lc9TuYCSWd@j&_LY#DNyrx zF7&T$8CDK`E8`?Gq}R@*XBT3Ph%fgm79s`b*~APYw|mZN2DMT-4#-`!OxK+$W^N^Y zU-Z~q8w>wjPN(aIz??%PxRiA2I3x!I*q^aS#TFMlQuc(d%wnC;t=LQcfwqJ6JiRz^ z-*3=e=xQq$VJ?N%hra2jUo7(-6eARzTg?u-DI^9~pk;6y7=DHe3#13nUz-@l#TCX3 zuo1H64ySJoUs9UdTd8WWiYH+>qu|9!^+#O>VF@4Y8=~4?F78(f!SfmOk!|xk?_S*y zkbg!z^K*gQZQljXPvnege@DC>*H%0^6JVbDNra^ID;E5_Rz_a+4`y*je})I|`2PCF zD^)uSgpW7m>C(st)NeF)b^ZhE_Z05Gxzo9VvVk1a|5{hETaO@sBHn)(QkaF`%UO8f zP6sfgHrsi>|M!>%(`6vbw@RF{%0AaDRIGY*8g5kD@#%Z%33Vgm;yF89jjt8ud;eVU zx5vjdecAYkkKZd@F8D1JcckvWaL>!ykJJD)bOQh^EAL+{C|}und~T&dF(InwjLo6v zi#?ZpJ~*G=HD}oJ>3ayC$mlKi|2tI~Y{>t8^Xi@1)}s^WMa^J$h0=84%lS8v(5^KH zSBD*RPWZmRM6fDbq3e5)BATN!b7u-qoCCDJ-MPOWy?%*SXa1Uw-6YCOa13&9vCrJU zqn3Gp)3Dnl?(K=nT{Au8aEknpIW^Q?*7(!XJE;Km;*|am;FQQ1QmXMU{FIAVSbx&^ z%HP=3oLX^{FZIIT4OIGctK^`p2Y6_PO3L|a`a zt12E&=+=ZZq>>BJ>Rw9L8(e06b%5kMQe&jJygP$8P_fP8U2`+pg`&8=62BFdq|Qn# zyX=NppEfe)dJJpusmy&zFz#v@5;2&46o8u`1BNOl0>dqXzKrzW$aRL@!a= zTx%pzoSIVG?$eG%EixdzlA61S(+SNjhg#bdckX5^c{cS~S(Sq_HDuY2S7>%kv`4PX zy$5hLu!3Tfz8Vwb(!OAZJ+ZHj(2)`A#v@A7s zi4@kXPJmix9b%~Yx3q%HN_KRQm!9Q{r#g;Rmp zb6*zKDRmL`Q&|TkyupA-^h3=Z)n(-Z{M)^DN8@&Hqa)~}-MjEQ1#j^%^N50C$H25T za|{f1g}llzgSw+)G6kMGJyIuMPNiv5>4l^fD|tOJcir3AY~AxBe)>QyE^}MEhEAfP zK?@Ce!OsKoGeG4qJ`&+rUcB@QiTJg$6A@a^ytbB~=|UZW8?oWO%EpR^m3t6Al=gWU zR!>WBs7n25ZGlQ-B|TdT#-2knBnmrEHqE!u7=yaZRT4~7Bvsrhc!>r`Ixcm7 zCS0tXcP_*71**+IFWH?>^+y2V1Lt3pxC7!*gnkcyUZVp~#exxLgwSyOk327t7?D(0 zNjpCYQTFuTcks|-8y(=M#OvW+L`ilwv7rR-QElDWT-UY0-d0MJXPWn%Nd*bi<{74` z$2~Za@cTBDTJQB?Z{*fax!-(rL-S^y!pdUAxNOE z#VkD@&Bn*!FNQo;MBCB8>TMS(#OevnGGMdNhFs&Ir3gP=tBJD?kQJv=A%}tn1)Yik zX4L4By|y7kRL_(6!{q_mS4jLIy=-Jtfs~+QQnU4!RV8VNmiRbN^lt zZM3ht%{M$&0#F)`W0x^1c`+_I~LItUGgKR5V~ zXq5{y1vFcV!u261Q=%yzoxHF!TZ^z@^gqap!`C01cppWyHoE9f?T zyd<>6d1M7o!6Pnn|Ji9Su9B&lsEEwGcIISMDsBHsKd9UR%LdgbArG4}{RB zaX}xpM_5#-L-2S2M_gNQNU!FOp4W4ibH8veE=aaTCD&uTr%-#n=pd|&a`Q1k3PQ4h zoVah4f!Pl=*Fh{iqE$d%2}PKIW(ePD2xU+l=!8Ql7=Rmtu9W3F#eRJcGHx?l`3oCf zT$ZzFg`dqQaN)^<4)=X@h*li>i0u&}`Kh~O^$d>Kc-rYhW#Jl`892t0^uqHT-Q;%8 zJQlIA#q;6Eb;ZWJHxn~Ih{NVSOM3v70W$KC2{elmb z>K1#v!uu00`kY^K&ISrq9-{E22q9(t7x1LtuEGhLvoF%ZvX6cy{~0y?Jua=d3!>Of;mv zc<>rlvtvGeOULgWqwYp~<|sn9{OF#e13glM~Jk`?;=h^@L(eFw_(J)XMW;lwX}&FL3kj6JSh`5Oj&B#nr(i(u`+6@ z_43N~*T}Gj_Qi|`vdL+)df`Qz*j~TP!|J~kH{cm)Gp!VS8?Qy(I}QXp43_ucuovSR zJ6tTd0AS>i>uq=Kt@lM>%D%v=?#-n;$9=5*ONTy zT@D|Y1dk~CyLuS64Y_uTee2fhm8fmd}d`ZDEz z@6W}WMVJxg-N`2dFO~iX&tJ7Mj@ziAR&qBTV|^d+>}K~|5#MvRD$hpgPU2U&C67%5 zicMp~wTn7D2gNnAUV!HtQWe*rk~(0}t+mUMTCdl$$cnfDt+mK0gGSG|VytZA;nxTR zh?{~v<%Hzq6F6}Hgb(mqbxHTRuG$*BIu^eAal`jIq)f53fJZ84%G*>^gz84&!e;#B zt6AliZC8RaHA8a=o+zXH+(tZY`Iem4gKT655}2{+ETz^x-tNJDNXXLZennwxMZ6p0 zt9YMQA&`$2Pcv`Mb=~T832A`erDwrp z8~c8)OBMz3fLqRi5bEiQmHXdUFxgpn!_=F5z1aI~a87M;z73eIN?K$_Pj`IxR6axe~%CwHoC9?Cvg!s z-0eQgkP_ei>MLyWGp9+VQ0llg`JZoAUDo2UADn*ntD8s`ZaGJ19tp{`Z?K6YI!D7rAh=28?u*)8p>Tsvn2@HBMz_ zXf6woFQ!@?GQJQoM_S-9brlR@9N^T2@if1^ROFPUyC2EQi%_d~@gB;_p&i#F`L!rV z;g9dovR@PQP83pj_*bG#zwdQB66jFyj{TmPdr?-W{M$6_TZ~V_;pL zvyr=POPK6~Rcd_xIIent0O ze{;478J(-WbqdDx#b6xobABazsJc4q7wI_;2g7eb#bEUZ4k|_3Ly=whFZrY?dV*PkMA#hBHh*=&X zt<+?Bqr(V}S#|c0UN;Dn4D}hsLP*;c$*n0V`pa_5j;=0%y24bd3Irps+_S1&Bh>x0 zD7;%V(w8@+j|_Ru)Gl9qZhf1FKL#vXn+_{rrF?S8Na#-7M#8b+f;FK*Ulpy5=zLk? z8*JHumZ&4c$b=e!hg3P68EE`0tqWQbV8`O5J;<=)&TEeXk*QWje*5b?0VF#(0niq) z?~-sY!TlUNr(O?i)*9FBQMPyWR3Iy+P|XU8wHMlLy(- z0q|S6_P@?r6#dRe0`6PLTid4na)cGJoH?eE5gFKz&hO3vTY{jIN$v&YDO|J-1>})J zjtf}-_|e}{d0Fxe&|4jtI{J>8vIp=p`4En@r9jXlMqJoj9m`I~l%-;*t^Q`_mS(P0 zaV{=^s?x=kzrCc5-Y12~OOy`6?>&D|Ut+JUu{61uXb=r10Mz*B<>)c|Ki}9CHrT^p} zasXujE}ZZGa^V>K1?>MQNZ7x>-=F#~1!?UM6T?YzQ!a&-QM%CiI@{;ZyjZF2rhY>> zBcy|KA@;oUDckrzyH&o*9)}<)9LOd%kcCR3^7g?F;d`eBsE8W0v=heDQ zzx;Nv7EA+6ndqArM@JhgPV4O&jlFzEJzv#EI)w42t<`Ycm89nWcwlGnIp?}%S=)18 ztOm`fGD6`(mG?q!(BJJ>r#mxFIN?7ngA18Wrxr|IdwTHFAU%ZE&T-(_0oALjTF4%Q z+_V~;Dz&w3d!=k$nUK&*#@Gveg1dtOZ(&DJ;-EG&j?zS?Wh{1Otvue3LirRkvcmD9 znR4>_5i`wu&8;oN0?wCG*c!5_sA27`%et;a*#N;!jP9<=H+Ami0$)M3K7_KRX{%@( zHRf)oH)BZTmIFUI%#w%5jlfUJW9G{+#IQt)7IP@tFSy4P0#)-0D>B00DbcNBpavBS zf^*I`6CGq7oBAqHckXmL6lMXfz0j?daIGT*bIi8DPnD$}f$6e}W2)-5jB`1%h-qNh z0RK8>{f!Y}tEyFXnOw1|+!q%93ARx^b?f$^7R}s<8on~ecfmJ?d!2I3{!i2&BS!2% zHc}_kqmGB&IVTy%8+sk@a_k)OtUMfQRGy_|+$v?Mqyz)*n%{~IOwki% z-pCbTl6DFaYHLN}JeTQSO&uE^S_ujK85?5a5(9aHT5!1V1Nuc()0LL8AYigPM=!oX zzPlUP8D|1@xw}r~bx?FiU**J&vd}FzG_y9p=VLit;^xEk zcD$}}Tvx-U=;BjbH9Q7rjR#ae4ZFt|KHd}_-~pD67uXeaU6#|hOqkoLVm%q>_8#BO z7*@3KEw^#<8dZ7gP$a?&@X5A8zHw{rPx)wFu(l+TIk`2hmMamicl{Tt6k|qq;rDhm zacrUwvzES}o^w3&Wta`vL|&Z~=S7 z@oHv~EwJ)vDB3nr5O#R(#QM{>*s7HV>7ft%FdUAcozqO29dFk!ipY3JhM`T8!35I> z4VkHi2DW`ndBlvS&UmeA!sQW{#d&Pd?QHyySN>lNPz`}=UTODdq0rS7>6Z3ToOcZm z89aXb?cQeXj&W4Z3WIEkW&oloLjB363ePS-g_t27#ymaiBTx*}6Oo+wcSN6IV7XUy z3R=YrxHdobNwwiV+`c%OcDy{yd{Z%BV`QGcUZi{SLPya?Bm-iK9}($LpbiiDg-2Rr z;fx_L233FBauH0dy3faKr3e!OFD78RF%HaM!oS&4cz+kwCbU~qr+7FYN)?Wl4WTyY zHjuMD*qHooQe&Wr_l+i7ue+xz#2+E*i zxEwpVK1{$m`>{*;s`JYP@tx{VX&x+c{_*ZT9Ei_PgHyG;0vmP0;&V7%VKS9l_;e$_ z*)gq#ASGaN+thRzomg6-_4LHQg0w(73fVdb zR-vHwCpO(k+m7|5AAsnTN<4RcXi)cW}CWvbsUAS3JkSMfQOZ!|M~@?7^>nAgYiD z;kiWlRF2BONGGt5-p+6{DA+BOaXn{OY7qDPxv+w+ZH_X30XK$89(YI#xGv%v&i76RSJm4o1=u&spkE^dLnkh~HYDnoinp13o)cc=T>z%JOq zz;_V2WV%_1^R2?QnMRc;2%((da;saHT&3ortY@~p{`B&Ply@yOEwPGk!MN6Ba*Jc5 zS$;evMf;kZNiTJ0Ns@?A?d6TM?;;c&csTeau-v`-Y*R^p*7Utw!qGl5@uNU(@O!G_ zj}Nnn_?(bPi(7={q0l>vX)xG-AmuoK(*K{+W%hrcE(dY{%&)Z{W&^zY9CHA4oswPW z`KyZOS0=97-n_6reR`R!Fca2HOIr+lI?$gGZlS4@g)W%};zEb*Q;gFC6Sm^XHqzD< zov>F9qV=wS6jJtmbY@y4d$^9a$fMS|6-I7fAE*1oQ@ZE6Ebk%j*?5VDwL)DApM~I=URxP_SRu6FJxQfD8KFIl}r0i-7 zvEU@Hq>8X)9qZ!1&j$`&^3k*|9}$P+Ej1j4v87Kh6@>gew{p5W_fO{i`mU%9=~Uv{ z((7M>|GLU5+D1_lC)_7I@%YHAi*8{9%L=d+om&*^yQz17#C2+2(T|$RNIlrQ;Oo6I z-V6mmGNEEpYE&IhDaT0XJkRTULoR0RKPgA$`*e$nSp*1~p+dENp{v6kri5d8Z(3BW zdPPDVUT)oMPU?mER+LX=-HzPkscsfLcX>ZGM`8L`fy>um^Lphd^zSZp+kq)p-F>}g zUB|t!LW*-yDF7!^WAs50^kqRSIYgz>ru#JsU*TB`u+^NE+_3a zB^WMxC|*oT^YD=9+*#h_C&~C>5a`u0fPbAb?gU6p{<%{HtCniQqc5I@`(N_1FOz|q zwIvr903yfu8|ACl=S8B#aY=p?$MigZTQl5lgejFv}$6sQbH%KM6yK zrj1XHIbJne<)*eVuFUm-#A*>Rr^af(FjK||U(HTRTCq-j|4h8(IT`q!OG2d>L3Re{ zpUjHCz{#_kcBbTNXZNTs%DI@Zm2vDlw;rDo^`t8*WqA}qkfoO6{I8`nb?fUO{XUWQ z8x;-8vx?1vS!G|QsayOdPgOQTenS;R(WN$-cNKyNBx0tfp807DUw)^b(b_FU3pOxI zLrt>*B$Tz|W$Et$L)-l2Y}XReS^otLs?EuNafC9vmzLSw}hoX2rZmLZqVt+zJE zkUONT!EhvXQWX|iJubJm@I2!W2Tl$Kt9)%;w}}sezSkE~+vJ%R2KD*t%cSU|k6MQ~ zQw8gTUAgN0tOq?|L^`bzlh+d~CVD=U6{&~xH{E3@IZSC@GD||TO%t^ zr90E*oDs|-OH6HS^CtHXa|qeMy{0)0Ja`pnFM7q~2pL z@o=^(ID2})Fp69*nxWJJ zd558O4T>DR6K?`-e*(={o(IVs`Us8I6+CtI9Uy3A;Oyy>F`x9Xwxy%oVYm)OXnz!` zHtx{^_aD0GB4hk_y`9@={01x+EV&qf``t?2wppJx&b8?8L-gSvicZk8k%&r`%Og7% zX6j~*lK{&rQj`_hCC~~LWTBs1!dBB0;f5D3Gan)^tbaU&S_xvgC@`~Dc`-CDExJ2< z*W`ZoxI@wO%QQ{&EgbN@p`Qv&Y+|7;&&jY2exR$qygKZM+jG)7j10N=$(RF z6#*gVT!Drx&OKWoL95)*)ovEGxCd_1PD75u$XDKlX)4H-eI9M0V-uVkjmNYfg_Gv1 zTKoba=Z>%^j%4e5xJxJ^UDEHy(N^=E{-pxb-6a~67vL`MYKZ~-OF9dSjS4H>*Q44) zW!PPm27nL>^GM{&sYKCX$)QLdP~%rd&dE87@{_#S$0MC*T}qQ7)G-DIMhG85#-|fF zOidzCn8!=A4ZLh1gg#4wVOic&^URy@9E54s5Y&F^OOZ^i9yM2fMUEr|pFMY-PaXpO zYl4jx?<;9&EQR$;5nB{nZT<>WeLND5tKdB@^|f{9(_JbS&+A+GY?`W=lWt+-#5k_efm`6+)V)*wT;*=F{&y%wQnUudiDnn5Zei z{`##-wLi6AEM{K*dWsL8#?Ru@N4#CcR#@y>zuxZ79>^HP9&b*^Q+zsmvn#7&gi>6OL|mff35OU@F@q@ z_3YWQitRrksP{3j*@f!==w7h{?v-GW&;OQM1WWUS{{wu}U8i^d=b%HHf?>=+t62Bx zk-0S+4!Qg6Xel(>B>(u{4FG?8eZFav=dI5TDNDT@__aD77HL1d-jUW7Xyk+vtP*t7rIp!sf-Jhj{b05`tDZPvM`0RnV0`&%YCB^wc7b5G` zn0j$$t}?N}`NJ{edsB5)9^I9mK!J>8pRy8SzTnSsY6$%aK0D{rdM+&reOywgFQ)@Ew3+KX98j|EXqA<$p2n#WAz!pGH}H;iCAuQX)Rt(Gf1$l)+^RWUyF zem^pD@`5-^9W+yr_ajtYeDcOw5Ijob>@W+n!)OM#9on=rlA-o;w!mAL%RAwgjHLP= zhPeKEe-<6O*tuJ0&KFKq9HwUCAg_rpUFK46Ym{RqW?vf8@C-yHahR7GarMQ1YG|pJ zCC*`zCY!+#B8Mbm(m>uE?&>v-L?5>-JunoT7A1sJzxXjru2}7re-k4inP;fwM#KU4 zN))?gM?sC?vhP%=|1q`1*ODwPYpL(IOkB4Zt{xCB&_=Se@NB)x#lwY>lZglltBa7j;vGz)Fz# zBRg>j-}qb*`g`{inXu4 zgIPTVOVOCF`PJ-OvUtF8c5jty5~kk}rmp$h&vIb9>f+VG7kDv5O*pyGqJg0Tt3li1 zgbnBydTgAB+&iZY__bUyoO&_;gD94^40UVAFe2|fVw+Nr*{?+W`S9(hV*-REnf;EZ zieCUlzrbq}rwJUP9%#`&&bN%4@jLK0{*?=?8O^TQ$l_19Bn~L*1}FG^&WKj&^kZeI zy0Dff1}!&6Ky`}O>81dr1kt@K^--U#^zeLjmBc#}wWdgoM_Cz3bldNXKjZ>z;m*WU zB_F*;U~eyDa#sxTj^l8-%!-z8E8V$?JBQsBSG_@Lh3Y-%9^;*&4{OO5%bc=cqE##7 z)X;GO|6^?zFb@Pp^J(dayLQESQHG%g3{6{Zb6#VKciK5hum~(v-4+Gc>>V<^ zGDBS#tk}3h-IWLFXQ}VuLhoN|_oiQN{}~sBujYp4s22rouw)guS4t5p0um#Ce`(qf z56`mY8FOa{g7F5ErTdL&VARi($j*^*HBlFi7p@mc5enuzwH81CLREtK(LSczE5Seb z+iV56P|ANOp4Ipfc;>MZl3zJ4Ep-IulQmYbc=x~JxFTCQ<7FC*Sn8H>ItJ2CaoJrEdc6?0twFnx?Q3;Ld_Tz;k=}a*C|)uC78`wVTTEa#cN*%g?(%#J{7ZkEk3Z zWCM~&WGHH9G8EjdOgHJHvdT(dd#y~loAdGAl`ns3Z|Cw2?f*qvbX3a!MRO%@({fq( zsl9ya6)G+zOPAcXsW*>fuujKuwS&mPd-d!@K19=28|gOXB40WL`&oE4@XrSPc~LKa zpywhg$z5QzTmZLO)W*GBEe=coIKoo-l<{&#et4#pX}RJhTe-DiwIPdJq3WY?h}44v zupNCiWB}y6OCds)hb&Cb?}t(+xoJRNuQiCCF?4tXL?~b34z>fy!kvWqwX?0^DoM<6sX!LU4bq=^!Ju|7%n3-Wr|XS-6yMjwvC%-4$r{>gNZ44=OH=K!cbVYM#*-1~j`RJ?gd z29~)q`-=Ief{Xv@V6hq5zVxDr$^BzEWtz|z$0qcfaEZ~v~jEqZ&054m>a8Yp7@ zwzY^qZw~%ZW@N>slV2UXHBHU5epxHOFIg9n-UatCcU9x=U+44IqYm{seM<;xnLO2H zX#Zn40G(|cdfn}hyZK6;ZI0%c?$4@B+e&f%;bPrbqqJ7{;9c>$C8Gy8&3j%Rz7p%0 zH+A-|@@&_wu?EVG_KEeUvNl8i*cZ4xF;ICHKnMK?8i_4P2!PT4_svl!fc&KXPuxZG z!~2CFXP;%MSpX%gIPItF3qN%CwA5C57S67mxD{W2;#sm`czdGlzVr4zG!88K^G|YH z37z+0HnZRr$}lRfkMnuox%x8S_1G=I&7o+KJT+AuKN;4Ww{Z03+`UdCoMl4S^795L zyyxK3)Aj?l2aab^qo%6*&t&F{DBHhe>)S3~)vRJ2(;C#hR6F`~U5UK+V&e4y$=sxT z|1HE`hJ8fp zqB{}2qhO1Awt-oAtE!?i%Pbs9kW~@@`C$(rj~oPceYl2%aUToD5Uq48uB{uPW>kdF z){KQEAksbDr`g2@G}=a5S5kiiC^O&XQid*sBUg$T{L`tv zpSxIK7xL?!udR%2lrDcp?oWi4e->y@D2b<_(gwFj=+_zmu&g4m zFvf7Q#yv@nATw;KcIyHAX&qH6dUfK#uf#SaJF!DV^5Odz(z)$G=awEPH&i@)5>5Wnpum=b zGImF8I@+~k`;(r-zJJCodL2%c)~IXyTL5*l08yN$U6DxSs-+g1+CcP@#Fp$|Y78$@ zJlod&mnppM-nRE@0mlt!xx;Wt#8Y1=89LP#&~W=qyknd@tdN%JPP2iUkT5zz8kE4F z%1%fgGgn=8{A$egwu&~q_(<1E*$zZ^a6W? z4!7@!$HJ(9JwZ#~AIMi(?ow0pX))vl8zCJj>_?_|5IWVwHP#g$*uAxjgmdU(wN*q2TMF(&>1fSF5-lCtV!}oWxlwkY=%cB=E_pb|#Y0sr} zaA7)%pJJ#oVt`=Msx5oIYM)}L4thfSlkmH}(c z%&t(pWfTY;IlW~c8U%_ra#uKevo&kXNRz+a#5b1p`b~c!MG(W%O!Q1gA%VSJik$i5 zco0}=2>O+i>C*aYT^73OgkOptsyf8 zD4CVx&&5P&6spx7FmShfloSfg7dF{meC`vIEYSD?s6I1h`IC|N9{sRQcbp^OM%$YV z0=mwb3#!(K#P*Qi=iNyC;;1?q&@4I(Ka~4a2e=`!q;kex z`4TTN`LQ|CS)(a`j1P|0{>;*9r2*_YKG_h?h2o`Q8;u$?y#RE)d>JUIW|XX;`RQDe z7olPgm+j-yYotylk zT$F|&AY70Vj}-QNqr2`|;^eBeUF-q(b>%7SG*N}}cv+Lnn`wdnK*h^6z4<(3Bgv(M z122r~ooE&4ealwSx*B*;!KHOorgCFJ!2L${{05uU%?0Go9+_)Jp}766MaA&77wt3Z zrv&2wrLpGb*_Ks5SIcTg<&5L8%U@GJo9--K^X~JelbfG@Kb2;jbGPmHUjMzb;9=Gm ztDh;Jx5;xMa{r0qvvP_v7;(}+-2GqpiHm2HmHsY&eW>zY6g}c3u#8aO-rR>|$ zT@m@o$iFlbn}1>D2N;W980>t=nqOvZ61{XWcV31xxu3q-b>^p0(5H&PpY*1n?3%o2 z`zy~9iaT2gReh9Q%xwj~moEK`-dm(pB9}sqsAV-p73DiRE1vI2dtNs*jP|QNW}>$UlsO-Hh&LAC)2yJkQNz|*?KT==S8Ijf1R;RL;eOP6e z$FfCZIYwfpk2c!ZjR* z)@NM6oE^_xU*A+w(9R1=^1{O#mPMrbnG6f2;mT+x{+4IbfYe&etF;x|J=~x`!~0FR z1S<9>ZdFtWFx$CM-Rp%nDn{x(K(xg-A zf;kLT#I;Ne(){k16v5ek)w-M5Uc11ucBa(WZQJ-MlguX`%^c}YtL zUhA-J-J-)Bw{b@COv%eGEytybFyB8)u>$48dd&|=Ot0N9*@wdQI=IBx2QL}( z;?s&AMu%_juSXgA72morww2isJY)aH?1=t8d0$X7K~^O$0464hl-gm2DXZX0$5qO^ z-RBH@d37ZbW9w{c-i3{C!5evuYX5F+A*`tt4Oms$uBfdSmYq}Xl)#VuTon`K#TgkE3uBw|7s=w?$g^MS>mzI^RCRT<+ zCe+kBI4}%=W%|+TPTDHLB`xpK7L-&ve_+V66qiSdn=5q_m>aEZC&6bq$NDYK_h;)n zazT7rqwPv4a6R)#8{%{1-R<%ysXAI)yxN=sBL%A0>%z56JXCu*(p6qmm?9nog>}Px zthr#hMUWkB<2iR`W!U$!Ec%6wgvbGI$qTkV)%Ra6Vg$*rGFrPbj6Dc6jx}pQdXr$> z;XYlm3a@n?npJ3GE>QM`Kt*`ICne!kVQ6(su&fw&u@modNBL#%t*ON#QDP6<-3P*{9eWyKo6+1 zO*i9HbAqz!@o#)H=#j(kf@C7T(l|ZSa>%bBBB#aVQ{2carNYNe%Mt~D-#WwF3^14k z0wagmic&Qml70%<^40k!RaZv*)h)KuWj$Lnd_4^Wf*=<&6Gwx0*y`>$PAEu; z$l5;t9!k!jH6+*I6`@gFdgZsadFGI|f|1bqdiDmT7u=(8zuYed(~nceE7YJKQgH8k z*!;R75TuW8^7xe$zG;{KC((;xcs+S#W4WWk#9pil1%#-!(N?YkBnLcV|G=qrR9>BO zaLjKdBLt ztDIdJ!0tCF@m-5lB^e)|mV`)T36kB{@TH(lA>HrbTDUQPWv@XeMyi)6$) zQW>7ZjwM!tH+$~F;Kk07ZeHeJe5!g%Z1dWI==pPnb!NYu2JOWq`Kp|i%j!#=?OE%` zehl`s-?>(IP!`wBwMhEf>*()Y^=AQl;eFL2BKHomv-s)Z~w{JL&$D zwJk#7av>j=3FC)mkiXxO(1pt?-71$P#X3&Z%ND-cihl_wbG3i#*XI+5ji3c4e~o;# z!kp$ZRd5qfbush_s}1eHDAp~~GK;|K>(V?uGy)&$@08z4QNOrt5acINO6}uTCFh>xW_PXYKB^xnvn7e8Jd|UU#Fe zFYZ5HVa$A|vPSk;4AfQ7VmYAO!mD5>2FeI*i*x)xMmdwY2}qrT19pv+oZ8drLgH@@ zD{;1~%Ctz$Z6hBU(3kG61;f4{2zBguS5)Eqrh7LKe5f5H?HXfzm#^J$8$qDaMx#CN zc_TL4lsGyxswe%0QnZ5lfD4=`0dwx&{!oF>Q-5`9SXU3t*uzNX*7ETYz`xRB_jP%d zN=7o@JDkd*HD>N#<{=`NuXlB~IpTY#6D`--L9vmgsr`(ED9KIs!QVi@Q`VRg(s9ai zPX>FHLbtf2%IWv1x{cP$`ma3lDP0ZtosOcO;O~f=NGA6InVkr11uD=UbA>x`!#ww- z#J(vXyM~?YHWagzs3q5>B?7o1S9ym-CVjmwdi zU9&F|#T9)zc@L9;EbM*r=4h$QeFQhdp;8xZZR@6McMAV9iJc;y-pJWDvA;)o6>@l( zeIx=qc$eDE%0^mgf520ZcE)ArZNvDp$0#sjA_aCZ{(E>K9!!d8u;G^tAGR@4duwa{6fVa=a9SI7mVS|}qJz~$^bChq zI)8mpIMqZCiIQEhJV~7COm597awpxx<Zo!yDN`H{3$+Y%@K7qBD){H7o~vpJ*C7(Q;<|NzjkKh3x>S^4;u?k?j^B9vt#HB^($}wt=Yg`<$VLiO6V--EBSvMp>*$Z*0 zWuq>pR8f-NH|=RbYld17)NT%pA@tNu$Cb2ZnG$n2ltviqpa^vnA@9s(>&xOXAD^&R zlj_ePgeaEgLwY*iiwl+?g0W@OAUKQ;x&~wp)s$`sa(@y7?!)oXVKqmN&*3)ZR%lED zbrxHRoMs;gtR+2m@S#A?G?^>s7?+m>Jj2T-EqkuxXV{RT)GvW3SY{kyNpOp`Y4+`jue|9bl&a{)X|1c zT&4fX33|E0y7jx}s*{oxDZ?@xzVmk{^oFUjS|V5}RwJMg{HkMa)$ zj*{lOvTS9XV2H zV$-Q}#lqM41Pez5Pv8MDTz4yK0+4vkkRzfq<$fGRXXNzg!^N3#ZuVCp}1(+!QzdV=Jt{@nsH5ZA$^ zgbVX3QwE(>WGr8BvMd{xcS=RzF9&}*a=ZK#QbuFze@e+cxW}mNE^ocXN*&Y!NDAr2 z=GcM{;0^&j=J^_3t81P+&15VCoBQ>O<<*hHOt>$=U$+lq*T^Uh)g863O0iEw%(jmUtRu4 zja_dKHL)VEU+VGwbl=;P9(OJNqrQeUh!5HUI{JTp#DD((5ASu$|MT$n1|Hs{ZfPCG ze=AOPSF{xx{rtVjT@PuIW)$9DWZU`ik>@`_fBxrS$9X#9N~QaRP|?zM&*R6LYpZ$+ zjX!QDQehY^M@K&CaQo}gr$<~5L*_V(3n8GeS@YR3(53>xjw$<%MY zJGPY=Pb(itFnCd?Uep^s_T2WzKrOtdtCl%(+%8Q)A@YZ@!T94NKaIqFRQH!IRx$GJ zp5dS5E*w0jzW-N%_jR0QjMpjatcy4`rNTA)PX67be~V&~F?7@jQJ_M|_WY_FGO*(| zWv#Wn>Tt~J17%B5J~Fw&Of=aZ*EzY^V)0?2MEV z*ot@>;;oHSJ_fP5yb)lO-c!*7$N*$&k7L@pD4XS#JOq%zn=f1zye=6qL3gX5SfP@9 zw+4LG%q8|>Z(}aTdHGgmDM4<=XEikCo)K%YceKD*XIa2;|2%bBbpDJ^VyE-4hnTON z>>-gp_Zr539Gl=)hp(qw+4m^6gZXhc&ZGq!@iDwqL@?e z*(-vO(#ArYsQ3Ge=? zwqzJ}sxnTXd_?LsLH9>1&9FFGLv0S zmHAQ3%Gxumm_EO|^l*!@Om$sYW=xuKt;Gp^24C+hro zgHpVovg@hXR*N}Ai0pBZm8l^mwB>fDg(Y6 zBX}}v`NE0t=?kv#S+F|#E&fcU92~Dt0ag+Ns6x^Y_C_DKIcvpN07#&&+fz=HVmh5SVPR<#u6NC{m}m@fCl@ zA$8FRsb+%tV`Nofjf^0)`!*{Rr?a9b(_^vX1}!1osjsF>_u2ETLfSlH2?djfcmizX zco;_r%$?e|I#T!2lpFg}|fa47S;cjc`LK4g zO2(BwxXYXbZK*Z^#+M0sE8);}9I1;z878f!RRL=KlKJjCS=eSNru%^)eaqc=m!(4tAcKX_uQsd3M%MwPPq-9|#=QkTVlb znTS5Ec}tc7D*kmUKFRk0{f|*!tkUND-@%47u*E34c7e(n}x>La#xjibxj}l`ci4gf1l% z0Tq-cf}+w?ENCdwgiuvfKzbAD(joiuexCPz%CWzF+~59x{+u~yX3d(l?yvfJ!3GsN zQiJp3c@@M2_K|>u1cELGcB|r#d>8X-%uV$A>lMdOtCPpa5yBkw_I>xCoK^;bjCY!L zWgkJ<0qOZ@hBp`XtX9UO85h{}*}{uR>L2N{&-j*tS+t@dU8bj{fKyh#OUwXu?14*~ zs|S52Nq`)dT-8H5&V1+bVf=F8OraG|X(u)-60s?3 z8FV?DA9)?{^2Y0M=_?k(TAlgv)8i0MbG;Lrc)QYr{uDVs*NR=)dEL1hPu$~$+kEw8 z{(JthW}EXbh94vXyg>HT1)O}pRue;%3m!aQ3XrGmNnp61$OTnD5dc@VVLECSb2vOR z`T$pY?Lu`Tm%bSPZ6odUGmfDRuVO(LyRauYp!U-P!_eK{71=`e$TFojH%lxuBs+2w zeF8-UcHs@Qva0y#?=K$5);)ulkV8bxMz`+0e7D`Ra$|r02MFFkVYFP06+9S+Sv52t zqpl|C984fG8d_y6*HX?LO!DMwaVYcMqmz30AMV?2m*)hFWHn zqF!~+eOvWGOYm#;zM^KYrG{#w`N4F1xVV#>i6jZ(Z(7<~^_l4pG|vjcX(?CV#b!Py zj!OJ3nO1e6;c)%0h6A$pKMVp1fSR}>`Yv*Z`!A&5D5Q4iSLs|$S!XtQ?pLJILaS8f zHnFSVD{<=mF%3)N-khRz&wc#%t$m}(HZCOzm*own`h`w!d)HRP`orE_ex1S#zX0QD zRbg7NR!p5yTA_?$J^;gC0U8c$27Nd%2nwJA2P%qHCI7G={oWabJ^R)D6q(#TUL%#E ztF3>bqVRm!>X};#R;?A00Mf6GjTNf%sjjutv^c!|CJrETYJt}Ta!3hDX`Qs?-A$R{ z+Rp3y^V#<1ZTnNk zZ&}JeNQRd8Ui^K4=(ROnGVWrOyWVy_DR8{lfW>_Hj~ybkR@8LhR?r7#n*Xs(ULjDi zF)~C!)&{s@z(WN%=o^6RPkl~9;j1IX6XtqlbVz|H;(WXy|5Kk+hTzfF41RcLLIPZ! zb=ojRBQOr`Pg9%9=U@m+^UgC)1f>-SdPC)7A{k{66cwf{6z$?BTO? zfK~J&aUhmA5~Ky=1E+B$#3(Ot-G9Ik5(1Z&1j)9GL^;rk$MBL9Nf!tg<7JCQ?GA!E z%Qojjf9jbtLF1U64*Cn@=#EqYkbCp=QZ*Nk1{shpUCUr8N?#y~*tzn+!&M9SvMcwF z1A<|)tbkRcYlWNF)$0zr%~G^_->g?dhc+xPPWg`mdKBZ;dc0wqvWz~esfGi_h*Iqt zX_}`ym{qSsr;p83>odZoo(bB6T|2$#ZT=Djh#E%vCmJ@>V7iRAVKL^_cvI73%0&rY z?xui72brOpV~cJPu^|Fgx$3*)3VB}ksV+lF4%W>mqDGP>ck5qGWDwSRTjZ%H{qZ5$ zUcIR3g8;tYTTpfS+l47(mr6#4&un7K&F9sw((>9^^mC@*n7tg#sLoMG2#McBG%kT3 zONrM1!ZHyLT(A;LEQ5ECj*A-5f?*K8xIWzMj>*$6pO~hH|bVpYca<|>uVE0muc7l)5eI7t~ zj~^nI2}%B)*d=Fiy%iAikeuOM$ZskjrxIYV-^~PE`R}-P;>MNg<~X2i*Tb5boUPwC z*{(39UhELjmO`kNt#DRz+3g$lp&`6+u^xh~?k9D@qWM%3&4(nsUL-`b25U8^Bx`q& z!B5yeiryA)LTnY~5jZ?!&k}(HLGAuzgK_+I{-Lx=s7e|V7K7l@x1CH{jTI}Pg9qgk zrjC?#WzFe?A6LgIo+7ivr?#IiXBJfjL=$9R`-&X7Ca}A@#*17I@OAbf>5ywuLZ)Md z-ts5w&Sz@LaJu_4)J)(zerKm5El)n$7-yO(Vlb~FWdJ^Bs7>W3v90|K`bDHb_P_*H z);M9OCPty#ZV!xjcG!x+_DqqMOJ> zEe^1bceg7HLdU`9I!?>Gz%V0xA85b2G|4BJJ=y%uKzXEBqZu2rx!cJ4n!{p+mYmSg zeaa7oPp&+C^Y{}^{q3eB4{@jhH+I&}Nde9maclqujdhhl#dsnWn2?2EziLM-$dT9H zdT`2g=m~5s92?_1DXvkO1hHC;!{o!oth)&!^Y|DhH9VLdAFY|AI|u<4F@IZaH-2lx zM==L8SmobznrGzR&s=3@z`(@1tCOUv$3>aQc&JkKr>93P;9C_&+TSwS^&--dNw1o5 zPyJabLeC}k9WLCQ6u29|OP30$UTJB(al8VPtQ#t7^H#kJzuMX?vhA8!&0d=t#cGg; zYbsU%Sb6I-;Vf@QNtnw4J|Tc8AxdF8=}#{{GJXVUc&ue~Aza{V3ME(iEJquYKA;hD zK=KQ9j-k|F(M~#k)e6 zt)wQ)4lyo@@WpAmEDtN(d1fY%OMrcTiot+Y)N=K#aEs&+>;`k)d88WOE^UM z<7n|#fSXmhazkqBL!kgZJcJJs^NuNz#uJ*QS5+ptgpb8bH$-6 z)3nfAZJ!`G=wPI_9|I5MHtc!X)wbTS5f_=3_=MiN1l!gE$2JcNRex5a9x2EDbR~ZA zH#vbB*JU|Z)*>`a4b^oHh~>W~_$}`>><*J7JQQR$3T;}!WhrxpNk~e}Pp09S6a6Zz zJ&z-rs+;?h+^&6p2{`XHyb!+3aopzr*l?Wv({NDNbKe}yC}q6rK5w~k=lj9zpN8Wq zb>rUt!5kj`x-ZdkvqZ3QX3hBZK;F~MY{Jw6F(YD#Mwgb&ML^oqj6T<;uU`o}{5ig} z_r-cSqn4$0$*0%W2>f@E-;|~MrPbNR`ciJlX1^RhAh$uXjQluY-fDs z@jjY74ro=(=tXrW9k2v;|IoR9GU)Zl_KE{JO7HTpPkEhBNAimEXxQ2_)YVR$fD$prW}g1{MP96plSI3L%P(DZO&;^v?1Ciy*pwxW=qetbeMDAaLcVw=Eaz zgDjy<6hmfyEQwFmh>N%W{+STCx-`L2#&5Ox@b|7+g1fOODhR5@cuff{#&hG_?nWoh z6(ozi=G6g$0m}euBVm{mpr+N624XP28kad?Ao*t#;lH#tMsQ38tO;q(TJHL2bw(0@ z7=F_UKsSmzgk!oL`q4tCN(dzFt(aDrIZVxvtOsDWmNN)Ch!{$*z8wJ;Q!&ipRfn|T z9I&2{8UEQp2N{!Q+Eg$(c6>~gc zDUPt_rNzB~TiVs=J3YG5!Eh6|d3vUzl#lJ=keK*wT_}6sfvQ#M$3;0W*Q>1cB?g}3 zWU%!GFF~nVnh+-wLc+h&u=v;mYah1R!#aih=W2jN7mZc9y^z0Otd*txAgH%d;wh9F z$=^}*q3CYSCIAHr`xTHg1BzmKqpsSYi%uA7ATy-OoZU%zyH)54h$ca?+b z-T|pOF+nj$^R~W1%&Bw6KLN7BAA-p!+XQ5SgB`?0Ur zz9EX^%G}x{>=bO3FlY7$Q`z(=*y{ve2M(x|knKC6#Ozc`L~AI&K1|pqI#$injVX92 z+ND(YW?hn=4w_6wT4^;&4fj{%%BFFO57P;Jt4?4SFFR$8fT_1lkfQqh)Xuyy^1SRH zuZs3ZMuJFeeq`27$3E#igzkjUd=Y$rj@cUDE(eef;FqciVrK+9Fn*AmTxi`;7?YJK z<&Oy>BwpdGDGH_})xGABh3VIRYK1F#O$KquW83P|ogBxxV+8-=;UAc944mlSS) zReoATP)%ACy9I92?&!$aAMO?1(aM~iG)5>DMN4-u^BP~~eS2)v5D$qM1&T2Pf=J=3 zmzBV#%W?>%6osrbnF-v($7Wac+(7huAY4I==pwpo*aGqauP%uJ4OqGrCFrE|F~1)z z^=8ujEa~E!p!+~Koq%*Y1Z8JFp-eLc)z>R*F@Vnz_s9k^{mB{6w}k1@DQ|R~uRch$rT>KWD3uSPxk@TyIZUd+X2Z@t6d(4*(BjwqLKGoiI~m4HYfunn$}id z09+{mE_Uph)Fc$mzhAWR_Z_D1MOY^E74(61DpYbD1iCyQCez1E31DW&$Q$!sa5Z|5 z>5@3|`GazRtf7N~5Ex#$xvLU6r^{x=r;Cu*6nHARdZK-YqIlmq-hC|2PC7-#WnQV* z$a5;=7F746Pm(_Sr2>ikgW)b^-`}}%UqME+ij(JjLJRx~zi4eB8Bu$>9g%!#uXer~ zttM3`!tQXt+Bl8(ZLDWz*PR>aVQDv@U(h^<62pZ$nY8&T zRl5*EstpgS6n>_GvkKR>Hd|`YY8^Pxj@2(LW)oAX7Kjb4KIB|V{ae?MYC!Qm1G@Gf ziwpYy#Sw&;zh71SQ@mA~TmPISMD1{25HeAbXpG8}9{p~#;@O#}B>WCvnO@S7ujOXv zx7GWBi!(=>`Z&L?!XyKz>ktpd?j$pA#soFfTN9_F+GC4ABqQp3G1c_lyAR>hJ&$}C z?M}=5Y{Q)hgANo=l^WJv_k37Bx_{+|PK+L!zI4w)?&?6bMrsQE4%s z0IDlTM+~o?=RJdD$Qn&G=;&=HoZj@IYBTP-QevMo_^{Z3`B^nL z=WPq{qu%SZd20fjt6JOw?)>H&l(lz>M#`vaJ$o$M<&!!v)N61vWD23nD1(LyHELP+ zB^M0FWPyE36T)i;fB~)_1U-D@yVECMv&napqgGkD{4osEH<8FMf8fEOA50b_A|O00 z7jAIX0KCRiWt5h{FW;g`0>KXYacqO*pT4}ETWH}!^4E{Iim0Eoe}Z4es^#&^BGv_S zcl;nQz(Z!OT|{!lnvC$>nL|XYu5QCU$7Ziuz3d(WLHHy^%W4fkDSeU{X63qO7H7u@ zGA|7fuJwjb)X+15`4#HU+85;tQm9mgMkl&ww(Lx{Js6dV$? z^ul+Fzv9|qWmZoN-8#B?RMBp2vutb}_cUlp)$!A8GcogD>TZvk14ruvR|!r4jR1QC zQv&(P(%;mAYbp7ik5m8dY9R7nP_n%+5GmFyC8C?l#;R{V7R*NTEb6vK3#;wOw*D|r}h35abij0eSl^*nalte2e<=#tvEmy!~t0M?;10j zE%_9OS17_X9}nFYa&Is|1BO9}R}~X$0x~?p+&yB^&}pHF>KG=#xvL;)MnRq!EmTn|vesaPP8iVVDzuW| z%j#zF12Ozi_e78Y6s3GMN&KMY7Hr2zzXLD1Z$lZIINiS3q8)y$?A5tQnG^^>dxfY#hEF>wqT^Y zml2TKB9d902-|ILaND6%_Z~l^J5bRdW!!?8@=vr3xnmQ%G$f4rbX@(&I^%X@q9R}H z2PUW0xTj?uq^jerSG$Q2(WDlU3ZG^M4N5GVRtp0BH5&Q)Tb$f5Lu+vWCon(~X z`KT(>-v$LEVxqL7xwLwW=(YDV5I&GRgETnSax#U>p(%%Lf#gN<&&#FN>+}4@*82)A zG{uA2Kp^SvfUH__8sMUn`0>IveEqkVh=M#sccC{?87Nxtp-9DCecfNGbYP{Li>-l3TJZCnAa2B>r1k%FFDpTZ>Y1^Pfo8dld)JZJ+n8EPpvOkLOjzzX@IQ0u258e}t|t2pMPc*F|m2_kTC81>okzq;A()#d~_$ zN**c&b1S2ge2TF`kB`?qw2C-dwbt&3z}fk}LMOQ@tnT+dL&ge$O_4zcdW5XyAvCH6vGj)@XM= zC8m<>cwAhTGQKPGutA9AGmWTeIwkh*;zQgDxy`5x4->6ZgAMOC6wcK4A|a<-*_NM z;txF_n0uRi-V0X$5qHJdffIYA23!b6>H?p*kTHj$FpVPXZn)D|_7xGQuhuT=+Cc>T zaFfKQQjdL_&ybfv$Jpun`TaTiYtStN-g!`Qsy}7oIRZ$}Ku2r6Ecl_onXq=|h;NuBExl&0B#p8OTzFLolTN=>&g18m zM_i-0w1XC1eo`3A&w%R|;L|oQh2QkCXnRV2XKm+}mo*t$)Ipf7EP0%`#c-_EA!6~U z&c8)DGgHLu>;tnJ6W@xM78WS)+ZtWZ;E%$>-fzbliBx_wp%t2Ttv-{jop;XhvnvI# z=z!Qd79l*Z$)6wKz@hERI`@RY^Q|JSW7F-mAC%5uqeN7U;twgfChnGf zo5Rl%84c==#%j}st z1p?>e9%q-7D z;bB*329k__-N3Q!RTg%G9Lp@L6a&!*(S_8v3J37VF!;C%>{k@gvrXy%{^0&<$GNzn zU|{wn33R~>)kuJ{93U?Ixw=j5Nlkjx4p`)b*)fBT%zH~93#^UPthU`m`n86Q!d)Z` zJ(0{ReW%UqD5;Id*_xK&whp&T8Mw#o9>9FjE?WThzz{nU&=Vk8e`lH15I5XJM%|Kd z*PqM~9#Vq7&yf)R)sVn=k{AOsj!qfkV`Pvc#;}Bq3;yykvJbWI*OHQ9(b9?$?W%!) z{G-RGMZql^r<~QsBTpj}&*a9UPWSl08v|KcFOM^aK)w9;wG6?`{zGQo>mVj1Uesc) zK6lza}#C%{{&l{T$ zoEFJ4G18FL9^AKM7R8$-G!F@8mIq6{<+KqX9yN{I)z-S*`u*%{O8o?Ti_k2R*#)%rutm#oXuRa95_Ba1qs4^B% zK(+@({9B=HBCX8-uOozM!C#i|e@^88(Bd=TD+>^l+NpP0vWl-wIswb~JSC5=0zj6h z+e730*hiBMVXHzMiCNgRzM{V*<|w|>rd>(|5Hk8*ceAKo~h(T8`m=3LVX zbpIN4#Wmu3_=*Vjn);bmzwe*DQ%*!V4~%wJFZREWhOmg3H&jpL$8E{FM23l{M8zE) zzwFGxkl&hmoG>DxpD^8hM|cYbkznAfEOwmqP2Ce8iZZ)Xh<+puzbz)XHVzw^`*As@ z&PLF=VEaB>*IC_Tsjt1M$P>!B)dkzu?e9_6XB6`YiIyTbC$&`?W#Q`TeboG%LaJ$7 zhTgjANu2>>5Nqd`UR78+FGGOErGsok> za1F5(5a_fu6+4951atWM80SPd9c+N;c+`lJGK{clJo{o_T}Cp!`fdi?;CVlAdKT^a z0K{p$S|sMI-A4i4s&1j;_ESyDb;DU>#7&~KhYUn$L#uFlI-#Oy=yK{HREG5+2sn{A z;6h?H=WS%It;3BN_~nePJ0Oh6XkF+T@n{f~jgQusf~yaWu+yD!)@{aR@91+ydbS2K zpP1M3NR}<>7Vp9>%X+ZYc2Xx=s&dJx) z%=M<)i!g^=>}IenzN z<-7CCmY84YB0e*1uD#T4+@-W|s~=N*kOtH}b}aG5KJo_h zI6RVB&C7$ckzHk=p3C)&j`mYBX0qPq2i9HNvd_38D8;Jv5sO;A@n+k*zOEN@PxqJK zZZGezP#6^tR$Grr$x4sd8a?kQc*$A01-Dy} zMa9krdlh*L!=}@v*6a1yG2ROj_waCTB{Gu!+G;v(J73-HoHk4!q#FwZfp})(UQR00 ziVTN@&{VOr@oZ|VR#1ATY6|1_e0GT=;+HGIWWu0TLNF+Qq6NnS0L9p4)?hrCiMy^B zEu_+kVAUJyyKRYHpU`KKH;E+g5zXGB%;<@v&(LSf7SiKi5~7?c@M;JR--BT0Swkhhnn31NErbf+C)F~=U?vdkXyym(Xo6q@s6rkn0|_C zY#7p*D*+^tf&Mi_fMfPY9#T_I%+ST-r&1+|*j**QC%S!lAIFbxRePjkMR+}BYmfh` zX~$_D44Pnv@INh|e>VO2ROhFLPX=mM(wAJEur(x(**Yy@g`49WXss$yGEPx`vmRlI zd;giVa;EyQg=(@-wuu8VYWah7bKiBaWA~FHDx3m8aecwATqEMi3_M~1=->INU(T4M zyoSHyJ?7e^wYzFcVVoY)^vj7K^$UJStLJRTQ|iV0stwad`ug`}eedIbBlLR{PDN@| zVIi-By71#CUl3m|x9Wv{z4qZZymDb$HJ!wHS8mL4es6%iF%)-3QyD!_#zp-OkJ`y7 zE@i)HH<3UK>P0)%jP6Y5*k9hA$v^*ecedc_^6p$w;>o@Fvb@WC3l$Ha?k!fmT;BUx z-F|X^ss795{a+1#WwQ}C8{z%-jX_NX`oD7_t`8V3S%ZxKm58oQMr;4D_Xe)b81EJ7 z|AqHTWbua`2g)jvkm4L>^`iq&yL)85;Qha4wY=x97Qe_x-wl!8yF5{!H;)5lwbWRd zYW!$G(k3Rv>1k`s!{hJDH11unoezHe<(X?sO4@M9(uZ2_!AEC*a$4BF@So}`G<*4U z^i9~t;^=pO5li(@N>SgN^Hu^%ipyP@HV#x?F^Q*Y8=5O}-Pcu)DJE>Jv_1&kms??B z&g*-Bl1LOT4!L{})gLsNzcul3pyAs1)^6$fuYupxFTzfMn_}{$uI@S<$a-6z^J=*E z6k6-1=gXJvpw)tg+3^+JlxSBFql)84vOf|(nW0#)%9YL zW7~s5K|7g=@Z&k|?3igZo|0L>r;@J2;|WkLz`@A-I88g>87t?5Y?$P7RUH-g89F7S zKIHn)T#4jV%Bud;A&6b))VhX@#Z4xCfNwm6>5q2IV3=0;OwlT$b8}AP`6~VWP2=Pa9EEd8JPZCl zvr5JO?&k7$kQ$Zk!>*7$*wOj5L=)wur8;CIjXZm+krwU4j#_Aq9Z}y~dNJP7lrSdcLLV>v8n3GBR=u08(x=6eBXNeM*25C> zsjoIY7IprhqI0j$#!6=^Iw9jj$jn=-H`i=2cKE+@fT<7ECNq%fzfz*8De7OHCXM41 z-yi-0+j-}R#F|p0q+kZiJ>yz{N(rQdWW$yJNQod$zj6SQ$qfCZ(e@FpyvMz!*kKN<#rHn_GR$6ST3-nl0)Yz(w-d(kK$4K_;MWW$V%iYm z=&UqJ8Z0_mwv5;!3TCachhetoOW`r;)DY9co)pVVpF4Rr2&qYD$m=*pnHq5lmx)hz= zgY4dtROv@Pr8kcVX4t!<-qIGj&`cK0YE`pr37I(uUQv3|^dssw-&J4pFz&K+-0$H= ziN_di$G04hl->emzCs}P(o&y-6hw9~BZ-CnA&tWe~lspxui-LOxEr`6_o&608|o zl!iS`U!JWEPf;7kQdQF% zw-+BjYy2(X0oR%3zMK8<)8UjAwqxk$Y762^DpHF$sCz^_f$R;I2$G^-_@O55~E z9|+aZ-f%HIvABqvT`Jv>J4B3>dny_|_=R!2G787gC;qbiI^>_WRpMLoEA(5y#nG*= z!KG4Hzl0}>+xmU&@VBUL@;p3bN7n-_H|l!g%<-3L?`}CXU*Q-2yZQ8|n{xbD>2TH6 z+x%BIMQzwT`Dc4BF~G0&KiyOX{GZ*_@&D?kG(P$cN?P6BxB=$*15%XoTO(~3vVCk~ z+!h-oYn5jjufxCgvo;5b+Qp3IVz0eM+;^&br2 zi68$9QnV!LmVD)y5*0xuA1kTx@cxjZ5H7A*raDcZ%5z8X6!YjR=R(5bL7~g_;AiHj z>kfjFr+7*bLA37LkH)O!9{3Ht$#aY0+an%!(csy3LFbhv zRXBEkoT~_Tw8Z6l!~K_Xf!<#CAW~;(Y03(P)a&34rwPgCVz-p}+~jW=uY%~~xe4jG z?f{wL>pMzDmO>ELK0E{j0uYGb^EO3kMia&4=*=B2D|Qwrg_6Uk4}cG+$=MPq(kZuy zJP;62h1j(~x==z2fcRBcLvm$A7qt$Wj46Xabw4( z1I(yDo~9C8T?F`>9VB;RrY1<@r+9?r>`|NuqAzw?ttlDoz0QPZ{03xYdHfcwUigeC z77t?JY?w+Hdzj1ALytM(_nm5!O@_aUdfp6CW~1PC40! zhnDG`DTgq!5}9;1stNELQUWs~b^t1fmoKjk3^0>CwacaB1=vc)5wXK0^x9RURNL3kkR)$%6F zLv$T1b+qP2sOn_`;$09??mi1FuMsY{YzeBD=((wYjsn!|d})Ku!!i$cRJUXL)63EHu$|eOVF_Y%&>a_t z)};~B>$%&51^JI_v%iIZd1{pKW^$^anQb{nls6!VvT`rP=lvYlHSM>@GWgEi(TOtE z$=`nJm^j}jZi$|4J$c>TW!DCt2&(lidta8_HWJA69RByDIPsv{fMAy8zf!oUi3H=4 zGY`AsS{QYCWW@0=oRMLHZD@0atqmB60FCM^$QQ98ZAs3Zf#Z#NY=_SaOoBX3Vn;44 zLQPJ&_7>t57YB{j=P1@oTk5P`^_4b-n)gi$O`kvd^w^&oAY3J!dQmR64J3&i~plYTU$*wFytX(JXX+rgtkMlQzhB7~$VRSlE@fUl5I< zgK(ma4cPB5Y-I57M{c_{f#^7aSOl?57qJJw#N>_vr7jbo&Et`7P%t~u00ont&yUDb z=%dgfkf0a{mr6At>{d<4@lV#B>qYZPBIuy1=??CIK~s=u#9p6j2CC87H3q4mk1UCk z&;}64cKlqn2jOs|RI-jwuSc6v$X6l_;@V6_mml{L)tPnGV?I6!qk%sC_jP{Xzfyw-iIK_>qihEmFBAYzHL{fllvGuU9;mx^sOq--C*( zM-IwlscHC^gjDccSTLJ@I|x7FD>9CUatP5VAPA(jSOP;>nB{v!tGZJTsx|D31_2NY z6{pB?VHgA4TrZ)gs|S1KhNgiDXqY#ePI^Ww(hBo#g1#_f=9j9l&QVngtM+ugc(UZ6 zr21&+i1O#pX8ngjY3TLMLB;on1*C4R-K4?ZrlWOvOYH|z-t3sc+3XCRWn**Y54>+w zsko_B8|4!RL#n;!6fp|Da-0tfY5`(pX&|;^wY0!(+Tc9=y%r>uO4+4kt5PTHvsY@j z%PL$#j`FAA=*O+y>2GK6d`u4(;5f{xTWg(CKq2bnf95a4}z!CHOPSxX1ssL&`<+(AEXSj_>VMWxL7tE`$y#lcIF_6 z4j8gXdQ|5>aK2GuBsN8oZ|dBgOj%lt35t{cFE~Hv>v?Yj6!=Q3gKynK3sZ1%(b~c) zr}fRn1L3nknhicAmi}*={TZ_U;0`Y*_Y}~k+9H%cv*xo5viM` zcWa^ldsXPu5AUw4x8FRU?|cgk5m0mOLpFirrnj0te~DNn^xWAOx7#iTurLHtKZz3A z#2B)3I!I$#>BYOq{pmv5MjkWeG9#?SEThjABptM-{s%>@&&vfL!7d6Gwlj?w(# zJxISW2oL+_{8_;0dJV9hrc7sNaMI{2M4(W;)eN8;orHU{xRl){ZJ(a9#0vT$fo9Ux zc>E?p2*|plw_GJjdt@JXY^-ez38^)EyEmF&1DO zt01tNzgviC^g{rQ1{Lu5S^bo z1~VR4mn;GU+dM@sNj6qZEC~rOD!0PaD5nrfv!IB{EL6^&n*}u78>YD*&)wTt_2NpNOp>oeed9T1lm5X@!cCoi zkR)|pDf60D`*M-Og8K;_t&Gmy)H6??E4(VR6>RHq)S{xd(Wnhgq} zM{Bi0!uOonLeN*8rKEOCOs;MSzmBQ(%onun=#v(m|y`OP2AiKpr; zy#)G?W1=?iiN7_nd;GQX?Dq3Iqm?n6%FBnl`}SK^LrLd$`?c+R3tmO}Z1yz%PS)9TD|FXLciOoczvABS+?0O zrbIKafh3I)M#9*hlw+FLMj`^e-fs?P-c-foAutZ4l20`<@pa3c_-E|UU5 zmw`}?+u$gNRJf;)IVQHg5oA2401PNQV)?kJ=!nPFm2B;It}UN#OGho8&Y}d(6~6p| z11k_aFy+4X2*+(!?$7A4rt&lfuo9v$TyoYP#4sE8(!nG6)r_sfQg!L)Yd3sVV?aAI zFMov7{tQp9l^vh(o;4e`I={-YC9@XFJPI)85&li|Jg3KtZp>SoSe|h_8`g{cy-Kja z?l#zX-}b(@K)tgZHr1mw25XLm!1NiL=s0UPETc0TZ89)ZWhS#lalG0UIti<%M4~ue zOrDMgb6ibV|2bV}`5=#7n~KYO+H(9v6V!u_g+mLW3uR+P7^Q3$X-voOFZH&hyOlA$ z==H1_;$lZBXW4uJfeIq#$www$|>Qa~ne~>Dnj-|1+1Fpn&z? zZLt>$gk+{1XHTyibI05-RR*P=hZBh=^4mimijGfBx$j?W|M22;ZQZTXbnFqj{B(kX zUj3EVxtS7urvg3*Sk*Dv*ZapTRBYJW@p;=T8?acJrIX3t`a-Yy_IV1*0dpwJ z_pZ?JAvx_1%HS~_c-=v!^JnUY>_^k^96rp0-z`0rR~(>4>utkV~-Qr&o)MYc}}((aZWWyZV%snBSS6J z3E1qeAtVPPJMT(auW`WzbiFaJGA*m zuCyxJ8?L!%TiHxP#5?tWPvn{V{F3+f;{L)@0i8fYPDx}Rh!RbYT3)z&HABR-%*^J_ zT^6;mL@ZAqi1>(%Z$9fSdohr-yA71%zIl0jP1G3w)EiepAW(~F1Q z4?TeiztZ;c(XnFPSeIF~!J8Ijm;O2K!(_p{UJ@fCOvv@e^7uItUBK1{8lmD@kYUu? zbcl1*(<$w%yWTyV2BtX`yIT^*S|DVcM#P<4iQG27jR|LcVAA=$IA-bLI8H{Gk}it7 zM`GN9wz_GFKGF0NNn(wV?Tcl49SlTRXi*P(LsFd>zA5C{i(4JGnM#{$*vJqAib4~E z!e*E_6c7r-OUuCiv99j!vm%B*B`BOkbh{xt`PTr;xzhYa6;@eP2F zcNs&cL#}x&PoB{J(z0#@TZJYEa~=C2cd7R!86bqd{p&5jJ~K^|dUJ`sk7` zr2X5=|5%KCeEIC(M|rNuLd|C@n5d)WOFcThqUbQ%?5~Sj_9{A|+e_Ah=bwq_MC?ho z{Ps(CQNOzU=#y$Y)pPOFpKRII*1!hQ%)7jvJiGe*N72f}&5w69moDu2n6(*QfAwv) zZGkRv3I5~l;^$6x+SNSxUm%%<$K1-<-%%59#_q~|RYlG15^ckYMfg}26tF40nzg_s zYP;E2*Bi^SIGdq0HSH0D1PdWSz)rvwFJH9afeafmG04Cz40}u_Z&89Q;}T$jP4t3( zpi+9?O+EIcanuJV%;YqenBVj(RrYXTL*JWe%p9(-yX61s5)z{K$I`Q#1X|wdcd55&(V2*()1qSPRXBu6lGv?7uI;jY^R!9BEuK{k zz$sYjPi5VUJi7Y?wf{C3E)xJqRRa`vGC_Wyd-zKF`pgT#xMhls)ya92EOy}Q-V3N^ zm*KO*925aiW7LZRnWPI+9j>t(p5Gi^FQyorjU8nB`OFdZj&;L{RrA`H0h?oNe{Tu$ zkMKYD-{D`7_dV{h8i&td`w2CVOy+uz3q&W=ARiKpI2QG+nq9$&8TsNdKayY#E7SLmm0$IfB) zrBhGeMNJ<)r>13Sz8kxO`Mzu-`)Pya?Duig z9x`9f^xg=$c;TlKpR096{!+xok?*1Q?a_Db=_uY2|1lV_7X%?z=}^-|t~lL>>#sL20sG0DmW+3w|{_ z^!cN_CwxjbiyM_p-u`OAaiKO@w*(>NPXVKLHvAsAT{42Bz7=^? zXx>x-V%ye-1jmeL{a%iK$|DPewf`Ba&PwdvY5S%o0!um!jnET&GNk(T(S>k+cJx4f zX}ZSDJmhxaT5gEY)my0jAK2t4cWNB^1M>JVPF}C4Iy?^LR9eOw6#|{ZYp>bgJO8&9 z-qN6Kkoa_GQkmY0F37 z+n@T4L`_2nIE^#T4!jFuJVkolD>{<4mp=Ab^R);nY8Cp_?9(F`p8+F9k+WUF=gvow z`wwkq*`lKv<6nRCM%zvN+E?JGqypNv6Lm1Em4xKQlzmj$rhq0d-zCWNkZm+_qo2;ce#GQ`@XOH z=pS%&Jdf9$@8@|w&&R&QN(nDA(0Qv`0*kTL z+CpsEdceE2?gZHU%Df4NU>Mv=U15OGK{nz*Y%fE!>>^R!4`vO1Y}VUhxg{tRjS?n% zb2?fFm=WV`{{G__lagZhjcsTN-Sj!!D+8_S3U>su*7L`YJX0qo^}!U-8GtK7P;u)1 zVV9*lLsHP6522Liu?QG@7&xRL#rJBDRr(p{>KINCM}o}V!%#I~(#i*%Tnj_2O>Y^` zM}Qcr4JjMGP&RTwzjKh-IfqbI$VM~auR1p+U?g)|MGQSW>tuE3@@u&ci~=kN?zl3* zT&aKbNX5t^mt?E|RYcYfn=$d;wdV2-@2`fJ2ECpbZ%>qYJ(ui`d-S4f2s&T?(RQh_ zA?WoT6`%FeEPwNVD*>ed1TQWDiN^m5{{PuC3PlL~=L5U;h0}Ud`R_auNxcY7{!e=kySJX`8@__s&n8;Z<~1l7>*lN!F2 zcQw8LVh(yK2D0ZEU;eS=b$2zZA!2FlwaS=9<+;nOp?0zCr+0m?mT(tUj|oW|eQvt* z;hkk5inx027>lKm-6ygUvTI-=i1R+U_2t|0@8XAtD=$vYd>J{3ocLmNb$jyt?Q_7l zO96GoZzD~9ww@Fxx3sNcXTZMf^ug`tN~V<0e%(3+bF_Ze76P>y=+VzT`@BES&%>wx zCUZb-m(fW1lLl)!G2I{@K!Oy#vBD6G{;c;O)+L^} zePyTXrH_v?G=B$G{>u{7T*-r=_vqj2F1>x_omjo@R7+~%>%$+MEk;lFmb4-1tz&JqU89KG;L7{Q`9+c7`C`TZu@wqh& zJ)^oN^&3cv4Ybw#aSE=&Y|0rlK#YY z{Q^54gh~MW3|D#|!%EKS(LeSX5@3N5wTP3(YcAq4Jf}=*N&RW5VkFExzvhQ@vkN>i}bu3jjMb9?+ zgpkqB%0^$**MbcPB;Dc9XzY4nWIBy6;Qv(^5in*9LU{r`N_rT$Ab=P(@% z{+{+QCQSa?Kc>Bxapb?I{rCT6+Gm?WS@xRm{ti|+1+4O0#@deFA^yKiyQ|&yn1+kc zgD8_Bgw)ohHhS~-#RoAVMf};?*F`p7hxX?ihu0ndwZjpIENm)y_w6JtdGsak@!|aO zo2WAvqW0)dmcRP785=Z4X0xAexc|}u$ABXuUmP}yoXdH?+?hJ@hCguMf%W3Nr1ZF~kWoxkFU2BTC9{b^o z;pVniVcZjY5Ct@9PwG)c)p>q2dXGsr9QPpYM|3Ay8uTD2~uVx299 z7Yc6?XrH79z&UOkFJdz7j8>CtOY~RgHtaHO%sJ0y)iLj;iQXXae5ZowhGKWk0#LR*rvDf_s-w$#@h7qXxRaw%M~DGvQxPR2sZH6Xan7= z`g*(3>k?d?kK0paQvG~jZQ^oqik!6lt5WT`HrY!NBfrekbmtge$(qY_uf7-IKg>TG zLXCeQ`>)Ag>o;Iy9Xnlbx^e7tW5~aysd0do3HaBgH9u0$^q*QrCkS}k1^(P-sA2C? zGxh$lw5IJa@BZVFS8ZqfA0PR;C97Mu|J}^lslxspBK`kpnS*i4{|u47eQ~HQQaqC0 z-O&H|rIp-%`dVw~n6UtQ5gI-q$}e zQbTAal^rySc=Y3$l&_UomQw6iLF)B8lgpz|Bdu~h73$q1cE)nwpEz`X@tkbIO8J4W z0UnV*#a3CnK8D9%Sx7L3<4mE?O^H=2WOQ*b6oa*d)aBN z=gTHwWw>M#&X@GcSn`ipUba@P7Fh@G=E8oA7*1Dfq!|{zlzouJetaoUzf#olY~(@? zkOw-V-EFJKviB+=`0ig`$h$DAD4FB2#6M}IvF@3W8pgGrreC5{?8V=>DcfK0t-`$j zCV4X6&fu|C4G0PZxdB78e#4GG9}`FcXXMQGKV+?tPPin^v?2}TL>LTXx;5a23>9HOdNW#AP`O$=R;0liMV9{V#pp^lF zc_tP_&+KcQduhM+0u`YvFy$6GN1q*OJ-23oH~di-pM2&#hn6a#MuK+g-%jV)oicuJ4~Gi=u8j;e%&p3S(ru)S|u* zFaKC%PRjF|KJVhyxos;YgYUaK@pgOKIwH#!fh|!;5z~tOI{Ny^)1c<-Cw|Pd{_KAW zfIZoTlkd=w2$^N)Yf|<78x6r(mIbLd@drgjvU`K%MD)tV`$fJU4OTWq-lKW#Qm`Ji zg+@cL_Ff}BxA_u&?I8me?VxZn{LcR3l1h`LzulFm0A*Xp*Vg3g`+%7v<3<6YQ5E?V zQ|U&c94$n~{zuxuixMC1UzeLM?mI)CDijO%T_Jxk&PynqjIm0u>(_rtU9+IR?lv<; z00eJ4NsQ;S`^GCaGA40+?LRC~qM+!67}N;ZD_P3JSx}ywVsSe1tbAdYh&12J_t#HU z5aKhG^g`niqNYG~c<2OnK1)8_3?}9B`Ddq)vSkp5j7e(wdp|WvFDQytGA=H4yaE7o zUW~>1+7?gOrsvL>37n8V891dNDQ_~=_8aUDK5 zdvMylU8+W4NdslLu$|r_)M&KZDRuVfM!)r69ye8fypzvLt;5s~$2RX_))uau z#4hPdXIlEIeA^v#4=GV=<1(SApL2Ij4&>Bted*4NWp$awqh%2eRo(t`2HpC*BMTd( zLu8K)0_@>hKiqE4Lo3{W0NlY@S>pTGd-fpvR^teSfe=c?W$Vh}p!&Uoz8TdjkJoyg@)W1|(d>%^;+!Wg(3 zBWTYhEN2ZOue7GPWFTt`kk|#C7$gX z#;Nf@Qg=U}X9wb=_?;|?bsllfX~gGN6yo>^v0PX)hksdG(RPW(W!O_=!(SF?A2ORp z0bE8%4A`FyBuADhDpaBer1RN$HRr&bWR1c}k=lEyXe`^qB<|na+Oc_AUYJRTPC1s% zGZUe$c;r?KvFYHL2x^Alef&wfKEotXZF0p|?8A)5L z@XOg)1L1Tj$M5dnMAHcuLGhX^OiVWM3&fRIJWk2%A>vctr6F@ZHaWa3m<-w^urZv7 z?h30k(ejZWXSO2l5#sGWbMV*^nq^C;QT#}hOx#CB-Uzah0mXxTOF-P;yjIv_p@{uZ zj?Yh-b(+>nGpAx$tlp!RrljO}seMYE=5Gp&CpaDp!Irz3&!zdv$?&>>^2AswO_FVu>9W=xy~%FMYMdTl#Iisl(7xZX~jqBjSpM zkJ^NPY(SG9|HLED&T5}tKf^A7?(S0b{H9B+bOGoi zb(n+4GKcD_Q-qpId}Pm@Of_4YR=YM<{50yfqQH7!?*2Z>hxChv;8o;(k!mTPfipEW zEgWY)D&)yl>owj!Z&iwRktx%hR>LzvAW#A4(Sa4jz6b3O65d{?S}X!Ha_^J~_F1#P z{xWc}3^axFkU@tK4xeP@X1MOsO~M`o#;KH0ZXdj{=DW%}8sgmgbXA0w)k)-0`YJ2! z6u*8eeLCgDc4||3WVKN*cJ!FvR?i6`I8cn?^X8)$%XG!>X$H>>`f6jbS0GK@&x7YI1~>#Sh*z7N9@SNu(|i2G0^oUp*>MC2oB&cp6pnMb6mZ?Lr*c&? zQ>toWQd8MwB9`jXf(_w_qLHupS9zh)Ip8k@lv#A(RGmIK2z9w3dwQb6<8Ck$xJm_jY03ih^@1I8 zHX7_7zvhTmOXvCn8d346=oeJa+p4@Rxm$0mx4f37LknMGE97Ucs-*?wHh36z>K#5Y zsj0_xY$fHCmZ4ti)#=Jt-!2;KPXx*Td@0<$$_|iSu)knzY#v5zAaij(Gn z9&iH}mZx8{tOZg`(bmH&r(e$0lv}hld-=v^b)swJm{aku`IS+Cu1O z19b-zh)DR{*eE6f0d5se+MDf=#IT2F+>p!F=uY`AKRhboyMhJ!!7#yJh!^wyADHee zIq}K6T+yBKkE)mkYQS*8w7m1z=E&Fnh?;zMUL8x6w~V^^ecWBe_eRHgr%xw6TvLN1 z!_2!EZ+*RWC7H*75PL@=0@Kr#c4c_Y4mTU1mwrRUjJ3mo&3gWWBh3*P-9?zLf5ls| zugTxW&?M$?$8b1xh z!^Fc}^b4*A2WmmW`V;jJ)_)r2vtrluOQ$t_Sny~^+#nCUwne&L};r&Vc^eluv z-O587tWC2ZHE7>`0nu_a;Wk8@SOgp&18T*>2OQ3yH0Z7R)GRPUyKjUS_Ewb)m``u# zaXNXby4{4qu(3KQ+txK?TLQjxGSa)cg~xl06{&@NmH5JS0y2V+783Z9Vop_ogU74O zemIPMa_>CQ>h_68bGcm>PV5+=^G1`wFfrf^R{y@+)*N#^$KSh_bw$ z!|#jDuiJ5vaZ5sC`fben%(c9=7WuqytLK?5_XlaBhYK)b>puN>NAv!sR%`Sjdv7%< zlSX{LV28=-ajM*axIi(wZv90n@9P2(0u_t7xHuIfyrN*KV1>5W z!O-pvoL4q2>bxxh*E8N`;P=Z4JXxNWXg8}^B?FyiODV0pHC3~GvILJOAQElxhfD$@ zk9{@5p0~7-!Cq-^VZIrI0G$giWE>nBj#l8ed+bH z+%J~y+IV3R?OHOQ( zne-06TWwzrqOx~h=4w@ol&frJ@manjzj>p1xufF^OTJ4l6F#1DTtYn_!*F}wv6Oxe zf@1R8Zo~YY459^LGIFUHA2fuWU!d~?oSXf=z^(QD$3g$U{jdtzS}Mc$TC z@tiRzg4+ve+xM74Vp(ta(Vk+T*S$=-L>>zp6r!j~13b}zIh4;2u6(yrRfz)sk={>Ehx7Sv#Q7xGeVeAeL^$LFOre&o6IdLXaoM+^Ox0};T9 zr5m9kSHbz+#W$`9MKHy}qxy&gh zQUzp=>W@_J6WcV=Qt;sx?3}|=fQ8;8GMF2vVMSu_T8%-mvH-gDCOnw#6p`qQ^nMeh z!J)t6ksL7>BQ`A3snZCQkJiujIQFgUR5o&**J+U`4_WivZ%&QO_Y$-PYP(p43))}3 zSWmr$N^`h}+OD^?Nevamt7q{djDEWIocO$vnqKX7t_>m;dv`D&r7n}BQ~*LJguu|i z0j^4`I1&wFbHlPpmw@>9@!W=V8=a$%UO+hMbr9T9vUeC10$HSJ<9K1N!?K4iyKCyP zEbj;J&4SZYH6L3A`NIJW+I*RXHiPZdsY5<`a!PFwBopOvB2S=FTU()*C>@yY_91bE z!^*9i!mi2qczeqn$~VAWm3%F*&qwoE9|@_9pn&)&pa&@q} zr0w0-HhW-GSC|sA9WBHpcXpnU;(dSPFUgfL5&ae-fW|FOH%MC!?=h3kt%`BC%C5X| zP&aeKRI>W@vz?LOB|o0*S`D7Iu>7~eQU`%52VY?K{Xdo?{0fMY|6rEJ>Xaf|6aTZE z1qe$`)L;7YIvwYvFf4rO-kVHiuTq0>f4X)M%zkVM}=Fj^4?GA^Nhsa^QOrel* z8;)c}83oP*N%T8Ik0D=wpEv)5GbLNX9wa?eZN9#6O-utjG`48m>4+HJEMY zk_qgW()AmFa}M=>X=w1_Im1Wwx|!dZwlskC1j<6g{ZT&V62V{et!3iTJ(&yA-kQPd zh>Hv18ZAlrhlh53Q-|JQ{kTkS$5`>fl*_% zcCEfUrgL%V&uKi`tf-0IIMfvd){^WUN!g~tOxrPhOlQbO41JA44C>A|o?#6GK#?m2 zvBzzR$KM*W zaS0S#SSks6Mjw1B1L2D_)$vH0dt%v*%S*s^NQOqhJrj1@NSvG}2{{87!~6zKIMW3Z z7AY64LuQXI z*bG5L9A!4g0M$}W0#r+eTme;Y^MO&e!_e`f8KQQlw9)XuS7R^d9iIfQ(_oTVzTVgJ zSOaes11|GGAtdd1Dc7ca{CVEB0+WW{;B#D70#^Q&oZs|hP)G+|3sg;0kYo){WMbNp z^PFoOScb`#g{c3I>*H&%>6mQet{dIX=)=tE6EA`(TG5=jIQ1Um&757kgxzJ80W<37 zu*b%|6O0w(b7h5PFUWzQwu1{fZ!f*st7*M=2V2?sw|+5|_Qy3cy@FB(&baNCea#~x zQg%H$b}u;HR02xE&C-}HXW2Q^8aIY|phpeRS5GZxPUBKQ%~WnRN_FSmIaiMwy`K_( z_9I=dd>~v#1w_;LPnNet#KODUxvmVKPMMCkV!dyb4xt0A8@I7s4KdOL!{!>m>^xPj zz$ze1pBsEaX6tiW?Px{3KV^U(weE}8M6K^x~#c70b?3M`u-?0a!N&BD14F%bMERx2FF^F2CY?LuHf6nx$gpjpC;V25-EuqdN2FaCF)=GeVi zRHd5;md=DsHJXxx^1UP*ZsGN&F!0yRPB~x4XPNnP;y!zwqH;qLM~sT_ulREE7x6K; zLY$d%+brinhuh;evT%*6Xn&b#nx^}J_WfS@{JkI>3G__%U9l;&j~_CUY_6E=!OrVQ zX5aP*yrZd^Q1eIZ?2)blV#j}<$f+xDCJi^}Fg{ITRS6rxc=SPBhRa2L#1u=ozbYJa zzf|JN)Dfln8Y)i>fdS7rn*^^&bBg zYaB~F%t|-on_?hBEd6pBkeH~&%z}}cQKP-JM1B`6DtMs9h+8AAA{BQ3ynLs;`4m*y z8XZFr@U#YpD5or-*?pK_jFUV>8d77WR?29GLg{d60u^a-AoE5DL4-PncMZ(Ql=fk! zJ>H+aqh9XTwo{#S%rXXH&mf@$*UODr%sO@@K`slEkWBx;Krz-pnHMPhYhbdte~wU3k&>W`)jVti&-u*uVloXK`MF9YEV^ zJ)J`zSh_fk6d?A&+?%nLtWGwyY~z{1)DY)ph;TgvDmR5ZOZODwhc_eis^io}KB8nQ zsFlnQvnkyq(bX>6;SQqzrLb1X94QVh+`FZS`dNYMGUCC};u&it73r=n+M^TimXFtd z1aLj(2bm5i^M@%fb}6(&jS|VHcdubqbJ&!!Jb1kAXS*yYokqPLS~|j6t@jEEV1WV< zrzHi9W*kz==LLge3F4{t&4SMKlnD8Rp3*W*uJEINzKdRDRulU;Se*Cn*Rp0-5 zHMD>C^X~pn2C9ikv)h{yXKi=cHLYj&?=9%Fehs8GZ9bI7`N_5I3|}(TA@Kb>=>R;S zlFt0Ag~Tsa0TiYDhlS)&prGdYC-TKR{W|r}ZBKpwm!>pXr$@0awmEuHxD!2Dy8Y4> z{F$Hc%GIZR?!7PZTde^+3wsc{838%fQ!Sb<>@!8L_rCbWAd*u}eexRWi?NUPY0CI} z4g?S;tGIaTub?kYUPSx7-C7IV`-*Z#-@M<37Q6|~K0UEbvq<&O4TSx1 zi>wN)b)Wd@-;rX7F5Xpe{;jo_x;{ON((j(2v|d7$$A9Mea6xfE+-pzKfwEmPpM{R? zR_m02mz$sBc^6xha9l$dml?4!F$)yAVg_mP5?B4kFfoCcxFD#cBGy!3s2C~l`8!=Y zncN1LKUeT|UJ=`6+kJ94%3voQKzqffB<*F+W$+h{@yp9G(mUywv*G~dgqZ;(RbY2< zgsrVibQb5iFm~yaz=_cHi%sJt#@qJlF+x{yA*XXs=8GnZM{JebQY8}OCZSd z$&Jxr1j2N4`LTreFx`aDHJ%Ss%{IA=ayM8>w>Wz{H&i4_6y$hBXWZdDI$ul8DF)?z z;nR~B!E@6E;7P|L(;BdpteR`EFK`U_2Q4dg*o5~jdtWl0@>9m05+y+N%hCL z@!OzhqKCGLC>t)1R!Qrm2%u&D_#CV7zDFbi93vQF>8>n-n==i4cKRLrRxhNSq4}xN z^>r(ckIj+_mYjg^KJqhUq&@;ZxZ`A#lEXxy)`UvLq(~J5hi^sZP+R1`FJ@LnDC~Rf z*eH)iBnU`s5=0)wPp8N8sCW~vn9$}uIykc@YClXuMlxQ(JJMXANsuc7V>U{OPxG8J ztKP4_g^9i%(Jz#Mn67ObI*(7|7wtQY=Y=IM3279-^oJqRhFJu5ld;wfv}3NipcTv% zH&VkS$CX#bL`M3%^X#kTvK2j2j~r_;PGBTWp<7}qYsLOxEA95;LTrNG8Y$PM`RvKU z?JS{OPK)AHm#=PJA4$JiO%^mw0}og$<(->%P9-KG4$TKF_LYyt6#Xg|)xbamvgI{z zSIX0r5)*ALaAk>i}h*83hmp^jxeT%5OtF69^2W)hyTM1=? zjhIq~i{~R%FNNNTn$wUQeVpRtNMk(rycDSPdOw~ zK6;>hN+^#GsV@-r5}G*+Epa;a(Wt&_hUsC6(sep!G8K3>bphM7Sl%Uxx9z-7yL>Mm z&TUqlsjk1ZT`cuWgeG62#)dkS>MAP#5J6kbdyHi~u|poo59YD{F1*bk`#+ zXIX9sOQ;`DO}y3$*3*RCVa%K#NwP1~R#;oGT%9gfk-$o?j$IJoYWPG!HeX)ep49_8 zJCBJ8NUs!dXheffeKG-ag_Ip64pCx7F`0R?Yai`4(;Fg7iW~Fqnq1>`wB*}^K56Ia zz8c^r9$7Nmw5k)QS=w+Wy1;|yDt)Qq+@q=$gCXf9x+zkb0SWcHU3+h`)i+LurosF! zz5m4e+@!#(fhE((CwK~AFj3gEg!zu^ToS+9%dWjS%BAgxvsqro6~1~P`3={>rb+-I zPZT^a(jm$SRVUcmzvOqKoa9MTdr@~hEc3?{hnD)0l%SmP-d|l6w9e^itp+HIk8Vjk zNLHV6i%b1mW_F}6{N1hIN0awV=e``#)^M?Cz+gEjm5iGmOubsCKD39rgp(Cv6|igl z;qnq%q`u=dizL~ebB)V^5EKgZI1d%R*D85*Di#E@haW3ra2btZ49!oeRLRFl=7+LKK^QPc*^V??N4w(eyOl_}Vu5dd zqK0LszJcT)NT4u)HAT3DNYEdJkty1*L{HzZYM3;6V1eWUAT(j0#s&hSaWE!0c(dfo zUzN{|QXZupx1oI6FxRPI^Psp-jfYyL>sTw*rFjD070+cI3al*v?obyku~J^!b$;pA zm4^=mu_7Q4ADyz^GAlWk^Xra%!^Hs0A}&-8!N)Egc{#yt@yz^*w>^N9IA9|2gUq3C z!ttZ*uY+dzTnqiWRFq685PoU79L5UzR{QvQ*~Jf*4i5!?rgXhn4eo3p{#zZp{}3qu zy2klTa#8#b7wL~2iR1s1<4T`u3T_$x)jIYEBD=BQtf!Xvxg98@w{8StE2;8|xb{yL zcBTFIp~Bj->n#Wo-ptRZ+GwaUryT8l>iB!#w~2PUpVK3Hj(PTY5y_NafE1S;2BY&?1JN8Qq_JQ|Z+(d~xqnq6_r`r~ ze^`zY@BCCVV1_-20)AxQ5~z%?lcBrz>n%dtcfaNc9dI}4!?BXp0No&xlOCaYiv&Yl z-&5-hAN&oFNE~rRmXaQ^h11mSm0CLuZS-_r%=Kw72SVO^XvX+pkDSPfb+!4la|U~0 z-U~5)%~at_6TEXb#nrX?)3s*S22Nk@UF#H89%jbLh&sB;J8f=5g;25h1#)%-lMcot zWcinxnw{=wMK4U_XbJlDf0Ji|6z{FSo<*rBx(r&}=V)G#mp1H8?8>4UwGA8FlwaoL z`WeujonSOfhvf#IeWc{1IZaB0BM!21XQd8%qr1gD%eZ)HuBRa9V>s1Z**OT9=mf&b z@bg=hm#2&S4G%h)v)`{zWhQY~A%Uyjj=fx3xMELuic>_$#ARbZjY zOT3DjzGLK9SS_w1{EId~FXw~}0xAS{8X=J36-0Q_jD)z?+D zz?1;Yn^pzJ^x0^SM>{+_xviSO{Y?Wc%c{4J7gU)daCF0eD{zQ~Ak!}~|9B?7?i9*g0xtWhw5 z2Vx?+W3G*D7|ah7xT69wra~GpUUw6@cl5i=-~~-R1AstaDV5%&McHoa*mNu zX65E^Apt=cYl)f7Xp1|xhEJ3nX2SS0Vl;)D`FKq?83ubQ>V>4ER{Km2jVX+xbr7dh zgh=eGQ+PeJCKM5k=Mja-tJGkkk^6;miI!j4bOPDF;advx63B4hiJM|WOjy<}FH85r zHco(bl}tb*&P!Nw%x5Z?sh1srb7Dl|`(b--!)xkRvae@( z3zkXSNKYx=y;;iSo$e0w5==88@W>vKIJ?@M+0vz`l9|)&A|p>1-J6wEubw1S&Xq?2 z`s0m(-Lcd3o^-k19GmIHr&D+xs%e^GkkyQFY+!t18#_W4{m$5W<7nWJw{#|s3ya%g zp*Z(r_+DySSuf7^YG?+__)aw=;A$yRbr+6R$h?!YC%``l!t%hAT?Xu8v7#z)cfdg8&111Cy_z3qha3T#s=l-_wrgLSo99%GKadTmr62*ZxcJz^U&5a z8t@u>nq6a0YDhl7(W#GqQ;?^jw?E6SIE6WR!i@h)U3HA&bfQOZI=6qmr^GLpHktK- z+!(iurgP4m-xdb5u3d~hcJStX8-bgs;JFsz+l;?t;6!#Dx}}C~i7#p&D{9N)d0z5) z{eqRib=2hvs8r}Xn$VsgaSVyfpz!w2MihN&s~nQ~Xh~DUG`KzG^rb{WTDdbC)T75# zjxH~nVFegB73y0hkGQ~uUt#EmD^yg3ORHEtJYEE}kUJ>}H(aPr3!5td?j5?T1H!Q>0oB!;B^5Xxu`!bk{{3>#Nga`R|E=)m$r`VMGR1y>7i#oDb+~ZeSLm2Ay(UbQ{S&hQJ z2OUMyuNcW;sB8i)5}P;+?S0;by{p;wwX=?w1HzGNgu072_yK8>$wndG(b zUyT6PCS*|kt-FA%09OEq=+EpTZMaVqj&bNvY7Wq$SE{`3 z%)2t7ePVibI?;I3A$e`R1x-KNX;|>`QgVNsQ+zyi)Tp;G<$PPT*e^ehOMX!|!i_X$=!!ZGXP{^m{d|zv1)GzMoCIzrRyZ zjZr7vkE0| zv*BNVU1y(dD+%2pFHh)J&DLS`82JU8w(|YO7~%Z}FzE<@gF9GGvL2af0X8QTY#l9i zz;XZcG09zfrDS0@W|!-Ab2!pxUoYeC`6{nkYUJGB$(uBEDyFlgQ~+m=n0yo*0BNsy^GV;KijyH*HEaujq!xFnC8jdc=)r3O5!)OOMSJ^C6`FCU zt^`|%gt}W|%vN8|_S+etGdhfsGcQJ^-2yS~SYc$n2bFyXpop3ltN~cdT)GwI;8O7? zcgY?R(}cqx4=3=8>I^x?A3C0O*QU3T0E^@qe_bQwcw*7_R zl4c8(GHBgA`)F`Nn)$w|uBlY&UCwdo^HWnMd`T07j`{eR7>v9IWqSN_#J52bdom`t zlMuuAkxt!hWPG~4#jf{V`QmPp&ZnM(3<-h<^2!}3{FU}@91)=`c=`?KG0 z+fO;VXu6wPlti5XFnuqkljugh7eo4G54rq7+TvlZ(vBq{(*p~!ve`A9YLC-w<}5v8 z1S50GA4-I~G&jrd25ugxXH#qV%XlR@!-_{4QPX)Ib^1;_JWastkjd^8aK`; z+OrZB60vYK5;;#WfAcBzZ+D+(!GI5qEcc$^$$iD1PzD6SiwY;rK_l zC43sm?D}Fn`!a?r=;2n(x#<_#68GQlDHn$W>P2p+;NpNn42SJ8TZoxsG~A@uLCqwk zJUw2_j~NK9N?s)kcoV_V{Ixul6u}z&;PUNX$roCQLicU@BGORKwArBJI zW-~e9hc0W1UMP%J&`c*>+d>s3B#P?g45hH>*)(h;MO32^!O??%SzYgqdz;fU zHN7mChn&0?r=X0kz=M+InOqrLw1kyul)p#|CrrIQw%gm>bg{Q@%OX~QAe(3ap0K&5XZ^eMhg`zZ&Zb)@MegX=ui60psr7%tx|R?`zz zY^Snz^EnO9ZDOU)%wRL<6b_&5)28-QhocsgFsnpl(Q|wASbSNK4CBLYS&?Xdx1-F3 zUE1E%L&?iFp0IqqE~#yNkyL71q}R(f<5+UMs$PlHA^YCS5HCY2`B6sV`hxKmp;>66 zB<1Z~B3g%oSDdpX4HDjYfOnl$^4@*sgkEt!Cx%la2S}H&a5O?#V7#H_9D?Krp0|I| z6W!(~oi%V*TCDcA;@BMS-7Ai*9Ad1fK{J96oQ5{VbH+XAJ*MW!!5dAWeJu3g(6BF6 zS2>sNGeSB@)Dgy}j??cT&7>a>D%m(aL-{0Bp?uIS#tP{fVexH|xZFXm{b|}7aZbxw zE9n^jj8sH&BHWIyEMKZ_lLPoLOnSTupGSDm! zvHBJn07ZOts2O!Wrm-!pJt>;j3nvsj{cPk$NP1Fu>5|%0hZ- zL~<)ja#bWCe}ni{?`?Qr$mjviQW0SgYO9t7*mx6rD5UVKK1lWD!pR`NBW*3bbC~?l zrDMmh4zx-!&~daU5odKWTSTM%qH%K$DNgw^LW;~bXNAbBmA0ENSMVHAF$%>^mfUH$ z0E55?;D8*c5XKTL-{tXkd0RAlYQ(|-NZ`Uv37r6&k#>iXDDFg+SfTXeoukFxzP35s z>)B~22P9t%K7mEb2$gIgigS*v)F%FXUfQI$&&x|<{BQyk0|IlFeUda%pg`)@TyKda zefBfh(|1bw75B-2XNeXhryUO6b)=K_G8{4ER42HOl{)sQE|z z5NGGa%NU>^F>Op|G-#u`#41V7?vZ;US{mp_#Wk>@4+;f{X-X&lq}!u8EL#CZsb$8pvrI*u%*GqvZo31-Ost* z&gE5*-(Ui4R}P1Mbrn}*pc_>>EmF?!_Wnru)rT`_iA@;xTll_0h`$*w6tMO5uQv^B z-)DFs#iFhka*wVX9&a@lq84y`c>tU(X+{M*0fFOlQ_^F>QnPE*t#ucZf9{nx1j{4{ zCWLaXV& z$lRa47P;TJ!O7)AQA9_kb+2)_WF;4M8+$T8oFQ#HcS#xE=(Ufh!as(dLCBl(S&H!4 zT6$dFx8aAOVkbsCq9e0_^+YI6Jw6e2tgPRtcZ?7#7S^~uhKa(Yn{ei4jSU)(esjhe z?rYY{V3E8E9MUemWeF)t(>e6GeLNJ(%dX%pFCEp`4q$#mbkpygJ*Jap+zFc|Nl6Y7 zX_1?Ef%Hr=rX@X_>sW$a@VhYvRO-#|V&CYfD!_I*gNqg|JX7SNi29-X>Z{k~J!;2& z3Z^JQ+}cx*o_blE6vH2bV9AsaWAA#53FjsA#y?_T(s*CED^LsLskwTtR3Z#91f+9t zE$5#$Eyn<*-#SA8?_T7(YNYZonM+sKBjl}nQ(vpCPFf(|^yIM~H48DF5;~77bQ1i~ zYw!tkosph0u!Q>XXg~i#m7OfIcd|4}%6%Jmc< zL|^+w`Vq9-sL?~bMJtULn*;8FW^P_TNV{hWTMMf%d)Byf>Uc$9!{n1bz%r=CnEXNoErN$b&Ms=kDB33m#a1;7c2%d5QtWW;nGlYA28RLcD>l5U zWh)2x=3R`Dx{n4+tSl57Fzc_2DC>T&Z-Y0*ydL=-$TvTAB~44% zdp`?Ia8akelo~|G`^d=}-UNVP2mK^*DPV2t2pTvRve1R0TCP)3dE1OAN}^ih-Po@qv#-KpJJO7Kc_xx&V;lF*;NCE_s&CU7q$omARIu#?5Rr{a6H$@e<#Wz&jC<~R^Nex-f#gj_ z)?D*D=VuBG6|!;PU=vfn_bAu+)^QU(`#b!Ic>J$cc~tBTgiRkIRrPuiJjAIcIWCPBQ8LDu#$7&21rVn{*>Eo8xT#{087TRY ztBK;F+}wLM)qgL%cs7I-gnF)Kv09iFKr_s#xyW3)g??Bj&@f4}G#tWUL2$4R#k)Fq zcO=pE0T*c^9l&g)p$|x_4PP`MLPZTNL5?*xpx7#}+Pn>!lz9zm(Ic!3v}tb)jOH^{s0uLkEtB(p|67dd#Bm+ zORZ6Q$>vYs$fFUHMiXSFmo;a^+qzwSuWS!J)3?w}v9&W;Ju^3Zfuo)r{L=78qRpNi zS1`|0Q_BKrS6!yCs!!JN{0BAR@oCz*C+cbKXPtt zP8p1YdhJ0U>a0}OAErRow5o=JHevWPTm+#Q873iN&shjGVRm6m?jc$R_>ax_ha!)D z4k}a}ty6_jvaH9V4lc*&h|RKXr5sdL#i-UP?laMqW$W#YV}?_$Fc1p`*04(J!-`wM zFoJT*0!@j~3Ugt+dN1+$*Jygu8){UPfFMxXww?sRAyRIPRA6u(2X}Lt-l^I6xnsJB z0uDU}LV(=x+I2vIGVa1gu8>mTM*DDrwO&axUMr_qvSU8^!^t zIk#R{)D)aF;rq~^ibmCIfX4mU&;J1|FFqrf*P4VTp`1rKY4x6 zN=n6TN4GO84TF}^7J+NGlK%ZP^W4LAzX0~%tUx({Qb5uF@7;p`zz%=@4|Ue={=pzN zffr-)2S#M<$vgI+0)J(#>;9Fk*1b(TIuFSk-i0izz3}9Wv+A??b)TO79l%LedHShv zBwuse3Nds%uI_nBAAdNF)^2W5>UcgO+xaX0M%LQa@j+61@ng5m&z+`UTO;$c5~O{W zDWlK5ym@;rzdMQ<@N$TMjoj5{{WkPr=BMAg7uR-qxyQpFSB?Qng14`n6n<#zGu1UU zt*7ke-WxBk9o;?LQ(_MEo?#z)h(cr5jlHMsb~?V(_=gsER{wDqef-gy4u#!ZT<%|Z z`*3PBx7aw-4*kSS@Sb|_E%3g*DX>PdblW_6zY8Op{j2-IJ!akN~_m{%0As zak83X`z1*jl(JGv2PDT^bE!d!fytZL@V>;{Xz)YCd9Po=kPaP{a1jE>`czV~Pn+f- zN_tK$%Ltw)e01D@+?R>$)-LI63_k-itwnalZ7!pi%S$JpB7`o3N;*W z|4|WbP-2sd$s5Avw`InK!JZB>_Z0^~awIRkknT{m`K2lVg!_7)IHtqVs~jKMkXJNL-n^Wz+>sEVA^1Ai0l+z0tDDTDZ#R-UDteMp*%-^wb`a*7xv(wmBp3e;X%FAN-? zYVsfSTmUXTS_XS&MJ>C^iy_3>y3JB9^wa!+4M#|AP+ufgh;#w8@;|Jb(@L{m;+$lr znOQzrh#@!BUf8oM7Uum*B2?pqAMF`l}`(b(mvU)niM;WViZjEZLf1H;s(|vDbI-8NV;Zo46bnG0mNs5lE81K!!+JXGWBAx> z<81}^W^5r3{Qd31tNo7wXe~ zvpi4<4;4l6m+po<$mvoycBiJ%ng*$GZ133ntsdWMt{hVPrj6gdn1CX_`x-S$MgDj? z-Qgasg*ADQx?3PVnnQr#xbj1dkf$}*I1jTb3f2;fdFoqk)xH|%plQxvQwu7DEWOT; zt9!Z$^GID$qr|Rs7HX|D3hZGsM5q?nbaK#I%K*dK)zqdvG}!vI6}Zn(2y{gc8K(9y z1`n$4M71W8ljLnEs}`8cBCovJ!pua0(feGd>4n|WZm=Q|0h!VQe_XH_UVIEsT0s8e zyxu}>`V1z2p~z#IsODYMiM_`!OqU9bQp8o%YxY=-qO7eZy*4G+u zuJt2EFPzkgpG2;99B)%`YCyH#vQyLUVIwnTCJ#J?e1ZX;VEpFgcEvvwk$$Jh%mZi8xzE(mI1}DhpQlay#X-1DaSBt@qT!x1rLPW9_`0{ojec2l zdjUP?>$v%A-^mD%KSA83c0@1%YQJM)6(n%fFwex-=X{d#1H06KtStz~aGtsaqjE#k z-9ps1ncSu6%cia!!LeKURfig4aEf7T*Q%M3M+!a0dRM}TXaDMw!naUQ8t0W;Pi18P zGaa>C-aS^Aa9b|25BM!pa*~cw#N+TQr_|kg0++Fc;bB!R|8fCqg}rsB28>bOO=GPT&Ec3mY4E?lEgY<936{l)k+4myp`>H!kBIE0|PZO32Z9fs_e zcBk%CeAuu=BTRz~PXuY5&mi>qg~qQRy#{LI83Vez z>a8piCW8`d*D(T4y;@CJ0%0tg1YQ!gOTPs*knNlB^RKsoV4z1=oS7~?@^0}?zuI4E zBG;%8@#x|h{)o?)+HOsL)z%+S{NPq^ui@fPC$1#yWD7-{=dAs2R63bZa8=KF8 zJvJ>#N3M14eNk;6OA*`MeeMVeTOaiM)BJ&q|H|QT0yM|}m4-!6{W@j&zr!XG!T-?q z9fZBC{IdX2@C&y3^87?#S0OO7x6BM;mzapZz@mUb=Z^ljrr%Pz36k->+vM zMR76N*vF|K9v(ctGCOSC>7(Jzdt0{W@rkOt{v@HKxI@H*`-r<>t|K=;w;fVEUQeF71j_v$*?s%kbiY3WLvhaz+J}Fg{VP_NLppwD;Jw@EnZg159e<0yh1`gxLY=31 z7Le_knuF`kdo5%FVUu5`jMD}w%f%6gpc)p%Joz7ep^ysk4|Q*cG^6@M)?)9V2%k+h(f&sVE`$b9@nA>ti+Qy}__t%u=^8=Z{qEmsEV?=Q` z9sRxwi~-vn#iV_g0(Gf!R$H4+wO&*#ezQa}?d6~DR^+Xiys_TK?DQ3=V0hapLlR`4 zLx@dQB;%{sbc3b}{Xc@jHa2PRRdL(QzWWtM*3t)s-)0bhWW=MbH-FyVd)(mN=*zb0 zW&6kfOGczk^SX7&Gi>umk)3Ra#nBw)Nw0Uw4IM`5QX&)2ZXqy?nlEo2HZp-Ug&RWV zk(*cyRTBY5f$`OiwgSK(m$C=tbQRypmP-e}p=wwf&NVWI2!FENdn8q&IB06Gq*ku)*QXh)<&|2le!EW70Qx*KVbEI{a#s z5Q5v8wGF4|mOsOoX1=uURCWIm`|M5Diz2?ZLMz;Q2fY&nFE94$XUg`at~%rSOM0V$ z^4NUuGUenp%We#*6?EwD(vbZf8>6|sC7Xc+&!65lm#-EXkoo~ntB@(1npg*|j2&tL zhZ3qAv&ya@c5tywi&^ypvYnZxPx`%RoPxux*;e$Uy2|~fYntUmz`pKrUkvf^6X!+O zM)9=T<%NT(rkv_{Aw@_=D)Gexz?|f>a8|SOz@+3Efwm$pQTg!F7@r0%ee6ep;HNog zjgbz#iZ^DvJjQ52f-sCDTg_b}qQePoCXWX#ZgY>3G@kK*P--D_J)I?7>d0qZfY-JW zkk6$Eja{SlJTejLln4=;B;&{u0@s60S ztmGQs_G7hRnsZ2fHtyoj zG>o=yuC7xe>1zH(C7d;tFk9#Q?eaQBd*aEsu*m?i?l~!+APzl!zbdG?Ac=3j#PQ0u zrF##bF0pPBh)P*tk!vrWBxdI;WaVY<`;|2!D$xn8bPtzKjp8-OGe(=b*8x}q!%}db zri%c>no(}qqUooi^b%zfhta6&r05V4ZsUzA{!0*8a4{ekjI0@`ZgT`vt13~K_C*FO#l2=`+(fILm8lT3RlPl)dGZ!=j3y%fNQweW z22Z^&1=+hI&)wQ?S`l@2pzvH$ZZhZ*WhK7b%E-2$O-DyXd{}I_UAp0v(SA>z*>2jA zjHsDux{kSw>*nsJBvqK{5ZPRwdfDI^r!OyzaX&x%X=UKGkq5Mw$$R1rle=Sf)m}NC#Cm5QLc@?je5o zOyX^q5NTdJqQXy~5{_GRLiNaiqYmf@LOtiAOytxIRyo2YFL@pmxQ5@{{81_+nCl+LyjH4GC!;6bkA9v z#&s{<)&GisC~$!7(?Xu!G~{EoN)y9{0+?iv`8zji65&cFV3@W$O=aTQoL7TNWP0TR z?*$8>S`6a(xq%>=K8X_LVDXk33ew$~N0IpN+%pBmuR5^+Uh{dU=RLY^4aOU+LM_-- zL4lnYhhIYQ!@|B+Yo`~qUa)<-v#lgr2Oh8FGCG?Z?Y{2ly@~w~W{7M4$Pa95^93SV z9oQ0sybGQx)S-Qjf2AA6ebfokYvt~V(F0%iJV3n5QMWF5_I8-D&g1bcPsu?7K9K{0 zyewv?#?vo_cOHB=%P9`JRILJyxD8X6f_B4Vw12Y^E|asHvVVm(MOrh75fm;2D(S>U ztV6ggOwJa@^oYL(|798lMu#qu43pNdpR5Ypn?;zsv%+S&4-ZbBy`2(JC2wib2v4oP z_cpS&FZ%h}l?5}mqhniYU9Vrf55hjVqUxY#roUsg#YHw;tHscDA30L^Uk97 zQduzh&smD{e{kTWN3MV2cCe~;_2G^Jot%ogukZh+^QKtDVz5+SbkOH1JAS)M>|E(C4(XY` zZIJ5jhu`;|zvEAu1G29Zwx7Hsi63^B%RZci zZhd&e6_s8*G5c=*cHxK`F%9L=Z2^Ab06$we--ifv!Y5kFcQl>8urQGh>Z`*)q z2k^(f=(5BP^Zo|f zO;XuXz4uU!SvF~#nsR9I@_HIyH$7HVbSP31OfwPBn3;NezurN@DdKOBMhcd{)fB~; z!H6Nh+~*($X?2l=?J3Q+k((7_-JOh-pZ4o9&JDN6V+8S)_GzxX5bOJjI!+GNXz zn6wBmV6ohfE%sdMLlQkS;DE)VF|sJqv>_@qF4ZK5CVWz3j92;`%KSZR7!=|&{`~OI z$r#LuZdmaUK~UH7F6PkkB(b7dJ*>ua;(iGqorR*ku06E>-t$#$;fI1REiKUp%<|Fz zJtC-Y{I@*09=yGtU+$0Ds(9NZ4RMVh>^8bTmz{%gD!THO`fFMtg`PGn0_U9D{K!?)vk?(4TTDoTH% z3A$45qnA(*z!$MX@!(@tRkJ^kX7MDS_v$}wf&r_8+G7NJm9wNmv$z}I(%=f2qwHtw ztf#oCnsj(&KYwU`RPu`wa{ZqR4QxWmbK@7D3#Cy(9;S-l0AR)7ozbpck&S%KoAZ8p znT8K-ef%KrG;|gfMcR*vkVi9xOUlKyK6<-=7DzA|_RQw5wYz58)N~f$A&;_;bnF%? z$4a2p>pQa&TA{dY1R=9e7EP|E8&$n1dD7g4hq!cx97xQ`TMDuvBikL`gY}$e{t7wd zEI^0OWQQzwWPHbMi%?|11;mOrE|Pf65MW;Flc9&ETZ(lfZo0WFw4scP_%6$~g=c)T zjixPn2$ZTE(`y9e)0u9!1v%Oz7nr+gez$FzovpitwDp?mQRIp(q9ep)-}xIn&EH9A z*)-GEei%sYx3Bu+ahQ}bT!JIY429zq1+GoIfQSkG(2YNzG(yt-#IhQudH zIOn!V)*Ar^7FzIFxh7zW(5`By3Q^Dmp7_S^I@4&-J0V#pXvEQt$~zDbg`}k_;S0nY)v= z(t$Vi-4XQkMq%1p3)KS+{FQ>&zT&CxpNxMY3-`; zP}ZHO@$18OOxNf}l^6z5C53gK@p_6OVc0t}oZGa^LR{8H3D=~8`y&S$RbmzOV>fnU zK2!6n+d9pBlu?FuE|%oK0WHlVpiuI2^?Ls(J_&~*Ru5YG+qCM1;c8*@t?_B`QK^5 z9qP_`moKlWCx~X5R+oc$;Ndi#ng$y!34!za>bfAE_q&X~IW}cTt5>N3JrYcXKRjg zCm3$Egm7E5jZGQMHsqAT9ZRwKY|LHhm?X#TZ6#_)nn3TRBxl|Iq`ZhB*#lapt+21M zFhxqjOVq!4(bi9eexwf$29KRmOD^>2=+HQ7B&yeZI^nH|dD&F(ZS^>3mD+AS{G-d4 zom|OWcv$POwlf7*LCxE2E(5=s=|u61#JY?z*4J;}+PPQJoFEDagIot8aO2{PJMggt6UgoK4mXCBoD z_Z>(Do3yFB=5BmnzHhI~NaZmVEeUu>4i`!YRAB{C^y5msPn_Cxxc+7N#|u}>Kp@JI zxDx-n+T(1d%T?y~ldEc2hj(XpAN|aQmYu;*le-_OeVO0vV}Hy32n7rRfkH|v@H@Rx zf0rM*c2Z9nFJpNVO{mcc_0ZDR4?i0T2`2l&u7(#SO4moQjGF`BJ}s1qzDZ2TB1L$ep&{Ea=F_{02SLxmUHnMD=G6J^~HAZ+_xETlN@Lh65kB7AZKqB~V!ebd4@<86X%(MVP>q*m(_Xt&h9>M;5 zsBl(J2N=ub6e#wvj0oIraH-pLY1j|%vp}OMz|6Tri~#e&)Ir}Ub3pLV(dQy?t|GrV#v2^yl#669P-8g) zlm^ky-%j@*_g~ZWUS;;Ut*IbB;!#gXq)+o`_Cf%kR=VMFTeq%bU80!eTYD*v`+cbz zZEC~iF+~&FP9nqbv|FdnXK!)j&x7T zLZgz(`Tci4o?Hn~Xu{NYmAM+9xaFI~Jm7oBPg=f$OB3j79*%#cay}_R>apc>%P1E} zr$7x=d{T{S56X0l{UhgG&>q)^WCGpHh~2{mSthTisE=2)&ofpv0rG@f*Gj*W^u@L_ z!1QNEuyc!W7H+({RR%M9anALPkteX)a%e@Rvz}6EP}RH2a%iSgjV9i;kCV1A2>shx zedynkpGXt3v95Hc5YMhB!-$6hejxCk^^~v}?1lRk16vIFER8iSfci-rw}qkjI;wW~ zU&VFUa?78io}`{rJGMSZ-8doV=xMwM{rWA%k*wQSOYWiyQsNVc?`>Toh!n zKt9<{=)MopQ!d;Vf!`sOoYHUEdwVnehT=HF@X#2*rlY_0JTQKj6p9E_R1AmTP?Sz= z0FZXiZstqB^D2@x)c`goW?d=7r23iH|foTZiU{Bx-LMOgfnBy72gPAU6yDCaA zwrZ_ZN9M6;UCk8xZ`yu@&?c%{neAzm5*7I(MJno<5fXxJjV#_O&kZ*!XY8QtwtX$o zylElwjO8f(DHu~u5cQX2_{jQF&YVn?*iH+}(wB-mjDVn-L6f=RAnmc z#WF%QOZ&X%=@<=TF7#<&w#eb_oJQrepGm+>A+ds3h^2O5U>b_Y=`$9dg&Bw<86kit zX*<9mw3+sSADNIHm{H8SbZlleDHc51G!w=+(L??{^qF{*60M zyjmpc3uE}Mvs^Nwy7i~Y*`JZ?@X4rTcY|zaVZHV%xk}+a0iHZi>7K+%k zG!aB~8O|jija=YP+i4_09){m)GU9Y$p+k|rik|{)^RhPcxu34x?~Ofyrm%Z>W8QuS zM`c$;b^6R54d#zYjox9A=aGLm=4m;ts;3|8f(MrKve-y0uW zUD;fms}yham4I;RZ&XQ;u2P9DEA~ErH+3yAc+e1#;|+>2zz&*iH*YY!6+b%0%SYtl#RdsioK<9BV+%Xeec(@Gu>RN`W z$6|3F*nt4SwsK(xMH8P_j3H3gBe!c3zV|Y=WOl)h5>$3S3`Brn5<#~I^W$UFI>4ad zN1i1~%E_=*bxtpz->6k9P%!~P6aYj|S|8`+B>}&tob#vozVTR>&Aapts2wNn&9;B5 zv1rzcn6llfil_+rda7jHGs+eWG620too`xaCe6#g7C)eWV!Zh%kf9CZf^C^y&QVF7 z$gwT!uT?lb(JTU4`0MH}&xl-JA4qN23Gdzr*j^PJ<%F3r{CvEA^OZH2*X^Nqze;`9 z<*4qzNIE^e=a`Ad!wd5NAmt>2T+%))gFC2x1m1qhGs7+9WAE;z z&Hiy;N^rJ31C4^buiNkYnja{2ObZ7tK8Fo+h|USg{+YktpU|{`sYUnawl!N6`|gN+ z?(&ZZ$!-i^nRN|2>TS;gB#Yv$`?oxO6VJ?rHD{50c+iY6?Z+~ZgAvxQ(ZW<@L;wrx3WuI{(vb80Nb9 zdNsPvd@&DC6bHGlw2&aUv}OBlgJDx0Sx~vVPmztBU54R*ukiusaLe!zVHVQ%eDa#n zbpxK$0dpMuikh96o45R8jPc>ejR6yrvSKD9y_eIa=C-ndkm7Fyi%B>x0l|wg>fa-` z=UHg@q?PRdwBz`%V7m^T*pn_*+QtozMJ4+l<`$-Z-C`%u{(Qm`ktFdgHam6rr>?O_ za-8jlW66Dk-8vT12_IaR^2!Pzwz`U8Zg2 z0M|Z$y**<97=-CSAv}w0Nf+Xm8@&NyNlnm>eJhXE-Kxn|G&Ob+>(YfZJ6_4&Xw3M) z#h-gpj*`TzVj7CD?O^Z;mwpk82cN1gWc)(bP*V8U1oEu^YE2zZDdr*fUS= zG(ZB6Vr-ne9g{j-ZclWI#pIrZzo4CZ@MA^O*t60?(ausPY0|`(;)pqb(So%7cIi+} zc}*;j?0WJ6EcYr)!}7kY(CQj(qiETR~WGyLdU` zg6O(T@Fsa7#789$ZufeFyx@<`V{kZK&5|n@3BG>Vfw)GSmM>noSU7v~%5nT!=`?_C z>7K+?5k-dVPHwyA{_qD|<7;2cCuxv}37-U*OO;*nwaD2XRq%}ydUKMKT{VGgqSN1b zIn5T1+>xNdjv_<<2oq_H2531lcd|%p3?#=?FX=TW&N&`-2;gmJZ`0w@i#yt6_`bxF z`aN8Png(j^Aws7%YewZjtDpJy=lULsx)(@79b1V#!-6Sh3t*1M$hZ`JJ%D>l=$wgn zvE;muo`V>%l(VqF48dMP(IJOi-H=}*HRZU64nq?DN8LQne)~N7P(C_twt~?|=JTW- z+ZI(`YNoS|>EC!LC%^#Wi;r*5wb3vm@Gvtoh`ePEI;sq;tJH+1cs_A|+Ca^E8Bug! z!a*9hFkHG`lu&-o;2rfDAIf1PV%eB*-nfT=(I8&C)NdrDK>QkF@bg7}s%fAu zv8>JK_;7cN4{|k3*}v4$LA)|8f#bz&jkcdLfpr^;BK^io=(rxw=yCJONkm?@7E%wO zt7akP_|heWU2c^^l-1m-3_aRIR+>}K;HnXk&$`_g=m2xSswD1CsoJ(yM%B`cD&kEA zQ<@lLHgUB4^OicRz!{iVv-!>h<#yYy{nDb~lmoU>zL90JA5W-s6zCj!3?=2FZ+;A2 z3#5~i@-!)l68Mg#j(|%-I7uwSPtAyQEkn=Y9|$zo_Ryl(Z0``BmI?gDM}8`(>H@9v z;F>b9X;cOwW4goOcner#YE?&C<_njv!%X{qGqjRoH0eZzvi)KR?V~#r|EuT)>Kdlw z<7B63(YYO4!>&#v#quqJciL^LB62Q;UM|?1o8D7=G?O6E`3O*LGwrcjlM>zZm>U0C z&RTN?Z}D2d<^1$2AT`k<(7QtE)~YRn|NCM`E`2aKJ@Mb-k4s~^R-iUluGJO`Xd=pIm!83VQ{15zKOKQU&YG?+^%p@JKf>(%l$u(M*d;#ndXa00s z%SF^`dv^Cr&l49pwsU{t56Zp)-|ufttIcwGHI#*^)YZ0WIHRuLnOsAItODNe>nc%E z^-z`IrR!M=Ohr&#%y}aqAoyjrIt}RFg5p6?1DTpkuUaVzV?YF!6=?aB=gvvZ%~vg2 z?fNY+@CN+{9SOCfS166sxTz#F&hIl%fLCJmE)k0WeA;{%yo?6Rkg_1Q6;RtZ_ z(PGrt?EAEu{G7vUz6Ie5TOW03)2=$Bm9j6D z>z;n1qhW(roJC%JoOZAI5~D@2l4TrGCHzK|)|aArXQ0L$19X=kJ7+s~VhhsmKa1(6 zW9&W=b3q2JkHc;?t!tV_!H^V<3ARu>fT}+HTlcB7lDSrczyq4c5KLWDg|8e121!<} zNV`a1v4wtX`x>Rb$6QT-@{cnJf(>?Z?6CnU)r}dYREX{k)K_NfM1vvDpq8uC>T#yO#%LkQ{ZfGRMkv@(C=LWjW%qoqF1{$aLFOWX4c-d>Z`f>88t?~4aQ&42LnH@4CZOLcxe z|8!+TN}2JCkMSZGlKRY5`tOE;JYzSl_(gGik3{n?w~biF_B(FfU!eb0$Cv^vfo}qp z{+~x8?6c}q{~K?6U$9%|neppSJQiE|FbAi5z`)mzMDi9vUg(O^|FoBoV|0dUEPUZU ze}%8aeE)i(@4U&sExBPN?_(x;n0G%`ssH13ky4#-KZW_&%iO~blrir!NGT5OpfLdA zy%FBBsKBM}YxVGL$O9FV8lR^X_4!kiowu*=-Q2=esM%UE`_J1M)ELle?B6~(lm+b; zCd>?+YX^o2cp;?c`nJbb-u+q?ne6)*`n(4#9wA3x;k`$u2E0z~O;fa}jUT_r<~SaB z+)T#i{`+_E*FC2eb_N%ePb54;(NHD+<`NenWndj7&IS5wK!`n{#`P8-(89+Ac@~Y-)vuSI7 zj1AaQXQXH7SI^pZt{3MM-`K2j8hVzuLQd&mA94>H#sj2_M;T4oa|51r7kWbdXAI}t zHHAG9IHR31(>Gq4KkG=I-=|XmpGC&0F~~$!@l|{Yq#WF5mtB~nKLhOOI_de{Y|iet z-lL(Ay~c4=E1w?)=Eh~k69y^umWcD7iHR|WpnhL-&z}rmw5fgBps0A_Y$Y9D9Grc& z687Q~+Uz_|-KZP6S3jYlRvJF^6jm=)SU32HOG z-e)(Cg#p;Kx?FkY?ohfB-|6ZY(u5a!iTBBAuI`&{%%<2hUNtuxPMhggy$8f8-;y*- z)fjO7^nOZ#yf6*GdN>i<@d~oV-S)B%af6fc*qM+*m>HG89%dOe&7k#>CMGNKJ|bi> zeADM+>dve-Wh$%W@H9P!+rvfO3ic4yw5dnpc-~)>&d0&9=)Kle20tl60;MCz_)Z!4 zI1tx~m2a?Xr{izU6cR9V1;El@!_2=(Sf1JWBxq`{WECxoG{-M z{LV)w?8!MsNmdYOOd_Ix9fs{t+z=U2{ zFUD*rDRrjmEEm;gapg*m&cxEp=JI0&vEILA+A0gNBA!EaMWHX&Xq+s~NCwb2J4$u= zI>IxarWZ}qb&VYXK24DfKd~h95$l?!V4~p)Ab^p^(6BgWwn`xeGl$l-nT|p|N099% zO~rL3({%bEt5dm#ocmzcxRR5sG9bLB5P!1zD%k~S9#fAcrM7Fv5jwnRh~hKJ`>qE^ z2QnKhi}Wa?NFWtz;wnd2ST7ROej`%ik(!r{!i;Sy5pHFJxyC?N6xaaMlCX7#6z6U= z+otEc^cAazjT__7e6}{iZN^kN3XYf2rebtx=%g0tt=1mes!0liCu0^YHVscNHv&}< zlJ>)=-B@S0t+b(A1bYI*X~nkiP2MhtUKby27#Re#iElG0*}!+apPwMAIWKja4$BL3 zT`eyb3xjO+f&r(4tNHz@h*;1d^hQOag%%nymTg4`g`L5L^0yu)BP!74F_8KaLiNkP z1!fHr=*Ho{c76_i4pf|)tAET?L_Irc@y^)LDy~h*ga8iQBfGgCDC0O_gn`!Wy=Ms* zc^?#XXv^>Cf1JM7@uH4Cv5R)UiXrhzor^$(C59T_VqKy z-T;6VhjfHsBtq5Ymk>V;2-?$D;BPXRUq!syNXthjhXKbNF$hL`$~XSl0kOulB4n4M zGVasQjTrW9ADva-2!La;7%{XI!(p$bXsGHwEmfV+$SJZ6*+g?`3xv94&*jD zI~;4QWe41Hu7%XYwy%>zuF87vzB?w}@|2Fh+CqUC?D?Xzz1qm`zUkjt3uP8JfyriE zE4-Yneh>r&K4$5-B(`f;<|)nVS982p4C0S{*SE9Je=ADq4mozXDD#b;*DJU8A%zFV zV+=o+b<;q*lTjCRJOg6aRlR*PkN4PNzKXhIP-(n0XYKD#!G(8+E(ZSp<)R>h((W*; zXI?@O&JVF=|CO)uN4Z4)U&^KF&HpGDEu7CQN+!-6P%eYA2Ru%@#n0}7cOHi=+%9j? z9XzJ*qg!He`R3>MzL~&r$U4G2zf?;XL{xG7`cLm!R%8x#xLvtG&u-V0zu$@KGp^7d zs41*Na9#Gs4xhe->)vR`go(a3uyOC%&2RGU`Ydi;YjuO1oo*AD9V@>|)y@Vsi0~dA z2R@gR{mlz0F3F1$-^$Vco_)U-2CGluJ~8tmXM1#!x@erPnS=7g{X6r4{R#)QFnTv( z{Le`#DFtz=H3PNv#(2J3&)-JM#3yYxlpIGwzSXMi98uRX)l!VtQ0oi^@HTgCf)qQ` z2hP`P+6!w&)KCBVY~v8BQ2my^%*bDvI_%dLQ)u9TesJ+k=wgx(&G|)+`Ewz{5@HWK z?4+3-l!}55D>(_Vp1=MWF3!&I!M(Ed#!?&Igw#qe6?L#AN^L&^u3~1v-xPwY6=Qt9 zra5p+4trRSX07?#6(rNyMP2X!kHM=oygDcvgazUqqXlmlY$T)GZI@ zV5kpx8=bc#q{%(M29x+@3GQ_#G3zpUJ((`I(nF5tgxCpm54hL)7;(XKIXH`-cZ@~9 z8tefj`=UK(D@_LjA6IqeMOJT_II@y;63VEd(IV@DNHVVeceLhYagh& zJcZvf1bT6Xj!C-?TQm)6SoEP-gt4mlDKR))3Je{1 zJb!cSywMr&9-}uq5T|w5$%=9=s1H(^&qIZ?&F9Gqg>feywDWs}FsYil?orADrweJy zpj|I{b|L;Hens0sZ&=Z}zFYpKvT~jqp{BECtN6F(ss|8dtjVMFvPOt{&KcC=u4DAg zPf`u+=L(TEA$!tvfM9P+Q<_MgbF%u)1;Ci8m#jK*1jXYYrL95usA}f%GPX8Y{x3U* z$tW5D!%?>PB})CaPK${Dj7c`1wb@QrVJ|g`id_Fr?65sA(fUC+4qxBP@C{K_C9HsL zvDEQk=q~ux*5+)l%=PM<t@C#YTTc~^*{Z=utV_6#?Jbq(u>Q)OW1J?DSBDtvP>;hzub99 zSJLKXuvA1oC)4LYzxgbDEm=(u=&|~tAs9ok!6vCI7#D|^F=>W zh>m$cY_tiEW%l*Cq7r@S3;u~#o9W`@)8v&g%*HcFqdp3ZS0~s3f5vop@dIXu8fHc4+>YRl_n| z_NQvU^3F8V%+{5WInn5a z{~yfBAdK1)fvExzYjK=>vpuaCrr6s$6MHnPQ>z&=(&zE4xG>4U3C{{_%0J#W-a&e4 z1mrNb$9SU;NS5$JiQ;^Oox1M5F|AK&A{P^Vt9`p!DE9Z!uXc!Q{V}oFexRq!E z7ZWcS{Pr$kPfBiKNdr_9TIW#f__@F=76&RLGfx<*#irz*H2knc0XyV_!*92M@C1?1 z*~otdeR&2Om-Z>?1;5V1jUwI^ee)XMJS}~A$)NW^D^5mb4}G{wQvsrE6XPY{8-BF#`Hd4>NGCYb4E_{a&(-s zT023}SM=|te-De>>Lz{awSK!#%dj0wCb0|Mweno_*Y&7dd(vBhD9TKQi)SeL$BxBq zum9#6tAoP0JY)S`?p%Fo-=Gc%Pl_NVz|tO(EIc%40x4rSFRijgtcyzjrb zS$Q?{%X6{e?g>iiyr@t`d%KVF)=8WPBlD}2K49yF1kNn?t|sa3ev@fZk%hQ)`@Lsh zjf{@R4u0=GoRQx&;2BR{!gGNIKOsiQNbNG%DFK`X^CY01JN0x7ZBN?L*lmQVoJDM- z7|fyFv>!Mb(>BV-2F%U5Nd!hF@RUK(xL2bv)kY4Tod_l|%)snd16&pOmiEhCEM2R-Y6Y_ZYj{hulL z#tr_;wh^-kM#8x5RTZw}N8z52D?qO&&j7glq?$hN*7a;H>h${f!A(lcGa*7z&Na?> zqeC-AyoO4~-3c4TbWOWTP(7J}Kh3|x)XV*3ThG+%sD1C*L@W`i27Md+gh?%(mhOs+ z=wnsm7Y~}yZ;IPaprV#$gN)WGs&8Btpys}|l&qgB3RW19Qq(MCc}%^89?p%Pz=2oY zx@$@$xui2;!t48Qyi8^i+3Vt?6 z1WY$m;a>)CtpI>K)PhrZ@B0lKaQpr=h_{jSi~!jL7GN|ir|#~b4!fAEY$s*^(%W5M zpob+BiWBIWGaPRi^tR1Nf(2qTnE;`4Y^O#deb!GTe6$^N;put7MfOH9h>JXKqUJx6!hktJX``J4fI% z8|a3|aXejid^xpLO9w?;vU;lEj?dSaE|VB#pbppB10ZyiM*U3rwB_m+{ZK+

  • 4d9_-KHv}b zFqDJ;AIjc4s_Cs;7fyqOn$U}s(7SY`Bq0zGP#_?vponx3QE4JodJ%zupn?L@o1ioS z6*TlBRX`DG(m|?#baH?0bKY~_eZKFGv+u|l`9C9Tt~uwkp3)yaE}V232t^c5cd2){ zC}M1rXh9IygIsu4E^@n$K)0I+?+PuxOF@T84Q&?T4fHJ|xI@AG+7NHvKEX@%1mSb; zr|h3G(90pT6{&xHy0WwMK(WJ-aI%-+RGDY1!r90onwlLPGDzLM5shZ4q;$$OpyLt6 zP8x*i)DkyARPPq8tAazJJ0JA&Z!@InZvf;*g*rgKCA9>8d;73^nV;byn7%SgDP~1n zTDDFL7eAZG{a75qbal~mL;$6$N~Cs771lW^hYLqkah=!*#~*kL@s5R{g3!%)$x339 zQru1BUs*R6!y{5&DPfm4+vUULV2U<<;@KuJqFs4puVqIr`3v_#X&1bXh8wYc2u<^pk6Yf)d+$ zY6TvTKb>>9aM@3nHq3^~+A#*RG6p|S@H7tcf1dpQ}MhE>+h6LMhU$qzC9i-|-YaSut=&W|l z+aVxPe5hDInAX*WzryrVhB zv{*fuy?4!1d&$YD=J$faE-O3SV;X_Fq3MC zvQsGi9XWJ6oxZNdN>ako754u7OekIc4G;o9#eZ2;x9X)KK)gL9lsBz^|GdIUFO7#V z;qi5phapgDG<;`jOb;+mzTl?{qE9^Yq+xTFh9_5Ycdk~EswLr)xeW-8*d;;xL#$Kn z^^MznDmQ-Eq8`?LV{y^7W9#h;?k4b0y%diKZ*55MOc$A<{dgKTqQ&UBJyUnI0q0^d z_H+}u$*25LO<_-dCUdYue$l8sd~Q?h(y1WD9sOu*l(}`G=D1`NZf;PllF!IB=qJaL z`2UlC?Em7$#-RkO-0$Y6;h_S<7jONeLh4VLGe@@XdzIJJwicp3u&<9v1d@~ztx*%~&b@_uPG z-j8xmoFi`9^$WA!I66&jOnw50B*E%flF2K6xDh z#EOE{LCc`u$`O4UCp^IWO#xPzll!!TO{`{2db8rJ1kKR}Zo|_9fAEm*y-9u`7BJ%U4`FuEl%`etd3ww47zcva2+#`gLzPGk z!5*4CcbRJnVQj9WMNz!^bu`Y|CMpgKxH*(9G=6o!wv|?c@xUP;Zn{8J)Y|JW%Js6z z4&!i-qU3QF(~jp(GN^X@ej@~~WQWlj4rwPwRbQw!J1se8)5hba9}~@M>_CQ*IJjtq zv6Q%+XryFHV|0Y4+)pTDqxF>)t#@OaQ5-zmWH=wHr=krFn6T)VE_@MAWRTc+dX|sk zxGTl-v1Nw%f!Yxt&iZnx@2GG9gS!Sr?WZA{Z31q-7Jp}K9YBrS#i)` zmVphF>+<@uxELW1n{V|g;KIk|>+Ao79FXk#G?}0Gi#WTANTQ_%+#7xvQ!+qMTj*1|ufh{OQaQ)hOj=IwtP(P85)i zQ0|de`S9m)CTf&q2dIsY=0_-e!q2mIj4#kdUYjN!(b8WOAnzS5DjI`s;fm0|o#<&< z>JH^BI1|y%ZvtiN6vriVM6vR00Me#7S+Qt#%Gd^J0(q>Zzbxu7v9IaFEUb-uygCq| z{dDQtl>krr%E;%CV`?j8xM4~(o9vhklxgBkVH>-+@SVxE_v$I9IOSmSM)F!yCh9ug zv+@YG&s`%#`~^~IOrtCX7+zc=;0NO&Tqh%NMH_s?gN;Ud$*B;Dk$IM+SzUCTcqoEd zRpFGf3AL6>l;%Vz$&4x#ArjcZ=Zl9SJYNY@jkRgIJqlyBu|+B*cd%2eZJ>xJ#gW|r zkpc!i-Ogl7t&&Hhp|Xj@i?7`Dj+rDZK5b%~p1E*2w3Q|ioy0xRNd3F{+*#a~@bjT8 zm;9U8wELaHomQHi{X-w9pO)8tkY|ga`0A)pM>7e~2#dy+=P=fUD8&t}b4o=Z0??k2 zbM-U)yLAH5dBWAgLujfii{b1nf(^lLU}|JbSL;+3ISR0V8t9zWc_x;)XyIWCdf36w z84U>wEbwIzXcS3xew2h3^p(<2=3xqhYXcAmDYcDP=yN^0g@87dTBBySKyrBeG%CRa zOmEHJ9Km@9(G&=`7M>>g8BSA`hCiGYmuIP86!7lq%C9;RphTQ|=fHQp<%v$$CW*61 zH!GSvj{2R|7v158Po@5x6hKNq1?rq$XQ3Sbm%I z&f&M2m(yL&X39g#lmxwv_nzuZLptisXYCl?wu?mXC*N{`+|%Z45x=&J#4}$k;CdUQ zZf;?iRNc%<+KWcUaU@|4J<$@75^wWaq-FY4X)+qh>smb&R&L;n(CEej+}MvH!Ge)$3AcmKivg5kSn3_>e}5<86Zm1u)=%h6ppvgZLp_Lw?s zsI~hS>kcA>vG=3O&!5;sDXJm(luZ%{H3d6A!pk>m0yqTT!5|JDA&?Cu45b5sZQv2? zS}{s1H)_Ve!yO+!Hi&YW;iqv4@uSj?55}V*)V_GSYCK}*-CX=u&sXj4Dx?8t78ouk zD|-?e_e&iQ0xyCPm2y-v$1|K1i`!OgUTnd6xxD8_$W#{SP+C=cwjp;owWNC}T|^e` z1N{ivS7iFcu`d88I2vnLVc`lWc!o^Q#T|0WrIi@hS3*p{ObF++z3RU@Hl^v|Kj8q{W-+ z!jE9Y6n`0KI$kK~#rZdO5RhsJATOC*{#_JMJ)c+>8w#S@*yX=yV?FG|yK*Sq!e6wi za3lQ7%7evR*Zh(ioe$ML!Tok<=^>woc1;N_g5mu1*(r6rIZj@A%^cNxif6v^CM8Ye z^6j`pyVvWj$JFJCgs#<+;l>+br;er&#JVPq-i;`YqaP?zU5l9UX6)6Y{~L@V_Wuu~ zobd&QimmkT3#X{|sr%FZABKv{e@9Cgmj7kC#+bLTK7su+RCsePz9_zS0-OG>Un$%Y z`D{(R#56n&?=NcKrDRcPEXtzf0K4(qbF%w|=+CjFrp8V*kBU_bv?;CRiu=j)wo6M{iqq>4Fm6zu6_RqSwA{2 z9|2I!{VMY|6lG;>YMz~BZ)im)XsP*IPD&ExX7v9}}EDra2!t_*q z^3((M8SQwl+WIWkKCfGG>_p12wKP- zsCkm=D;OmC*^8vPZlVC;Vg3;cFgWX*5_H8y^ZIV2&<{N$r1r?e;OCljY?G`yk4Sj-vujfo$t7mx<%XIOLmB4RU7p!7Cj0Y6 zkP>Bk<>8M#R|cR@N{(~;5{#y+Sk>^Q=t$dyCrd8b(aXu!Ij|erL+s&lzHNEu4k(cm zo<>n-bXu5{Mzlxdhw!4zm&aRF=MUoFN-;>TH1$66%b|sH${i8(bv%zMB55y-RWg)7 z$4#2AQ7pjC_a{vM7^Q$3SMl;8n?y%HyhcRQ5^-csa^1<*F$E)v5On^C=^{-vwgmTb8vL-bv|jBU^#N$VP5OPDA|* zd)uiv2RyV6q3qJCsoihupDlgyZ`5ug`SPATlymTRdwX62!hC|by_c^q1Z8?ut|Nam zNUw2<*;3XC7YFK)rQ?+u&~J+T(S{GVVMrow8&>))B$iYV&Vzd$rXwKAcG{D{-Jxw~ z7mv4kg#^hJ{%K{|JS~a>o!$c<0Q)&s3!hT3sgvB8`;XF;^o=t*3Cv*xRJSh>7;%Vb zDnAO_bj7PZqrcbon}67T45WVKB> zde_7_y&G^50UXo%r8+OHf!J8LLl|Y;V#roc*~)*+=y5Oe@lj%vQLXtgMq~++&6h%T zl)@~M0wU0Uc+5s&YtfO!fO(GG8$MdWM0xl1=*sbkS*!y>woaQ^>f6c>_^-;jbGWdA z%URuQwK&zl0G!eodIb1k)HTt`HM0eciL%Cmbf~X>~+pY zJ!k1osAj4b`guBy_{~Jfy}K1E2QG0wL;8@_3J;-}QcL<8bYr{8XZ}~JfaY{SUib+t zMXG!zz0^J@vS@~-8HC3E@_7_|l*69w70UjLOgTTF+QI*|81zm1OOmI4$=Tz(mjM>F6w|7D z;z6YiFm0aPjG?)9aKWo(h<6_dj_F3{IxEcbZVx4^b%BxRLBllX<(k9TpCt~wSu#H* z1ET_r)jekIAuRok>@n5RUlJb_ZoOwwE7?GT+}Vm~^vN)F_ekAsfm@XFaJ-v4eY^Wl z^G{uk5ZDyRSP5Lj;6kRhkb}yga*zsLO|)Ths7{ZYe1I%MoY4d#U4R4_SIGX=s10cHk}_y&{>A4+!y4Y^X~S?IG(;3LaLpr1&^ z1Sdj@x`BYXJf??cJdGSVgqPQiH<1IeUwEh3%JB6+6V~Qu_=h;#&n#y@;jHOQq-;ps z6PZr%NcqaUR0Oy*w2B0#b_uQ~Mq_$yV?^cdvFD-6JgEj?=hF$~;c`8Fo@Yh;6EnPf zpe#3jGAMLJg&ze(>iL{c_~O+1u{on3JI#djGPeW6@MKM#G?-cm4NA4q!!9!+UozHu z&!MDkHLXIarKh0FD1%tGxn$4siy-=_o8Xcx1`$~`fo+rMOSvlvH2T`S(m5NC86Yg4 zO2aRg^lby$yAubi2|5Kp$V@<0yHiwZIM0$QmC2wyat>46`=&lxEiiUG5QtX1|64w* zN}J@LN8m2YD0Jiq(hYQA$AV+I@>%R|czsbr{}YwTf2{Eq|D)qhKmXSn&)Tu};;%J6 z#pP3qdeE*)ERV#%Xas zZP?;aC>nfV*MdIhX|J0W99*+F`)#}UYlQfus$@w%l3VQ-Ii{`}$^YTCJ6%F?Zl?|% z_f=||6rsYtM6T}NcjM`5jZ=ep{8!|~#Tb}Qb)U!!ue>qNFr-}B-g^oc5a81iG&{MX zmzCT~vyV%__-%ItXbOQPH%ah}=s>MA$twptnBdpOG49&b3@ugK=&iM~fz^*bfT72a zQ>Ki3{q3m=ckbVr#JQY_*rp^Ei6WCu^#}eQOGx6w1^0w)EL!pQ#j}3`tg1+ z;Diq2WBy^=MjsI|#2w5$01!77>9sm^+_U651L*B$Cq;xq2BLYGet?1BFlNt;J8)d= z5B`gRdA}%|`ZgtXvrojTnA7y$x}icC*S6MBJG+p{^tg>W?d+FFw|jE=0rI7--rXPv zzy$oX$Wo%$e~=kah@`t$yYZcOc2x`WwfFj~h$LC+rNq0gwltrg(Y#p#XqPcIk-Uo9 z+i+$|3h?N`@x!lQn+Uu!q%$0QMB!f_Z9U0(=;PcgB4iN?kFjSIKw&kR zCL4+@imZdeU+>LWml?!rnQ-}8gf^jkkCyxSBK8u2i6i8F0iBdv1+_CS{e1L0nt`Nt zK8(9fS5;9Buvk+%^Z}*A>^6ctf0fJjSz|W=e#y#n`Sy2lwfT?#F0_~ zK}8F`yH@4(d#-|^-JP>QC)k9cPS=zU)~p%Y@JF(YA5H9*(lJhCfXK|{BiuK>qhffJ zwjM2aHGX<6-dJB{R0;X8k+p{qQ~^MYquQ39Vs83)*g(**>K=OuyQB zpquL$qVNqmEf)~W+O1BVo{&awgbw-*jgJ4oO-udRNGA9RL5@pnAbge(vq_&9$g+vV z%6&;TiJ3Knf~U@IZ$5`vhoaZB+OgukC?;1UQLzmggRx3h1Qj@n%M#g0d8GSDx>bk& zuucc%kjR1v< zD60u+B6m#-a0zq5Y`Sp1>_E3~BF{ep)83F96*?7$@lO@vP3&mb1lBixL#@ZK&8dOZ zygZTP0=A1IAyf_$2xJ_HM&%KKf7iXC-_OG+q~1mzU=G^OH}kTOkTt~IuxFBpvg2(`r#T`S~|%;^B0^fC?vn?TnH5k4@u0o@J+Ef zwwk~_tlsFQK49a5xt#~hJ zs*uA#m@E!Up%qD_HtF8BHV9ltmZR8$>3le|*ydfnxzb(u8dNO^|I)3;QsPeU*)3G{ zo(-X2`6NNdiiPu+V*9z|Q_Nne_Wa4-ddeqE!(5^q0s_Sy*qWE){@%Oq8HzhFQ%M(n zi)MH)=&t7^j)?kq%BnMg=kbIAtuXc>z(VEElyhQ6urcSWJ|Fa%-A9Mkv`#*YA zS5oqSY7PD)_ygDq0W0oYKnV$i#2Zus8LUDBSyq4*cQfX+eHVs?fM`w=DI=3BHm%PG zp|&jc#e{o$9=xduYKdOY{umkqYufu7jedsHr=GSHuZWO&io3(mjfWaHGf{@z;)~{9 zq`X!&b1U}uL1a9zw4OSGL+SaVy(19jZ_n7pvzo7~w1l5U#5N(DK}?7O(z9qf8X7)r zPETz`=Hc1waQlcDX*sOWSl6&EpE3bxmBQM}O<0xzdNr-ibUgD_H#*k9>L1$5H|(w} z)RHFf{Y@0MdqvOBGz1yGI9sUdoZxx)WKEvJwzrlvvD&ujBC55-i!In~ncUJNG5bf* zZMq3~P7l1F-@OQn!j~6S^~${==RZydeZ zY2K@;3#m(zg0#8}&{E8wn5LY)J(O}*$$e-n^^$d7AC97=Hh}9X$_i(+6pu>dspAr! zGdxJ~rDu=<6nL!n`#sV;-VM(`_pNEI?NcHp+O)DdpzK)hQ&xVo&?J|8i8=V;Mtaq& zr7L2x2ANt?QG!;#7*n46pEbr(>L`l+Cf+E!{)>>Fjn1^~{^$Z{+}m2D+*)1uIWcAY zX1i7}jd!=^;TS=*@W4vXSc>e6MhQRe?}uJH(>bt$cSv~4VYavD&+B8YZ&8}$+IS>1A{L=1Zurz&j zqb38Qw9&*jgem-kX~`2Y+*dY5JcLm-3)Z-Q)Z7V%7~&h5DP*Q*P4zYVSI!4xW<>0^ z`6E0OrAlt1f>>thz~IswP*KJ14M;T3=wWhe!$B2NjTbZpf*`~_w0bVI8-l3c?rp@V zY$Kj~+HTKgFlv4&rLc5QHd+Yz_Js8*e43mu`Vo%bTi6by5mo?)OO3T`D0YCSxl6MnuriVxklNz%=xl>l? zP*{545s@Vw0|a!H_;FXs*Q^2Yr1EEeG+^ zRX0*o1!ghkY|h=VeRo*21qQ<&j#9^NXgoPC@kTxR@}}~QOaQ>=VLj}}`+6g75IQ_B zAE9+Hd5sUIa=DdXM&SYnwZhXA)X>0nvMjF-6Gen>0wi<5bnuIOFIHE|R_m7%GB~f9 zPx#6UMtYhHq)QA;0;eNP{^8Bx52%!k|8{dgHh&z}u8(L6ApWwl%V`az-5h`a=jKS@ z+H5$~2X2l;Zle+_1Ex9cCvx_pIuca{JL*KH^Oujq zvnjyBY-!Ds$ZQlcDo4nS|6-WuY-v5)+DkG9x>*Xl@X4*G81F8@@Q8&zHedc^$K#X2 z1G2PV(=TNS$8tj^?cYVLH!Y@KU=vS0KN9-pKnhNgl48q#>qYdZEUvQDnTm*fu(tnj zYIR?z;d7b&r_5Ea$@7mR(Eju^0do@>LTXVf=~sNujEr=JY+NStY>lXbDQ3^-&} z#6#iusRRXIL6jDhZdSnv6=7IKa=HChrw?-oR2UT;UCx-+iw2f8dTEmw+_$2cK5Tms zC4UJw8Ub+YQFwRf;=;2gA+XgIFJ!5bJlkiC-a&2;i~-0Ih3w09-Gng-Z{Rgnh7|iE zn@#iku_t>~q^AOi#Fs@5zwAn&jGQ4_s%s5CBwVkAvb4q_ndLn0s5IA5?u!MBA#TP* z(O9ku!DA@*GtMj?yHc)LYT5j(iiqo&&E0I{p=*(Ef0<4owKT|F+{7J=&m?HfR9lsw zks>u$HV&1hlQb$u6o0h@K4>%6Sj}rTQqQ25Bj>2804W;hU>U~hhkI3J4(V&nj4s*1PZK?{BO`!&?0Olx;II;W&}N zh^=7!pgueaKB-%zA4slS zSWiEF(D|$1GZs6aYQ}T7`LhuTJE9PAfIoFDXlI=&KI+V7z#uycB(M*oq5@Gs(iGqe z417Qc7>GjkZ($pF(0zam7y7qyL@+#;WhkQor)BFkX@KFQk=hcFEJXhhog~iN;m%^COfQT^x&rP&Ft~!$US&DfE zv%9VSHkX91{@#0^_PEpI!Qktg@M6CJozflZUzCua4Ow4~eD^$fgSYqKlefKSoONB=AKdN39PG^yuhNVD?qeUdy-SK* zNy&{@2iC+s%&p>G5<{NfPPR%(;0770Rs>1V+)7nU^~kZ+?YrHolt@lw0LkH@4fQNU zO#FBaKhEoo0vN=gGlhpSDanyxWs6(6c1x}KtSKivEO>|ot)M=PS;rj@LGo+~VfPlR zI4$n_FI{2-gt1Lj`?Fr5%$F48Ky1r(7Z?042&f`81`W|6FHRjLlc>(APJv($!z_lB zhYGZh1NORSNWyeHQz6WcPr{1}P&}0K5aEMvmgNkhfiE&S(jrUZW$1@@#ifxhJ~zE` zB_nf$S$Nz-nAu_H7Yi7=uiPy17&rT=nM7OeTK!Zq+Z8Br`e)D=$yPm7B#e0O7)drKk-11bM`-{idE7BbRNfdfyJ}8{v+7aZuM^r07s|E1g1<@$zrDw z*Ltw?F+BW3xsB}!YFp+ryGpO$E62WSyTgNCb~_9V#wYuWg|ANz zR%+Kz4ma9mDM#C1?@*5S7G6_Mj&|266cBwD2(C|taBqYl46`5{9b{_t4WWKt^o0+$ zkN%<5CLSaQ())Y8Q?32$Ipyxpn3&%HA zx{)j19x7`%)VZUUWZOABPs-W~P<9ru_5$!fxir$nY}Pw%Vr?)`2S* z`fkVHS!)mV{o2cJRDbX43vWW7*DCRP{lGS!`j`VVb9;Wh>xSY&-(>w_jn^g0N3PKq zDh6tNn2w}#-y3`fia))utgQWL$Hp$K-)}<(L0SQyNZdj9S0-bTff=F{3t(XfWm28O zLqUf9U3y+zF1*J6yihy@u7d)@PL-Qz!Dukh+L5ZtGQIQ3CeCKl3DR-y$ml3KV2K&g-qdwcUw+WeAK(og7AGsJ=u7)9KrZoX=_9 zA_~yOh-WjOlCzvnrDM$@+TOcm@fmaI@(lz-_`Y>WKBt2(Nb|j*G?qb#0s&+I;Txg& zQ{o=@l)*rqtm`aXqR(#4nt<`~kD@vuB%lRkQBlt6O zI68yG?pnMb!mgy6kyK~mnuU|s#$MjRt!;mrRb7i|?j`4F316w-(I*%sfEJ$jX&%jg zUvJr&S4>daOl>x9M5S#TV^`C|dpm?l^~N86rdU;CRzsqhd}~&#NSe@f!W}ZL&sW~4 z&AUoO3?6!oq&7QbX7q8m#kCi+)3UYoT8N2*tA4)UjN#+(SZ>7|9%tblP59-YYK`IU zT#v6dbaQ4SdvVu#G@V~&TpYP1R7M=LiEJQ!Kb(>nzc@m%GOGD<>eH=@BM1E&393#U zd`}E0a#&9df3Uq z@(>|oH>U5--w=saJ-5BMK9iwO(NX;&bRp-%Et#wLrS-+Fhb%>`_Ye8>JO^M(M;iOb=;$^y1(_ff&| zuDkU>bqEVH1COt`Em@6<|7@v`oo-O#j^EI|TF>z(NTHv(dUqyp9b3yHW9_w@+T_Ib zww=OPR&RqujwO{cHs$Af+G$OTOtLRX4eYE1v8ACD00)7IpgK7ld=unL{3kXT=cy5j}V+*w zZ`=rK<-(>qsLrJ#IQK~+Q@Dadj+Fy)U2qqT1JK zz4`4xhs5kjc*)dERkHNy9(3CaxbgKQ-@xv*J~CE)U*eJ-nf8d?RC~8Ocm2abO_hr} zP&jv-?__YM>aFZOzpjpAHs6Q{y;4+uA5{`%d8Nc-{=Thg8iylhMj9RRbKh`>x1He z^G^KRiAS(VTB*99Y6hs_KqIO6qoVj10tDS1fEsva;erm&m9YB$n(caY`udZWXk<1j zjqAqR`(2`GZm^91QDfSswQ3I9jJ+k?J2$leZHnI+3GX*gxb)g}yz9-&udn~Dkyt;@ zttq=2Pssm}alZD|c;xQJX8oty*OMPZ20!y)IAwk`M^XlaAJ%Q!wI$F<-9NhPG26WR zE3Cm#wd!ME+D*Q(hslaP0WUtik=nJqqm^{>JKOx+=Susa-NpTz7az1jX(MBc-=A5} z1abs)z8tQ|`rYd7?7S$Ehz{8S(|HzsKLfn1`0tLEQMOcGt6|5`vJc00PwRzJ!@2P> zb`lh zebJjrJP58cg^t)#PQ=R|tb9#STB|eb30dKBwsAOQt;9pc)I;ndpf))qwfUCt>^P-S zK;jQ?x|9H;ISS8#;&7Z`kbp}SNsXh;f&mL%6Z-5Gp=JpNi)mZT1wsr>7_qtsfX&28 zj2d%Vc=jbmYC0a1xo4N`_CdWM2jl0n#DCsydOCGld<||U9yqJU7u8I>#dC_ zEhy`eiJ=BMddwJm%wuJwu@pnEpt0q>%WPD%)@-ac=T=BGvblZZjNyKZe1_%$G%{M(rSGW^U~6cNt5q@b%R>?ETjas$Zav z)bpB4==#;Z#f*zTa7!aIq?}vvEvu>WZ+FfZfPsJOe_hc`KqVkekivgg+LWdeHBf0C z|BbcUHRCAOBPe}RW-Ez(*AHgkDG(RjeKf%G_I2K;NGZz?>6Sp+a*~qs+WT(`{}V9* zdW%{3-Ujv-=Ns3d$O~y#-W(8L;6ep+C*E_YOpo}n*Os&{?EL&#vAdkKy63)v3qF~+ zX!ZWh>eu(a7yV01+)LHGmhv9FbWRu_i4Gk0Zz$}${`S&i$u}jtNdAVGbUmvY(Qa%Q zuUUWfIIH2C?Lo`56=)M1d>AUSYc(LcYO43%?ibVCVN%B1n9{OW!j~P%A=C_6~)1S$xloXHfZDU_NHH?&pcKlMB4D2juFsQmV(|BAT+ z9>k>6&j&-Xj*vmAi@K!Cuv@#NdsCb3CZ29fKpl>HgUDbee19es&IiIH=8A?cMr?zg zUXR?dZGDEz92o3^L0H9eV&K~S!2VS<^6ldHal()L@?9O=*b|@xLj?rIMZ(|!kf8|~ zSL}PTzZ$O?T5x05^F%Kg`rYba zj(WB4l?!rT6Q3iMjSVNL9_!E&^Nz{MeX1SlgCxvzpHUJPRJnEKS<>4YqM85*H67!A z7KDe7%27IzGW$cWH_O(>p54T)t-OoH9Hv%%#=HK`M`AZq!#hLnRB~%UX>0)Q@PTji z&sPn00YA$=9(Y-4Unsk1t;WyV4~k*pnIeNBEteB;vx!?I)n7w5WecAQhW8fiez{3h z9gKyoC0_NLC8=K=`huroRs!Mg&K))P;x6pl7uu|N*E;)#SW3IxF}e2UqO;T+GkpXd zBN}vj`Dh7=yV54K)t%E&H;Hk4q=s}%xu!poXg?tI)iLc>K_AYGZRoqkUeH%0mYq3| z*vGcCW&AX34aVU@?YCq6##Ye4?WVce?C`~_w~xKPUJ92HZHG4AMH(bArL%p%z91%w zov+i^Wr?!ln0@ozZUMG8?lC#Y^v0j#^KC z1clkh`aj%8@=ZetI>e`FqN9mkg(B-e0YDZF05K2p> zZZh*R;FJ_&>tz#uwdXI3fHA?NcsPtr#x=cgNOCZkcsTIrTt&&{oa@UAcR}1D2 z{Vgmh=QecLF*uXWzj6T+JSRElix-G4xpA^M-h5{F=C$Ycn;%l@&deM5Z=Jj;DM#ZW zAP}?pqGQ6({!pJz<0uQuwaH5?5FQ&;b`1!`a%CyEj&$0hqr|e7di0k?7!2;J=RSpQ z3WXsPR$uC2Gw&|Xc8?3+1m>Z8>+|~*R#l!CxFEL9i(LISYF-FNv?@PdmscZ*W9#q} z5RK`SX*7u+vj+8A|0!+!wyIp0HSmwvYJ_a zGi|Q4Cn}G*y}!^=JE4KXwup9lb_lVgY;;S%kK5{nLAtm4G!Lk^`?Zm`wg>dZ%C|=_zI9W*VuT0**HK%_c1OMwG5Xi^Vsat>XA>iPWcJ;6kU`!_C z_y^7xYkiL6ouK%Biu z0Zrvek($?Ppy{XD^~`Tiu{*~`_av`>@ZRa3H-GTDvaz+IZSJOXDxY1-W5VT2Zl|x! z_fYok<0RCTZVW#Ap8p#&WOp+VzSEF?rf*fVmc0HWAV@t!bNG$e73+k<7nc4fIeL@P zePy@DZ_B^`9(db}>Y|8Y*|KT-<<~)ne)An^6O8+R3|Ys-oH=pZM!|Ee zP1;Z>s2@ZXnNmfx`nfCnBj9txw!Q>juq21&8f zU4$N=U*&bvvBM*Zwo%+s1?+14(&#@}1PBacM4!Cx`*G6ar<^2_b{SIDh5Y8_YvRo*5b!v)_Wu#moWdI|!7h#c1FFV-vQak&|z; zFpBFUb1r5pAB6wVREv!=lVVXq6=bHc8)%*Oc*Dw%E$pdcHy)H&{;Uy+fKX0M2)4gRJu-Tpb^0w+cg13Zz@!N6*oV?tJ8NRWLd=<0`m)6eL zh8O1nyeCq3GDJfz(QbP$2I6&rzN*V_t>k@mm_?VA zKK0q2QPhfEN;VZK971z_xZ&*Sdrrq+P+n>u@{Jkkyt$lG;q}i5YE$e!Bp=iat7-9> zKhGId!u=sI29zqEZPbwSwBgKW4)=E~XAZ812%r+lAXtP+jQW|#tK%K(FqKqIinO?C z@p;*634V{OJ&9Hs7w0cMS=xgjH6CVm7xitA2|e}xINt1bv$uk!_lmdeP?46?Ci@u1 z=>cBUWP<7X>=`fY?md%lT>Gmg#lAmVR84C|MEERIF5ljtOLcy=Kc9YYZGRyv`t-qK z-qYI$OGSmJS(F%cb4~wIwON3IKqi333xoiW2pS&!@;}waFx~twYS>>(7Z+u5|L|Vl z9|PilJ-Y+d20Xjxe|jos-<59gug5bQPl5mOc=oqyi`jnlU)A<2MW{x4NYiPsf{&rU=UM+JX{TG<60Fqi9}W5?G??!!_9PR7KeUgy*wk*# z55HX4yFS~wGSd2-?~XNQL{kPnvGDp3w|3&HL0O?>D^0wgO+>v?q7 z6>(6GwkVfl(E)36`CfO`U#0r9CR0HU&sqci+KZ7nY3{Fne7cw@MW-|+@qB~*pd@{% zKaHqfcvk)Dqow)xL@uI22&nQ7Z8;g)!xfc^uP}I+T^_Vb$c?A3<^n?>T*~e#{;}A4 zIYiO)RIdA63vh9Plt5$<-E3BG{%75*h1x+|u%SL%%2w+sw=+mroj;FEe@h z?0F5|o?E0++x({P)};U<ZrtSuV@I`kr&Ur=qIXbyzKU zK5<#dnUPP%^=Mf_=Um;Sq{Gokg-}4XyiCWQsN%`jb-9n__5`z&2S|Q3pD3ojTrvNZ z-uKY+$pK$2m4ALwBTPO&v(ASd$q*Q%>wdrY^|kWus(oSo{uR$zdV=*t{r*PKnf3jf z&adC^t}QUWru<|i)nk1p>nrcm4a#^muT8h}FPwgH97tK7{770!w_8!TCe|l;$mTMs zdARfxsl2~uMl@PU9W++1N)(KZtg_N)P=;iL_eP_C0gtF2!@%3_+z~ni1Xl&t2?W|* zz`>(zu21tMZ>JBF->LLOJJNzI2t&!CwBi(hDOzC+Ro-49$^TINf?L)%A%k_aQH@Cm zRRXO7CDlFwm;d-iLE7mbRo`)~^!?-~I=8uUpAN-&#i?zl7mKAx?C8&94sE8LV3y1e zge8W2%{nzUv+mAoa#T3Xldk(sJ7q`tJP=oYd^EV2d1G0Pq}d8+mtYV_wS}iMvtiDe zS?AvP7hFE97t(^roaB}i43(NOUU_&e!s)#8$s$l2^=Xo@Xl<1~joZ5FW)%l3GekA> zx(E5$aKvYzVCgw-83p*y*)Y=8Nr0gYpmH*Ny?>?;=Qx^I=z0BdI1TmEi5ZAGH4(^q z-)1~Dm$}7POH^wxzhEFW*ZnECQDOA~@hscKK)dtbmYhg!9K%wOiU)14N+oHC8`-x{6E^^wf5$Y$F;;_|O{9u1tadn*$C zTD0}8?vhMtbZyy4u=^)!)GZ`O3!-4T4S~|xpu4Y{mKXb zqr|yS3%9LySHF)xpxlG=1-|jV)H(0a{VEf?J~xw0>I*uQ3|Q}0V+-sZeHXas%VH?k zC0@m=JOd+qQvX@kJf%K8D|*%R?Y^SP?Qqlvo{G)g86gW?tgRXp#FMLrDW>`)wUvlJ z_b0*~6g{Tg_yGEcC3Lr~$IJ4%#L19_`J6d$oKZUc*%~U6?jc}S!>^o)c;7XO)XIS4EIYfnpOE{d z;Q8xYl@n2yoRir~Ek5jxeBr=u?ulP@4!Tb*U*o(p{H=lNmb5~Lz{5D1PU^H$(Jm29 zTKP{h&h(1fV)y>hy=@744muB#{_9XL{p(Qw9rF6Gt-`+T9v=ZWBv$F5%}kkCRqU+H zlJ=Y*smK*8&+l+L>0bTbetQD*T;yARvgm0Ztk3Qmcs$j7LG8-RsWhQN((K2)^D-*K zwF#po_gA_tdtxh!HSc%0>>N5XN_~6iG*B`w_L~nEct=WQJo>kkhUeiLZLgHao$J1v zqoWM~V?8t9Aoc=z)79^HN)~zxm4z_Nq>0|IDM`A=?~~^N z=q$y0_*g}v$A5a3W?jt6`s3Z1#Lb_2>2)4{oy$G-CH{QZuk8PNJGgdxtZrp&{1%1d zE;p8Ydf{Z_n(k|+=De<_}rDU2uKUkxLr`{$pWQU_i~p$3&ijH9uE2u{IBvGE0` z=Ud@qmJotjnjfRXQ^WafvS1bhr#^@EVCKI)P?Smrc8dYWYL}=+R!)@yZ|K0h406n5YQ&9eKvGr;n&s*=d zp-O8R-xo_^#HEUtVz)EaCqHb(OVRSwz41CZd2Cd-fHbULSz+qYYw-V&vle@$5ID7} z0Xy9Tl=ss65*j{BC4Se}c>{c0CyF`?3*2}VyjSPtmCK0k4Sq{`g9#x^-Ghv>IS#d8 zI%#u&zjA7}pAmP0`7(Gvfa=nBzj=K@eHL9H^A*MjoHr;m&#o7{SFOwvb;t4I)7vX9 zgiv(UQ8JNANL|hj1_q{NSDEFz-!=2E-L;mYc85%Bvi%><-h-{leO>nrNg$ymp?4B` z5j0e(DI|2HDk7kUA_BuglcFGmPy*6H0Y$osf(nR=olZcyfS{l>X(G})WWUZa_u6xv zb^#ldH!*uu?DXPq#z{lUV?KaqOfB_LM_ zx7I|mkzyTlI-cclo4p?IGf(RFz>-G&=RTP za!wu_mHB71T$@4%R-ZOJEBx z?4k&=U7d2^e?*F971Z=20Hp+$ATXs9e6sZU!79J+L74-b6=Ze?#2L%=)2V7WabDou z=nH#uxyLmnUkak!U4Gt39Ss}?u8#sQy_?%ulP@eg-6CJda@Ofc;bzYbzXncIasLK& z7QLk={v)#fEhv$P|Li97PYpo^$^R>GfB)~m<@xtf2;w{OILVH?3E1UHc0gjSB{fA! ziJsog$YzaeCXbFMOq`X}4_0}Sm#~~)z+aX^0DD2(b9FUo>K#91(A6hqi^=Jk_GJ#y zI|s*HOp_h^6oX<6Mt6RX8eV5qSm#bml21M{8u$gVyivf9mO0!jril909`aY?6NmbG zq+#Uh;=pr#-Xl(>%E!}JH<1M%4a(f;U)eYE-e21lpQPb$$9_ z%F)z7Qt-iS?^n}1l5gJrdE-s*jNu}$u)Yygd2{-C;7XSgKEwd6<-0d!ZfU(QUK6=6 zWEea;fOZNQYosxOqWCPZp8WW9{-w>X*W&UTwe$S@w_!V5tNR~qB5%H3_^k%zJr-TH zYOOcHC>e|1-%{_=sd18F#6)ZM#z?()ZA`fk=>J(5SGg@SL7%dvB&+{jRc)2)0j5Wx>`1i-vP~a-pO?4AZ9$on%~c7ecsxo z$)9waLm`_f4qRgX7?E+gRw1e>ru)u`#F@u|ts{W=YKmvG?p7=3I?=a^(7Aa$BT;*PYt=gQm-a{Hiw7X9 zJGjta?H6AH7vGO?Ta2GKpDbv{`4P8NvT`#wH9MYu;CuG7%8QS*R`o^-&+p$Rm7es^ z;y4r(1(F8Fk^df#DEjriiGcn;lnwv0-IEj5m7bgO`NSq~h7Hxb;;dnsESj>Q*f~p1 z{!(ll{AFR7w)_nrJRK#`mTiN{ioCX^`R;s5zM&a&g*ZQTo8q&ufA>AkS2RHYgaVP7 z3Z$T&?&|O1by4ZF&6m*c+lv%_YnWQ2r^5xc4brl1h|fkWOlx`0Tt4$=lJWK4s@BW4 zI4DGA$}IcIX~W0``0IPEi}~-uC(B+l#eQEB*LpNLBA}XxJNqKCVfmfoS0RCc-L3NJ zR{Xb<8<9J;SCEE)(zFZzts=8q?`LR9($Se8q-0wA@iH#0_QJ+vhEV0ElnV!28mFXK zD*+!~!Af8ei_qzb0^Lh{hBO4?7)@P(9z_~XDWakhj^7({zX24^RPE(gw|bJGytOvE zT+qTMHlnhB9iE4PVgd1aXHMc*Iu&}7z&yb8g(J&M?vjPhQYr+sCqsarsg^;LR#+6o z6I7f~vYeM%+JGzL1&!3ZZt6ANNxL=Gb!^wG!{ne`C;~xEnm1?GNC$X!dD0G)Y@ysL zOH}+;hw%NJylHQQ!m$qT=hT}pO@g8>pv;@U%iXKtWtaecMTD@Zq|x-O7TX^gz2_*k z(PsiTW}N)|eH@0;${))~D|5hM@_Lrc6Wo)zM-^l@1pODTIrq&W<8qGKTQ7utEPoqs zC{lMt?vcTe+@~s zavP5ac|{!5-lsb#>bS8X)GCG2MSX{=;<&Z9X<2?810-8a`1(>S-UnV4EwF3MuP7R$ zEi+zJQN-LvmKdRoUMk{cY6?DjiIr+_pn;553RC!JvAd)wiz;j=`WUli-9K82$0<+>%3TaUQ=>;ekVJL?4}BbbF(;;WQ$n}_)1J< zg{7v9O@CX5&~HSee92_@heu^M6^zVpyO!MNxV#o13|=QNuJauA9EB^&hE$0McKEm4 zV7XM9W>m>58{NCurWOOwGKh{A7}Sla64x}LeX8U>oy_xfoCuwIrT`cignZxjc_ywR z!!)rOM7ljj>Vrp#_M&Icx~Ie}SVY;j>YlZ0nr2gb?W9Xs= zJG)<2#ImdYL>3R}MCR0Ucy<{r^RL~lPh0SZ=lkQuiT!EE%usjd)XcBJiD0?kX7tpr zy!Ps}*vs#lpJf!;xL-37P%`R!CT-QXhv$;pd%MWi&}$;*U{%y2&PJ7duRA5gOl|e> zgO-XIbzpG0MEwGsqExhT6boi4Z zO$TtEtdAqE6>&pYzRM0(y-1=yzNx&3*{S^l0Yq9RHA*m-n#7r}QChEw zerJd>44g8r1|Opk=Eb19@*c&}f!bq=(V`SJ#BNkUr3Y?(k@-f=logc~Z+%TF+lnm` z8GM}RSV7nAFwOD@Qz<7^Y45lIyC6SEINc}5roC#XoR zU+hwENs?Dn5uqXN>5~QOF&mjCKJtv{;#^63D%S+BU=fW^Hp3%_vstR?M~$b+EpE#$mO?x_)#WiW!`k> zLmyCDxc$bS(n5d9u@svg0}Q;`369nH3c@)F462jqJ1GI;qG<2;CSjH+7Wc1EM!`_a zMHV=EfdbP_TKXc-^$aYGf24L`xBs6iCC8Zd1x-wvO4e;?_3QVa%<@}$B?A$v3y2)tf1 zFaA3XHNz|2(|{h6j@PP?@}I9eyQg+t5kKORz~9m0S>R)qrR)z8XTohlUcCL+!=C_&Y08HuQecfQwnfK@0_;{5zk zyr-+J*kh0uZ$Vtvps%xOM(1)AW5TZgT4L2YSf*KIH3mCnc#9v&M2#jS2X}I!Qg2p^ zGz?Gjuhc#;$`Ws#=~OWK1aFWVG|kzDrv1Mwahrg4sORZWWI`!K0Dtp z{Nzrttd_3Jm!%zqz9J-2YA$eW0G zdsoT8lIzruD8{N<3fc{dIuGrYXrLa^&3{0@iCJ#SISZZJVWc~t<~h+27r{aA#e(}4 zN_BfaaFbTgY(Xs+`(>lm{O%yt#T9!GRsgQ3u>13hblk0G(cI=ZdaC3rOU1gedPDV@ z#n??hdtNuMP!neWUOr5fE5bYQ#3&eCBz!hcPse{V->zcktBuNsPQ+Z zn)pj-(WUi z5g-6I;*Y}lrARl1i<;T9I|8#je-s&$L?}aJBGCxd7jXrcN3`z9Hv=o5IG*f71~{0W zE&aAvy^o;qJ*Hc{h)j~XKvC=|4t}n3-fUArouKx4l5c6f ziHL@+dsk_#^NC@6oV*FlpNR$TqruC|rh+oA?$*Wyqb$d{Pjyty;B9@Ige$IlK1+=@ z|JB$lVRa89c@}l*CrTnLifV-F%yS;FQQm{VquY6MI{7ec}zIf8Wl1!=-n2=yj5!CL>{%q zt{+r6ise@LX;rD9g{pC*&>p5*6Ib@g4$6M~cyk|~UCwhpi7nWzmA_FmrUeys{Ue49 zzHgB6o^w19t#Op`k|A(o%`KjIy}(x4y7QJkiKndKl{Cb5eSq`)Dlg!fG8bDxe6!; zre3G~Mmt1-r8bu0RVy&8y~61vxJ=y9ju^HZm5pDvplZToQx(+mDb}iNGRU)3{u(>71R7JPVpe1Z z6UTtq6^%0Xq>SRB4N<4)t|Wd2upG8efSGsUz7Vb4?cG4!er&2`RVi#_Kp9j?K=h>} zf_oZoue@&k0d>C-`IbfX#rAP>3KSxtNxM?40%!fjb0ZwEY*-YIH)v()4hKMi-*RSj zMnsrN*FzPg3=S1?UnpdKpqrFuKpwG(5)p|QnG!Gedq5u5MO`}#72$T4v}bEXTnLp? zWxZHHI-tafjYNr@5SP^tm*ozr@R0ZhkFz?jhVZR*5K+IWq?%QQ@ThA5%C5;$|evS>$Vk}O}G0&|UGK>=3T00J4RLjXzz0z}?6C7~xZ{GA<4&KeX4 zop1}lJo-U$Za@SMJs0Q40J|3om!)D~IRah*(ktW+eoK?N!X;;TSPDF@$$^Xv1wX9W zJ|0&&X}GJ{1m1Xb!ZT=q1w{uz*rM12-_qp1YBJs^s?lDkPkXQu8` zjUxjJ^ITCUPjzg2qvP_LRTelwAbt$YZvBYKUJ=4kg$naykVK~{*(Smc-P1Q`=mTz4 zTK0{iOhxjMV!iDA(a9?ciK+DNG3Y=7{koDPLw~2L<4V8Q9aKNV;;zVa8gXF7)q3XEFfb7ermRs&~()ovM+|mDtANY4#_5Y8wN~G;Bj_UvWdRcI7^GMO3 zw5mO_dHDBj3N&e6{hsd4 zDN={dybEG?DEmYw9IVqxGv?P;!`5dB&9j6wrX#@4b& zY?H#Rwf=w;S+cQ6qnH&gahFXVeX9042kYA9Hhf)BL!Vtq++u>|s!{uKt7k1A457V+ zN{a5hW?e)#atFkV?OyQOO7Y=bV`)h&)}Z@a#MhQ&?>8Zzq-wD`=cSoZVy%kjYg#-$ z9>JN@U^1f8M~m^LTRv<&x&w0U%xw+70>@u$`|BLiQ)ffJ8d1Vuhe#T_hacRY!zj(P zox6I#e;)15)Lca(eHiKK0x}gf!%=Ly@x6jaZ2S0QjMf1+ATTSvh!|Gp&lBp>u_Q&( zNvjtp{@5$&F+57#YT$hSPN-KG3g$hw1U+N1;`dhG!6E4E*8QF(}U=C$}HQ zzFRNuUHCFeL{V@6L@%HBu0M&pbAfLxd)9|&<{1P}S13l_>y4AZ^)DsrN*dAQ#obQb zj-~KC+%`pKzsp3GZnQC_Ohxaze@Ux|%v+9uAKHd^J0C3YaS)xi+)$wbPQG!ES=*G; zDndQoZdvBu`!T7?g!?LnwMJ*hBaeEzO_HjkdolV&IDrLxB5D9E7@^2Og?f*SMGH2X z^XCdYdFA}e(XCdh8Lz(}_4{#X4wb}3DfC|=g^mPYdad~bK=H}fU}A3bw2i}rkJOG~ zO+vlX8)QD)R-{KU>B~r%A!L)-ocV`>bk6jbqTdE3mO83+_nA${gco~eUNydz!pepmWvgtoUDwEb)a@4bW zTg4~1{lO{+Z#{aqp|cxOr#a~^ap7($ebG@ppYiWbZX@;}DY&9oo|quL^G>Tqc{HN$iaR zbwu+sm)JniF)AvwSmM3(Srty{IP4S|&h|6s@w`Xcwc{UC9|L}Nh$W=!0R#-*YGu3X zpBmcZAxZLpABIlc6oI>WO+7+zEy<${d1oYNA2IOl%fK-wh^1=_rZu?CL;@frkW^2c zrLuH}(CLf(Oh1~M?pTbW!Qz$6GzI-WspKnDG&GPkO=#mO{(y0#*a;JC1;F8N0!tc- zBn%)j5|X4cU3ea5-x?W2q30&W%TWx|kk<}(7Xf}CiVjsWORHWn%DhQfcK^2gI0u@#;G~cN+I)teF%tyZe&;*TSMS!icF3XP;a+ zc20868>VC6$0B&V5R58~)0eho5v&{oi&X+Jy3gX<30`)N@LP%(ot}c} z>`c8-zlsdPaT>^7IB%!np1EW12_6-Q#eE(JKucpR&2=SaUHb1ntCL_1H^*z2SHXH+ zS~Ajhsh|rFZ7u^2&3xXmVQf}o;6}$6estSTpmg*hA5p{=A>~)ilOs`MkXAFZh$9)_ zyi|%}5(0DB2z_#b$Z(+@*8RS%Ni;IJqol%-Ghpr@JtwwulGh?2J!f6LY5KO7 z;+mbQc4*BVw%2B#78<(~^7=+jef{sF9(Uzd)+9xHIb|G|RW3TTmSK>wM`>uCVQk^FZqm-@E*;IP}DT&`ED zu+;u6a#b@?TtrP)TZtK+wQ6cpWSN0Ap8wR!BZlJDI%AtS^E=-%T#e@C8Il1>lA@5U zoZEVfdmeD>URqTzZb2D^*1g5>KAtfuqp)}FwQ}3C2_M~9&|QTkC1E-Vad$2K#4rL{ z?%s1H!QE&LgG<;|p^QaW6A|Yg5P)frq6RFDjRQ0C5BK9}i@QSRtntkeJ%#BcXN0JM z552C^0O{?Ov2busxd_5`s}*9-*Fh^;!AJ0&O}zk(X~ZjB6VGU=Z@l?Bzri$RtF`25 zfUc3X?U&CQp+QMT?Xt{x#V_r2^WTM$A9VJS1@wS}^dDGSMPPw9T#6xv=a4 zk~CaR)FdLRXw-0*UmIf-v#&uz#WaQRNS;$%@A5)QL;G>>pvy=}kxqqZ^zhhcDdN@^ z&{@mwpUk~+NOG#sBt6%SM!~QBc&Y4MGxLdI9S@EvclBoPr~lO}Ex_qZv% zrS&QuPJs`fO~=dyo-^Y5rqRZAYD!I3(!n{d+t4rN)xUX!zODc=SF183pWuGx71A&( zEsaMqtY;j;o?6-1m&3#|y5v4lfyro~q5?|7u|K3BRcoFPaTs#b?Tc}Qw^W1N!kC9# zMk1EEV#8@@;5B|F*xSEBZu8ybmsINBvuJMSEa0_#23KS9MB1QQstlrRj}kuQSsEvL z(UaI9H}%$8MwkZoWJL^4zhdQ3Zd!LK#G9C;2?#&zH5EBBgdH;Ic|wOtOqc|zqQmp* zNgSPiTVL|-?3I|aEAEwe5n&uLP?69=|8x=DkY$M*-vFpFMooB??=3dQtCv{D&^NI09)YUBxJ%^mPNb%N~oSXjZ+B zw^In&{h5hlou5V|ms_HegePjbLCzrTPI}H)I6oWFQl>Oc;?!PAH2+!JFO-BA7qjYT z;P#oR+tOBPW269It)PpJM`kN6Pbn{986x2|d$yj=sy~o#L}O)o#OSY8omG`T zn&ejq5x4-yh)s>Xp=Nb)94hN5)Y(jX!Q-hW^o52xph{k?ob+rA?jEKyhA9li2G4^bS& zy=?EAA7)9b@s>nmKw6JRx)9J0RGs|`~EpmutKxTwZC_OQWXOa!kdqVPScT^#rOxuZm`2 zG+s=dXn}>N6zswDX92GM5=3GauqPs`aoRC!|B!s+6)Tj!o+_lF2fX8b*Oz&zRxy$z zbm-4Bg{+3_EbQ1E=-B)A;*TS+2UCSnAm@4eb7>90DBvL&ML?LcXVj)PwHoY6-Qb&z zy1L(+h;roBp^bP*E(1VfEQ=ism`896&>_N=QRppNv7#!&uz#HWu;D_;v66c-tT28X zLBNc_FUqpq2hh6m18JSrvSlJIY}P|Ew%SN?It0}w3s?1j_>|ji6&K3S?6e}=ntWQqcfPH28LEfA%O|P!w80fyj1j-E*VBkUnXtv zh+QdNz4r`7Kh~?C5n=^qvQmb;E=^U!B(s7v?shV~qTEwFY%}>=6v>C&A+i~TTTnyA z6%lB_yP_^DMM5rIcdZ`jTTu*5KPqx8t#}-J3iV>lNTTx(?uPX*Df##PkQ(PnHJ{Oy zzW6Tb&m3Qxf#fD>!7KwfGRIKPqU+drUGUeR*Tip%XjeYx^P&`#Kh{#*0wF?PE8Lem zKlPsJZGyT~`RM#T1Vgs|tkLzppV1Yc)w^WQ-||=y2mnSWPXf~Qh8RC9YrcMwwY!Wt z%Kh;A?(TOGa_hsW>i;nqILKmE{|5#G3ak$nQ^DYWP%=0GC4(90;(xaP)XlX&U<^P; ziCiWEij|4RYs}mG9@EH@=2VP`JJ;sy_nT>o_<4t|%V@*!wHIpk=|*F3Bab@Fd)8J{ zjuJ#}d2h!@+rEg93{jRC%EXjln00&G*|AVAFM!VG^15FRm+%!juP9@hQm3w0`{?3! z#)Yfp{&te&RQ9`NY{GB4yVoD1ut^8Pwc zjEDU?b5VjB0=AO85wXWdLbc|_eJ9YX0Bd8vDV9-k=o+z!+etzv?K)rv(8w2kLe>r6+h4$)yjS0jcu?dXwUPU2S!VuI zz&61E+dsfV#q5;TSWq* zfNk%uypPJruw(j*+++gH!PqLUrU9SYZ%Y$BE2ud{3376S#Hv;u=aB}p6X6nqs>?`S zre_aC+&8A8CGbzDerR17*tKi!X$Y9@?lr(+T2WFxk*INMtAK2H^*s6P!aY9AB%rQ| zl!;{fViY#D3}t^Z#s^ehJ!wzvueYt63SF#Jix(9ZDm9S|(!7>%*8yE~QiSF=kbDUk z--?!Ub$0%HNS0HeKEmDQ=h#S+LmzEAsMTN z(5fkH-1^Jw-3B=$;(mlYF|lH`TbW7bX_ky>`V14k{GOIGcfMh*Tl*2GCzSu`JvDtU zqLs#9wS97CwgIkt8gxPIP#ssoJ70aI;TN-Ngceg6Vgz$6vy0<`1|NS1oNGE*K_I}f z4}ry?kVQbFf5xV!=35EV(D}J~J&=o9ck`rBz{s29b78B&S}V#GPUc~Hv-ln+A%k;d zgjoJHZ%y7@o>ymC^m7aM*;fv`JC^m}P0S0k-$69XGw^-1| zYz)ul#^df68Bz;Lyk98s>=(fqAx2O%2eAXU1q^4`CMBkN3UK0jX%S5xnD88X|BfJ0 z&(bEDCp|=D$5N`2Kmz8v1E=8_k@IX#V>B0+IqFhcoH=hP@RP~jRW>_T*xqOLTk*l- zNNz@fL{pi5Z$UrK-aJlr{eif#q~r7UfhSkj%PHLDPOTP$PXekc*mTP;cD?=(dxr7Y z`-HOVq{ZjgU)G<5c9x&nZ2$azXZ>jucLfDzIn*G!QR#N#FN=Tl=Gy{qzSVzw^XsGk zh9Uit&ck-@9PK{)uT82|=p1mN2b`0}m?2#fBk#@rdULe;TuTg?uWvP;o6aq)Wbx2t zu6l-)1D@G$l#ivQsgtZjlOFawaEKcI3L{M*qcEVp|$qs)3sYd z&*(5f8gv`7t`P@9`@MhugGlRx&Ro9q|0R0nY7hPFJ0@PWLz^Q4P=5ADJo)R z&uY>rCT_uFyJa;zmw{F^M=jcA!ce!zVE64GGa66e6xHP|fuYIlnLKAj>4SVn`A~wU z1uG@^Chve>DNV!4Wy{DYWSbisQkyV%|Kgd&XB1it4k|671NHB~v9E+7b2|EM8wFKO z)}#$%_v;QkX!N9)P@Y%S+BpxFrjpF{u!|Oxxmg<$kou1cA zlV*r$0orbp|J6 zp`u0V{Vtay7(``H>AqVD?4mkq3%L@UM3|K0FCII|o7F2_FRa(~Q4(B7G@)E4_T2_L zec@8krUsj9gA(B9OE!{W{p>u#nx?=@?~S4UvSNG9Z>M@D#3%M`ayDBYEe8ZM47?|{g&zv1= z_16Ot@>{<)YeaL3sBaFFuMMv@rnE?O8Ns4_a{;y%-}xzjJ+kj9|3>yFve(j9KMwk< z!JPK0T0~JrL?{Q*Tp)p6P1aRwbVC|0S?5RNfwG*=(l;~mJeoHCyb$IyY)uj-#h2Pn zpm%1!5(q4GuC+oghn#5im&!NE59K(I)^%uL8Zsi@{y@9KNp{tI1X|53l)1%|(Bl3^ zY^zSFs;)trnRdLE$UV&f$~eL@ZxU^X zEfMbl%-*qcGH!v4H%%0Mn|rF#e@Ri%OH#RgaCY=UZL78w(ah3}gt;=oB^oCmZ92t$ zSR*=v&{U`^P)FcA8NiS{K)r_S&v%ffmz` z^hZIQ%F##M(#m$BtCGq^rg|20oG7PpbP&jn+tx2OVD_RE#_iU$dflrT3geg^wH?=Q z$7C0*^$?H4LRlrFXvVHm@FQhJO%DEJaZVMA-@&&@gg7=aZ{%V2Hbr9pJ>G!hZY-=A zPd=y=2qZ4WLkcBc;E3T-qq~Jl&r)YRjp?Nf>3ETWGQxcQr;xXk5Kgl?R&sknq-GsR z1yj#aTxDXTF3W}dQHR*TzV9CJhs!R}9r&`2Mn;i&K`0PZns6Lgs)AU`j1KRO4+xn+ z?>pAW5HAErKh9!cG^$Lsc6yOv!tSL2m`8s_DvcX%ggSd9no4QGeX+uOL1&TBMS}ChU=Y|7XO|hz~+p2$J zT+&u;o|EWFKT|Vnx73$qhYFZ}Byr>?u#U>&QOJdQfqtspU0&$PtLIdXaQP3_ad-;W z&t4*g^?tr;=7nb5m6ZE{is4sG35SGJ5jnkWd52}6y~5VvQCP>~MIjb=A>mL*@BJ=y zSrnDB_>z1=-tvbn+FBK^Kg5F!PAdVd?g&t2N{2kZ0E;&_RlDqlF)M-{1w07vlTM#E(T=&t?jx(QT*k_VvCjY(GT}eW3Q5O{Q%n^Xg5*@p zE~{)IRNo(#iI6dsGr)XFw=YBi5FV0KbgE4U1?IxHDseNI{bHEz!s2P_PqR$)I?8#y^r4EKWh`7BV=%o7QfwBoy$+uI zLRPWO1S7>W&o37$eiLW#SiomNp9eEhgu#k^WlowvFqz z1w&kM%6E012^>+dr7`1o^0mFm{%s8gNqQyy&K}^&2>8&o(nfB+F(^MqttD)e^g#Lf?@#Y0qy^6DQUh_;(xc4Tn<|d z@E`IV;`vzpAA)#12m9iU%_`Z}Gn^a5n84L_sgqZ0h% z#_U+=cq3eE&*8HJ^n}(;`cyc;7+KuYr~|Qu_i!Q=hA_6?nvVB8Pb`PqMq%QTGHoCN za1cTKv6XtKy@y-^(tWLmWGxPY*O~Ky%~AC%V3nnMT#c&F3G0CC50QqzF+Z?J%Nqu+ z)GAI9!L2c;ZbqE`Rx^d)s?biw$Ex@d3JeZP;`8c2S+gVddU<93XZ@rlRNHo5|? zW1xGBQ-Kd5Ja8r|TKmc`kAXb%alUE%F9SeIz}%Yih2|Jx>Y!ifaAm9Gx~1KQ#t8{5 zEamx1a)8jF-3vBVnK|pQx%J6fZ?4860kF0LohuirER2F8ov>zxzpy#SLlL=dl^O!pTQ6j~06{Tn zMQ^ZYf?I2!ZL+#ucE+PacX@>7*_bfCt(Yg1;n0*Kq~J$nK_{^(bhGvWcxE^4V+h?P z;ecfbzGkHxXY~nyMz{Am^|Uf`O04y&YHp|C4i+@Jp9QKdJU_l^VD%#F*Vt;;SAk=4 zn@W#gobb@d4<*%vd{1PNtR)3x-?h;X`L=+1VlHPLnq!VHog#K#&(;}@J$ZfWv;Q4{ z&svlB?B`6E{EHy{h0w$ul9kWs+D}2BPQ_n{eL2)rtr&E}^dBMV{``U_AcOz-1?y>{ zi2tDeF#M2z;E&3AfhHxUse#ksS+&UTj7+}9VWYObaeZpKb9;~uIr(<34*Tu4|Kcie z98VEXl27pEFJ3DZq*mN6eyearIw$hT1?<<5rTh<%V9cPTBF%?{N6>3~C6l&Lr>i>$ zRbpGqoUC&B51I$Vd*}TzTrc@tyxU}W;z;3J6C7kszmMX& z-Wz)&X6y@uj`JUU`_`Va-ZWt6ysnijvik1YLgl{0S}H9Kf6{dChPIt0I`8@N=%<L!2#&Rn4*U|t~ zk9ALC#Lg`3b{sjE+^q(MQ@E5EwX0MJY>z~MwC0%FT-5ocVM9{lAR`38;$vLNgBYN@ zWn%w8zbV)#XR4@r? zZR|H)69Iua1I*Q7KA96@lV(9FSLGFaZ>c}d zy&JY0l<-g^&h}GjrVa-a5Sp#IZYkQH+5Ut$I=3|61maRL@6-vz0!l% z7eCs9Fx+U$=zjkBwMK>hWNqWG%E_2(kJa}pHH4fAxukC0a>~!eH`{xVBdXgS+F82O zr83F-KPx7WeK?qIe5{X_=IhYgd*Z=mu)(AC%izne$!|5Y>(4Cc$SHslc&1t77w(g< z_VLFei7R5n-&@ZDKCb0xbO&_ws#F^pA7mBl>YeSd z>3+$g)Z1w&@eXiMSh|1+w9Yi`xj64^#f@KeO@1=S>VK@e%ksvt4Ws!6(#OwkpWg-# zZ|1C~G^;)<*%*OJC?B)ddtcE|scXCX?s><8=Amcf95)SwCK3BwVJE$b`rD^8&prt= zG5+fx>E8cNZU6aS5oz9k|5v0qE#C`ae_#%AF4K%xe^T3xgXxIBZFT;|_sQ_gxrNn7 zY{$cr^ODt0Or+6fyt-~_MHVltUT(%?Lu2ySWc*@pMEaV2E6H|9mY}(?$(`8YiQ|q| zf3fh&ES~FR9I3^zG;^k+E<$eA$-lh11s{35``fN!;}b%-@=NE^<);@L`M@)F%`m3| z^Ll}kb+$RS3_LHB+()~UG0Q0D{N9}8#yeAI8Dtk=9nn)oR0xEtdvx|ZCm82KdFz*t zz<<%AezSj=$&q+T)q{2k?q3^Q8sBj(*LeAR_=8XR9gU6FeL#uayIIdX_p)}oZgzTT z_=X%eIwaCzx%aEp<)_<`4W0Xw@fQYO8O3G=BF{`Dv^rU;I?1{k94wi(tAOAH0;0K2 zAs+{8AR{SUYH{5L2W#pGKn5RJ2Z$4~#6!CsG-Oc z5eh9|C-kdDnguz>83K z(>_r_@KBO`K5oY>3Os*7Smxx^unf0eMYY}ysp48DiCg`fuscJgcubE|X`)7>0B0iK z#(QgR>ls38dy15<57~a1s(X$7V_*1O5zVTaSzGd0f7^T4=H-}g`GWG2!J#}`r|QNO z{BWH|>YK&;(hPcyPGCK&*o84FY+@)gg>c{ED{s}oY~aItY%epAsR&z`LF1@U-qO2OUHB3kn_UY2VxLKjYqrtPaKU{$J_3{)f#X-d-pqT zrNZcj;WUAB@-vv-^o-vA0ZB5$PpBsQbudKm&Zf~Sd}jT7B)ioXfrfq(YMkKmkN+V& z=-PkeCL+!E-~UjwQn+WBlP#k8hS2k|VcH*SDxuA008Ri{Q~lpFvi{CZLeAl@Qont; zrWk*}MyFIRztFZsbWPy|1|8j7>f0w<8JBu@vtjX2*=3A&tjR^e_0Nj{Fmd?zI<~!cH3X@BA%Ds@^EN9eiYne5nyShfCf7&1 z{Jrna`6t;&eM|EsbTFX07{|9izA?k!3|~0}`TR`A4<%&;SP0GbN(>p?ACLGVi8A}m z#S*;%1NGEv9#qPljW{w8m>RwMU-3P^4;uq#7_?a1!K;H(@tB>}T;1a!6!j>-=wtz4 z*n+ADp~Gjt;3bOr2QMuNKeNXDTr)ccDBU%>((0ilN$MufB}tldIUZeJ*oYi}T6)~) z$4w{qSM9oMIg?+Fywhr2@HKGV(%gRdREmDTZQ$sYNn1Wn1J*c!uNK#+LtXj5Ivf&N z0jTj^H32hQ7ES@#F{1d6@T^NR6KdDz`rGzIVfYx-n>%>_@k|s5Vnyf*5;uBe@3dOz zoQi*JRaXG{y5E~w2YHt@{e`M&_~qPTe=niG${uU#4Q4|}hwV>IRXPm&HA{qa8k*d+ zC?S3j>Az#n=xglunc%+JOl*`RCsTKl*E$@h2gMlYvRaO|X z*%wyY6dzQqw5z;aSow%;Rax!O{Cr`xQ)i}PwaZ|0VYQn8Q(fyJ3;j=UqdN83KU16j zNg+5;*nbQEf2WW}>Yo(igaS%4{+Au;{|bNp{m%c_@Yhj&4H&W&;IfPy&cZW;D>i0QM??G)>b$k*dUr!o6~7iAFcP(fI?g&@UD)V^SZY40 zf8q9NarJW-zo8td5kjgFwgte!hguFD~YimlwsRyH4{F5s1C~9*bqKs@(Gv z8=u=rtMYl`7$&7Bs*dJ6u1k!7z80f615Fi-Q^Du-0V z&L1+f79i)Nk}#7Wic>nKFDkv!=Y3H2Ddp07 zS!Nf&j5tqMgo)b%gkP>PqTUvL`rB3IUcS$igQUTB=-b$kC<41?59gW1=e|8|%5EKW zC+Y#0%yi(678Z16XKG;H8Riz6b^+b#eCqtRurvb%5>9K>+RS<(SgCa-%;x+ez0XD} z!)i6f{ot490{&6Np!KbTu|_YC-ju=N^K)e$2zQtHrujDyN@;RY>(epWxS{Dcmp>S6 zHzHMMnmiCLn@&G`^fu`7*^Xcz_~8fm=jO{q=;ejwR!sc=&+s?ob7m3(|7qmMg7p6{ zO$nTjBdg^9aI*gk8uUNa|NkA1c)kC@Z_N9gt>}Y2p)7B^m`@wI{8xi0pQ6`n)z2v} z`Fwon^!R>L$dN;i*=u`qZ$d6ho_c!d+D`dVz_~WkZ?5g$qbpPTkxSm&)t@bR?>o+K zEKix=ls!fLy|GMs(Jlh0@pxktOD`?FZ%`Q6o-|GFS7CvPYJ#wZ9J-O4p}eOrZb|9~ z{?yagkE$a=*|-J6%S@k^+cq+<-fkox(*{FP(nFW9piI}RTWbRYX1C5CzsTPr^7OGd z7y^=DbTWVG+AF?`cq||4VA4M9{}pk|#`_0yr$5=L?ZwTS!qDAG6jXQ&AfOa?8}zx| z@6|uicGF3UGnCd5`Mg;OO^wZ3A24yN2XJnFMd#~u7G9ma6NTE-_>QwvqT4wwHC1=% zZFlGZu-;nIzXCi-t6gz&l4oP9vFnr#w^q9A=0YYiWt*(@BWoK@K8GvM1Kv<}=k>1{ z2WuqDti`N3>lEEvx?Q(rm7kTUZFB@q8CLl758{6Hmz>Z4rD)QrTu*l-f@AFclhc`s za`rCKa`WA|g}rCON-e+vCkR|=YgVvEcIG`*m~nH+y?pJHh1AWOK5O5Zw&uRFq;=a> zXJ3!~srmB6=5~ax$2Qxi)1~e0e`Q-th%P*dX@jb$*Q|MTRcffZ%s;7bCg0LsV?1kD z+DL;uwh9>V0I&d+8Z%a&Rg;dFgTC<38~?+W_)qi^|Kr^S^ly9|P5=b>*F4ZSnD9VhH zEt#WEoyUw}J?{lv6AGlnvx!?Ewyzl4Z znW+7JW9gbRZL`wixBba4ZkM)Z`Y+hK)C`=Z%)S7Ss@cV~D8F6r6nYy6uF3@2Miop;8P+ z27zy)3f@`K`s-T%tVi6A)kPlt2gL#k8$#-81|NYPkmpU|i;2cRI^8pdNvugzVXnsqIrtU-3_n&(>iZ5Giv7tFODjYL`fXe7`r0 zylg+?q1UiO020^A@a4<}97{&EE63_b(-G`v|BzgF<|m`~W(C;GY9S8IZIk(zRtOC9 z&2i9>V-Xfji;^ zFR~`jt1M1S+kBqtF(qB1a`aTm?LY0$P20Qe+SQeF7T>}(1dBE69+ylM9q|1@FR|ok zTOPWm9kt$PwSk#%Y-nqRD*De3wmEw?Rzi!t=0{^0G@A!a`7LwKFa8-E)(dnVh<5tl zUf};*{d+Hl{FAJhMywE@wm!4IASfa?_~ltL-v09y`+^x4AYw6XH)tOAm3rL;*ob}=27Fgd^%Y;Q>2)CCm8!iho5%9FUSMo7prE99j<5p2~&8FD5 zSC+0{*iWbDHcr7rE~NqmOCo_;Gx97kQ&y)S2-d?%{5AM_`AT03hObW67*sb3d6yXW zK%I3R^7Z(D;gN1f+IsA9)?oZsQtS?<9_{aL|QEYA!OM`YeCt78&#z%CuLjp zrHvvpqZ=E1{vFdg!r|ey!@Q=cUYiYg0VAL6tVI^z)fku)qa#-!Lp^|y2`PYL1*h;% zk+!{;HWW78vCC|kplsgCGSY%0t0Kg(6bh#CpHF%lN(}4|sXnxoA?|ldIb{YIU&;6! zKh3xeuGM0&&?WOplIf_xE)eSD@dvpvl{dugq}BBci6}OZr6wXlW<%8>y;jTRmxk|0I9P_5jMcUEmMh&l z^qM*vO1f)b(`wXfwoq+y*Hd{mMk4oXk|gr7TkeW@ns%kO+fCf+mApHBg~8v*0{05) zZ2xhc)Cb}I|LWv>H^iS;dWjYP^UKp~I>`;!A2B|;6wa>!YQY@^u%Pm1BKyB;0_C}+v*Yu{tGqV_(E-)eZXdU@ru z)!D$#xRG~KWzF|*_c~~^Uh59E%W#C$ELJ1D-0p)w80Lh`v#KK1YqR&KfIyp->H2Rb z2wAN#pb3TOS9rR1Y^miLn4LWG1mFOkJ`uvc((n;3uOAM0BMf2|XP!P=&$;&e=V-SU z4>S7up%Ija!ewBnDGw{}Nm`D8gUY=V-*9K`<9lVaTzP}j7d0z;3>|5YGTr;UIarS` zIO-kxL2C&wQUy+;IVj+K?)RXaz%08$rj51#Da0Pxh$7`Q?TDG2tVTAWFFmOHmpGaK zX#An$@7O_ojPV2thkt`ixL_o$_Lxt2mvQlHEWv+`9C&)8ZP;py319)?W-tZt+#PQ= zY%Za&AW76UlM%2yLI9)y7MRU<Op?VzMMSuK zX4wYex#gz~ysK~`Boy^j?zp&QiJ0J~=ibk1b3K6lQ6G0Q^~TM9kL=Sym%_tAGUP)n ztg^ryEAT0uK>=p3ZeyzJtZU#R#l+i&$GrXt>p?Rfa#6ZQx_|{%Wrvblo;9l%Y_U{x zuyaWvZh^M5t2x$YIjKKfgm>t}4wnU+-Ja?#4!JezE*}18Ws?Fb06yIRoi+JCncCvo z5;GD13VHy7j27QNPn0k^kc}sobuffaW}sw{N?rMI7r!%MVmBP=^G9CFlaBsJAg!ah zz~Rm8gxRv^XJyi@OI=s~vPdKq>ZLB;D}5e2(Q)HSXU?@}EH`1(An$vJ-bSqS)VIJ) zb@4GFpB~?i>nk;XB=D=Aet6Gc&mvZL>f6#8pRJ$pnwD0Di$+FU)6oNo((!&K$@6a; zRx_l(d_FVYF*Q+8Bl$R)bbhUL<%i1CW8}{=Ts9-ksMrmZ1l;-Vc4T ziJq)6j=J0jz5oFWCE?D+es(hEz1&_VnEJQGe&%@c(7~L07%53@zd9U$k|m?Y^<{TM z;EREzp2b%;OmiN$)cP*M$}QgmDL{wyIEyZ#oz?UM=g!$_j-`q%dx*+w@XHBt;a~HgXGKG|D-ObLWmZTAW&fu zp)YT-Vx`ym{OW!{v?CkhAOHu7B?iNQ@K7-k3M_pE6?)y_c)e#4K=@kik zW3Ht#Y$nM8w2BzTQ5-L0wb9@p;_)W7*X{{!p!=XNRVe5{#@rG?&=J1&ZQx_71jYJYh=Z2kC0$%0{( z>0>Rwwl}Ju-~(Fpo-KELa|g=af1UU9XM)%L4~iMUi~6^KMGg>B@|8PKT1^(dhL!jq z$y)z|==+}qtoN>n7iU)vd??LKzX?Fz!)~Hy=Dt{+-NTz-%&nAYNhBR!+PGYuzc&%! zwvXJ8C7S%zwY1Ul=w#VT8=jlhf%upH&*FG9{R34dH;~b@fxln<`gx?c5FcF})UwYX z``Fdh@Rh^*_kc5@4%78Zd%J9srx!Zpe%-rjbLQvH&cNlO>+-hX;#HGhj5{sKQHK;d z%$X1O+s00pZp4o(wVYY)sm~7!_p=t3)|9A8-~0K=8Q<VSu9zMQZm&^yIr98mX^D@@RPR+yJV>tf)!Ct8AVWa{ZA+3M zwFh>a{m6y{ByV^WF%C=Z*Q|(o-$VEDhgK{iWrJBj+PNx8TsTeUP}jR7dWXVGv0JJ8 z-`U1;@v?~bjRP)ce=h{WslCjGcTA8#mm_Vbhu)XJE)o157g~!V8f^iJK=2MJ5C{aH z{B;N_L(OFK@sn&B=FxcB8@9eIN?QmSE6uPe^kK94Hln=nP?Q+}SQVCtW|*(fPfXha zCYBGDEUdY=jyQajTJ*z%O2eU{fGX{)y*X{;Vrc9V%X;DI39H#(?F2uFGz&S|L~ca=g=% zlB3{184~7Yg$LZMcuXL*?)UF}KjojJYBkMjw;-1+Yb4yAeSeJ}7Q;Tjp(<*%qgEV{GP;AyU3$UzJ3P&7wa0Wx|jZ8a&F4k^5mUC5~PSjJom%r=FJxkHU{5WcMV@_q--9 zBZ<}#jho+%zOJZcde2nfnX~VcfA(md)KSgJDLeEq_~%p6;?9>g3O#>@?@Nm2Rf*W% zjr(>T&x3eS@gHHmr8YD@^BUJSpR}BC$U9fn5Z!dO6MDa92Ob$X$yx7nme~4wZzwhD zdKe#wTQT(X%<{P}LH@Zj1*X2Z>IT1T8t7yf$(%sNfapi&w~vNZ?KL1)o|q@`EGy?F znwRg3ypG=IT)fXUjhI_<{)fCp)a+XSt9j;3sBL%?!O0prJ>g7)OC^k^+%8@2vkbwj zrOPK%14Q>gcP4smCc9UhJaBP8^Wr>Lme;h#P&m9j(QUH84nk^6!K3+v zdDIY5;a$hsnfy-Wfi9Ln2aEL6HXYobZF2B_UjYD?X7df6Hu?|?2Q)4yNTRhj^R~GM z1n;{Y1Ua$D74NgTCBmgbc;Q<9mk~HF8+0rD1;V-=4^2Z@_)X*;Sy{jC#4l(@Wn1(+ zeGP#^t;#Q&ugt#-CNf{&XSqK=OQzyJYsP4RdB$Wm?AOfKt9Tca2mvZMP@KgC@B>0c0`M69;@orK*Y3Oc2a7CTH9XzS*YZ=~ ztRl=OGahCcDV5%2+-!}Wl(_k?jls;1e3kmC27-&l`0#ZEcG<`A&EX++hds|##*AEU zt`Mc74orIe!(G9jk?Fs~)Boe!|IdbY--T;7Kp6c?tH)pap34{o{dlkHo^v(Xl(O@F zIk?Nl7ra=gMywK+pfH)PI(7`jXSdY^(OF=-k{ihzA2x0`pVU&;^xyMX7@+Q0*Qypf zZ+w0ArYUK5`nOKYN?9TLne(SR-fIeexykHWP=HJ1GqXGJpVwh-7fVbdMzh(ux63LX zNc~GhGMvge-PO2pxpMz)C8v_6n0Mts{FCS4@7occvoEk=9~xwah?@AgoTdP|}U^j`4FgfzUeg~Do zg!{b~Z#4ntI=_%aw#nY!rAm{xrEQ3ir*^Ckn{!3=t*VnnMt`Cys2~leks)?WpI{wM zd72!rV0UbLIYspKy7(V4AH&XTc&rLwfXz^}f;$QCKPI70pb03j?-US^24LCq?_ZVW z`&ajA?l~r|Qi}S-?r}Wui2&^C;N>HS&h6*oz_&a?t|rMmHS*0^VXAUj8>OdlKvaD> z!uq@^%OwNpe@Z$6U4O?D4;B<5^PBJZZE&$7aSe6&$dUu!*0z7$uy0922N?dXAoYQ|02Hno22~1sLyfr zNl@=$?eF51<}JTtiX85F?dBeaS^mQ(nhMhXPxbWQD`76>qTFGi8wme%(eQuo1|%}= zRjiX#X1N>QF}tr?0Uzt`R^TC(1ut#WIfj}FHok7qfX81&WKDbnw=Hi*_bF<+e<*#d z9I15R9>w*=fz&xA-7`N|D%7BH3Jsp$dCRg!9 z<04Y6YW)pkualo<7yV^|`&dERLS=y2+1UYU!qL+HP8-$ji7^8(e3WhTYAPKtp&Ku_ z=&i8R28hA%_Ce$IkpUo{Q-74YZ?IaB55jLn>9w41f1m4HFWErFtrvzJ0Xl?nq-DtK z_gtxif)X0o9p<0#Xi&))KByY=Ncy|ormj`cv6x0AH9XHdG*-StD;R&+5PGF*E8IOZ zqFJyUq&^v2J&S)TXUxEFjsi>H?U5HHrqeUavkjO}Ku^7mdW*z%_ujwluvJcYrML*=2OR_hMR3>i9+ME z%RgTfhVpP9&hWn*9|C7%>$y*->!K)X3*enF#bMf;)_AD#?U48aC%I~RpQ^VS1k{Zwj{sKc(N`n z8Kk6$rwn~_A}e*h;60Rho?+jW>G=F~-?L6~dGW0HcXi&|uLY+$vMycWP}T7~^JM{z zs|)q$gMlZa7rXVoyL_sWAjAq>BP4X;WkrafQ+?-3`j1-`QLR0GsAw` z<)f(z5ZmB1VZ1TqinZJu$s&~_k&$%7A+B<#U2;!-VdjeQ^l&s-AuuI9%naRzicTHo z%EfiLUeb-4)$|Fv2;y)M^vT>bluo~^GBJWxKY)5y-^M%_d&1pOO+90@U6KDKK3x)c zkmhNN zX(6qUeQeYOG0ttRRn+Y6oGa$9V8AqxOq?UAlWAmJR7kA6a?`^sVO?4be&!9C&q_N;NmRG5M_OCO93v-&`mGeeCXuzVic$jAqu zSLTQL1Rt*BM2je=sAjW9Au{g+i2~?%g%h5ntnzM6#q#~JbzKEd?8Ajadd%!!Bm424 zHeOFg3C24t%iKNj;XSm9*e)Sgno7_;Lhv$3Qo_jds zJt2{H9I)D##=3q0YgLlO%!bJwO5$kneo+%#Ouc8ZV0)YhMP%Mg%%GfIRkQ2CruP0q z{(jG~BFVp!)OMY8iu9s1Er8J>I!@dd0{nTYb()<{WL7defWEN9&1ar#cv>YWt~yWM zz(rG|+Tgp@Pc#u9q%I0n7*hG-h(~Tl5m5Iy*<~WOigu`%WVbDQRs)qTJxJLnbF@cc ze`m8UD)1~6U2=7&E?wtIxsGRX89|~VU2dI%IL4G#%5F8RZ_#=HJ{^ zLRgDTGp+_Ok(I=CUWdjVnr5XZcC<}#2M5;}9EIK`$?bpUmTq}G8=l$)A%5TrSRTj2 zzZVNySHsYazv;WK-^U9zpdQN13tH^z{|K*3z<-y8OEPELCB>Gns93W+O&4f(iUA0% zP&JWwW*%yI#h}720(q_rX6QU7Y{OKwk)KUdkDv*n{i+P!#AL{PF3&U;RTedj2p&Aw zl#$fbCiVvK&PuhT7k{_O&o@DJ#+6aB&O{MjBovlVm;PHJ73F#iqAaz@h$?MWY*@Lm zzt*rLaXyGD#^KkOT;vBX=5jv})JNe_=abCtD?EB)ugMY1B4jss8dB*91+b~+dH~ue za!TusD-Rh5f59N4A^VOo!KWjBD#cY2p4M_9qD2F!O28PbuU>R;_@1XD*H#f>fimP) zh!{7q!G7BA2Jfx1T*g9AidxmG@J>_i%#KFujo9`CMFXQ z$rcD5E?XgxbDO+C-LZw=c1i+7|je?~!j%m*aFwT;ewYSKy-J}J^>5gN_6Og7f4tW3OK3I-S9bk;bCr4uuX&o}H*`#}O0!FZUdey#<6iIz+n zsuI!v2^wEegk_SA28v#aQ$TEyTQ}hRGq)`70&yd{qmZ8qRq2lOhxwCkP)E?%8QC_( zsYwbX#v~O30`v%Go03B4Px5p$#|m-5C`QMb7b%A3{c=0UkRxGzOqNbaS?sQ{706(jw?wAe!nW2G1R=?dm= zjO`cDGi>AOQA#c%e0!DeF!)~v5ThcX@KHM9I4FMaMzp5JlU*f-&0ds#Q8K|bYr zhY4-(DWMZGD`olE&_F27)8()J3No^FK{*mBucD^+^y4pMZI8d*+~Dt*U2<@?q$3AE zeC^lq$Q!11MYeur$lnJqQt?rl!QPKl>K(>LgHcKikg3s)KRmV5C-^R~ex2OKOtxMZ zvCxD$De0@IKfR#)9_U!XZHg~0kbA?#3I_YP4mT?sX{pRCMTMKb5>k1+tyL@P`YBJ! zd3?Uu9i1&I-?RPux>FLSJIL|O_67ufQc($?BglK_eO4Jb#VUC(<0cRlZ$(Tn*7<_^ zG82S9e!M%# z*^k=H9gGIRTMOx(fTKDEc@!*``oZ#A1}Hs6YW5U(_b-xkrFYd;brdZhlaT8hnvE$r z02avnU{g?UlnLjp&^qON%vs9vMh6Z3viU1a$8CJeX)w81?jl(!v|K;aoMIZAf(rFZ z1(289_lGV=AyyDNMBwP2q`B>m$UlpC+-GDmOc7A5HBard(YHb?l%4%74Ml`SXq6Q4vrSH9BtiBp@g-9(BHWCNbxG-VHoLB0 z2}bZ%7Q#tA+u|XVa;$Q9i`!sh_t(&RFNWdXghz(<}?>C zDHG?rVlOo$6#MFdYB)z=SBofg7O{^S5NUU>H8tF0zQ`y`(PXfWUnyqzLT46FBzN4d zyu$cuaBdM7-1S4&cm<^i4^ZEqQ<0|SSn&Hg9F;0+OB!^0MT0(~7(ZdkC$5_KKbF4u z__fW&A`Ao>Xvs=T@yh1arPN8*e+n@@8ROKad6DWrJeTM)`PAbIOy zII-<-s^w&7Exzte4ynZ$+lun*0^D_oRhkC6e{~&+(b|sji4SMx!q9s*A^U92UaXkF z2(bZgr`U8pLc-0Pn|%+ADT|4O2o=Z$A3o*m5oJN0jK8>wOX*k?pT$l&%&vLu>4gBA zW%(RI?pkDuLv@hSH=~SSruENhi$Z_peHay_@UJj5FWEwo_d~XtdNb8XSG|Z znK7ls+M)Vgwy$^M+qf*K%I5M1=?MM3w%om^PB+J&+&lu{6RM6MS znM{!ehW0o?IjhM_q;V8xvS%_p#GEDLuZg!&WC7pzR#_i9Ou2DJ!C6q*c8&@4+7m@P zHqk2Ey8zv{qe?;)!|V+COh125)73~wwXm&(i6a70@m3j1+uZcV^#Gk}Up3br*C)v= zHY{fNA{^)iWXva};+yD_Zq)NZ4@H!Z*3k_@b2EtR6uDMT*BwK?jL-l8Ek{YW_c+Z% z*~zy;Rk@-{y~Q%$?$A(LasUpTBND@sNb#+ z3mH1_Nr{Dw?mM`YlIZmbS;kDTuyS;I^XuKBu_Sf;k2m~D#e)hw5{!HAh~j@~a^Oj$w~R*| zMg7Ym%C#sk(h9=|1=2OtxkAYv{qzU4-Z~1l)H(`Otw;iNua18nFU4?XjKU=1DEV_tvQ>WTkl%YWi8UK zmA1~2uF_94aK;O{G661nm%VjCfT*hs_!$S6e(ru0@(ekxT6Yh*uWLbz7CWYNZKmBu z-~y_=Syc&4i%i`Uz$o4G&{)f1zi1@IS8wOK=rNyml@9zxx>W+_og^viY;H~h$j%UY zpgZYrs=(%H3CF8uwz{LP=hb}x;v6dVlmq92FsPW{36utaaQs$C;`$eRq(#>9)3mGj zM15y`^@b}h&e)DBq3Z7903itu;Cdb}?6s^RmBnvQ@OHUm;AM4h3FtS0a4SXW7S$jS z&4Y>oGDIK(WN36xkmA?OT*tKvQT;|7CIT=*#G>Sr$kQ^SBpgJo{P1VFQMuVA7FFFV z#|{n^IeM|v2LHO7!Lr}0S4W+bYen%<*y)pp zbY2KSliQx&NPdtjB)AN|JCD0uJsVRJgLP0?@H2U^W`I1)ijc1ghhcm0x`+3*yoKQ} zTBizmRFn{IMX5+_Nj*gblO|5T{=3_H-t}UfW@yK+{!8$MH{W0LV00uno-la<|+f(|C|H6Pra%p~Zxp(EJV2o=C_Y}SMP4g%OeH<2_)|S*nBMfyZJy)Y|sG@gI(J4wo^;%yb|_| zG$HGF0z;w2UjAW>|@&J@VDhaq<9?^Q2emOfeQbC$4rbvF&t zt7H+o(>)uM2Hj0tp0`$L?i=YhJUfYMANcwu!+xMtJMPxKX+aJ8&gfX->64sHbx ziii-a?a_*1X4NVe^b}bxG$T|1I)pgF&bC=^99H#&_L7Jp65YA!D12-YD^CyMGn$b) z>WWsh-8RZjc9d#F(t5a>#qz8WjZPH4V9B|d|LFUJD3c=mC;6ma*Aa0QKSPbHkQY_` zl3G6a{blD&Qw79~;8TqF*m1}u(+i~-JK1bowN{%Lv^KM1gc{W8>bMcZ`U45wCLXiRsi745cOV>7J4ncVZrc;Y>j;OmPAOIL5(4YfJmcSB81C9H ze>PaTRn;kT(`C=@#!({DfQm<#9is*m*($9Lzqi3fQVZhreR4ZfP&8WW?)z?=*Ww?7 z3|di%ji=I(JRf}eWq?DQ-omJ!D6@Vo>WQp=NaFB?C$Bi9qjW@EcM+2o4BFwB>x_=( z{mivYLHZk8bjltV;)5WNgw#$&3Hs`n(5+EPXO6r`{rT{7OIj$!L$#xXD@b&Qq4|#I zE7^{D<^?d^uU5Hu0D5YRfl4H+MM-I)qSP4iq8=xa$7LRIDTmnXwl^qIoq^`Om(nRN^5X5O7=ED?TNm17~yKx(t`zNBDV7>eCm5(Bl$_@xZUhQ%K`!PtF8Nt zpKx@Dv)SZJDpWC9hCx1;z@A#OZu|VX3Ky)Jnl5X)?Vk05?%n9LN6`}fjMBNw!&+qM ziaquRO;igrqePz>w4Gt5VHZZBWw<;$A#d=lZsil65QvD|vLUUfI|!RW0Dp`}jh6?& zH7Is(F%68fsS`?yA32Ki9onK^f)4te3rWycT5<+cd2SYXzaSIAQ!|jnPaCjr2lP`E zwrR-v!=#PlY)+BL1%>((L9paI!H7YL*(fSp4VESOI^aj;C@Vt zKrB&tel$(7NhaOMj4ykB*xp}m7Ue(anD$od8Xj(OK8Z}1ddsxco8fbW`|CM;1f>oZ zfb|UwStkBEd_rl|w02G}=6G?d#9RDD&)OjANm5?A-oAp!SUOsJ;lTd&1b14J$8j4h zysVP^rgDw0Fd2T6v_dn85t$I1qfDWb^9HWoL@QsC(027!M#coM*pvu%6Dcg0%E8Jb z`-&=*?Kji)=Gh8enDYkF7{L<<&)4eZGOUHe^yN#JayGha<+gEfAu@Z{Am)WG6huWe z+A1w#bb_x86nhT}!@~4?74|+(zsA#30hZg;eNXU0VP=3(ua#y!ZBXzNK*E0NqQa9R zuQ3%_qP7?RMyO*z0@#Bt4UC8 zj4~Vv5byws(4NwIn(&A>s~aaWGBN4a0ANqlpA#NOIeCIi3JUcS0uJ zQm+&VJ|A3YiWom)^#>vtlD24n!`^h zNVZ`v zso*5aA;XR3_>=}lbU0a`FgWpQtv^d}oA4&H@Dv2BPeYuxQ1%rgnag<#X!MNg=x1fx zWGMsxsfp%UM9Ohrw7v-`>`!3gjmhJMWGD zt?HE<;;d=sU#ACbpsUrEths}o%|m~hkHp{KD9D!KPUp3TE5GN%U0Oc8>s@=;^80%v zqh;i)^RMQQzkek3wS4~7`|H`(@1Fp|ZxrUT-nwgNA;aa#xOCrohvm*9lksFy!{zj& Nr4>k-62nrfH zDj*0Vf+Z9c6g7$kE0^E>H}3tsIy2|RDKp7V1kh}JvP%za02<+K|MD5vy z77!3XqcIpX4vUr$6T}G$;e3vMMXu##l+e-jR#hjcsi~>&vbWr?t+oH4spc-NeVQ)z+C(i~eZ5@>M5J9Nk=d1^>BCh+(pgs+U4!#m7C?gD<<@a z_mQJ6=0|rO^Y-)g_w)1fKWrNi5D@6&5*Qdr*%jm)6clva|48uh;LxKsp}WF^!vdYd z!^0!OLn0y~q9UTB;$xztqhmsYVq#)q{mCazoQR{?#qG*Wi;tirgm@(+BqRk|Bqb#! z$9N|vC#M{@Nl8gbO-)TZ5tOzoBQ^bGW=5EOM$XC1^n}dJ%#$ZiW@TlaK7IO3j8k@Y zHZ3QIo*G7{({tjSb8~YUseudzBQGy6KglgWkCvaGUy$rtknC2F;$D#ISwKBekegAM z;!;>xSW;3_deXP7tgO6*QBhG*Sy_4R+_|dqysFB=s;a7L#)<0l)ipI2YA#gQ)zw|R zc#+L!H#9UfHa0e0tZHhgZEkLEX=(ZId`??qZCl%amo8npa^=d^t5>gGyLSD0JBP!$ zapOj3=gqFJuI^jAx_WziZ{NOs=gyt}JDvUg{R7=C0|VT_!NK8Oqr)R3qr1jO$9LVo zfB)gc!^z3XM~@y&PfyRx%*@Tr&Ckz2efsp-v&HAnpTB(ha(Q`qZEfxC+qWAV8y`M= z`1I-1*4EayZ{N1Jw}1Wm_51hlKY#xG{rmUdzkk3EptvL8V&mmWwsf=6(Ii4ZyKzwb z35CISZ)yDBaO_5d`Ts-m|3mWsa!8On00=2-&tVVHks|y2#yJf`Oq{Y~Ey3DFQa56* zuYn%^sNUiffbtkddNe!LTAbY%`oK%Wx1XjMEnc+P75nNzOYmE4y;NLd~3fOy~(ZSwIAU)R*<)T(Y}p~!DE z7CWO~44(HK)2%nl*m@`Qf!WFNX#IXUrRPCU$Ld(A!XE8e+oDjt>i!2C+wP@`cIOQe zq(9uR)bP8@IB@0AfeVI-Z@2Fjysdg^ekw;m;lr5gMe}Q-=lky%-p%-IA$8I9p2cT~emf!1 zg7GtH{Unemu3W+D_Sfjg-E`8O_M(dzpX^GiH+$FdwBF*^bCD90?%X;Nje}zb`#<#| zFwrEYBsgDMYG!8a7U4X+g1wvqxsYK#Nf(U!BbmEg zmU}8nuwUh&>1*&w>9rxv;TTVsmXDkY7vq(zo6ZJ?7rrQ6qZ!?}uV%EOgw`!Tq5INA z_%^xO;`ervpu5dT?}mlcyyurE=`N9OFx53)3iilXC5&9)+BB&_SXJqA7}9L1&{S^SYK__l(VCpMClM1vS=lbznh#wIh6 zg}|+5rp&>JJHbgxnRiqUKH%piU|oCR<$Zq zrl41)qB4Dr2D34#eM9n&8X2+FK$qTGn`YW%fGxTF5glO$C)S!JKN-Dh#09z%_Xo-sP|kZCah6VPDNdOnr@ha+_~(1}h!rEk zRf%O|e7gZ#lr6+OUf3*I@%0|y_^DvKbj?i2V2Ug=L0=Q}E(y{kEBR zre5++aeQezr2#o4lV6QuFI!noPQNjj=rTx3Uo}{h4M#n4n4!r6fEn9HtG=u#{whTN z8%cI-UETIY!!>n69m0*bC6aM<=;BMC2(6w@1lb83v1%%Er7fFy;~GS6b3yXI(Pww^ zr4Qo~T=KpX9q6b(e7SE_f`js^3j~OYCZ09xl zX=#((7wU(I_mLVIeZg`YBt+c9fq(>-vh2!q-ocxn(Udg+IFwG7%@n`uQz&3I7ayGg zw$pE&`F8t_Ubdp1d%kZiN~UG&nkz$?>`*f&|0Nz_GGU25Q}c01L30d#r2}n>gu>$7 z=(1(+33A3{X%K@SU~$`Qr>wgTskv6^9q;G4U?usmjj@zvDwEm9tXI8eXSNuGO&Asp zj~9s6znp-njSZISh|ea86X7Nc*|-Y(Xe}zbsCy-Jl+TxCobc8TVjCas}Ul4p$6o|jEcU-Zun0xii za;t^+E zv(GeG4D|_u4@fMM5SCOyO`VJc*R(s>)V^7@6--#UqiT5K&6+3er&9*hT=-{R9h(=b zGJ0~Wo`3b^i}x}{RDrD1%7JX*m-Z(SBh6e)dr~Riap^^1V@_^?B}e*5_OZ z?>0z|PZC-rSx`DbF0B0QWZgXw(!s=O08fRuR0IWhu;DZ){%C!4#}1@i`5#95{7*CA{_8p|ASfQF zIdcXuJ42n`&jn#6`!_t#{Q5WhZwHX1f{m!0@RNjAezH3*9b2eXmYuPG1lm?c1FW140wp53RN?HHCl zju)7Dn|;82Ps}nDJ`Gwp0+Qi@Fg!>t5gona`vBsjWbHMgM|Z6d+-}rzL8RPeq(G`N zEm=7xLRgJ|0$Z+&Kw^vE2#AlEeh388VEf+=OuKQarkqpWVVoHE_jixiC2@ zXaTYN4S+rm^+;d7$R_R=-b(zjU`qPwZAwZ90|ZGc2n=WSEfm}}Vu|sfN!FGx2aauS zxz{zxdo`PiMg*+$FvD)jO&zFP!h51{U`|-HP&{Bk5r}<)`8=QR8ca#HafwSaxK~~L zuBW)a8ic|_893BMyuiqULzV97>}t`WQMlIHdC5={qR#yq-~i&U6Fc=AASQvSj%5P*l?Zp4FcVph10kHimCyvknp zsQ>d3bndOnx>Ss%f}^;|xDJ6KF4|=;R{f}q^-TGwN8)=t_6Y?UM@0nkAVT;PV$^eD z(;%_`PxzeCK<-r(tw(skfDg`blf-Ssj^agW^hiFP*vS7gB8S zJNlx1lWnrMfF_^CI!k1ET2hnoJ00uZi+@oKd!J(8x?yuTKvQ*t zBo1UjLe@|{AL@&gmt)Xhn}u~$Ha^?<_BOsg+d_R%BgF+t;UO6Ss+R3;lu2CP;k&3x zANKueO1d4=H-f_O*i&R$>AU5Dr+%e8;2Cm1Ff2m8RWK`Z263qT}+4($3 zz7(_2?)+1a#1?qL$Zi z2S=D(^lmX}T;p2YXfRs|t+VS8{LaBH)o?ahnS1%rLN`?JioirECN(p;OOg4`(dTU_ zc7_kexHZ4r^Pe45Jcp7$&4-uj^K%Rnx_~4CmD9z7=F%G`{co;1B@=hjJ^GbQCqt#lD z;IpWkA-*hOHXzOer*lw-#|6f4lqD)wII&~HvD0=5yTQSD#{*7R;-gsz3$m)$p#xLA ztB1SYT9vPLxSKBPi#EU3{^HhMZpwlJ7n0d>#a8IF4$PV0`t@J=hu2E>zQw+C!$xt{ zkjw%hJoF^Btu;a5l1JA>sTSDsnIS!Ec?n35`FA4h~@fw?|M}rtz^g=RGN&_fw?rQdD1Fa7(oeh0*W4 zUb0J)k))oz+dF$#98E=VVfm%r1DxJvw_K|)BE`NoBHQJkrm^c30VOI(@NJY_JWK$t z2S=la`OZ@)%A@?AWkAvIp@hO)+P>TB5@y3)x6T!odf(-v&0b^b-iv58-)p>L@ID?b z|2tlY11JG-*-Yh5;ErBj>;#b@fDWChxsw&7J{c{Dv$6U|8b0wnv%3lsadwXus1kdl zsW`Lo;%v!Bt627H%t0bB@~qWI7B1_k+DW=GxD$_l)y(}9^nh`)=gQU?d|atyx+_v0lBoqDF@Z>XD^zTtB- zYDRxa-aKD>UkV58C!spHBX@C)3%I!0@=?jhfmqjKFBUgmR(A|7@;|_RoyfKm@TZNFnNE z^8&D!J)*uW>~HpP&~3>34!8R~_bu1)BW`fT=GbQ8eH0hu4IpcXkG@UV760m$qsv^> znf#}Lt#t!QIOgxD!V1=fwaTssIvqH&V;UOLH}v|@ee&^|l%qxxA4bjA0Y5zQJXKlv zisKsKWqKfE%j+>e+qj#3s%d->!H3XrsOs1E^CzZNW$v0xSZJQSC-!0Xp!sl<8t4cw z=@L8P;WVCy^s*V9Ybi9~C$vsYgPb0oKgdDU{}Pvr5NH!Z4^5BjpAregl)-%oCXR)ggU^=DU%nl(Zuw?ph!0lm7sEC`v z-2(yx$IXk$hnK?sf?_!XNF~D3&f3z&-+hNYpT-Tr0B+~v80-{J*T8CwdWw4>yldh3 zoqczPs3q_nW?C$UxcaD{*UMUGwu+Lvy*B3=vfq^`7*svl0fWX`BA=Q_N7 z+UPWhZJNbAAwh7blT;<84c1A2-o zu?7s9#vaa18C=I7hte@?J46&fWkBD8tSE1q;ujImpL<95%pAC;dEq~$KYGalZ@KS_ z_2Rw1n1#6;)hN6aQR_4KxDU%>Ua62bn4hIgLMwH?H z6W5%j|LwOa?os~5<-F)yT@W0{_OaSVSnmkP&3z@K5s$d&r8kKwXVZFL`uC%95;i*x361e295&0Z-EaFB$ca*^k`Bh6`V9u8vgki;DTd0u=&YoNbCcIrs92u9-t3)6C;{+`tJ&r*1>M=2tmf{Xy6RE1D3 zXXMV~q?@$A#cJ=-n0axaX7_Y(^o<$1l;AgZ{iXmc3ufdZpO^>NoLg`N?ht z3RJp7s&-jO9we-&hzzqtI(|Z`YNIF@4QVbrm*q6iSJ>R<2n+JuJmMYQ@q4tLPxHq*<%CyFxTC zL0HYTDFl@CrjdrkV*EN4J5#(a`*h>MBB^Mpn*~zW6TW`OG>@ljI*nfVue`-|Fc+g> zTkF%2ij#?S+FzdQ}*rrs;x#sJ$ zS+$vdmNUJBLLN{!1$F-7b$OW_7+-QYOZC9&=&NO`dgXSxbY7X--q&n0(Gn(c6-CD? zrCaJ;>X}8CI~XkITye8ix6wPADWxjojOGJ$xDRKwzulv3b(1Ki#LJdU*~Rubao4C&(*W#ksIWj{BxUbdg`%d2O2}!+G@fOYaiYYRpC1o zs`oP@;fjS$Rf6ilsCI{0+oZ>e8`r_h&AMLhc89sBYxtRv`|eIbS8RT*)Lf~FZ#z0L z3<+Qj2|0Vmyua4NpDh`E^?haTI!NGZxL0V^2Y0Z5EN%d6KV0D2$?z*=Dcx@07?sro z+VEh(!RaW)g9(>hC1c+Uf0x;r0F~C2yOgUP4f{0mv{(3yTZoA3=*@X??QE&hZpWsE z(OW6ULF{2j&U*0TwnxJHh~)mWZ#-U^?Ne(${$fU`CCg6rCkJgp$i{A4lwDU$j&5o@ zPq{f0T^H&YL7~IExkFY-GGD$~6ogGAYstPXva2tz3OlA&SGDj!^xz96$({4P>}Qw@ zC&snI`X4z zz;d4Bq4Ux(PhPSXqyAvAuR^P=^h^KQ$%!h(6KOV> z8K~O4m4F}1LFxSi$yVx*i_0yKvL_x;A#MQD(|SWZI{Lzi#o))J+hsb*xaWg%J za?L`OEJ#-bC+ZPoDfvk`gW=;rwIh;)NEo_7k++eBw4QGv%YEF&TOdJH3^EdA#U&q` zc+!}CNx)}r!T$N1un~>#Wop=QDp-~$i4{#G7=0$e3xQF8=&HrJMV8^eo5dA#Lkg_` z36YZwNH4Sp`X`*%dMBcs`q?h?+G>-+;Yg8&bUX-AO1*h}10W^xRQIfdBrUDWo<}%m zzLi8tzke<08}hhl?=~1Ox@;}?*xlpS{i4w?H^vOEJ+3*pBlTdnGfEZg;li}yL1;G| z7y(cLEQfj^SlAwzql&a}Z2l~s7^95s$QIe*at8?))M7wt&}y`}zg9q#s* zGbW?MsF2;-iQpnPFVu-FEm6nNWqdAhmIc8`AV((^B2~f~T;F;n!eB7_Q5KjXuijyI zuyr|m4}}5}Y6JGn;gS9*4(+QkPxMOmbP1u7f%b2KQqI%eV(2V>yq&|MyRck;u-r3_ z4HjU#G}_}qd%1MA<3W4;WP_z&7>${Nm8-Kl#T0%l*qQjn_k;8Rh+;JjFZucW;jT97 z0og^p&T~~IF)ji2&QaiYYN1RAS#Ega&`#jO0QUY}y8L?pV(70Udh8q(U5tbssGbo@ zMk0yddYBg59mh_s4=H@+mghxDgA{O9Li~*@2lhw`c}%q_XP~BLaPP;^DinBs>8RoS zGWN~grpqQK_d7gJlrdDieB2!@&!Hm5rvAcnrH~3gBd%rqm?=5U{;>z_BN!#C0wqZf=3T`5vrp^mnJIb64(xR~6T2OV z(is$=1ehjkWhGBOl81ldmkwV>kEIb{XM(?qjH_u34NbotHg zA%S^bUO)^)?t+Ki<6_-_FEpd!bJ&i9-?_Frrfp!C1$qH!{@lGUnkoGtO?w9U?aD~G zc1an@T51`^Nr%YsId;*XmW#(PLjvw;B8<}^#dZi!`IXT47VT?-Diu$k{qj+^TwG_1 z+y~)``A>n_`LLW9uqpZAZ*Nt2RA@X80Fgjy@nuX`9$0Fgcg*aaqF_?bew9JX-6}KT z`lZZ$ducz3twqllci^vv%X$N|+wRyxeNDnURb57o^ zB<+fKX2Rh~Az6`~Xg&fCP=(#V*Ld5u8qm)uUudw@-1?}&Wy_)$eyh?8ZW)HhkywL) zKk`3G*AM>cICh(U{@Ij4y7{_dN!B^2Ao%Cc$caXVg*BMm6mdu^AX(wI3NC#hA@jbU zzl#Lnxb!-nX{hH^a4k(vN+N|}qnR&+`9~~S21-rWKu5k#^?yvY`$EH5lw=L=b`8c2 zrFEpz2Y&BRu_t>WeZ`(Znn#P8ysW#yQV4M`^Njuwljl6pQN@aPq{=$eljGL?j2t?_xoINi>M#D z-Jpj;toe$EtE+$|0dYJu!i^b6VkQF24M^Vmo3KS3BM8T!P=$`;;k|6+hyAs8aEKHt zGhK9bJdqBU#tXeXgn3d;Gbi1AL=iZKBQ@MF0e{6n zL(V|~Ks=ouT6*_Y8%ZF<^w>7tjguR=4eR=Br6tP1KrOq2;1N9nDC@kh(dM^j5j*rI z#A3xg&{1X*647x1?iUZb^Tm=alHK>N*qPd~tlK4JX{y>>@%{!CO3F5rgrEBjf2Yi} zzslXe*%!!%X$!SDeI2Cmtn-W*`!?XZIta+aE`7giSv|~5w)xV{eMtmn9L_X6o^fxs z`R`V*L5+c;dyx{Gz9h_6GP8Q9c<=?$+PI7=$N`c}XraLFf2oh}>4@m-NVJDp@pA+` z`kdxQe{EY)dU7f0j93bye@h^f%M?!PKQ)fnrtcfOe2a635lMxI@L@K*Y++69T5fg4@fj!BjBp?L@dcPKza$a| zcVW@hOF@F;&3lZfa|_gs2ta5XWCG;SL@k&&hmj%c!1!_bqa*|`n?gdQQmu>T?Aw>e zQIS~xG^J<3?Cj;Gae+!qQ-)$NF#tyNk6XQnDl8x1@(&7D)U^7jZfiNm=Qd% z2j+`}`B9t_kj(gP#s>|AyC^e`%J3?MsEvcf0jewqV#CXE;GvBdAU2$9_SD*$8OPZe zY(qL4kOb7Xb4#hi_R#5tzK%^a!kGeHGJ~H-!M%gd-aLBf*gDJ=53dH@i{vwsILr(m zW(H0>rB5Syn-Nvb2q!VHPEIcD+!H-hg>x=xc{fM%Nnxy912+iS9>$q&3#JMzap4K1 zrqi59BMXg!lIjBM*`;c#Z(m8utX!~4!YZZQ*xnp_ET++`HS2j_T$)UxF;|FGa*;wY_12fE*yYIl)`nN z!xd#v8Nmh_yWPPaMmPmNVmjl2hj093IXtnCxXLgrh1hK8_!F3H^Wa6F?yxZ6-n@LbSYHvsNS5ZQ+rON?haXD|h8n5hJ2 zbOii3z?fO{I@$(5(r4uV#6AfR*Ds|XeaH=CpVu`(t;KUf4ix^Wr0ylcDDSK7Pc5*{ zdVw(AI}TJR&zhn20$x@Pzvipjz755yv-5n%!+RKUZV1H(WvN7FECs&N409=h2Bqss zJUJpR*68I1F^h+~vSGKcGUAL7vpNfc+1o4`5@PYO1n;yYVPy#y1B%4xY;z+bKRq2Y4I+RN#Q~5 za5*~yxlSxt5J@8CJbc1fHu?o4d_DIT1{21Uj_!JPr)YFj1z`g~Y^8ktaEzVUu8Slw z^eMvg8n=A{EPcW8Y{yb~3V^tC*4Clud0w4o;sV@k0XiWkdM!xg9z`>a!i*xqtn7t< zYOtTRVZz2GuWc}5(is#^t~(1#@sZn9aa-^5|2+b?l!Ta3a$d^8!>Soi+?i>tUaJEy zs}>qVUxO@r;8~M_OI-nGl1me>16H;J_^zJ>sz?3{>ny?A6J^6nDqX9_V}hAB9KV0+nclF1T1S7!D}{LK<<{% zk3qoFKK*ofGW%|r-;8$qd@P6ldIP4~dO__?R|980wmB-%ouPvxBABbHE*zSvo zSa}_#8Q{qzi_Ziv>@M9<7hWN-lH()^b3rnS??3T*`6Q8*OWZb>5P-Rk;yD6-dRE2I zDJst1Rxkn*Mq!e}OfSO_;oXaoxLzORnpXcbWij;n=hqPc<7CV8P-+?R>Y)akx5j_r zc9Ia|bx2hAo8D5mpRIYYd8luri9U9NyV@AAaL&Nmwa8s{8ecGI_O^p<`b{ zBLPPALIG-c>XYz9zUm>zQAl8HW7HJsXC6Gzqb-%>^LlqJ&Y*{}EUsR#-rq?&8|I!A z4<{}_Q!U^L>4*)1hi`88r`jVD_;4W@JSN>|GkNB>*tDCk^%SG?h|Z_w+YqO^VpAC3lLssuDD`RY*E99Ij=022?xpClJyU-R1cvFbNl5Z zw%gbN)Uu34mTBG1<5`7}ZK_cOJne}KO8(G?cGAbGHBNr6ml1=)%?&~_dbce;_%h)4 zat+VIZnqr!F>jArgF0iQ)s)^7p$8+UW7-`Ms>vVmcWF`Mw-zS@uL>YOv_>S0H$p$H zgyCjje>=h>7$`eX>QxgclI&sOk-R{DYZZQG`=bWE(O#} zbLSN`EdDVP)+IMC-2HHOZ70!(QD@T^#$_CuJ8%nS9yV>E=$h-m$xW{I_IVSZxD6*G zA*R(2{6B~MZmk4;FB-i4CH~JnwCvPb$_;ltk>{n8AEn#1GmbJ}i=OH8J9QXo;@wt;Lw}$3Dnh2SV=jmt4o6 z3C3?N0wpIsFx|>_i8`kl&1^`$N5gPZz5l`86HdzTyEq^nWZ!ekP9xU;+GmF&%!pE0 zWL4@u97GGb7DKtSGmq-NIRBKgmAk*bh@g1*Ly}CGecEE1Xn3hgT2)Fi39gw=&q&M3 zweJfee9h8g9)5ovU1|cvXFD!1QpSTf+Y@edS~*<&9J`*Y~8Tf~F@{w$Sb=#Vm--k!{5GFszoLod$7Y(qnEh~%~*`%UR`$vLp>F#_Uo=zW^>xh zcOqE@s)(H`BCc)3q|DqF+xB|M4>ztvF5`ENdrIp>aqWV;}zeym|+MFXA^?eDaX zjYmqdpmFwyMDJ6Z^TLC;O^D5Mj-pauQi^ocLpLjWb z{?LC@;E8IT@W)ppw^XNUjkNj091tA@XsX8g+I{pjDsbFSgB*dQ&JsLESf5vHoX%hI zzICifN5x($$$8*_n8cJH@z^*!=tAl>S+kRW|IFwp#|dxvH)E-Z_V-7{8tc$44)3ccB-%B9|WYUit6(#lEyTtDWCoM!z(C7xM)sPqV(^pnhXv<>Bbg zLm#IiL#M{y8@KgOo&)+qG?cL>_Nea(Hkg{56LOK}D~p*@b@m^XxNRbeL$-aCsR#Eqyl z*`ey2rAC;)G2PafdUEH?pG9d-Eaj3X-{|bYSghU+T*aitR-32u_{V8-iP6l55r5)@ z=%TaHHRZdq#xIaMw)e}Z%{tG=?LD3K^&4Mom~3vEn>k5k0bG!s9@)iY{BKOp^7S)D zQ%4I8Uw&GZ#ttl-Tsv}_Xx*+ndr0?m%B-{AtL9mkj^)nWX2XYO1!$`o!_0=nw(sx-=dJd9>%*8dFypom~i_z`S;DP1F%9`H5bNbftb$%yXTV(q2z zsKZi)nRoXv4NHa4;pk>*$3bt?6`_(?H)ZL`h0(Oj%jk#$tF}M3o*35%F$^~?h5i-f z+C%NRm3qy4-@Ea^Pe!uQyYFtru{q>pV<`}Tqcb6kaOS+_Sg7EUP#>n@-Ega%ye66D zpdiqdGE7|c{{{}3#!z8Qq_wj21kU&G#PRD27Hcx=lA~g*bs-nLkc8uNIgz7{#cF%B z^8ZOq!X1;S5XoinH*Sb4a0mOW7BzD5oymLSb4H%H3Cew;mZ0v0OFLocHR-wP)ehcg z?3D~Vt!cbn`f2rXciSA}Ko(i3grLxK*tQt)M`iDU3A zNSLJj2+JW|Nvv}{7pT+57`I!O&s4q%*Kq?0#sC1u#|k<-aG8b;D_AbXi9E>IpG0#b z_u~X$`?no)`fo~%MT|-~adX3KKgqnIGEKfCi)b3FQm?6_M8Pgst2m}|8tR`y^N9;|5 zp9w@(HbMY^By^(#a}j*_;v=fJV~BNOMCIfq?0LCck_{-uXN?kroTyKI9k_@SXRqj& zk?v^Vs1W2p#pUC|mNSDV{G4fuk>wcL*n817ylvEGV1i&@7_hYwY_3voesa|FS^>E+uShFP0l zTKW<0486b6CqpTW*r&ZX;Q9~6j>234fCE6cco!EE5pNi`hv+!E%e91ki}f9Q4zaT_ zC-FHSY|H$G4$`IjXI+h_vu~v|`-~7bE`YIIh*jIFERS!i{ls_mMw`U-RU>9yS%QF8 zTO{&EM1beN0)uz4oVrL=rpUj13S@Xi)1u|6ZhZ$iVkS=Fq1!m&-qYKO@pRE^yc<pIVamPf+OyY` zuTFb~i&LhR2#zj9Vq^BjM2gAm`1Ve>E_6BDg55NJeQ4aMZ$QAkHWMAgrwf?}<%ixj zk*>NgcxbNhxY$V&7{tp~zN&pLuEumBS3Ri1_el6B?WKE<7^$5_e#Ixa005EvUlF-I zJm#d_I|8%y_YJgWItfy-E>(1J-XxxHCB^}A<)``Z^g|CC`T@93ZGzIDag*$rbE**s zxF7@oz|L0Nnn>QTQU32aPt3AM`jTO=`_t%|>pAJ$-VkKLju>EtgPRNHCBA|4weUD$75+{M@2{=vEllH~K;mLrtCq048ikSXLj; zWlU&D>cx7SVdgvCV*84nbJ?HU)65YO)o|~pipBjzh{VBl63Pk(I#vx?cufC&w5K88 zb2>nnzB^_9yeZFp^M%B~_|LrVf!lw#v-tW$Bv{tt>^%S%63k+lJouYF?C|2G$Gv|~ z!mkEw2H%xS;Qb2R&w&d5IV`jkRP;1r86wCgLFLy0?R|fSRL>q0YsA^;RB9uzGBhE= zp^*dI^8CMbLC+`ee!#dUlOO;W-Uia`B)|VT{q>UU(9!zu9iHDTeXY}nOo-qw$uGn> z5N#(Kat+YI@4=p@q0>ny7WH>5ph*~($aYVR7}BVv5%^%k39>=ffDA8N(FkncJjg6l2;xO#HAt@+^1zw>HH24m7(X1TI282KcmeztL{)7gn|uZD z*0069AiDN+MK3O#O+|IG5jlXasEhcqVq+Du8rMp*nr=2s*UHM4DwygP2yHg&uEs<`uYhlr53EOx7E=`ZFJx2S|F+ zP1*(mFAbPDA&6_#-wpM@GpMdFTwimnbvmuE#X}}p9>lC{x$SIaCo4iBO@pWuN^x@J zV2}1%^Nkd#_FU1U0FcF%G$ViAu#=c%6OIXV)-~;aA^AP_qBUVyG~U1bK9|@>+EUzs z5R8WnjmR>563Rz*Pi?N2L5>cWwy(#^kTYcBHl&*a)>(O>QcctSWmU$(nO_<{y1r!N zoM#{`hiDtn<&4^AxEqHB!A>Yj)T<2ElGXn_fwKTZrTV8&RwxM~CNX3U9!QV}Hu0N& zPZcqop#9yTne_~rc9Kmc2PGE<yhrBQK+&KqX2LBlxTc?!CvO@Kj4Tka#UMEzKw2q0O}EcVZDw_37PI^I~(!`)wwhR zfoz7`yZaQGYS1ksnrbyo{VF=ox`ls#G4E(-WoH3|z(pA0O`WETSUY=-%Ug`Y6ox|s z)xDwJ3xnXkK!^qxTmu-eoh#7imn-Se1H%E|Lt(G2D0|*$4G)?2K+J0C(rwvtP(}M{ zu;wfj-G`&5ukB}Au^q`< zqhT(EaM_wsfI=1Zsxj%6PoH0ax3nC!l^v`m?@I^rPLRH&P(eK;gFjUis_IvQBh39# zap$0V8*N{Vlwu({{w~=pohB_>rkq1l_t`^)4(YDL=)ZPE+1V0SAFY=Yyte$?Tn|5F zSjc~GP&RFBHBPremPR19t&y@+!H_3Di*Ie7KQt4Tc*Y!Nw; z*klM@uf)zO#&iOpa8|rGowdo@JsLZw8;AeYdX`yx*QCGY)pY3o#oW(w21BFjFP^ zJ+MFpS|#T{(pNu=W4T#d86=miV)pkP4=_RQSRFbSf!JLhoj|6%qn04$7c+I8muV{N zyXm6E3x}HNkyUt?l=GrnOZOXBUpegY)+wS1)}w~8rv0jf)E9;Joz}34n3qrIwv=xI z>sOkJ!;Cc`-12=IrI#O;S*cYPYH=Wyc|&^1WUZ`0&2{x&($K4f%VL=ihTE$VP^z1g zl_Bw=5$)=%V~%1Z4U|JgCSSVGur$qS{JQYY^>N+9XM}~@vKsbarS0s2L5L9mG3y-C zwQtt?s(u<7c*sd@WRE{wg+wzRG+;xXp3$z0-?qA(`VP!N-H;dTs7PLb?6|%?R&m~3k`@?T0y#pNf%BtA1l;NQE_w6T4 zaCGTD5;PkY?XlecTCgg0P-Pgb$0p;yw3%s~FyxH*=a5aH?}lAw zR0jcN!aHbh`}box%Osw`0$8Gly9Y`>S|q#(T~)tI`}FHXQ8`%M+Dd~*JCHooJvh`o z3Ng#^kIsRZlztqBbAcYNYV!kkjThhL`PR?(zS0~bO2V}#*VQ{|zuG^wxkMM$g9&|u z2MFPM$#hd_<6j2HRIg#|Y`aOb?KrR>e4RgAn`_)Bce`WQ^@i1cH_oTQs|#WA?|P1z z#miyC|%o{yqMp#y)P8TWCF`RgJB5W=S~G?orLcG{RUq+I<)2|cJ} z23DGt-|xg%Iu!luaXo>Qs7Zhr4r5J3RSP$CwBoirw!fr})@w`XYAfjK{P?K!s;$%I z{XSes+|;0k^$nfj9bLnCh~d*M>-3vG40oO914O|s?UF4eA1k$mh_!!L)@~L^`b3G(TeW_OVbgkoecZuQ;o(9nWUYN)GZ zy6DjUQY*#h19H0~a(y5LycHhz-BDThg2gxAD`0Jnp=56A*#`z8kWqa!xpSdAHm-1d zV^AacTilSP?6@Uf^w!?$?xR06H9Eii5*{MTl7H!mCkHnqKTNIlGfaK;BlOG?aSg1l zHz>D0Ajh$kfoFd-xrFJL2%}{qfy| zq`_ltq}!f*A^FH-Y8Kk$6e-~oifhSIFq|ABR?%bti%z*~{4~Q0RHKwvGueT2)~|cB zm)Bv4b|xcg%q4|WWC4FA)s({v|J-ZERd;V!KQrYNZ}&CWDyq5NE)1CzD<=0B;c)_1kEqbyqtFuBW?QBvv+hj%4VN zI@V#VZJR0#z(az8?V9l1f&qJ-pg0231pBhK;=AR zx}dZ7{&3>Q)x=MajM4%Ii_oUb!ogfI4u7{&Ux=0k8iW7D`fsTsaapXppvLK) z{gW@}aA)FNw=>N0X%kFN2f$)~Utn(^ysZaqGw@#Xu1r;qofp^ddR@q|O z{j|ugpFzte@~2eJqfMDkd>naMIiTHG)uE;1_qs7k!5!~?fCg*&|qy2Xe=f=|)o4 zH$yKK4ALE6WK~`9Eb{_FMcacf7`9yzP(2GP3HQmL%2>Erd1HQ(U;>F^ZFXEGOnT>vQ|qBPT_v?eSBoNOAqhmA$gR6FvraM68cjs$E&ieHm>bDiIS| zFiIYCCmVNsFYj&H6sA0QyO255uViBS@8M!Vr{=W5-ckm|EL z>kAQ6OnbDxZ(O)J5dJasYRB%%zIw%h;F8lo`;dBlIrkrjknpN0;{p5?{+eYDp-QNf z|B%-W8W6duF;emASXyqGBjE;P7}LR#^tTk`GuE`qa7P@g<{$K;i2Hh1A|(9d*xZ+&X@MS^`2L`!ca;H;6qTBIXnbg z8qhT*Xkzn27ooADS-UYxaJFTnmJn-2oW+7YC`{)T@j)7mMVGAj>sh-+ePxUp#j1Q{jWVe(5m6UPm48N!W@(%9s6+ z=1@f88-?^A!mDMY($_l=1tj3;pzMwT0_arK7gArY$aA#qjc1wxP(yJ5(4s#2x0 zpP853O&^Nijwv7hAvz{uBsxz|d99w$<&6O}i=(d$R8>le8sOg5AlqlgpD}0AebI1V zQ$~h<;HLwh52;Zt)6=dn4aNJc!{Vm$|F;}Q6aWBh0QLX?t{j8I_y3V&n1bd@W(?OlfY+0lM0M=3pjW+`7^fs!o#kc8E-&CJ$^ zrSwlRLg!E)PR;(@SiJJ;joh=umZe3GtW%$f8vw3WOjlTbbyJJL0L%UAydsBB6Lvf% z^`hv(An*cWEeXdm6%)S-KxKW% zQv$Y1=6B0fiM_hx$0lu6ON_p%xlfuRMQ7i{?lXNB^YM}~WFQ1dz=Jq!ygim_Yk}08 z)=V8gn&>+;C7ZI=;i6VMnvxwb<@GDqaPF39{&CK-t+VGoIo635HoPzk;JD#cPY95B z#&tfXS>)k9`RcsV9S^>1Z5>WfpF2rhcnrsmnkc=}dq+z}<^Iqt%|G$)V5ZTO_<}3P z03*Zj-0Myx9wea2PEpry;rN_0`Obyf^xwIqB99D&q}3L`8jFCF>8B%I17QOeXj9mq zUmxn;KD5|qi}<)Z2~fOPWvj{fdd*QU#aanz^!vS))A8-K>dE83<~JOhdgrw%k5V)x zPoD1tfRywWNUoP2|9oG)Viq!IA$-sSY3`<5>K`uvVTH<+G%R>4UX#;eLnQi_`CRfr`W$5frX2O^;z9}JD*vJ(ftmnM&Yr~R7LU+^t_VJ0~? zMO8QwyQ_9=iu~@C!3J!3!Vo;z+E@>k_#XMO8E);18dwA8$JmQCb+=MG7I68gIvNFs$L}SL)(h?@8H-0x?`ZhYR?Sn)lO8GQ$6o`-?^`>$)}8u7j0)84cV~gJKrgP zo4$XRvG}lMy4@ypN`HPH{7N?CyO-^uN~~31!d6c3{Ibf|(qV(R_TFKcp|Hhlf+Yg4 zDhpnc_~2|~0$w$)Yne<0@0P;MR z?1;Wi07CTUffyQdNR_yizv`GOS=BOz`mosf+N3$mYJBO$Ec-@4u!Zy{*`^C(LsLKY z%E!Y&vTLK?)_P*ehuwMRU&B^0m$E`7+WM&Za%1bW%@PyjVZ9#hl6K|X_*lzY*>i>% zF^2)+UU!JzKd-!Zi#`FF?>^wSlhN_BKC-`ID_Th>#v`W&r8~QZ>G!JmjwU$T*U{6D zP?B@}+PXLr$0L?xHEQw`U~al+N$wK^ zqDSw~@%f#CBI1;kaQ$UkV~2|Dhcb=k%+d494vpmAIkU?wm?Pt-IPZZqZgvYb+a}Z) z73pfXP=$&rwP^UVNRi#5$YNS@V|Faa&~pCQ6cTb|8;gix$Hi zUeRVl!jRc*4MYILuO)ahbNV{uHfaJR``wmH$4)JT;$o$CUqYHpHj%*&AcE?0kb9ZL!z)~sEc1~GwQkTCy=@7(oSbzTY`2#9?ctiBW^k6oQ6JrP zBDHL-Kuj*n`SwqujS)9=6o^;Sog!26?(`#~&iY7B;;l7{xnp?%0~|t3mBFnZJHO*C z9#Sx@`&a=LHGhg|4{yQc(%#lXd?fJy*%;o47K{3@^n6=Q%$T{A8)Uo0k#KQQ)1jFo zyrbaOj{L)7Sq}Y3hh$VZ1`Oy13yDwp7OmizWk%N6Bbx#M4(W%=zwqoNuB0JCAu{G` z%X7_tg0h>q5raBlt{+B8ypL_Al>kJzwZ=%e#0>%+`~XUW0A^y?kcW4{BcJg$mDMAT zPH88ayA8WC%$U&$K0LE!b}w(|IFz?-o}Sc;Pjw!2{&O^}KP2>%qGyc1B^1G3W+2u_ ziQ)x{x{H}^^LNDt)z0co7>KEUMg^ps#O$O2K1uNV8m&FFFOxD1X=+b>H7!rk3hrl9 zW=@EA)pp29IJ`x&hOi3Cww3jWJfUl!M(7;V8BD`IKlRyWyv6>AW>6 zHZoBMgSR=jlD5RL*UtHp;_W1ormy*L_Zme}-x)9(LQdwtcpxXxfQLrVAr3~0Lf?va z&2sc~n*S-88%$nvZtnTnlUo7Z%zN5LJcWvcU6l2{6Lb7C5FK5)^tKNlr|HoD*R4oV zxQY!{EoR(oj>avkt{r>LgBpG6anIo1Kh#$V{TeC3b|@&C?mr`xgQQ21_@*}fcN z@Ss!Z$nI0-mzOv04N89~gAa*Xg-w$p1G#bx%#M;o7(kZ}6P`~LRWp=Olf7SWD>g?K!6z~0!VPAhI@s1yVRl@`n`?R49?ZsV|etQN2kSPq}jPE*sFm~xhH>Gb@_ZQ z{b9g$SzBcVZzu^5y-4PP<0*}t&*T9EfC_+*i@Yy1yKmCeLp#;&zNE5+&92#M*uy~F z=>7E_WC%24DIh(q6FEbGldxVvVZ2(-z@C7#BkmM#)=(3}H-hyXK4HWmr(WB#;4wF7 zYPnYNQ@aYMVZXyuOUh~#7r&3o_`!~Qhex&$z-G=M6=qbAL7I&_5ZMfbJM(1Gg66 zg-i_@HVwUtw&u(OOMUoT*l4{&>iP=)-%Dkr%Z&NLh2?kARf;#vf952H-2i4HxzyPj zEtz*L?jiN!DyHx?69QnyFYchF5bs;80>mwVjPDzD~72s}Qny2g| z$BG;qxf=*t!I0=>Ai$rI1izaM%j?`@LV4z0w99#9YOi#fnJ9a2`PYfM8q^Z3%wE9=YuqR9JuA3e!g zx6hOy?50*o$OC)UD|*K&_*p#h%wtEVu8dwoau{Vi1*oqy^-1;epcBI9EYZKCZk=oZ zs5L`wG6g%r^oMzF&jZV|+-`qjAL(qY*c`jf4VLm_dC6G5zuxdpj1Z3^#?TV8*O>X7 zSd^}N>o4O>D>r&@1Gvx#p|SYHDTq^#k*KZ$P0^}034(BWh1iSRy}Lky4qxtLxb_zM z6&pR~fl<}C{??qjg~QAQqAy0D#hzCXWCOieF#Rkz-AA*o<<4w|%JOctP+Y}{lQmq) zOqU^u=ONa|6>gt4vCR$NkDZhCQiry2Db(6o47RvH7TVsmr0P5(}a&9^iKN}_+z zP!}5^5PIXcr?>f?L5X-+)Dzcn{xf9~59jfi5US=urty@A)i;ha3i+oQBLx92D^3tJ z4Z~$tTpGWfk8O^v0LVXHe_GMK02&pDcqxe}o_kcbYh9;-(XO~`5pN$gsJn+TyxQ2h ztN@I{z^fTy{Y=EGvyu|Fjix6vKH!m2m^@2jcGqZ?wi`bu%$b8hj4&V2mqlmk_3y|} zGV6r)*H5PmN>YW;AIW#T82#7BK2%%8?AMTR%XL-qXZ&bZ*}1P7d@@{eWw!^(1P0+@?&mOjClSuCYe3;hv^a}|oer?0Ia2x52V-aQ?WCSQ5@_SluSr=R(HRr7pF;XJ{xuiI`sEpQG1F+?tF zI*jDdPo(dob$+31Pb)bTr0#6X{9~cqviqqm`Nz2yf*V>tFL>(eq{jk4C`*CvE@xq1I%xR zx#gDTYy5~!0^m4T7vb#9kS|?ejBLl3<_eD<>Op1!05bAjC|sJ~8jzdrFJz-@!wjSO z2m9p_N&63&w0gq_gP?eI|1PJi2V<iCNG}^r}?TE z!<)g00Q?;`x}>@*@yhT&qfWzwWQl9)gBddB3S^!|w3Oki*-F5v?3!b-h_?IPo+|gUo^ut(jkm^e zsNctxkBCSx0bIca&=>Bnb9F+rf55HWsvE`A{!EGvkY?4%(g4T8q}2rYyOl8_M-Z?B zbk!_|f51Cs2KR7r)(I(cI^^-0{}hL(r-wIRdm_}vDGPaCe`$g zTPl4_9UZvK?!B zGI<4FDTB5Ic@z-E{^Ps~lO{Q{xlaOj@i@CL3mAddLJ}510`k}VQV)MYsn&XH+(dn* z>Fw$uC)gl9dRrf73rZ zthSIL3!=!!2xi=uXHg{iccE`91j#%hH04SRe>F=`exr~lypm*O&$~FqVSZdV{bp4B z)9FQk9uq>w@EzF-rKOy6(MRfUBPNe%2a-V5VwAU_+}`d@`I2Ga0^PctH_-8t}q z%2;(d26Pxxai#mYqm?X5L=Y1v3$!Sp#a~i%>}ZDfhJA6*gP&=7g#Ck3FSs% zM$V6OnvqNZ2pqQ5I|k&#gUW?0x~=r*4lmwF7{2+{84T>RKDBDJRuC&IaOW>jmIY8_ zgFNX1S255Viz10(a!Hp{N))Er*c~$jnD@UmAf}hZN~>(fhy`O%@Bu&3jk~5B=&1@> z7LXqURFen$MX6mX^tD?FzYG+muwZJ*UV~(~T=S*`9U#sE$J6D?Y45=1lm+y9mTlN{*fW1hT$V4OVIH%=*0;pk#jp-}VahQz@_x3)h zmOT*SyW80zym$8*h9p-ReGDMDBGTjpOCjv!VD`tuwfe#k8f)xt96O3DR#45n1+-`>GF@o`rrIx~ao;?;6LlmtVJ1o#dVs{NHkn#D8GP zwt8MTUjjg|W^}5?t{f6~%>4z|fYCw(M*6?BOh=)5&vKU^T$eD&CVJ@4Fe=M$p1&!2xNhHB(wlND?2S`Clj{#r556a`3`*FC-wA!^spjc$Gd$p>w%yOmZAss*jw@iC2n zAANe#XiPf#Y}dEi(%nZ{q81%yk%QcoU z;v@iswmP=XEJ{iMQ_OwK!>^QgwyzIYBsrf9sEz$xP_LEnv#Q0>;M0Ms_EG&^-=fvv z1-~xBgC)UoV&8iT6`}#w8bj7FQaQRa{58t`No~S{<$(=PS9&uvw-$lof!3vvjvPvP(7lDarie}~J>?tY9U~RQRkqS>Ax0UGFBuuF-0`OitjpPR z3Ldo=Gkef(f%VEcAf7xHQ}{xtM{~blX)7Oa_qU~-=XpQ`_HjR9{o~rPO z{~-Vbs=*A=e#W$I6wkH|8I&jX>o!&TrD^z&q%jBk*RDhZx?*#Xd#a^ zRQ42r&FY?z&mvPTISXKp-+4FG)VsNwDq;U5L&2Q|$7mI)06s#7ukiVpb!Bniw>R3# zgS%SbkD@+%bfxlZ{MJknVcOm^X>5A0{4z7Mue9b7$DC@KvZ-$TGcec3OE9Ef%3mU& zZt>#xoHG{#WO~YCx|kUzth?wFijCz{Cdm>j;=b(M{h_Yqebrz`<<$?aOU@aGL_TZ%E+Y9Zfx?5j#&G3cGWUJiKf0lLFCM*TtV(WA-V@n{Q z(;@V7_scAZX#VeLCP(GBQeFdB55bjirt!lV0NZ)f{SSvgD6F|$15Xa$_7D4y*f&P= zQ#WE~2gy^v5F6Wcn6>5$jlgTOLpf)RvDcQQIxkG2t}dBt#4M)^0s#Ei@zj%~&!U3> zYc()11Iu8^fx8K@;Fm-7o=+lI-xr#y+s}|em|ARH6a&$A05_OW+#K% zCRNI#%spI^vx&YwK3h!3<14^?;73S_*?aD+&dyf+UKQH)m|_a!EIB@sJa||esN~&}6Oyqc9hU|@ z{=EvF_&!y33$Uj3pZGW)bwf>%h2L<{$5=0XmTNGo)G1Ya_5RCqnYbSRJ(5bAkMEMS zm<(P04~%(je6aG*C{_0)i;Q+>fi@%Y|C5mUlR#SEoAX22Ep>@smE^V?s3zZm4qlQ) zIPhA(EKEC-#A{#1!3<|~>Z%iCmgGE@J~57!n+m{EZf}rBOxCpLS|WlRckx$DzYF9$ zVd=FXaXi2mkl{xjtT@u*;Sf`fPW+lG_a7T-Mq1(n=&tAUDxZ{>VWk*wIqX^m3@1ua zG$+$=#-8x_9?rk6`{BgVQE61<$%Gh*M&DkK+yPD4r#d+K~SUR-I3Jy?Gy{Dcq zAUeG^Y_!}jwK%6F`_0|Ph}n;NKQt&k0{|ad+s%!BAXe|KcldnrJJ-aub8`Q&Y>ux1 z$h|T#rJ0Fde?DI+UcHDsb2@#wW_em`*Y}Ui+Ye1VHO+h;@=KB{1n6<@fkLXZu-d>w zjiygGMbHMDIL;$x@3+wJGtSgM`=*}sr^QwF?`v7OI@TQR;2>POSbEA_!saJuh@KUW zJbTDc@^VAw;^S}tz-Hc3lVYBGH33xrbvPAjjbF>QgyCeo*wbwn>wpeA%@rW+5| z+Rcfkx-Hp7^E_z;;G7h$!F=}sEpQQtR&ibKQM4ZHIBwz6Ug3DQ;Fb<&$-PSOoFPQF zG8vJj?IR(aKzUXxP;#|F?EzP_Vx~KR4zD+o+vyysOx_D}?oz7UAX)QClJTY;?|Gye z07${-u**99mN#Xlb??P>TebSIa6%$t8eVXSjF0$$vxqiDz?kA1e6OXe-sEcmnz09B zBz^mlv9386)vXk@E^mV)dbv+_R!*XJp<=WM0jC5-k)qu{;HSS;-_@$gY-DUr3aDsk z1`mjO@L02W<#LWAE!IDJLmmuS;uF{wo#%dxzGw13ioq_ebYk zZu_*|F_QQ_cFQWLXh~V+j!lPNQ}~^?KC;R-T2WYN#AsU(3F6O6!(;#^0q9AktUMwB z-E3f?mOE`)&JQ7-JH-DhK?=aI$D zRLrITV5eW$q59z|fjf|B1~i5Q&DlTPUk){D8w@4(5sBO=^x!=fkH|4HFHEAT zRPIpl(}J)Jt`g=1{i(Gk2Api!d95sD6mq@A(#aeWwFWtv0lrWw9teQA0!ExFb6)I# zF9l<`KQaghji*DSY1C&dYGNmpjA))YFQ=0N8qS5iX4D5o(Q zN!W~z>~v@G;_+)QGY>;a#L8w#Z4#Ec^3H<0_o{xU)nOnJ^3?FTtk%U}zFqrsNglblxzZhf6mnuny)r{m$C?BXCcCCc`8 z_piFEWXN_!4mX=$u0#pLK?~^j!9Fx(rt@_1kv&!RTOu1z9N?0)r34ZuBJnc zmjHtr=QzWnr$>4;D#MOfl9H21B}vZUI7Gy1L)^7hmEAUG`Do*rI6|5W%`q`k zB$}bDSFNLcX-YIi{sP|Bov&0zQvQ(-#FmbKxd2;lK!rV}2jMAN@6*~E&E~kb{%UTj zG6-`T$eIO1|AIu)>zdyd+11YelXn&S0(J<2I9}39_*^R}MX_50*)Y>cK#PnZxWIb4 z`zY9zL@6YVhq2~Ha?Zeb^TOO86_7LIcg_%=%zC|YllY(?oeFg^YKNzT^N7Ri&TvmW z^E43>lKwjMzd0xp72MqDvPUgZdlUI3pU^uSjV$eT?uf-d`m#y!n+J39ob#r2(o;Ge z38ST|f98^&oM4qw>@Pr%M--egcmL1XJ^IMpn#tK{DdlLE-KrENkOl$&0iT)&qvA1N zQpY#I3+ru7G+tERA!?NPL{dg^(JSuPz|OCwdq2^*iBZ4o4K4cy;hq8sYm`W0OEAOr ztr}H@_YM6&-9>STKRG|bnYw@ed>s;T;#-DtI>i*{bb(BX!9l~-3Tgbxzq{^TVaK}gYGP#dJEw9NU>{~K zF({%^?_gH%hc3OhRC>!G!Sxz4+e9*#J)n}C@W@y1S@Z8XSQ5y~y|Y}ytXTfT{Yx!D zoxGaPRu@R6lXhEjHK00?i}wef;*}ll!#4cl+y5AL9LoKOsXXlxJ^l0=Z{lyEJ82NN zxbtUK)To}Swx{$&L_-Dh5U07>|7{=L>(Dvto=VJ)wRJ0&9$LbZ5KXqY3Fed4El z{D-01GBf@0o?W9X^meXtB1M~d$4gwyYiCfwW6__~>4TvJ$z+IM|G37>t$0Bb$#r?9 zF0%TF?gof48GIg_?vH`E?wrVU@uDhG2=nP2_j$0Z_`B6h7s(=T;l%>@u(Uj^75qPF z&?qHmOy;@N~ZfZ*TfXzvTB|DUVo@#2Pi5 z%fITtD~8~8vc*VmcLd;{`v4#wEb!)3Rt4oU4&wGO@0rr= zYWsIS8Muokkl<3!bKAoB=GO(}TS;MMSDL?klBb4ZC~NOsuLJK~4O6u8c^3*8NNT88 zrT7d-7vdN$6-1g~=E`6*JSZdmaw$dhu#Qe3U!gHIj2pyfj&M$Y@X>cOtP}Mj;ci_h zj+V{A>!;)HLIPpXX6{otcWNXX!fC!qA(FEFah`*J0-jox5*T8s-@PKkC~mkh;ycLJ z3uqF98bdI3yiZKDd`={fi|(I&TxCsD$%zn$T$q<$g=<~Im?q$$7sesb>yRu3uHENT z?#f!K2a?tqSSg#cZEV;7jS?mQ5U|<5a(~U$gyN%S|M+2GqqROyW!vSQ!ocQ6*=eqV zsqbz((e>YkK+7p#l`9$*{=5rQS4hy9=CL=&`1;RuUM!OF9zE+Wv)Mh|%=NXLcc(;` zR>xpwV@AzL1m{&_2KROVq5!!N#!NaBjPMyBR-riVLeLh}7;&xGdDjZZ-dF!NE{%Si zyZM^A?Qm&}-o-i_kwM{H!cnfWsnM>kQ!UW3iB*5VBdU+D*IbB)@@n^YauNWbF&z?m zlR~gvyb5bIc?4oi%IG@Tygs-OboFSg`;Mm(!StVH=fbo~N$D1k%_{0Q~v-=A7PZk_DWSdfQYBqR&)0F*i*(i#gPbp7MP zSFaK&kNQw^(V<3@YV9EqRrx9qfP6SZB!c)3W)SW>T0)7Z;0%5ah(mh|0Xr=(&|lfw z>eN_5+IL-m$N*?X2pUa<2CMnG`cnk9($#mG0n`uuus_M0<4IV6{lTAb>@!L6Dqa9U zl0fv)M8ByfHp)*uy{!Xff{3m4=7C&VUR@t04H~7SLWsHzw+UZ=|Bw0 zbT#s520YvynjVWY#3Vyt$%0tGd1q=SC#uxxPMAB?P@K$*0f4Y%5DBD!0cN0~SINPF z;#__TAb{n*+13kBjY|rzS-s^NK)rw=KPicl>K@nS<2q01m=PA-yGNkhWe=*r_XTLLbPjRO4=DfS;U#Eo)5m^M&Xg zF+7b&5}R7c2opITJt)T)KmaP507SgYuON))t~l%hGNRWS5)a#aXPJldi)HPvvj2}9 zgSe$QoFmDtEnC~F9t`IU{3j)L^rIM1Mp7EbjhiZ^@*-6Z&eEhE(-0ylU)O)BGU+F% zCl0CKsOg9yAkrEzRpz`PspgwPCF~%Ja6_T*!M48-&o_IIoHCJ|uIM@pw~U%6_gkck zeRwhDX4`c5^6krGKfi7My=qlx#i?3~pr=te?FuH$(s%={<#e*DYtzBaLqp+9qt}EU z&v6CFj($<`h+R+Lm-o)K4y*n2!nJ<9?uIEKrDpINj;HG+N@{KNKBNlO=NQI}&429r zk4-Rc%K+(h#zdDI>`Z)q+mWxQenWaJ>~r6LLW2E6zt&6=Y(lllj1P89eW)FM3(`j< z;gXtp*S}PfzVoS7Ch$sT2$04SS6`XEW2QjhQf^@kkuTs<$(VYXP6clJn#hfFUk-fo zjMq$rvN48OpQ`w|twY@Ysu%8b+@sUN69$W=)!d7AP2^&<4!@zV(_+TCb2Lkhr_0vX z?W2c^P7kQji_V-hq~G*7W>;H$X(FT6v+F4?DyzgVWk}g$kaGRWPnBC? zeNgek4`?2$ccgo9Wg7RsE~r+eOU9|$hA4Kah2O{SsnrymG*YjmbRB-wySI0^xu4%yv*o#D zyyoLEjc(1>S4R7qZBr+Wk34yOKK@AiLQwaSjt_DBM>-b;-#Tb~9*#{1u7rxgFKmQD z$=&awv1jrBkFHBD#LPXwxraCm4B+sB|KFVRtN%aFSy7k$!=^$%9;{wIq+Xh_5& z=`%0f9=Nx0DcUD5OR&Dic+9Jh@X#q+=qfNS3BA=# z+KPKS*zx14S+X_n+Y5hr0F=40iZF#@ z^MMSd0*9X>wtkr_bFtHItz5gxA}`uxiy7$@V)Has*lc%}+X<+Gd-5quv)z^nx!99z z?R#}dfGRUCL6lF)vAmHPaJxt_`$!+AHOE2ED(<+*mURa5AL;Dm{dn=+gP4z}ey;gk2<`ml z>U4bh0S6#`w{7k`^8pVMF91-+0f!&?Oo)4s!$d5(#K?j61JW{`kSXcTpB|UgejTD z{cLO<96IFa_@yTDqw&@}$oq66YT3!`-?%HvcrwlS`|w`v%LZ3@DuN7qe6ch4h@7K0 zOqMjC3=s<&GPkkjKn?;MMk@Um4PtxG=9>yZWqzCO9{Msl#C6J|5W?YKqp~S>Rn~Iw zJf0k_ZotgTqiw;hGr4KCGa+%qsyNyMQXhuI8}`2Uj7(wdLgr6TBSf zn}ONCuY(gs9PqzMQ#-BxwV51a%J;i^3EC$O;@^REpI;AXa&q|_)rU6Q8E>61Sa8#E z)Fhe&+0>=srpss({H+eU#-E;}Otvx6zfCx6KKW(`7~z=A-=mL7OQTxb7Mh#0+?ZU- zH>Fb3J>lH^KReFPc5nY%jzk|{4UWuRZ)a7#mkRFa%T#S-Mr3P^m{=4B&2G3k&8PHN z2c7PR3-_4*DIL)_q4n^%C||B4Qcczt71of-BrkZ*c3pjM|LjVN?u z6|Cx@0B;8mN-T9dbLaDUJ*+{w@0}Ot|4o^3wv?Qkxuc=j9ojzZ5aJWjYmfu}QX=uz zIc|F2l~7|)#CTmTvnc*auL+1SIaH6-QA$%WE#UWP^OczIgy^@2=f!j`#q7bxLHp+{ zI3Z24zt?!ts|_@uCRx$5fnqSNkiTi3pJe@BRIreQvt zU%>x~rTFVoMg133sHlWg+5bqa5P5%0|NAA&D2G~eNEkT@1{8mV88O;}^-fx`i&Kg& z^WHBJHk)vknI9e2y=|TwsyUeTVgaNySHl1O_h*TviecS$Zb4t0k~+FlTs_@J@fyS8 zCQBG*b(YQNiLaJgCm}Y0<*!{sUoHDx^E-!% zdmNq{hzChd(XG{n=@3JJcUcwv`B7gkRPMYciTcBw%v(_nu^Yd-%lcq-W(mzQR~~*y`&!gys#QB^2~J=I}b+XR?g_^0x1T+y_9a#th8Lh;odvK zk_$T!qh{@#fKer)kn*VM!D4sqy$JpaSo#r~_N%K8lw|*mjwmSE7Bz>QdGL$%!Tk%c zVq$n$dWJr%E2*9vU}+()Ghnfa6UcTE9%~vU4XdY5l8enWhVWSivT&shXtDL75}tN2wF1kyCxblCRvYp|1(lrW~v& z7w^T=%sYb8mQ>!kkE}F5zgGrz_o>gja;BXL*7?2JoKOPJNf`?O8shq2^EJ_&I$oH!3s zP!ZsFEe#vuI#cvRy=CKkf8_r;Vk>oFymP+?&k?93s%Q_r&y66e=_ia)Z?D_suj}th zf5D6xK>o`O_4Ucw8)E98+|MVlQbbP>v(UaOFadsbx7y51*;nDHsNdlu?GC^2bL0NQ zTllnBf)L&H5foPsckR~U#!S|fT?EM@p$ws1;F8|= zqNSrXQYWo#jORc>d&QEK_AFbS{WxR=z52DZOa8CUz5Hv8L9SF~#MFKtF>|8&!z683 zciE*Y01FcDq+5X81G)3ke$-V!TCIg5ylFVnKx^D5}jGyL`IEN#yt)0=IGbL*w&T+N?1L#fvW5x?luN(qfXJ01O zOH43*Zit1hY|6NFTu;G`NHWP*5?-GN@e0?@&m6kq*RIO3WgD4z?du}i!xHC91lz&{Rkw)o&OF>ozD3pR9A{udEN>J+ zGmXL5jzO&YqF#UY@YOqO>V>wnI6m#_asM|OgaH6)Ngg+Vf^4*Jb0jzx;k|3cJ31%u*3!2{erK^lKRvS_0-e>IygycK$s01$WPPOj5sGXB^7C(Z^H^uzj{ zkt<}4KUmDRrIWHBx+TW{tFS&858$Iw`RM>bCKb1)D8aQKF;l~zz;*pET9k@ejV3@# z$tO9sMl)D0D&p)eF6dR@9!}W^Y>q76vU- z+t3o&Y%WgPPRdRyRZi`U3=T&;|ASm+*nv9}c#_jLol&32$QeB1HjVF13tzdmjI;t& zkpNU+rE{2>0%YKtB5yn6^tC0O$wEV(#f!SWNpx$Ajv;i%d|qd1_L0v3FGhARD_iUY z3ZS0@A(2;OawK(;BMiPt0hv4oZ1fl(f%}xk_WCU~j8qsv0S{$1BR>$tzL5jWwcX2> z4AQIf1eZ^Bg7Y(O08wnCJ z&;d;C$Q0lXOISR0@{Y0RP^$___{I1?ugz9q*@}N+6|bprX(VMb^d{Tw87uqs?2SEG zAzuS(nQqQx!V}5rQDmhc7WgpWI>`Kbg*#9R1Jq^njR4Xk>iNwn;k4ss1n(4_K=oGj?Wl*mW^n~L!-#jgl4cNGg*oWTs~L6ta?g| z#TTM&9930hG^H>JQhY01D(G7Jx;h}PxRercQ$-$HdaF%i>vvBfZyBu9~8USMr$Rq-S>tw^>2Vu`0G;6w^9r+0%RUC({xhMKgKoS z@NdbdvHsjGkUn^%SJ%mI>h@7ZU~4HCKY|`u!JjoFykmqmXsTKg*8GMCv-_h1aMkOn}zL8~Pbh8 z^bR|%U^h@=;#EUzcPx%304>oR20n?uA>|}Mvl%L94M*@IUlU|=-ZnIcljY8#K87JD znFurPOvO37t@HuN3&?2(7&iNvP)S#TvO3zbF{h7goOVj$(-v@3JolI6`{&-iKtt+z zp2TLpJ9v1%Jo34pthf#N)|dNh*upmeh49+YWd#w8m(n+5KW1t))sh6fo4 zkLfh^7rlLPs-_5?2zk`2(X`u=BrRXNf75kP{^~n&%8wWK3(j5H2O~T2AU*!O2a*|} z@D?qmbW6YqQxTyltWdOKni|KpYNGJ?!ICQ7CzNjoh2M7+u8@;v1NpF^EE-?99%9P* zBCh{L(R#yIGOAP^`IyavB0m_*s;ia&ngRI2D5BL{qG3Sf-EzrKhS}%4;vK_H*Or6mL=xSg?lTSl`F$Na^NaQCMp7M z%uFpS9GR7s+S1CxZCg#tw1Fd6))&i48}gjr`@H|X*ZV&g>pF1YbMDW5-#5Nvt7F;dn$AbJqjtnY0`(;l4fGw~10@T@cuz_1n>r0khxzSTBwcb-y$4bi;s%3cW)R$W^3397a$u)*~ME;8Px^a7SX(w?}r` z=P`3?CymaAfHZPsxYJK8#zIM+&$Ay9OZuVP?;AC%(|PWPM^tKOl?j#u`pB-f+PsAb ziHNELl7Uvg+Se?qjO>1L5^@hjPq+2;&j6NWk=BT#E+RSRGyeK! zw<9i7(g8q8@Nii4)SOebA{7CP7~qC>X}9*iByF!1`ragjsx0-$H5f|&Zo?Vp4#u<& z_EbPbIIyRNnmzn;>Bn}IPNn~IzWssc918%Th~!ZgcTNr>#6yFCYmFmTot#Jh4<00| zIo1XCnAfXFq)7|7UZa}WnpJ}3UvUe($XU81kB7;*+8}3fsI;2V{4On)1Y|vX@@Hkp za0<}EBbnS=w^yyY`I7#vy^&c5-q7!uv}>AbX|v`{esHid#;s3j&&qlrqC|MYs@2H1 zyEB(f8iSq(ZpTH|J`Xqo`5g;6QCG^hK+Y*?#)OCsyJ3)73TKX}y(co{^Hg}x!cH`b zf8-3m;9-WjFH6-RB7E4l$I5*pm{*!O2cgB#cu9ZYn+wnJNF;@Ob9f{>n)@*h8p%ax z?bOts(QQf^F4UEqplp{hOO2e@{Dv_-(TLMBiRkB!l~w?jKvX-W{M${eRq2WRy zaey!aQ6V7|M<@WmiT`*Io=1IjeR?V`q^teQzMU3wMt^$8_Y9e7`7gzb z-=&Cla74ev%c$}YMR=2LIwpOx2Y=N8dh z(j~sDhd%l-Bw)g|Lf7m*QTgmrHrB>RRC%|IxgP}FRVble9L8fasz^(tQej4i{%f0k zPi*bxL&Zei6Gmscm-SBD0Rj9TMjA4YDhlKd>r8cjZd@;ijV1BXeksBUNwd}J~zW#IyJ}uizJ-G7j5#`(+ zh{buc&*WT)_QN)jGrUF0%%TJdVYMXtf@bpZz=!Y%hKp&2mln2P0Pc@1{}+gtq{0uW z*&d9R+_)OtN4nN*B)8?ZQua*EF?Qy}jQH4y#`WD2Hu1pWrvbb5%@4lNY+7ZDzQayZ z0(fl&x1E=7b#{o7Vd-3n!hz+5)n)EiOi@X6@bT@`xW(Jj##?}R(FkfBle|aKiGy#5w^~VXmP$hbYuiW|j+k4Xb2U7H`9d?91)A%KrO$ z1FZf93`#(6%D(93>nkpfZuLTSa}0!Ln|$%RGz-&5_`MeZl{UDkI=Yf7d6yIO97ru( z!9-P8r|a#z^6o1oaX|?HtVi^I22#@FM==R)g{$8#OVBquZ87`mNgHNReQ}eVpV$fk z@ySagz`*#nR-Hg3GD&jBTE^L587Y03w*nZPH}duCFMtSp+8$AOarMEqZ`!T@d0MVW z9=^0+Mqsioo=4rRz95J?QKij;1qrm%Ne1u+w524eHCs0EUhpM5!0TgK60Q{VO`d+IbcdtPQm#A*p1IWV%MpNi86R z4GtsgLr0;=)ml7MUe|(AV>4@ABqXJh#+>k=4Z^l|Z~Bpgdeq*sU12|Urwn7?+)4ZM zv$W1EZS@0)6^kFX%Ko#l_PO@PETzGrRK?+p@3K#`$2qHQJ8XI>I9YvP0jKX7ffPA@ z{NI!oPT3;MICeICMfRpMU_ma?*0&qLN<`P}A77iZ3Dn3%C^F;xZ$^y;Bup=OG@GS< zp6V$+2$IX^|NZ{*=aTqJ!hcvh{8(H%HUbr6aDSVL;PB&Jx~7joV1X*JKyp2q9%=-Cpyjv)3tcP zXcss7vTy!jpkoggB20Z(;iR(!G?{uix)j({fP2Wjy)Boo_tuVhFADWDTF1A$?doP2 z`snRs6H$AAlHBk%fCK~Yh4p4Mx?8k6)Tm-M_>cDPqR~-iKk4C8<>ZcwJ&PRQ!o8v) zl8d%q6QGIPPgtC~%kT7IBK8}h z;tnHw%WecZi!up4b>81d!S!*^?(f+CD$4I^*{8c7Un=qQ8a)gj!vj5Wj+0Ve?(GEx z&mButSYfu#}j`G%p#j{EjD<6 zDV2+-eB5WuWcGzG7Z3u2qlvTF1KI3+G?hn?yd_=YVD^ZSR4r^<7EMcT{-V?Gj`I^ki;lhH=IWtCni^BZLvfU)li*yP8l_|CJi53tnSB-Q!T4njtoRpzj?o{`Ap&-7vs<-Rmo!rqu&(GO8?566HO6y z^6LtpsXG>Xb?!ghe&I%j(_tS;ec=4C-|0V{nmskSzs@9DEps6lQo4#dq8Wh4Uq^K= zz<0QGoR#yKN~+wk9IpDu^)S5amX+b^fUIWyls>%iWHh+vt}wabsJEA%ixu3+0k5u! z3&?C|Vzji_J^tqp`)guJg-2)S6f9RN?pM2vu+*MR%WT*e2Li77+8IbU(O=jU`##to zgPHG5p-=;$A+c_wUz-_av59ru#`t~So$D(#FwvK5`8P!2xm|-O-KH3ucSv%3__@SW zFy#pW8K#aO*wUejWD^;|Tt_ht1k6QX%PqKN@UV`8ERAI}MeQNk8lB4Hbfb}bd~Ev; zO^hmi=7qs`@SK_=co3sDJ5{AzZa2Q-(ARGbAvNLk`dYhHitn+kRODTPt+v7T$K>lo z=h}qxuI7*PkT(dgK&q!B2cHCVL8H4pWsJqH&lkln?vW`f8LXD1 z*zMSj#)RrNk`B5(tHe*>;?n6pO~->#C)!vR^#x&qKVrJ))annt7pNBIxohZ4d4Bk@ zpeirm`I>Ted^ojFM{*cY2?d!-c(eRiizD{%H%&}WpS(I@o7KUpTx2KRYGT@cr{cQ! zq|RmL+YOeR1^4kvM%i3h{x9i~c8U3JRd}Eariqqbvb|yxX zc;#UQ8zs%lvq}$@d$}}d_Ca6#_+-AySH9;lrn$JoJ2vCk)mPT(^MEu5f@jbepop=q zDEeirdi+@EozopvZ^Q0}n$yKk_b4B24O5<(Xf^lwDV{OeC%cov3;U!F#lbwcLl!qA0?F1SXmg%U|h8aTsykq}Bz9qtNzGvTW429yiefaO)y<@K;;JeB~ zN>lnZs^1r|a$oh-2<_Wp%5T#L_dFQgm!9s#IxzM4O$Rpg{5o8Fp#=hH8pkGIebb&UD@v$Tr}@#zVRnH zY~TUBgzcbrrlK^FXreT1@BTP4x#RRJ*vf=w=GaZk+7syeQyZNu%N3jQ9m;la2{vzO zWOXgsn21V_zL~UpyOI2s#=+f>V@xB}F9sCXep%Va6D4?y1`)#)3LiTfp?~zm4>pxq z9`b$qH>vikpMYVF$(>~eIB3{4N$4M3ls)ab;Zbf$O?tD_q3{kR_S4+us z`B#I;+pyPThSWsi7vvZJ8}(1&Mp0nXIFlB|MhjF%6B%(;=@|m(YAbvi^>?D&$W)1UDCnmd3jL31>_xitIAE;z8kFe7CtqFXnf!N)}(Y-2{(S>-(^%U9VMw#8o z)v$)0hr0~YTgVc*>e{h@G!dj#3qZvLgV(#ONg>pfnKP*(CCy4>vkrgeT$U zAw1^C%9TQaX}d6Lu4P`smW?Pb8c=A1{Shec`c|`2d~pTcJ=$pWJhK;H*!!;#*m2AD zFuk9_vEPMZ=FsHA+f^NCQHBR~W?BM#X! z6G*Id5QG!lMRk-MZ$s&ulTx)&iOvquG-Nm$q@WQyqXBJ$T^J6K6j*hUC#u7Pk$I=# zm)UpKnG$~+JXd6DG#zW3T=xC1iG;jUc&4r&u|PtE&~V4@i$G6eJ2rb z&LaJ(${ecVfj&einiBk4FZzAs%B2Txu9moZB>Q`J@s1LGDN_ z8tDlza=5vYlXQr4(O3&0yt;w9AD#a?w%*bVEuH4*k<84YGowu(eL6Kd!u7_`AP#Kv zH*T14KKzmQS>FwKz+^$-h$h%|OXS{8M!(3QqrehTv>%A^A_6<>d}`o!yn;Bq zyC=p@wrdQ6UrdA|6_V(JhMN8+3+4y8Zon|zCK*5;eFWw|2}r#rH_zJzR+i;x`W_tE zX{>n}v%yLxqU>ZCvc2kF&WOWo#Nl*K)Fd)Xnw8stBUUq;p0h+RBEMFmz-;O8!1zH#~;n$?>=l`gnY%WYQ87465mr7A!ItUUcLoX%>zCrgm2m zZ3CmP15vF}v7;%pP1ioHc;+pDI|>+nbY{UnOd*;MTKlOrNT&@rwaxF@nY#&X2oDOw zig((FcrXZHR&p-(lV60@jHMLZkHWK3iKyCh{^>FmAUh`YHb1APH2U%W=oxsn8>@~S z@Dl7X!5MK)eZQ+wN9e2isV|r`wh4`d ziY76f2eXQGkElV4Hk7Le)^mwN>86*N@4i$ zyrsg`Hq;EiHU?V-)7V$1n~P0H3MYOsY03 zo`;MCm|(&2v9wlb4O5_l@?eCV*>-5(m+Dx&Yi1*=h~F+$J6a^Fg#r_1Aw-5ZZM=9J zO2_;DU_4423}Q`=#{+xqms@Yk@JDy?8`?r@Y-;s)-ZMNfcab`0d?L(NyWlVRdSY~m zd1TO03hI0x6MVb`JnN*6yu8*tshMqix;AbYcQl=!LuzzPC{n+}PeCKeXhfhNGkybg z&_f!ruPwUrc02(Yz$rYiE8?!hr=hON96wf$pgCt`m*0sZ8i{oXo$s8E3@0EziLi!D zJJN}iWDb%_Dht;6q+m5)lY6(3&8(-F7?efEBorl*y?68Bp>1xVY$o_dr)ZP2qB5g@k2918eEU%AwR8>qe}`VYCnXXs7oP> zhO=L&&EY`om+dJU`w(GJ0|)8iSQ;{rI`cgX8AW9#w?6UXRIOM>wYSgTvKNio#j>wQ zKa5zum@XNap6}IGzzOx-hep=DULIVH@gx**a4T&tk&Q%V`N`WU=_M9{u@|`uAw1aM z5`?oUu5xhs(|SQ5r@);U>EpPNiaSfAGn#0~m=<@;21H={4CUU3|y$LbkcVU1HGmMRhx9UoU+vvKpBMHnH zfJ)k0Y1e01QW-_suZ1B5QA#sAQY*fR$dWZ;feQ(-V2PECJo9?rGBA>|galu3XgZR6 zK4je{-BBF-remvx^gR0W* zn*We}y*!^@uB3{GUgd6B+&%rInK%=p{iSuF?2yhdfc&P z=2O`){j#Pbyl>x)SuuXqYKU9UX0KLY zkDV7rK*o_-TK{H_5k|Bo#^XAX$1=x;zA|?|JQ^>&q0272x`s@}?>dTJfBOU(&P56d zyPQHhk-4a_Jh>g)Hc*-y`5}|%w~1^VJj{xpjIP=^GP!FgT5#n$Zu`mCM>S0uVf5;^ zV(B<@R-E=`q~EiMCFDY>ug$~s67frFQuXh&vII@1@#gxjEdk%q}N%z0hwNf}mjbTt>A`S(R8(>BkQ&Q!$H8&?o=3vIOM zpQVw^Fyh=e?tt9G-(%TXMhbbQ)_;9WVa->71Aks0+hA5rE^XhHrJdI8{ozOc?!T&2 znVN(=0|5Xb0bnt~-*nwo47JP~V+00Q4uTQPu4ixlKCkBXIUSe8(^&{WC`Sx)O<~a} zg>{igTa=9fAM$K__>`B%OCd@T4?v0801XcQjNu5G5gb=M+$I{GkD$WSc(}Jt(Vwb` zniMFp2D}*vl>^dzMuf9gvh(%$$$gVD$la5GLMQUj;>s$LodZQl>P8EQy$n&gJ#kC_ zmvff%J*f@~cToUZ|5yC9anj1Oh^*If@`n42j8E}sPs2KCvyo$UE^A-}aPP5is~Myx zI2d$~WOh4i>Q2JKh)2rn)eDytVD_h4Mn1p0o4Du5)cW#||8dTWo&-9;qnB*M0G(s; z(HvhA&Zocz)GcDB1o-eBT+5t7_1K!UqIns)mUajX(aR z+JKcV@=glU-u2*pXM?HPBU=kLX;j{ho$$%|O~Qz&x~+ zu!OE}X#@0-+}bduWW)Mn#5^WeZO~x(FYLu09W-AaX`j|s68(|A?}hc)a3}&3H%j(2 zZbWE#=ILBn+OI3D(ZHK7Duwn!U`jL|6j=XJ8vThI=4rZIV}RYB{;t8(41}j=i#+z$ zN|_27DL6U1T~r{@EhweT{ZpIVE2eO>LHogw~yX}WlPlpL%QN9={fw)D-ly5VAX z-dt?&+G%qyU=0XXf&1y0E1VJ8QDmI4=S~Ggr zjkxn+1Bki|E!&HqqwimP0J$_AdG^6inG$gcFuN0sr6sR+K;23{++5tfgJRM>sb+Uh zBK_oxNAn&Q-;x&&#CcT>clq5&umBqTB znG_@CMHAx5QmehW@_`E`XS1%?>Q}(74|^T?^2*dy4o-ToC(-h#SC?qh>fOWDPCMVm z>n(n%O?a9e@GfOK+vG#W=Wdga*?<0-@N>niOlJxdPngaY?tExEcRTpK=}fs@aOZrb zcyQOJ+_3Xzi{}!%yB6zetu3o0NE|q8nk}vWr2p}&7N2HYCR~0e zC_3q+effrnBXmT(XxRVs&X+*5|Iyl6C_NR+tc`V$*7j9kLQrQO@EHf}fy# zdAyG;wbRkPvGj~3UD^X|YK~v>ZrmMcygymj|7J|Sa^O$*0HeO9zn$^@NwvpC*ZqTT{PRnoc7`10_*~HBDITKuAQ_$ICuXwR~Rl=WW4!GT;9kwIvX(5xgkeAKL^ zEEH}Z^=6&SYw}3(Ffn#OpZEI3xy!NsJ89=-2qQSoR#Kot`AR>!)mX||>uS!$Ond`d z-2j&!7ICpAyjZW%#t!T8v8EDt(yNlAlW`gc_wM~+UmutHy6~mth#~jOorc~|5{$w}3p7r!8lgpR)9rXGU)IvG;W26s<&AJl%g^eVx z&)jjV7YxdE>}?*jj=dGKO}XIb%tdw5QRyO`TNrap;MjwSNXD1-@ba6;FZ(Z9S?l#9<#C^IjE|=P;3`5+ISB1z4=pv@z*Nn=qF6uoiu-DR zlcf+u1JS6%bbY4$kGD~*du8sgtNQK(`R?upX|VbZ!ARxHIQz|Qc#6s(2W98uSX@oWEIq_~_IoD9c{5GqbAt{JlK>E5*)Ds}i5bQYy>tDacN3 zdFrfr3UNfNeK4}`{n;=5`Ci^R@mu9)!ttBs3nwO0$}QqCK^tp$?_0S#AD zXfj{%pG-H!@+GX?Y{D?*8HuM2WhSMzwK!`k_hc38_3BDJH@sBXs9^rzNMnlio!fJu z?>jvG`;Uz_mgOA@$a~^{bjb|Ju7r-xMavh5)1;i|x7K(|^7ATdWR}UD+|pQbm~>eT z?DTIcdObs3#@yC1CUQ*c-tkK@TWv$u;WhQy@1E;9b)hWz?eIA@0Sg|(vliO76~AhQ zsr+ht2a9*)4FAKWd)=xd|9xGS7?-awN_RBO97X-<@4;2r9M%b6+Z#fHok&ze9hvOG zb^i-fq0AK{wzI^yN_$ykcqj}9W|l4NO4r(0R;!FYTU@{A>BgYB-FKZuXEjtlE^!T; z*D%reJ{*#~W3;E?=||j?%6AKg%Z^8M4URBOD&`=5Rb8)B#_5 ztn+Zb%pZP3Mol)@7~4j9(AZbCnve2KZjinuK>Xo#l}5wo6y~W;k~&M}b)#BpfA}9s zWW$#h->A~fO9+E2qopZuAMNs|{%X^ku6Zx=Rmg}HixUdh>hFcskJf1!o?a^texQc= zx!h-Lr&b)S*Fx>)6ZkM^2VaiHKivP%E-J)pRgj*x9Ju88Ni?bx+yCKRcED zU2%rzXG$VTF!^5cpk{ak%7*(=`YsQ#i>D#MVW<3Y z11UUn+WekMc;Yw0+FC+amESs4K0aRRU9Vkv-V2TpoG-J?U+0!3uXifG7dW2o&RxWw zzNt8o?r6YHnrB_^0o=OsuGO6l2xy8YG-e<@Kt%f}P1{)J)^zozx46E>OLVQke*Y+@ zI+^AgIkS10^6NJ)tu9~b{V>ur>QLzsDopWh+Z&_inG$esoNy<470E=>l^)b%vncl4 z?~5#}bd?@+p1;(b@+%@D^B#>_)33d!2ou9)?z4OH*?Qx5nb}zlrD@_fgV)^&kpzOg z;DqBn{o^I4-m2r80{{nmfLTmZ2#%5WFqqnb`*3?srADggeM>y&W$<*gOnRTDdx+R= zhdG-kvm(^FwesnyUlZ-82lt>oN+AC`-3^nVgc{X<>|NFK&6_8#H zks5K>H?C&*FAPy;%6qECfTUr0%nS{mgcJDzyEitfkN zKzj}|JKtq}{1pQe17M6ckzOcf$4~6=FWi$~;s*{!Su(L>WXw4^v9VG4a5b@QNwOV$ z^d2IhOozw-CnWF?+jVgi5gI~Q$|L$qFNzH`*se|}r_D$OGWT_b9pp~rY{_i{y~`GS zwD%p*K8rDw!Ci(>_k_7B%Vivxx9P>lg+OGRIr5DhQK%YPj|_m6bdWYgk`Lg>UZCI_ z#)l>2QIDHNVnG;#ZHXz*eD?o7XhjMk<@NJ zW}1RqPW6{?!ORnr96k6+dzpcwkzj<_F2qR+pq9zL><0(6Jx5VZs46#x!h^ zl!5QW^x?(M@>C6>d;fYHSMm^`P*c7QGi$U_$K#hRKJ1`L|W8`A-J z*t#Fy*wHqCXRR^n22 zobvdf%CC}HPIWI$tcZ$~3)$;Nfhp4f0;ilnEDPKyy-))IrH)x`dq!#hvuCF!$z@1L zpEAR5*(pBKFf-_?rAV^(@X&B)-CZVUmbg+1QGuMOFpuH1`#glUkOz7kfEIY z9bI+rF@Wcu6{SG41V^HoCH=K}H*#sVNj{(@c1vI`t$BDvewz{(FrbF+k8q54z%?I` zo6ZRQ%s=iijOn9_jgJ8^a^5B(Z>0;ex>@=)rb>y59K9`THEV1(gWJV4>!@JW4~ULukQ_4ea-d+G-{6JTjND8Q1+AbUGcVZj~5T7 zoW^~^ZFb zIq9f-+;0_0ZUu@4w{-HaGQ_^GkouU*_>a^ypXxA5$Mo|M;NC&KYgK0~#MmD)Gxnqq%6qY*#L$*Qgp1I16t}KWJd`QIJ0G&8UvvEbzU?I({0RM+0es@ir>~L*O;>y7l zAcQL4!56D!U`4Ex}G|I20JFe^pnNRsDLu%V&`x1Rna1#6PnGF5Ojz&K%_?b zvgBmWfBTzjV$0K{+w6>PLKT%>3wJy-*9`7Hoh~q3@#jn1aXxv{}Au<(TQKeBz~?j%w?wqn5WP93oFgP&L<@o2Y#VH zc(euq{eDl$`@4be31WAO*mcgadlU5TP7(skD?k3{URzdK&Q&CnmscrC(}UE#;>%70 znwfG2$CAvqImCY*$E|R2LJsa9g7Eu30o>4m2w?5Ji`^v5)Tmb7p6!RsO*&-qMnRfyAvQLm$Z3!*Mk4t!|UX5y(p@C#A`|gc!r1O zaRQ85_ZyA2@mB^Nj&!ToW4ftuto!)gx9v{5ZmV4eec~tT^e6jzt&}~6SMK*D+6;^; z)y~Zr-l`XW&m(q-Ce|p+i1J`el7IO2n1pRpjn@K~C`|{~F+6%ZiaS0%efOV`a6$#N z8gJ|#PmJ`^?r+<7~tTKr^r8FHA2&fTS)e{K&?AfE58C+NFx9D=ijeiZ#B z*O4SX%-QphcxdB`^xlI*s% zPm(i$3=eTRLhSo&yp64OrFm3RH};JHGue&;C|A?nt6D8i+Hxf7k-Bal7NL+BnV*=u zb=aYxPl-?!!6z@1Iq_kg7`Ek!TpjFq#cllZ z>J$08x*X+Qly)>Uug+WZZ0{Z80!&0iFX|(thfs9Fi|NlLcfWhgerX8 zP3usZWd|*pjdm11G}vmx1oW)oYzD#2GCwjJHhgpV!}LcE+x(8r=o?H&QMfe~(AWEp z4EbVBM+Mjr_a@8gs$ry?{fe@&x4u412pyQ6AshQ{2Sxi7uluey@V|FKl=u);GCY=! z;?QhQzaaYP27PY+!Tr?|O9Oz9?IB)O=QfdyHiBkY-zVfvE5)t?Q9k_xY}D^Y6`Nd7Axu8@B5#+?R~) zAzGI|wRV}^>}a@}YH@1qG(5NZS@$1yUyDN4o?9q01J=BVkFx)+eBu!)Gqy~uvK52iJ!@Yi zvn%+Npxh2AMo?#SLI+FE7$5z)E@AHsqTQ8-8AZ3BzPV+EG7aF>e!oz_G)p>4;>|u+ zai|C`EBe21be@FW;4}GKG2>SvrWd{hb|x>q22B_@K6D=!-Te1zQCyN<9RL1df#Sih zy=P@joi~Vx=QaAVf3IZNp1&hJBsn9wffU;kmP+ z`g5+DJj+wnq0*xEn^6Ish2vzq1}}ZTFeGZb`gh+gvs0H}-aYz50sG_Q_?0&u|Gxj6 z3c8o}-|X|7i^kch(~GJ(t%Th+2swt>_FNJeQ&jqpKBs4N#?FpwGSAE3>zUaDqvP)t zV=M|D_5t~#LFsl}7gLdor(T|pUC{|YUF)h4yZYynQS!63*gNS}PRIPmqspReZZrX`Z3r^P12G64P!Q4^A2vFl9C z75{5SNz{ETYm2H`=j{!J-pFk{YOd?i$|KO)0-SmiEVUAXY)fykoMR^-`BDjF{(TPO}Wh@U1nT)GY30q#@sQTmK-q3U#r57OZIijUbvfxp&Y4Z8p`12}rL(G|%Lc8P z&`Y|2lr4id>OW={gFEzC zX8Dk2KZ8@=?k)p2{T#iDWc@QG22bI3&@eG^GEcbq$lwjdljo*OK3(YFN-_$MAw(T} ztoqX1$@%o74@1e%s)ZB!K(iqHl+U}S0oi~nUafK)c{Y&+=)J>#rr5^ZJJ_(p>rJP8 zx9SUYE^#~VU9k{uu3bo-TJ!og{d?wc#)2@46Ncm!yez$*>7G#@ou`Hg0aw+{{D2Kt z-)2@*3(RxUF2r!H+_?Rvkd}PUyXwn01WJAsxse>Ai{D`q z$~3H7%ZJ4QuWvWs13N&4C)fkWsN}^;1fa)YmuUE~gevxnnZDg2&{wv|L8$&0y*0#5g z94ThO%TP)bsD(B{?qM_$cR{VRB7RQsV+~Ur!)Y*a?2j|zVKmD^hmzLH44XHd3>{nW z$$#gRpt&saYOceHaEXe$O>DRYmoDSpD_aji4ljjOO{C8`y&ASb>=5*^z55~RWEgP_ z)>uHQh$RaDp!UC>*iHV*Qoi-L%JN%PpUZu^l#Iwa=CfM@A~LJCgUL`t~7^ zv@nChn-HCFe72BOfXY(Chw9EB(@Y5hGlz<8t-9bLusFF#AdUj@XsH5B_*R94X(Sym z5ZDuP*X*P1H5Arv&7bFQ!%Aq5Js5M3InTF(QM0igTqym&i?fYr#!b= z!#^&%Aux2LBVfPd&OL>2e4lh`Tdyb*?^J4f04o3Qs*-6)aa3HNQcf~!@3VSJ3gBY= znP&&LReVU<&q&lF!_v0e3)i!eo&o=2?A&FCUu=a%{PL?$$giq^bBU6Zv>|iex3Z(d z$b*7Orn)PcevUuCTNR%R!;$HhK)%8UXO{WA1UKthzVb48=$hzp1S}n}Jy$o3k|Z-M z@w2LWn+)3;+uM0BoYcNwt=jo!O`L{oA^%1kKmvSNWKAP))z9hVv~UL3Hqvaox#55| z1XtUSlc6a5sGO-yY4Y)ui0{7@tX3t;p$1)GR?wzU*}$go(@A790OwQt&zJQ?5ui2) zEu!|@9+WLN4(-w7R5Yv_srQ z@1C5p^QgbmXM9 zU&Kg2rH!GJU#<%5Bgob9>;Y0s2riv-QRP1}>cI>BA1U0%`+UmKm3@}t znS|KnQ7zvm-;)wFe!x@(#54Z2BKtC59^bCQhpGhi2eS-mYNfBH1i$U$PD{LZ;dle` zK9G`_L6eoR;W=cV`#^*Jf_FDw}%lwbV_Y%PgvM*tZU@)5 zIQPl$MGm!ORP6(xxt4d{`jK7`B%TBU;YrxUQ^GmLNiOn$;WYMI=VzslnqyYIkt+cQ zUW|{Z{IN6^mOEKzs?2b0U<$y)(cg_~woNl79i@KR7;(!YM&o{#c2@=ml}-aSnyeIURx*_Vqu+iVV$SCC(E5;X z28_d@Mh$pYrT zMrITl3G&kDJd-?KXaB6h0{U$vzQ}3=l^upYa?e2V59`RVvxEH5fptU>Pnx(&!6uNHtya5?aWrhg~f+-BNx5NcQ=exsnG!5F=Ut8MVnA2Hs zsiam~ZRijIN!32L(uD{jb3^dVV9K+YC1g7lm4!cb2bJU;X5=t44K$snu~BWl zceCiIG}EUsBQ^u82!Bq2AD^KLnkZ+=#{NDwE-r>`pn9l`96p?$`TP;1{(wC*hR*b3 zOH8+_Bvn*KaFBnNnCav_r^8J${ZL7h$nW9E_qPy%>;hi`;(St`5*Y%cv?AE_2;0_S zTC1Rqjd30pt$~_tu)Y`T-=*{k{$hE$h#*sD^d$I>!1uQgz9gJev48%7?FuRQm}ifkbAcA7~Xu3X}aye^UM&oa$sDrUd%MHjeG;2uO~g0^E4o<-|yqP55r>^KjW zO@AC=1D)F9G_iDL~l}cnq@ENAXaIf^ju%&0z zXlBfCWx%pilmOxHjM%rqa0gc*2uzwY3KYu+4NM##*zfy~nc#~`OE1mAGqdJ$b136? z$m5;!5K$xRLT8&?fR{RI6H_22Ebq)a5ROz^Ey}sZ^dZ6RoW*+}%s@ebS(mQbDl?9b zq;d*;1Pm7{!xzttZ#fwJf9N{zn5O!`U!PJsprw={lwGEvfMqCU2xV7f3M$GfvdS*V zs5oeW4t7}ziU=YKiVBE=y9@ig$VWrI_<}eainLnt{a`zVZ1hcq}4ksQ>c0L-*rQJ)sa5*n)}&tXQei0cPD_Lc;(n0QUTGRFaik=K(cnK z!Fyhg9j$mhQi!}aayp-q4<-4rNPaRKoE=2k6zY4U-aBZ($8dh)v`pPJofhc z=k^{&>|o#%k9Z!jQmbaZob+?1m70q%O zKH_9yPVf?(-oiQQ8*+KA?rj4s)Z2ICk;YYR0^@7nzN>6%r#hv7Lc;(tB1O45Zy_MqvVcctHW1z$p5N^odZr(6+s=rxN?wksz%fBfKA|_C{yl?6HVL z&osroKx>37mGvuc>jN&Fi(qLo5bm=Lw_+@|7(j~ z_RTPVW+ftLJ)BF1B~uWI0&#~4*a1p$Xd}Gissrl|Jci01oGwqO3_hSoQ7~nhEJ0la z;yr4QLM|dZ9XJWpLJxlSpbWc#b~Ta<2j!T?udJY27_Rkz{EGulVo(x8oVmn${04q+ zx!7MUic5Q~v6{1!$1-6v)*&BX@}**mG+cQPOH@EjU$mlysCxl%op8hz=F z{r>kkjw{jfw?1&m@6M`6|8`!;gv5k<@4htF6#;-1Yw_P(ZRBbq8gKbsn_yp6HyEPe z&EE`W;sOu<=BQ1>bsijOy)~N1gD3OhQNVDr;Nci;Dnb9=;R(BF(9_|@wp8Zl2vc9(?HYN&A1` zKeB$Hn@z*MfV*?z`r+Ymi)y2epf4b+K>1ja_`{mR@_d=Z<4o|Kj}kfWehD~l?Ga+Z zsf0Irp28_>j`Hd5)CqPhzT@b0+3)6Is{g?3A$D3}1Y|*oQEX4@-x>kJ!q`y{*a;*=dL@F+aLSYKj-XB53}?G9u?QAHru&Jy<{l#Tg|jZ(8-7x?-x<}9 z?DpPeRVz;S<9Xn7>fyDl5JluREYzfv6+wnTkc?gU2m4(SZZRJsDDYPk9)dS{JI{Sf zZu^!g%-Vuv8(|q@0K)=6B;rYj2`OAXVFD!)RL7|P>A{KVPGa9OYsE}9vY}XpH~@%D z^}!_);}fUYs^N*Gho4s-z;D|Mv-@-@gIO|IK)i6n)sSN*mrSKattWZhPG+1^t1s#)cyk4&hCe5P5te=Z2;i1=<{cA32OuN>($9>< zN74NEYNoSM@4ARIrfUCsP}KKJQFS_4t`3iVTQ% zGla{$GGu&`!w%WVmi1>~K}y^o64f&PeDT;bpQAclF%{srC~>e|eFFf9Ik5oZ#Aa~n z1S-}D3@rXqUaIu;;e*TcF(-vTr+Eo7gfB$clTDw0J zWTJm4hC47&TZ!d@Ebtm?-+xsF?I?NyptaIm8ktuEJJ}A7vPLmq^hYkZX=9?FI*jQDC0?UtO6WG$$q&qs12&_KbHV z26dH~S$LGli{yX@T-4>0q0{}PV3pdR^*OM_k@pdhVK4w_U3S%O{Z5nHhgbU5^7mey z4r58H?YkEL>(-@>LxF8O{ZuAM8@bn}y^ zFzlglG%BHPw|;qbN8*#Pfr~+ZcK-g*)*G0ZaUS4GDevG;PUB9w%xS z?yi%QRscuPhVo?4>*o)ORP`?uY*#)K?lMC%e_{8wI*bMARuXs!nJ;4DaZYaY>ZL&$ zKd@z2DLZbz&_Nk`cX_JQvFMYI$A9Qm%a}BUS5i*O-3@3`r}4($Ep51>#&z7{+=b-0?-yu#Z(tL(Yo>jiocS>s~}y z-hsPD2_N@58FtKg-n!EH{=ucIx5=>oi(u9TG5^=V;{S(WMqr4-MAqq@S$ao)hHp7( zc(6Tga%$|#scj*A223RlJ!u*_c)_RV)>ZJ7ePN_2_B*BqM399a=Ekp6eON!&f&#$a zbnn0E$+K>oW*C`je8H1`13%Yd&G;GR-EBHgDcxMPfCV&|GTHvHWZ=oaqx99KHv=7m zOFlWj|9)DJk_2BG9uU8vXPvEKT)9g_UG?O$OFkj?>`l=tuZ#k9yu?)4Xg%|o$va2n zqCC~C)6?IN-Q^4>+Ohurp3Js@@qtGk*KO53?{$t|F`vEnVXohF!GEZ0r1Y!Ih5kW3 z*45N+aSJ;VXAZ85?xDT}hn(*ynd*r$HlclgJU4JIq$R7|B3T^7x1+#g8b1lnDM!jhs*VLc~S}4-8&3d zKaQR4*Evm_eSgaM4o=b)p2gB8#NLLT3Uug}3-DfQNawMCO@s~Vc)2w#*2u8Hwsed; zyg#o>-s(wR74`fRy%6@EJO+Gf1aIp2uv za%Xg0MqLNbR`rz`96(&S1ET**1YRd{I{}7^>185ZvH-0_kfa9V+U<=Ww1>(kI>lJYmXO45%M6dZuxb6p+v zJ0ft>8@pHb`qgb2oz1pFTDLPUrk2URnt0*Q>vgB1)0O}fTBEI$NVOWV3C zi`ob6{ucZMcG?IB>0qkwy zEeP*4{6W06;ct%CCT$4Z^z?9j9Np38Kdx){?_p`FhA{QNd=6>8ynG3!orFMZ*^5T; zcN5#|)sIag#7o-SnY67M7e+!8erguSn`h(hw>TT>)gkRGXS@<8vY+d9HTsz6C$zt2 z6B8CM9-V)z-nM#9Ra8>*^i7ZY0s%6bgLBG5hU$*tIo3-SJC|V#JIFD(4!yqqClZe} z9&GK~am%MLn(U~2pWlP?9_5_=Fd%oabNEK}j9OxKz451scL^8B^4Yjj$8SU8$2K}` z(6~d2-QeWcD~Pn$hkD+q99Q$ls?)LQxytYQT<-;YOq}~%)d=0iyhtW@hd^@o&&eF6 z=vLGwPpFFd2e#F8cxT3tcl4{5ST!YfaYhOhdgFY=T!Em3vb3i9AM)w8K{=6oLvEg5 zx=!#;@exgC^Ck6_PPTcCr4-d>PU)FYeCi{kgiP-axkcJ#b}gwejxwkEX31se=kEsS zC(*HVAjYwbZ~cXJ9u;acw`YOI zv9YOmdH6F_V@m}hc)EALptO^Y+ZH19y9_ngYi1U&tP2~PRi`i=3s@#ZLarigZIu5SkKYRUenoM`@~?m3A-NRvTXc7l;%8TGHw5UXppzQ)H@lT|hhoE&peTg((_yKf zAHwoN;jzb7N{TjB9@xA8022=uy*D||xynrKisLF5|GYM*IxmFlUa>EX@vFy=*FN5% zlRFj(qTJnlmLV~e1t&&Gybr^GmH7OG7}vD!$4{*0lb)^TC`VV^kkj;he(B0Q>2jM8 zX4)occUXMfgRYry{B=@nQVLXMlxXPt)d))^mMgz$bTO}N4WvvT%D1EDK~DHWtuByd zsy3VqOJZpO1O z2t|hB{&CHIS_PQ|?Flmt_BL85%Jm*;X08yxxo<|2-H%4`JI&25loSd(1Jc{aPJZP* z)~w4r=H)wd(a3KDtq70yt(N6l(+XDpX%IvHE`(z~rFT&CI$MkM%(6``&lSxWPgr9LR~#IF4dU& z-xF|E7L!`rqxud>pZ=k4I+$Z<@AMtkl~jcC4TK1*H{T;Ev;Z={C8TqP$ofY$3r76! zy;-7gF4Yo`6hS>TT%I30wgt;XnhSo(5E&u~_mh%=y+zCKC?3l*tHn1LD^)XU;AT0k zsDS=%?NJ$|KPUx=Z=RCdjomIq1A03Ek?{ERA~c1!wE!FRTsC#vYK(mt<|AIZtVhu@ z)!Z4ftGoWV_8tgIAa;}=12SsQ2vR#_bha$&eWrwb@Wv#hO9h^EZskcr9q_F}>89Gu z4gsn|D9sZ>K_VG9blk-svPmdC6Lrj>RHn9_{!Bn8?ZM2ot55Ga-XXJj#mUji534B) zP;h{ly^Q*XJdVbW>I5wL$eN*;9sznn7cR4uFzP~!nJ~}DI+7X`aT^vF z+C0VTEX8L4@b?u6xw1Tnm`r|z{wA;iT1Akw&PET>q^_(UGNN<-6G{^!F|&Nm%OP}M z3+kdkw}vkv66yxeZfhk;_~XS8Es#QLzW6Fv#v6hFpwW&>Psb0&IY0c0*X{EI3DHU*NZFz6H<2auF1Xi#p}&#>>%aqe^ev%870K|?nskX!x=bj2 zY8YY3gD5acig5W#r2O`cypuSH769jrBg*ioL7`L%S?3GMCT*>B%b4cyjXZ1$IVBt< zn1@SlY`|+rvwtJaXMq5~fOi#<4dR<-2y{DNf=5AmHX$W-uth@Y-4rp2mJ*d8(rS|> zU@RPWgsmo&cBzFQ_m+I=jiK%E>z*T3t?%}}AYEvFP-V@cYn1SnTlUC4UyB#n)Pj1@ zfNKhHdgTg_oh*tq^tx)0vSfR9nH)MK4 z+D<4vgvERSqTZKCC(Gj&!^t)k^3A(WL0iq!b5He@Krk(0d&Xk!AQT<;5!1MwkF=0^ zLD~QvjnhHWNr)sYqN)+T-y5n<0KoVyrlmxqsX|TSw1$M23I)y=0p|4j)2sfDYUA6X zp{E||;0}kM={%qcV#?bAiTDXr7bVnqA7KBvYHpIQBZQ|AG;B#9bc0!ZrX z>xX~f%cb{ctnk82xIBM(33H*?wiYoh0pu+Q0tx_5{*V@GT@jaENH>uXiq!)?BP62~ za-QkFJ!l`x&rkAHW*ZEaajHDPrBbTT&K)h{P{IXu+JzHVr^_l!ijbuq8K90L#%5@*u$6D! zFxWJ5plmU8JdB)GBA;B9SGkN+BAnAAAw;351eg>v92|(v5(zS_B6%Y%XmAd%od*T5 z5SN(TsQybhJoZgz32!5>luXxbK{WB3R=z33gcBBi1b;U>zoK)-JEdvhX>-`JSOG(+ zgN7cW?4{2sH-5Re;LS7bL>rh$Xkoz?_!V3RwiuUNS_wf>V1!biXe;X`8M^{E>3#k? z56cp1x$b@PEn;T?OK*ufekMay6>+t-sL|;%eIacOB%lHG1O6WMA+GX)E0W9{H_3c) z?{l^7W(AuGV?5=Fo_6`@BC1^= zj`D7IMV*#pUT{NYsR-c(Sq?96I^2LN+NZhg9Bz~zbsB%^+im8Z;vzly{ibgTL>&)V z+tlEBX<Ra&3m!vCQq_Rov2}FqjKP7{DAnbTYF{)ZgZn#t5FUT$cfnFNhHNRZ~ zl8f<%fU!|fwWtSs(-*oFhJ^~|t;%cK0k_VizRH%q{Z)EZ;bHHldtSrMvO-9aceZR~ z(l}Q0$jf_{Kkp?^6?6_E)EGH9+WohUttA`MC?R;O&sAN&V+@f)ZNFKWoJP}A(afu1 z&r5$Nh3uRuTHpP!dj-(rXI@o6E2Li+<-46hW!L;d_W{Z=0tnKk0~LoYs=Od05NA_- zT4~zP_IHhhKS=7jnAX*`yGF+2^}0Z7jd4@p_H(J(z;Qx1n#k2`obXs=`MWtIMB%pF6lR8LOw2ao+xI3v^Pk*yVdM<8TnL~9k4!l*p>wBhm79xGSN3q@A z6-2Q=;IRurY1?m7Zv`*Vb@x?k;eXpu1s2xn>md)v0z|yQBWZh|w}kuB07>)^Qj~Od zS0`j23CX+Z5p`a{co^;aQ9DVd{D^kIja7r7GWAtL_14$$KvVq6R!D41K7 zjASGk9F=6}7V z`>LX#5Kr&>SXBXFOhW1q(MB%y2G0X5B`?|L^Bz!8=A>7mxK}XdD=CUtC;4aqtMCMg&_F1Sh^PXXv!AyxoQ}4vo@{J@8s#Pdf z9yA%}j;)Lr3*%2J!W23Q22(!DNq-cs87ihQ8;-3jZlA}T{DKw@p+%w=bnAUAh9+L# z(zG18_e!0?-JpK%k2JG!)N%aj-opEcr0Ga+rGY;(#H^vYSmi`!*N4qdE*n@nnK<7m zk@D$8Ki%|JQWJu~!o5)F&D6A4ZLhC>PrkiyyJ;B}hOJuUISWt0@?7*WhIMp1uf8+k~C(i`8pra6t zYuM@j`}&00lU*|ECbDIvLzkZoz05Ko`qW?ORCjCl%=VEUt&qJhP_j+{Q&)(1F3Rv^ z#I2VB)L+sc__uSF((e-_3EuZTYOwW_5U{tM$F~ZGs5u#e!0|BM{{H*XKasXF^2GOc zr{|={Tg>j#z&rCoOfV#Jh<%svY=@@$z3seT6|vdx(a-yly7;=|!7rnhz*~s8PP@dZ zVVO38;l7JQ@1~zl3TD%cVvo!il>8-s#;f7$K0ujwP~PHY6v@sZGum6_=2N$}bzH5v zn|{9q;j}bp{t2r_d4AkmDac0>-ezlAx23-h9O3LY&X=Uf zR1fVlJ=iw9zyEtf*f+M+n>*pjjGk%FcNmk4HY6pZJ=&c`pW~Um4-znhV9nJ|^K-8- ztrW=yK>NEVR+0yeRzUHG(7wN#mVv-)<2Ru0=@f5>tLV<-uPO~GykmOdE1f4I@=kP> zm3N&U2`-geu)ZMO#W0jtTGM(*Gj>B2Y&J^n8WmBN$FS-C?I>RgP_=8_E9oHxK$Z;Y z4yegKzmMPY`JICi)?!$%%UJ$vkq{PyCig014{jJ#mUyFOiW?zH2V zzj*Xf0^An+Q)~vJK2)O1gNER(j?&D^M3J-AGfLG5CAD~G12tsEmEPYGlW6z+{PWW( z%g=}9?8fgGg+6*F*R@PKRX_fT57nYDK!RC7%7RI$J5~M#T z=FREB5JF2-&_lM`Q2|6TSv2?8EPLUdiuHEwB)5oxGOi@EFo4#XW-mcFinKg9?f+^n z*p8*<`0YQCtsc7^|83#N^qn-}Y{g?vYV5Viod>leBl!$t~J^V^bRiF>kE?#Y15P(57T$t1RQ%!Aj>28TxvxL!W; zvCFmg_)n&cMkWzbYpar2?!nBwz_0JyDXg74w}XAm5o1$5r*l$6A#SK^UYRmOaG*&x zl>1-IM&oMrkGh=x++yHUeQDI-KO2SCtW}NUznQKws_$|R8%pR1yD;`Ym!Le`ZyPfG z+UwOi3R^4VlA9$jOh83g^7-A5Ofc62*h&Kz?PJa~^cpOxrcTHdZh854a#`cs8gsL! zuU8NfZi)A~Ft$%h#tBRMSED|2D7PL0SCQYEjXdAXbMxIJgES4vsw!wSE)gp;yELMi zXrA#|Mt}6%-&Vxl_>Si!F$H0NxNMS{grckqF1kX-6`$)YgFcA3@TJX zWy4SK9fz0Pc17F?(ptwVMLK-^d@kF_aknvMJOZr2U}V{uWLq-i6vG&HGd&)`n&G`?&wW^Hr#$M6YV)T)oF3+ItVHw zzqr-J-F~F-a@RZEufe=k`v!+6ml>=bpGR~ypKNW$OxFD#D=;%b>=^XjJ~?-fK4In0 z;CQD^4Jj_3OAp>{bZSPEQ9;*5WlLQor^xd7#!W{krKypVF$tLK)tMx@!cW;hOl(iw zFctnr_+HG9!yWpj;UWs#2zqRKz683`m2arxPr`f@O1lQ?%jfmL=J0!~s41IObd#Uj z_3LcP_K6i~tU>Gii9=Vn_Gc;F1tin79u+(#L6tXE!_ATO`*Y>GAY8~-v})7$nl9RG zJN(A3IhEBd%(rz_kKsTuDbilm+ieD5}9f1JO~!^>u@`h^w*MrUB#``>vxh~JJ4Y*DF}V2?fE zR^O;(ppWBw6aR+lPB*lKOy^err*{hD`6n#b;~p4;C}(C8Nn#>=gp=QoVqfE42!he2 z7dMmtq`cTVM6#?hK@;46Tr+%gdE5?flABp@-p4PeYVPUg!e{c`q!iqEe917HjE{eek zfE)#)_!^M1S+Fn8a5n=F`(3R^P2Od;ID+O2KW;D!^2xcDCZhDRY#}eD{`BOT4}?ec zuNFU*D!;wJ&;Py{m;)i zd)wNIkMf~y;j=lA9l*A!NNMQ012f?-vn*3TL9svu{%}L|Q#xu#M45=j*}NNi8S#*P z!yo^6$Ec=s%yQ4bPl56FA6?SQqB%L;4W_D%N#SAsoZ5n=H0Nq^#kTQQjSXay^$Qtz zi;(_s%JHr2H(_z{y)PQ0tIpoy2fAis_TX1={dvOGt}TOJjmb+abN&qGXd_!=d(G!# z^*@S_lxOD)ygAg_x|s~W_vYa*@@&`a7rh3+@tzGP#7eN(=FfQe$Jt&bi$&BHg`0}> z1N82%7Q5`oRsH+NI?;mM+7M}{4mo{Cg z?=jl*($;$`8s|jmTh+@sU)_8~0~Gji5tc(5fxMsZ4w%Z0rK(V6 z(9!gI)fH0Tj*F0*YPC~p%c=j_Mg~QFr8&N%Nx|CVVdbh?BlvZWpjW7SQq^??L@E>xP6kvpG|JnwO1RO+JDMO`d zs&Jzcb^?QwO1*KEj9Z+OOuxceet9ju(in`5CQfL@G2rF?49tdYd8u4BNqy}Ks12Gg zQyzXK5gM@EsVm!t@i#?E$B+_SfIw!2{gC)jqOJiVq9Bph$?iXc0RQ4K@9yJ##L$kH;+dqpOi3Kv7s2F79-%pM z7>>r3j+7~l*ae{)({&HW{n|s3_Aq8T-3n|IA?R0VG-g49|ll@UTDFBU@=Dk<5gXgJhY#kc+3|F^FR6M< zw9)~Pi=)PI%ha`7`hmEuRm*kB&k7cXu=XJYt3?oW<5Vbh*G zK$D&=`Gez8sl(#2wIp8zA7B{ZV1e9c@f#qEH#k-ItcG}L=^i@~P7lf5z z0l?Eef*dlp!hZtpzKiqY&aNna#a1Cip|Qlb>9H*Ze`vWktC7s?Ecm0E5BC?Fbz&Fp z-b&rbS!`7E8a-D=VHa9osNRBz1_RTAGsRED9fjfnovx{PFv~nb6W$u6AgYzL90?Ut zjD{TqRmAy6f>NIwR6uiMP~{CgdFX*Cj?3Ch&jZ*OYvfZK`}aVdlDsAqpqwFgutg zzC>o7`;r?<1)HH4Y#L5`bHyETFzN>U@Pw^{F2eEASdJVrsKU-SG+$~$>fHvy6VKH~ z!I_N(yW^3!e?mN*Uk>^sh%5KvL9DY;tp%b(A+b+7v4hC0{Zgz*;*}Rzj{WnoK<7^O z%ylU+X5SClwkgNifU9lh9ua}Oy~b=(f=82mJ!4EPVmbO@YYdCSw~dpc6NzKqCWw&>v3mS3XE$$I>Lv{W;)Rcm}e;*#KTiR&vk(C?1n@Y&wp_ z5E;q@SOE4PVZQyneBabT-z)40BKv^z6?X%~VUK|Gk4kcn=Yly=*C6hj_JACIfU>@X zq}kTS4V%6!hsv+)ZZ)qPS{xdF{PF#1lZvg1WLe4vJe`);A7eO_ePD|d{NMzfac``B z?`zRmg%73?kmqMp1gGNo_gR5-0F94`PL?0Q zo^#(mOf^YvW=r0mOe9?4I(NP^YIfR$+<5*rqOg*PWF2s01=HCPxROg};615*{{HBI z3jg0LV?QFeXg(mv&EC`hEUc5|k7M`#?{4wPu^0ZGJVxj{rQep~dXt|ba{M=nKw8ir z&!&=XqNwm582dk|QwjbdDcdPn<0&+r@%IAj@+Vd)nHB0iv+3`{MRV3JB+FdaPx--U zu+b*LUiHWg@dK4Pwv-$X0xZ0dA{hw}r@4wl;KOc*YR`5pJKF^|_P-UM5k>oRVhOBa zCDwuE*H}%Dnqx{4y-JT$Lw?_oH*372b(f{+9Bf(@f;L1@@$7Y1ioCG!hvjsL5P;ct=yzH6aXqAHkOnX7H;>uJq4y(>5;#W|7WOLG zmXx#KjzwAciEpY{%B&rU;=@8H>=^RZ0^{DpOH)0Lk0TjQ0!MZ-KH49C&$cq>Xesq@ zBs>I%fd9HgWo^5JTUeW%70En_@SiSy{II9-_3_8$k)1G4U&P$*?T&%BK$A_e8{Rps z5zdFnQ{btM;gKhAWw>#pEA7*G5gZ&y=fXo;;GeC)Z#eP!2=YaEG?yJ)2`9@xx%U=0 zM2R)QypV6d8zp?++uW8?Yj?vR4vtn_yvt4?f+((Gj!UHRAuImm}Rn{o&6# z*$sTVAIEcPWb*;)z4%UIfJzDO4qMb45FUxdAEZN5Y1F=x!ze4tT`5jKrS3C0dO=1U zp>Sk!!7wyCf&qVti4LU>)fkTss7;jw?TWm^b~rSobzzapU`JK5!B@v`_qK1I@na80 za{@X`D&qd^WZNyV8n4{ZDwxNs$Aajuc12Zm%dXng6@hy~Q$v}Agk9K4c(opU&Tm1cW4|>lc${_5{?b|e8j+6FLKhzyRglY%f;Oo_SP zra!?HBc_Vu0f5W|yUiB#gu{*O5ksgPmMM$dkOcr6e}rmgIz5x1g9o(+KqQW30F?|Q zV)mv^hIZ#{fG|sEDN7!=k)p_ilIW~VD*L*r4mC@SzyLY{ac_nkF=sQDE5XRpp=4>| z#Ei&H3^`pIcf`gUQGJkJzRge%U~&~9$Vxzq3}NyiMienU+}AB+CV~LT(l}y8Mx5W4 zQE#WOst<@U05H@HUfxNutm^S2x{YEg6o|NxfkiT*xPK9MZPdNALS9bRgJ>gN=vJEINYYR!t$Mu*lC2M!* zo^S%oW2pf9{mZ~94P7j^=~4#1k|9oIp!mr$$Slzo?D4Z2Ss`HepD2^ozZjkVC;L#A z-Ueq2Acpm3poSQzB?h8}X*l#l&s)rBgOwR5`EwoqpZellpSB(jsYf}16)-T|zY+|F z8aYdkBBtM&69bw=aE|?6jXA~4&F4R60$fc|XGCy=6d~cX*e!&xN8Bb5^>?Hxa;RD-aHrU9Y(SHqS-fMD%#e!+lx=5P!@3pueYkf45NzHm%tXC0C zLY=l}(WC7VZH|2?;f;Jt?9=AHP{Z`kQ~Jh?7Z8>~Rq989kp=w=etO%dXZ8<3*QYbf@9g^y41&Gs$f+lyroWqurYFv;4!^v9U!MF`ae(>q#4$T+KY9R<7=8 zx>laS=>O)D!Q&%f z`Txr$Yb$Rc_y{%oYTK&3O}iD04&I`DU3-tJeDaSccD&U*X+|9Z>mRQ^seonWS2wf& zPg!|<=-h+j9RR@XZ*O|}k4yd&1poyWbiE_WH(TfW0`6wy>K@or*-|lZ@_u!i)azS` zvro_Zj=u=h`_tuMdEBz z-GQj#iG+0p&(BtAX>-r7D3*tWFn>PF1zIQ{NUw7bue?1A4*wb?|8$z2-<5pXUlcxh z@NeSns{xgLVk$0iRX3tcqEBq)ct&}h`}X;hNc(BJW^6zw4CDW>rUNW1Yn=BEbLG{$ z_iFE6=s!2-${YN&XN1sCm;>9q@uyx`rG5S4Yx^7hh-aJmXHFb=@aWPETUA+{FPky} z;cD>&i@BT6kt3hx8U9?XCO;7OePj00`|xw>vmgc6c%ttLmqrMY^i zB8$A6gYg9OT zBFr=WQ@D!P&R=+^QCpAiFN^KI_WJhjX+F`s{ZMmqt5om|>}IiTxMTc|$sdBULA%e` zf0%M5ldT-zD|24We9nfJ`&3r6-)&3Vv{w7UxG|m9^wo*Ot@e9Ry~VcQDqnh9Gg9t- zeZOZrVHeS=l|5)H6KVK$sV@6Lv7HF0f2_C-HJYK4*dK~`d-TgwWb3{JC6rOehAG<2 z{7yu>Rija1aV%8RZoBQ3u^Y<8gA|g?!l+#YPH)&t4aJ5U~vJM%vPPCy2efnkY<~Q+opUtV;Y7I`^*)M&Z57+p@ z=#xeI-j{UH5fcH>-FNDWjvT|pC|M(aJUzAJ*v6dt8?v*;H6hHHp^5$k&7KZc;QRy) z^&dZ+L>UltxGI&gKz1DwolLWxpPAG6y3sfFcc%D6ft1F#4cBdPj`pa7tN08_dxK-E z1@W}&Ojk{A?Bhxk+1a^*C>u$eJ4po|0((q6T>}@4?6BaHW%g>l&=(sggjarWnIRyo zGuEV!3LDfvZ*bOl-=!PvG3u6l-ur9hCz*i|!=Um&o2*&VxcN1W@Gk>O|AiI{d2Qu+ zHkwv#no?1!jtUK=5^X+sb`aB08GC(eJaG)s!AHEXgf2=WhNwV?=Rp zE8Q>OrE`dxA92rFZFLBR?Ag5Cbve8IYb}SkV*es}q@EX>GGH#QRY?7g%( z*cO%c1(~9h9@Vu@ebY@@R^C(D>M_Xu6eFUHvb&ai8{?|^wWNSiK6Kl6a@f>~l>-Ac zJ*w~Z5ti+{i$1A;(l~e4#k_l}Ad*uPa+wQ&89wjbPH%}ith&rzTU zLcM$T#rfc41o~

    3w#Cmc@s<>(xGM_5F*E-x_Tn7)P4jd;vMwYNdU@7xeF_GLpss zNhBVF>{0nCKt@!F;r94lcf4y~6ekYFO?D!VC}iC^K0T+t)bz4so1&O?T(^8D(Zww9 zq;`7vZhTE!jP*z;ICPw?TvzdU|7#^FGuL|6*Eo}mm!<{5z1{L`Y}OutVGL^TSYn*# zE^e1BmGnhprqRV_t)%$v4jqkeR1T`(-ja14fMvg7UAPk3X+8=2U})Tw+Er!z*9sj2<1{mRv{JIL_Y%bmiL*L{}LL{(-Q(vJy9zxt^50Nevnr?VkZ zlXYNamw_=-ULDMxADznDv(<8F$NXAx8sJ=lS#`Bt_9;>{KNjm!*}IuK+!ICEZ~u|v zYArsCN%P0`yl#AKUd=>PzGzv66l3yOKFgzH8)Ic$9d@v131)Oni$}QZ&g@z#4-T^y zkr6wy#8U8zz4~@Dy~8&zvfV3Z6?**P<}LQ8lZTu)D~2F0-8@zpZ9doAxlz2}*oG1r zL6v%u`3AN!aI`*aXJ!KupyN3fADJ>$Lo?6oVKy;NAE}?H6w^P!*b@Rr^(CB5jWX%? z6qkXO`R|cQrDkCq-}#Wwxu5f|G=+&NASO+8DU6muk(1_$!H`_hfeg+33a?PeQV38s zv<<73DnR*bI_cQ74%nU!Q2x37xsCo8={oGsq;FX1?)1$#Zw8J4Y{MgK@Tdn2^m9SD z23u~}!g6{aW`>ubt$-GOi`iN#X*ja!&O%HB17VDXz`Y?dLjbs9Z$Lf<8juLQcp?^& za#E&s$T}BcGbWI-V0!qBW)_%Z8|%p#k8GfoThxXCFc53HfPy&1YrImEqaF}jlsd3k z>N$YEg+=+7>elddgW7iAqDWTZVY)5ACXg`3L*n!y7y%$+*o*mynf4w0@_k>$n)Dz^ z>eyp7+4m&*?O0#A1GRIz$Y11}+tkHLfLIsTRkVQxA!7su#*PT<6QrDWz`RLP-s#Gk z9||4AOAP?%c5lh!H}rGcB&u2@zMD%Pr9r{MCHTpM5)UFvfxznkDFR?h&MxAEKQ$Pu zqkC^iFJrwmoIStuq%XeA{9a2|nv=F8Vlzwu2o{j614IHq7LSeL=8JfcVx)}55IjB= zOu$N$q~zS+r+C1c}=SQ-_e=~<`Y zd@(mT=~0-&t?}a*m78Zst|mG2^-lSffO-=kImDjpSD7UPn)QwyB=mDE2sA4eDW-m+ z9{50tJP>u{V5MZWh>y(TnXyU8ziZo41Y$T^e$0k+{6wM1ny$N|rDt?J=lrl9j##{3KJ-VSvt{X>5^%i=Y`6v{ZX!ug)kgOzTgn{Ymmc)r z5vd_Qx{Gw;D2N~n#I|C^c1-}A1m}SNMb*8BGyVUMAK$?a%(j<9%z4hoGLm!5nUWS2 zMK$MRnNx@|r)}ggQ8}fdM8}beP;;hKlN2525YlNnF3G;H_vgBPfBgP;?Q)ITJfFA6 z{UODpKh)wNUw#Nol&BnEKq{zLL}e2VZ}t; zA=`6~&^#caUcxD^+Uufl2C_*kK-Ymj++F)$GLAG|ayI|K45>+P5!1$#e5eOg6F?8g z(4WFD!NwaMjj9oM&l^A_`)PGBP24g)8g|hVm3k#4`AU>F5S!~>sH~wxhB$IHum&x! zofJPsrMzhh-}hU(pN?teN@`IdAjDVS#(o!d8NPCUyVqqg1qwFR)rn}B7BC5k^ZXu^ z4$W(909&^ zvBSq2{Dz|;AF{`;=f6|`?##cx->qw@jcL&JbD z+$TW$6%DlNH$RU=&r*-SAYvokPB@bwh>n|#1WfX8{39WLf?^>Sq=|(%YJY0?V$~j` zFYG7&8?{pp14$-h+0W_u+GX`!I9NjP#Vaj2uP}{dIGo+YvfD6{9Vv#`Kc#BF6tA3u z?(r;;N}lWYhFPCO)ZZJ3C4jBbcpyPszIz(*T;z8Tp?mfQU>^w^?(op+e8@mm4`Wwg z8wRVCp$*eCv(v=qD!XSosaIEd3MTJGwm>$~WqzDa6Q#=i{@XS*60In@(}=!CrRTsu z-SwM^hn4xh%fN!^;XAL?fNh-%m}19;Dmb*>->p}{WJ4Jtmq);O4rcZabQ5b66w>k^ zvJ+dl68fGMMnQyrTIShy1ouG!omc5aKRC7g;vY-eJ+ ze{FxoHC*D{d3@#8JN_-b7nnO#v=*J=TYJshj0(O|#1yGVyADa11DsYLF&8TqV()AR zU_VbIvhjZYz#Bw!@tQms;MFCf+_$J1{-jtXjGA`sgT26>_NY0BLSi7C@DK8cDX2uS z)D;t8m<&WX1Li?MT3ItVb0MVTdaVHE+k^K%$tT64N39w{r4%)!Z=OZ;ya5Uy0moW+ za4ffx`AXil5UNf?!0R80iNsza@Q_Nxn0dy1Yn6{_XRYC9UO(QstJ;Apx%~xZfY|cN zO!3#+jal}SasK@-wj_yi%|@B;J#)U#5Ecx+^u+a#G=mQrjrTkz1Bdh(@+^mB&t}o zgKgW-m2LYg-EIs_6M?^OfS}Ai^cfyleGb#y8`tv;m|@6rkhXc4UcU5%fLhZ=46D7r zKzaHN?8wtGiNf<6|4jnB=qf_It`J$sk(AK%Gy4`V=1#o(i)VE6;0cGhWmkR(E}^?8 zGSy_>EJ3u0=#ls1S8Uo%yAB`l9u|(K1d8AgdL!PLk1zldsc6+=z7o{lva7>$>qq9!rN6iTUGa+HO0AJ$X=#>n_I5?B&*iqbAgj{(nygx3-EQ zN-COwR4s}4>aR9$clhP@<1g~iZc`&LPbd3M?>`1BEJ7?>k?J!lI%5S(XUwg-EMKaF_{ z99e<{@g!@nC=_|jymTKbU&NliG}%MO#FHTZYz9w1s?a4NbJ&uD!LtuEiM744_5bis zDZq?<8T4LJ$C~v}+MJk<87rHUnt35bhGz&R@6ZZ-6ug}!$`x+kQeB+7Es%7FK(1|n zVEU#>MF8C^C{}UI?XPWjG~yfvGSq6&=eNLpV0+=|;UycIZ4 z1iC{3WQbmV(Tku=9K`3%zevl_Is7C~^0G0v;+ zc7Lfl=?qHzPX5QHS&MTTC{69XYxr@hHr(lE`|Gc9SI(Xt-J#)yT=hK zJLEKb`KWF8e|+CmqD0HtOF~9aJ+z(QKYE(23YGRCL2g@r|02!Y>>r8Tb=~omY*5{x zY*yDII9q4^q5EZ)(kgzQUUTgJ?->?Uh76A(x+HDRO(SXP#pl*`p&(RY^y}gnAwF&Q z1T47K{s+FB(aO;Tj`Tiu+S%eDeaGXWYXXPU_zq~&fbHd)f~-WSy>pXWlJ9m*9l&lE zn{LS6gvcNQ+u}dLoW4X~dsm-uy-M~Dn4|eMIhh zeLq?J+O1pBEYdYaPgTRCPBoo@)>|d}y0X|rviHV}+hYcM2?*)?=3uMdB~LMVm2kNO z)9|VwMSS?X!u8jkS)Wc!T+tuba6FNpZHOX~p}DhEsGP*Oj;yCvm5!`OLyZrxEN|$B zMR^(@Hj_3I(oZ@_m~E@hy4)La@yLF2{c|ZH)y?PsA-@mTK_f57@LClNoMd)d&y1I= z*^CZ2xyuJjoTB{Vkz9sU(|U2_99f1=gm*Qg;SGPwI_EDqLb#3wXVZHsA#HIz^pDvA`V90Iu z^~zR0+3g+DYcUbv>oq99bNkA;f}cIF++x^dgbb^9&B1EDjLRKSVU0O4wK9JMKO6S~ zdl*`HoWX2)Kv;dgLSV^8%YA`SW#MN791ONR88WAE^6GOmKWG@~$BgQx5Uah0GJhqs zj~{$;IvI|a23=7g?ZcpAdPe;n#h|0pgJ%v#NkZY$3S5_ouAG{`%u+2_tzJBz zapXPzK*8V`9gbTsXq-yRR$^2J=Sk{?QMm{PA;_M`vtw2y_3H1}g6TcTsw`kt$FyaC zJ)h{i#vF9(%1aKZhYmDLI3JO0nG0nHGpfSFl2)rC>OKsLbES44X?_t(%!#NrYVF0E z#vf;Ro|vc+M3MRMO#4xc2p+}RYhJ{c^Mni;B_%qYJJBS2#2lkK_g5{woI9u zV$8gga-#f_y3)^GU5N!cl+$L2BG$#T1~Z9z%F)8xN{caW`SJ(XeS+$%Q5p#hIg$PJ~}X^et~49l%C)R?1B# z`KqTL_TzazAc8_9h)@lnS2|IUt6C(0YoH+z6G1kUq@y)3M@Omh;X5zDl%_@QHhth) zHyS=tUu*a=yA=kf-$)rv_mmOxQ6A)ZxhBrY^I2F~^lrFTKy7IuQNQ!wAlDx!pu^TR zC7ee>l+(e%ia&E?Auh=icR9VBz{X{+T4@DB_tJRSlwND+!dt^AMcF$qE*E6`IS98@e zf<5eBYnG;wTu_B!p0Zg85dRW!V`2!?_O%TD-Hf(|i0xqq8eHAs8zh_q z^=mHD(pxFr=^92&(Dn*C;%`v<4{mzC$jknlVlC&hthbUU1Y4I-lHA^3-=B%HKc@@$*hvS>&a$Ir%654&4%(1CH# zGO?$Q^5Keijz|4U6z;;+H=L_=lvdV@N$1JG5HajPNX^`8qJjVJu{Ts6?}HwPnReu8 zwP}u}(&Ww>?D*jDtgtlgYN#5?$z9Ut=HnM?kttdoIe)aEWxLi~6oC3Si)VsmStI7E z`<`vLBkaWsHYB&eLSBh6QJ}W%?pM!W8Fu)hi7#+3x%`_lY~Cb52PHSEe&s~1YcWd$ zKlI2jE2{jy1G_#=(uErACRCc*OeqlT=W$#kZs zHL84@-bWm-Z)ls1yu5oyOUCcANzwDX%fCk6JM>i*Yb>4hekuhZ*AwXALIc_BHgk?e z;et7-WgT(AYe$^;Z>jv7CpRlr^_l+NcrZ z_I>*C)ly#fl=@GKsl&nwE|A56CA~K-HX_2d$V(hm_ZmDDxp;E##yJhgo_)Xass|f> z9Z~NrYO8=#CH#JbC{0cs+~S*fH#P_!X>IIb``T$?gX8k9wSup)YRI``B)~d#r=4<b+&pVVjZGQQCmB#Fbo|62uQSt{9NLzwT-jqFGk?PkYk=ZJ8q#LH9Q}Svz75 zsX$KvpF;r`Lf_KV@aw0o1v`BmmX@xc{54UU^$D)=)6>doW~Ss$wYKUz{y}j2-d6L& z)D&|?wjF3n9Y`T{b)u2SGe7a2l9|d6i)WKgr|-U?japD4(ed`#m|#d~SZ`GKoX7LD zL*7qQzeIU#m6|g+F%OnT06VkEU|eDpUL_`SXcIVqJ2CM3Ep?fW_G*^&k@%x=8|^hl zMit8hivhO)=Z>#ZUn~1H=&0H$H`2Ur`hwlMf=n&aZXvt$@NBN*rrF`t;kP9z7y3WF z=@_!O04)v$UgA&!$n&=c{UQ4xD_ev`Z^YTDFtPSQuGufCMJtUI`2(E(_@e%g8|N{M zgH!p(%Fe$3p8wbh8Og_#A7f_lHkghxkI|W-T9;@`$T-ltf?ZdDktvz4=n1*n3aPBI zDYVAQ2w>m;w7zs{%+e;@p(?+OYCJ7Ou1el)fRp=;%T=fH4n*09wjwUHoCQJeHw+T& zD_-ql9<5|1tjN+5QOO1n9;*3G=eh z?ZI<|rutK^{aX85@Qu|4>S5C6HV|T1cQ_c@EXxn=M5Il3h6Bj1dSprmGmVPMpcsQe zfmCadKQm&d`o6&#fxL>HVEh$;&h`SEz0YDHxy2&p%Rr3_e^6_&$hUsApUkXHW}F;8 z^Aqjf!xdfN* zsMZ;8JzxV7X*V8fy#Fe<=H5*ws~r5FsovgxH|+SJvOofia9f`d$;pc45_EF)$#XvlbA z;Wpo5Mh2{Xsy1h908o4sNDLrw0UIZBKi^DO@^Vq;!kyUqFNmY}r6l93s$BePxt*ut zgT2z?=o=~}j^#1p0&J*L5}pEyorHV}3lT=I38sQBk898;oAMu(Rou@T+Vvme1whusI5Y}Gte{r zNT}OOKe!?X>LEm?08F{*3-M(BnWg(HpH5Fg=^9gTdrF=+%k!Mk!>8Rf`|`BkQn!CI zDV%J9$k8SC0}QW_orhzXNoZ6Y8sS8f@L7`oT%jJD0Xp$B8fLkQG$`~iGjT~L0nH?0 zpZZ8K>y=7@N?4A8Hj8>PJKgR46_;A49eUsSjUy0gAls9R2(H}zD+pB}YnPIS^nq+A zc;^QK1qajai7Ay5Brx(gm3xHH)33$U*kEM0rv@tnB~8J}2K8AiC#@^i)tVK?r%uPS zPaAD4G{!lg!W0m7>o#Ol=ca zs+7tK0oI6w4`g@B#wz)zx3ffp;ZxP=SgF}gv^y7(*~6f*wOPw2$Nw^7sEmUg=xcL& zW*}o+4s|+k&+hyH);SsEp2~WPzIirU?K@qIots6?D}K~@&aae8(2Y zE$m4Ii=H(_M~ay04-Hx9+p%kT-jx!5f~^DL9BJMILk=RMxmzw6B|ZW>m?lD{bTEQR z2scrlg87X-J$~ciqqP@VQMwXcNfMqSi9<`s$o4m{+?3uRkjx(lSu^IHhEiH3GJ-I$ zlad!fLdARTp;0H(f8J8-d@H6iwiPn1UcG(wQ^mM4546Qs)sTmxkP(#}m^+ejA%7<+ zFPOx9tfsSgc>7VIegR3Mc7S2hNS!&&YJ7F5fLMoPL5u|wAxp^UrF>rk*jl!XB20rd z*#OGBP~r6X!`ts(40Ke=KVUG;qROO;sOy7}Ee42?DI~iL5j@owD_2o~LGA;i)6_Qp zVbV99H!M*en9eWxi%RAQ3Md^!cl9Tq=nm+i-TXYUnkG_l=r;aGUqF=iYim3EpOggj z&8(=GRz<8Mgm)~_Ns>b7?6}(|;j?{@@^r#x6izV0(bRoYXMb0Q+8){dbO&M!8M8C3 zDxz7|tjT`?0WA4HLqA2p@adc2mY ztalWw!Sefj-3u0uy;qGGeN9Ij`s5$XV;v?khdUz*1$3zn80=RyEedty6w^p`aiWHC z*!calh~y)CAZ2K9sJ@UzZv0)qN`L%be5{1!&B;HA9*Yq&#_VpUiTo#W{S_k^1s{<{ zd!rmKls1U42R30NDX2F^$T<4t6b{oP8z>H2Q$#P>c_f znHVr4)b2_a#bi>L^tUx-w>rQhE$}ysn6hx|`TKZbeylKR<1@X{XjQP>9n)diFkrp+ zpfhK0EN@)^CUW+3kf)7MaYWCx%6*t>#@h?XliCbw8qyg8=@!LK?uI+D)E?BKX(HzB zI>tdVGO?0*?@QbSrFbtKChM;&0dw&_QU`8C6DF^0|b(Cb4^Wq2cuT6r) z!T%v?0v!S5Z8u4weeI=1eK|zV(FD?TIXQA25GXl~^gDa+iErGk?XaUraY$OO@)ShI z02)M{N?!PVBC;(MNXssTsan&^H0S|}bbMM4_~$he}I4dt(jmR9dwx?Xn!{FeT5{B!;j z>14Vz9YVCu#Q_k6HB65W(}Ap-dqTkr7eGiCkCoO&t z@JhN8pbAE+IT|os0?e$Ej_Syi37`kkTi&784JL$-b=OP%K_3l;foK{aHr|J*68?SA zfSFSB6apZxS5F59puURNCA+@GLs&-M3_xef6_E!+D5wHd=aXl0Tq@FR^fyk*%c<|R z*slKtEGz$iF8RYZ-LXpZ$aNJfoT{}MTo+f6m_yEnBY_}py>5Z4>05A=ocTz>ENPz1 zxDfr*==s(CcM>;vZBl(~?tO~5k>Hl!hg4+c&}H*EvN|EWvcG%5W6GrYUq07f{xlWv za!@ro9*RLqV%>24U+uey5F}R7wg}x2MwHcgG&Uoz_~q4|p52bJn+~s9ET6W1R4=#v zsOPki88M8{nSn~kI-Meoej8Sb>~CaV+H_>in%XZI`*-c3vJfhVT| zcD5vGab|Z}xoP~p@DAFc-`lkJE_`;?wMOT0-$FCkCcSrOx-pw-(@vbTB4#gKyi;fM zZcpe*#a&VLIVdd_X&;IhwhNmksDPJ5&Tar*^8Ce12eTgj^TTcoqybK7MV1gEIaUi- z@X=JE|7E91d2!x1LFMd2IVJNbaQ7LXoGxwO0Cw9w+;SA^D=}t9Lh@K5n}z!@N)& zVRW^;X?5=MEeB=e>-3=yk#z9RHuie&(90{_L4}N_)=?zpYTF~*zb5VD+w3;pn%tkU z@%D5~*Ty?rY6AG1rQZ;si(i;c%zRE}Fb^)l|UnAl-= zKs|aV^TEw$yL}I&WFNn)3LcmIKWMG+KTrJ%gw`OrmQ?lRa(Z*oaz;TT-1>edpuK*x zjajDe*BbW|rdKr88am?42pYONeKYcD(;hJI{K_if{o{*)FTSYRr>!hZc3p};bpQN6 zg)b9lO96VLY`M{a2kk9>7yXP57U_O`K15Y3NMEyVn+Fwk^MTkuZM8NjAE!ERR^3#0 zI8Wa2?fWABeAfmK=-R~J_8af+)5V)wwOJDeMeSE%aK@G?Qg9z5+x2!_)o4`k@ZG!u z@Dkyu_1t*ZZ-pp+-kPZM^j^)cZ+YMr#=5QS;hL@G_Q#!z9-jR=c=C9{r;(JZn>RrE ztsVRPrd{o~<>`l!`Tfh4%iFVvQ_*p0aJ8dBUo^@!a(TJ+lwR*r2H} zu#&Q)>&&BY@AfCR!b=_2cAsTCu1Z)IvPpLRaIvE%jZ3{%*v zc;56^N|@5NNs@l~e*UA)R7XS|gY770yW@~pXX}{~`)w9ez8~ z@e;?KmxK2Yazg180<&oC_{`pXzyd8EA398r&{{IMSlMvJ@Zyil!5NfoqxGf(nN_b7 z-&Ook_1QEl*I0xYH{fsm$=6z}<3!lKg}|zS0*jfkn@=2C#wYOyl1JgCc2z-|Ots?# z*r-lzTFBR)-;8fw*PAY!lH&H*6wU^W`s|mxIT3D4>4Z)0DYdhJkmw~Z_o~)F#Vo#u z4SaSk!C`KB!q4H)Qf}#1SWoUS;c)v3o_N{E+)L-XPeXxTO3#hQYEf&`N z)cuk7o?-4~Hsb7mvkwSvI+kty(y?CAh$O_+dVtn@K)vf!4xnYFUAC0@)j$PzIIi$b z#pa3LAJpm(vxlDsyx3YkG2sFCz!LxcsP_K~4C!7le`NV_%;n8ZF$tFvqq#T-j$YB~ zk;)OA`XQBskrhjI+HdGht&)+elKS-(r?!Rk08=M!mtCFdZHyMg`aN59x_)d8uJN=U zWnoJ+`?yc2`P!VPQ>ak##pdI_HNcbNZ6#mcGpg}fAfY(KzpHTj$lmxg#ZMJ^_r01g zWwBnmHJ*WDTjR7<`vQmU#6e;99R5hpmETZ??Uu_* z31!!l-)Bs0{WPPH;R*++klep~u+-bJ6Dv;3RsGCGDLaQ`owqJBX_vQ-@@{k-^<~=4 z_PTu=A5s6p!OX8`caKcNHTJqlJ-=Wui1?AMaF5qu^U|#J4(E!kg>B8Bp#c1`XD<4G zXv1cDG7Q7a8B8!GS1Dq2==mVKaa8@qP;i@Iwal>1YZ*1ga}U*p0mEDS^f%^w z(*Cc-A;)tWjlm6|K7GjFe4-NPe01Dm(b<3A$GtRtq`!8dh-trWRvJ(0mrn~gL>K}X z{`X|151;H;54kPAPYDatc5586MC;>x&XlYFVxb(C#+!sn67DZrJoN0tcWkqSV7tE~ zHeVjcCf34}!%kxE{(?Fk8_`y`>MS7p7E;1|;7WZ$H$%Nvl#4+hkW6yM5M zD~ZHszrZHBE>;*cjyqKEW6RWetLZgU-5N(W7AI&a+zVik%O`Qp2c;4(sYppIWoU$)TAZeb3EHh{#NfEg3YkvSP-szjTdDpdflUfGi!=_xm0l41>|GZuRt$BVehUYV-hTL|Fh5(aiJMQk z^I}&r*Ylih6|-<={9tlLzY4rK!IIlrnHP>1&{?**gL zVz3(RVSP8dIEE6coL1*q<9QZD`;hherRDVy7n9~vSh zh@$o<_1b&&ge%C--mr1&)l-i%BQ}1#{MmL)6KCrms@(Nx zOFX>jd?dhC=8F=-bEJz7PHAm8&w^th^c>53nxl7>+**&%=&DELs=f_iSkCR@3~sgD z?{^br*RXBb_eHdnq{7PC>*K|=3rg2uHdiu6$BSb?2XWY$0MIkZrZm{8u7v1Zov9Ye!a2NA{h$N;wBz0-~rP*LsgOiC6!Z| zYH4>mZ61sl2fBnR4G0G}HYcAnPVjU+w0tf8Xu`>ZO0y^o|6z0I`y3mo1~0LWvUw%c zJGfd~ZAS*?4Axouc!%4w!%y~NEzG2hwL<4U>oG5UQxB{;JE!uBzgd9Tc`{(_A*Bty z?r6Kch#G*9C0xjATs+IScnPJM*yY)oIip96jCtZd^{9*OREkvN5Z_p#ei@!;x@!&EX zMU)VnmsCRn=_H{;8YJL6WrI#zy8BIRTPp4&5$_5$M`~@ES9A!okbK{CqP-O=7C>_Z zJ9{W5a4Ws5DOqi&aZ5xT>1Z;zjHQE$X#xQy$Fz~{(MUH|N{PBCkSwQ4=&=*U05r}c zA4J(;v=+sO1__Z%Gw51+kgJO+8@P8>%+j|v3C@qlyk>mg% z=LV7WP(VyI3#vkb_(DQ#e;f-$xGs`dA2_*Re`1qwXN_=JluK4s!s059V?A4{jx8C_ zhJze=$N*X`!Vg73>qG^kBZy=&icU6d1T1(o=`n%yEA3)U>;0|?hK=9lTz6@Yl)J7_ z0KC@LJ`sM<6Ho#_+Gzf#Q>pCIE{cio0(Ry7E?W_PiMxN6o^f>HzozbgK$~bK(guon z=n_Ek-4x212m|j!p{kHlSz@6AzW|m{B&I{t(T*9MFmO5fft>#gwv2*Y%na^Hg3m9W z++PwvoY3=+HvbOMk?DY7`H=GgP)AL_?JzrNBNYL0AGWgO)@?RcQH#h>phrNruw~9w~J`B`J1L z!NzRkjG~X1O)r4 zQmUSZ2A3{^I|4_P{<}grB!n9Sg%3sw;N#^4Do|nwTuO&nP^cMP9Wfxy7h;{oIz%aR zcd5j>JvM;WoSde_mQ@=5veNm<(dz6KsH6bSOu!s>CDqRCziW7QhD_^qm+lctRuj=H za7Qs26-7nZP+&+tgusWYaVuqP${wTvCFzywLcAs~ip~S^G1gdD8Md-#tC_s+<{bQP zbBvtxoVm{rFLhZSRFaM$WMl5lS4imEPa2#`{DYmO$ESs3>H*0hBEpY|aAw0TxUjNL zh}_GPny50BW7Q0svf`HV>LnZclh*HU}=82XUZ5;e18+F@VHyf!d z{5jfv6I0rEgdR}*yd(9NJGS?zbPo}HaHJ*&QVSk(fafUS5BytmrORl+i$C~FfAHl- zKqvSYF5%G ztxvrt<7Na&S(jL?JV^&I*Db76IaaAaI{)3UW&eZ9O4~A(LMTQ6Zxwi~x8mw`FC*H3 zdL46k_T}r_)HTSEy)+puhSnSM!Bft~SHcgyr6oV1OZNhpMn1{}fIe6)S$lbdRaLD* zuk>HeIa3VJ4+=A0kz*0^EVF|7&!-$ zZ>x@+%|*jY1Qit}8pIfoymxlbI2o*}xc(Tv)NLE7*CoxPV*0E9Ph&^C(W}lDoPwk z5HXK-MRt;`XTGvOp|isS<#&fJ<4=XCNL}+PD=O)PZh#;=`$2SIBFSvP9;fkpG z-T2+wSB!z50`fHsp~MDKOTjjQ1~btEYZ%gX{U`o|;L=+<_8B{V$V#f30>^M~INNla z#6pog_}_Awdqk42yLDf`R>O9-ODv$*e|P#ykC;b!^;c1@09MFX@1jY+WMbzB_b>j% zF9@zoi=_K$XPbySL+?}be;azp<)K5&D=ZBo zsOQ%0feo#4IsrNVsK<anSqwv6qyw%t>O11~_I$A{YUEz&u=Vgo@_MUHpKCZ}hlGnzh}f@`z|Zv5iP!Qt9=uQ}*&;d? z6`^qL*8YshQ~Gw&P9u_=*pHVpM`Tt?q^PiX4*K1D^?xU&A!js<>Xp=|uh$3SSIL)S zZSm3K4e^qn6$t=zFGW&ZUS;T%>Y0hVvM06UcMWW>ZXyw;-3|TmO8&pW7oqe5l`AeR;}&)$A;x3eZi5!Y#T<4~-W z8wFbN>Y0xk)S0VuGv?_=Z>8aSjY*E`rtDie@|ROHlv8GKmX~mM4S{#;ClTl5Q9O8S z%NcnS%4fZ{+-96$4eRhi+F1c}ktzY9j@&T;7kJ<|kPzGZBumCThzVLJT<<+BdlJ?V z;aH>RnBb~uf&Z`_D44_+q)f|{LHublEdc>*Gi8yQEWs!2uiM~6#$YQOj^b8^i@W3t zM-g=ASKnW!s5{B(2Tz%lUD=#XdhC4JED`^ar1wsUg~^0I*eDavQx9)CJ`$qvftJ-} zi2H$zJJ=;tNb20cZ!^QlR5e$EJe^H`t7>kc-kWXoCUT@tX#vq5<7_LWzkWr-rYd0d z>fYhXpclGP-4hu8lp$NlJ^p#Cjf)!o^5(%k`N;yP4VPBrCn1{ii;jjBPD?8N`KZcP|{@1$E|q%gi;{tErm% zrnGab0_ljtIkVGtGM1l5JwK8+z{b^GZU7~t&>;te(bY5kB+?5Cc1ID*upn+b38KON zy0gA$=r4RFhx+fkX}`19;&G+m+Q}XFuEm>KYUUAnbQv#esd)TvRcg1I5ati2q#+0Q zUf7_yA|rOk{0l|UO-097?wSkrf0!F|%Lt3V4fb7)HtAK3?A5Z6HotPra-D;dT#yt~ z*J_>sB`=}d!TlvvyWmP0#tY3BNJt{-{&mw~DGDq`45|FtW-8WR9Q`?{m+&MEDmUSI z=jy#W>>kA)>gFo;+J-044Ln#3*FQ$6Uql2Ly~dE0(Q-p~f@&C-&F{OPFIIKPBkT%s zl~n71v(4QMTa>gtJd3gVpxL51x82`sXcT>L1KDxp*J%2Cj@2{V) z7E4t%J<23@xK{7};M=t0oJ0OgiyRgy{u#%q(Y?5KtC+CkrKshZfs!O(y0-ZBpaD53s(G+>-}i{e zGTIg$Im1TPW})jX>A9Cm8;a|W{6q7ghx;Gn#m1EsZBLniofns1_Dx~}NFjRQA*y@v zMM1pTlls8lUm|)kL}|A3cfP)}P*jV_LTTK)2{X(Q3hF~A$Bu0|yae&BC^)kL7CFus z76ePFJJA-0z|%GAw*LwskdH$(@nN=?^aht(hwpw|{V;s~Sd29UzG6Agbty0>mdZG} zzs@bOUQh3@x161FDcjk{{d(`K`4SbXG#_yI)DGn8=j+|S_7Cx5E=$I7E61EZ^`dVi zjc9zPL5ULhOBZDA5gnCzGVby=%jX?_ap#JymZn^QogEP3P&@A_IyW(KUf zT(urs&#$*EC@(0uwyAws+UKirV!eeVHprwjx9##U`%W(2VLq-??nRvT1<32Yp`{M1 z);I4>M}0KO%~Ix(r6$+5yD98Uf8rhs_gw-fUn_u4IkCn z`Emzv9={%2^_c@z?8rGetiH19A$}4ivQH-^Jow{ruDWT$usN9db6CClNu4=dGLztT zhJCabp%a+4{wMOCg`sA&(*3TqT;v4pOO{C%L#Z58m|SX+~%Gk-)gJ!81Et`GL_Vtpa%Y){q3(;VkbJbjLwe zEq>MK=0B)|+~KE)iga=%&lvM}sk+-S@+z;t4Ob zhs@EMmkU!ypj+5*;=OOBl&Mj1s(56=v2NUY)(NK69G-la5aDK8102M$#WE2JT0 zsWt+TT{$itY2VL$95s|sYgTMV;pXs@=%{;qX5!~1jccnOcb^X`MtRPi7)uzjQTI7xWakeOzC$n>G2Ogx7rP0w#jfb>r2=yjmUoKX?Rq^8+>L z#T*pC6llCENimH~(ARRus}jNgR);K;CyVzyPVmfLakm=il*9)ROZ}F~h!a%Q4ahgg zqXirORj=Uh6XIi6uZ%ioPCC0FC{=r4=iuOaC_e#AdE+$FvLxZ;HUNr%i#!P9BD}>3 z9$XS!BWtNye7F*>{-c>`|4gRjaC?Q#EZ|}N3<8??_Wf4kI;}rhvpE=HM^SKQ<(2@Z#K=CO6WhYX^r*||e`!(a0jiWb5-X%&miWr>v zR>H?Amy7d65AT`%xR__e9jz0gOl#h7@uQZgCJ|~Q(OjDO>1M)UhNpEKYj<`VSAU(h zEcV+f(O^mMPh9!0V=!KFH0Y@9Z<+_;ltDIJnh4dc%rR^p$6arDrv5u-%;AR<{^$j` z+5(B`ojC)A2S9GTo8|9*#@9;v<9=35dEw%l=qTqfpeozRtk0dKBSMDVd;YpB#@j zWH-M;JoKi~wq)F+D7CFL^I46n*%3 z>i~xXBMA2%w9|p&X_~Yu+BMVtaG*-AXQ~n>*qBw z>x{-S-E82;jKToN-HKL&jginJ8N{-+uld!V4IkF;ed>|gnNj-U_E~iiC;osU?Vdd> z)#Zz7DgkzgeQ%3etm&vANT_ml{gB0L-C;54yHy^nd)P0x z%Eh3J1KPHvq;~GW1O0GytKK*hWiC`Yj`Mn9ogMKsgsv>8uXA~|#g#q7KID8sMT{OM z>F1bco_(Mh&lxnmpjjM2(0|)hfwa6A>^mgiuF<>faeJjc20h-`qi}z@G9jqM%vF$? z_DkW~Ms7BiMaPJjPPzEbu-SCrtw}1HdT^DUqEkxw(`*xI-@*uh^ec@JkiSYm-u-D% z=OH)5iVrQVMSooC12M>Qb_5t?nYH?5?wz`&NHO5tTsqPwO};N1$*1Fv(^

    8S_3{ z*ECtlU%Ni4{Z`;qp;0T-i*x`%{N1iQF&V)F`dL(wR-JXE59i_i!z z40b;C9gdHcf(LY-`~_$H!XViYMkK&YPh1$6LiERc87|BrgvlKR*B{DWjLidpmmsj!sK+8ykVZDsuva`4P=Xs;D%m z&5g?9LRADrq9F=w zxcyXdeL7k|krD?<4!2$Qx#;=ckydBxWoP84Sjc zIVy~*yqYx_Zt2W4^$a3x1oxpP3sRd!lh`5PWHn=scuN(Hd3I{kbv+S5QAiNz#c~iy zhN^y3m_rZosxcG-}vNM+ZPH=;+@G z=#y~|+HD}3r2IfCBh2`}VyP#+vc4=on1xJ@V?;-_95FzVUNItt`IBad=&C$V9-Jh~ zmTjin_0umnY2%hg3!1kZMbpJkIbJkYCp+KCxiD7r(ANf{A(H5;7)vBGj|dTB&n38K z(a8gXx_zx1;tWnjqZt8HV-Rf#dv1=RutrL7*DgsPq(?|lpVQEI8u}%@e^-SaYNTa% zo&-}U!6Nm&%2TH#{vTWS9hKz&2Y&xzqaxtOjeDeqBhy?sa;1f%(zL>j8)s;iAP8!v zXjW(obEHiyE8947SF~-T=4gJfX;yMyeShcN_kGTNAOBO29+l<$dcGd7y-5P(Xyi!3 z1SgQl36yX)Q2Ogg3aVwu?G=a(^C3PWn1$#9QgoMP6{;X;1Bp8wJX99TOE z*iBXd$qHH+itguDNMOa4tcepH6HF`bP~7lMl>&8q5lijUo%}$|o(nDoi)}4}J&^+P z6D!1e65M7URDOURQ)}ckx_6Y(EC3B?N;sKOyi(?=whktRgny@R`z$}zMoTR|_=CPPpYBTb{s``rKz)Gn#4kO_}m#+6dO zyP&KY>GIe=2T&JqVhG@U*lK{Wap>B~d?GKCk4zE30cjUl+rj-ze)E~i^8l)X5-39! z0^+c}Pl`7xf}p1F{AIAw*3eLox?v5P?^z6FoP-0BG28E3I(@MX`OZX>n3@xuEYLa4 zrJPQ___TUIS^*F7LDyt6d2}-GZt=z)!>99xyJ;Zl9tB{?I?KmfakMBU5@e0UFi)}{ znf?U%aN_7plb+d68I_+fS_A+Bmr1U0JR9Xx*$h82Tt$5a`x4; zcK2)N_M)*A_BNSzA|07F!JSd6PN#A4PUWFw7&jEnS>(YMdAru2a(W{A+Ctmluh!|X zHweqAiw0XK2)^kDU zb`F6|bmBx&I4Mi47|Q+Awx~0ACPL#be{Vn+5nh!_FNA_3{0uzQ5|PX_VWn?RL~~;n zITSJ|jX|S3LUI<7Xa2rCn#2XxSLsZZ)i%Pt#pS<>T4>}pa1>_zW%-TYsH%`>(q*9!r1K_53Q>J6yK?~@@NUr*m}YXy5xVjcG!hqqIPDxsk;%UtVC zQ?!3>eOqS5ih$j3k8adeA#su@HEBfDpJ~+2sLqgmy{SM_3L!p`IOAUUBm%iLVgc~S zb7Sx>IW$yply^Q_?5a3zltoM-CWyb!oI4_bRd96na|>wvq7M6fH2894n#S0cNao%+ zgxs@gCiU#*Ln@F6+RH2k7$u|B8c?Fc35M^lg;a2Ckn_ytvA6;z9M4*fN2ZBUJ39uxpGVR4RAZ7A z!ma1h5io#(H2<7bV{kt>7vQ1Usd(NlgR8wDt=uzIaq^#1olS`g8+23eWM-06QqII3 z!VZ;-wyH$IQmA0d&ZP^C$OPrqTT?lcN&jE0B%?Xy5#n&bz~vzj&%7HcfWE zl!QtZxxE!3oj37{D7@4jWEy#r_}-`u+`l^kD;SRUDEwfG0Unwp@}#da1^Yc0)UwGu z1_?E*G;L6Z9GncGQ63jYWsIbM1Xn!pn3dqziS}ou*KrEjB&z~`FKN@8rDxo=$=tw+ za(TWq>7nN*(?s4}xJ_L6lhhtK7{t2ctDi0NrZZm|R9WU0BG(gzXtz*_H#Vz{7^HK&p~xS9B*umgu@7e9Ua?EBx{{h~x2z(nJrbhzu5KJ9_mnpJ2quFCP)$GVw9npal z@RLy~9zDi9n`Ewo3&)PZR5HwV6#0!gpwgM2DR+~26gFhOoK8!8cs5mC%elt~mCffm zfLhUTnF5#;qnR)OScR^p6F#TmGm?jA46MryK`)ufrFrHUul$nHgOIPJd~tArK*#`u zk_F()c<+&?M~7&n^h7>#dk<6v-MJwOwRI%xllj+o&tE$T%Y6T3(M$wA4?+T9BIpLn z-Tsc?wV#_qr7VODP>%wlDZDK7H*YOxIxyxyg_>1BZJA6MEpIgnfZ~}7Xk<14RWOXC z)Nm8XFgSy$Dk}h_@B;Lgy_y9<54PmZBTNI!Owmw0nF*oih5lt~GXN_xHzyEfnuUzU zv$Z5lRXhtX{Tfa|IcI%{KX_j7q1=f2)4GBMcFfKeVA);fI}Cvjvx3RU7)!Q;q|9y@ zyh6Pr2gQtxLQyOV^Zz?82rMiN0K;O49EbvErUA61%o7iRxG*h-%d7*T<{eN|0R%0% zdlm+Sx-jl#(#yR%nq!cKhEUUC=vpm6SpX;vvvlcbRSDFbR+fbOrOpJ0B|LEe(_`_g zeaf!`t9fb6B9J|{bpdZrTc9qR;fp9eYFX0uA4Y*?;1wJgp4H{Gly5oB*}gQFns9HbX6m5UB8X zDIQRphu+u#EzB-65|`(bP}@5&b{*Wj3fJy{l6#evnHA8pyk9mH7T7(bqnJtzK(C|h z%utCr_}UCWfwm?&kMyU1+>$BvFI2_^ zFOuVc3Y7JEQjkL;y591tn5Ap+*=V3*YB}sQZNYf3T4#0c$N$@Tj#fGBN1@fJqHMRz0&`xgd;>NZr zP1A#|ZBDBrr@Xp1JUyTJ;m0TcT+36pRn^KB>W#uONCJsBr$WKv_~M`2{J3EGag|Aj ztdEO1BlLP+xcesV=q-IKG96(=s1&4C;@C zHz=$wwsd`XVzb)HEcaX&y8P_{JKovYOECwTt&2~U^xr*bD>ppC_~W)HBbb31*5{J+ zk8(j~!VtxwR})KV8sy4%c_KoZ=CE!1n}nF%tZBrf3Fi`=+N` zYDvMf!Z5d~9`CgVgw!y;{q99-$uH#|)BPKBC#Ls(L4f}UZ7TkiwELK$KRWT?_NG*` zlDPIF^Ft}Y(c2m`M_obS;(3w9(W3XD^So>6mxYj}2s+Q@I>na9E3HB2dGDGf%htO8 zo$_uewrX!oyZWx?b&ige>#<;+lO1hMqa7}@^oZfky^4rC#%G+1YfjhNeGNQw<^389 z*N2pbv9o*Z)H06u<9FJeAF;k>bK(EnQ=dt2uG0B`HOpq;$<+(s4)FimEaOmUoAX2X z6Jed8)NPhA;gvYNY^ysm-sniX-x_v`n;EkjTz7aRV(2W`EX%<|_#G?X+}w@*IeF~_ z8W?B^{MRh2cMg>LfX(vS^n>T9{T2Ez6jk4zufHb@I<(35g|lF0{7wd#JYQ#gnSIuO zxz^Bcw=9;BIeHmvmUk)tnf5+$ubtA~u?3-dI$=}%mKzS~nuR(S)9r3m?(59j>b4_$ z=6?T)|5AK+FMpo&MN(HvpNbOtH8Io5M+3DYM$SJT(;^M_maXP~EYO~5c(kSPxBp$e zH3i3fUtBwZv-I7)BzydDZlnY9^!&eO`5eU$XPDNH(|MyyV`gfMQ%?gKUi;=86 zZM7pQm)AV@-R$+mzG16J1RxPdyj?X) z<$2kdm+t2WN~AtGY}|g(d*9)8hmK5Z@A-lr#(9wp-rn>2GtqL-0{XIN`fxth^!_$N zB(n_XDUq^J`uJ|RJ_9&!urG4t3(mHCc*@dtkLQ)RmC(4#5J$=U)6kH2rxy>zdbU;K zy?(!p!07;_sJWB4vofyLU6CBtMEfC8!?}TTQq{(F!kkv)4@G^gR-FU!8P@IibsDxC zrlxG{HXHPhJ3eT**y-xTLTY)OY`%i0{E>dWN9vp!et+d0gaS30l{z+fKK?b0V=WzS zto2-$PLF6YBH=;ihyStGZ4C~imM~s;u=VZ1sg9QGh&)XD!`OYHtKYg?q|?6lSe+yn zMnA3fytD*}cg(kcJP3KSO9kux9nJW!F#}qD@483jsk>Tf17QN=n$trg5^vQ_76t!x+d#T9x?iOG)q4qL@^}7~)u1YIC3!7SH=f+f}AhEfjgK4<@zMreOZ*&|uG(3$?`^wpl;<0eS$Pi7n0{0(_s1 z|3H#%Ujvvby83SS&5zQ4gCD}zUac(N%4%Cs?!C@`Tf-n2r z{7*U3?Hgqyt-M{@rcB)h- zkztMsyN28aR<)&XefPo}Ejz!3)fNdAlL&ux0O$XMIgbhaov(-06o`H8a&}r@KOb?b z;jFLzJ95B@*GroU2l@@Z%KTTg->=>#=~Fw3rq zrqahN2>ZS&a>g@LgK_o1@p+@#9U|XL|1js-b#Jm6zBlXs1~?CX!K65`wa2574mC!Y z?f5=SCXM~-(S_Kur76P!;o$0TZ%l(KZ8ONqL2a`h9lDCfK4Y|RgwL5we z^xu*Gfzis=EpP9ccR8$T_pZs0Y`Jw8pqKlqVqyo3H4gLp|A2M|nRL7tw~QhcLaP1R z3y%~wZub4QP@Co?96zl%y*2}E#oecM#-i;*J-_01bhGt8ka;dw@6V;Ww5-^wLdrS7 zQoiA7BJMNuCzZtQiK^~X+l=p39H*}{-D;}t_m@ZVnVOx+NFdw{3~;hd=fC5Cep41j z?|N~3vY&}=(}-Y=;+H3R4K2FQ1pcLUMi>=)f4?Tp!E3*&F!6~&4})rMo60C`ScwJd z>#41#K9d`_OMT+ybgt9&1?BS;n86110w2qtkFso}hDvgmqN{lvsDC%_PJ}--)9v;^ z>Gf6mKVJK<>R6~w(gTMJdl2289HkY16HM-PAe|1_V{Cu*ookoEO*s4!JFFNLCuHki zU8>#ivTwC%n!l6CNR2<$U;ZT=J@ecT7rBw_vtow?Hvvmx`>fV`%ipoa_!QW-v-RH0 z=Q#g$bD%0OQtgFeL(9(TCA0#o??};)UQWyR!_V~d|CuUXAFw5g<>PHL0k5GMHH01#zP1e?_s zBHBv|i5+lIouWIJLEPrNP@|1X6i zQVO18tjw`@?A5MoZT@j71>{b_U{OIU3W|tYKhNosDqSWj9m6YD5#cr@0L+%<|z z0G7;k3@ZBYT#;XaVLU2ZPQ`v8;pR{)pRU4_dy_W#>bw#`kqhe1K6p4k2yI{08pQ@t zYAglHlqqz}l=`JnB2DaHd*&Q9dy<*Gw+GWpRpM(ZT>t7;2PoW7^Yeu%#LA$cF0CrV zX%MSM7ICVwnsG~rCK+&NqH-jtYO+h0tl%Lngs2hS=I9tPV~cpOd#Wt@C$j|pKUexc z7yQ>KHV!lsDKNgY=u9Ey1*PI?1y)YSUbwh-r-t&7MCm+5v5|`I@kMh<`!1WH#l~ow zoB{*EZ9N&TH40>eYoT=zSXk|kC}@HVXVPPE^s-Vf-Ef>@TjRSYrEUE;GA_?P96D(S zT~PbY$Nj)#2@1M?+CaFZ=n@_is2+T2M$gYBW`>A;K~fI1{MSAm6{2_1y-I>mTX?8! z0O=~)M___+b@hTv)we+WumA#{SNvW??i8YxFGU$HU=G%ibt2SkH?93aU)lL||AXnI zT&Dx2y$}N-kjPZICUU9OsK5OEK(_|tfhfOMwpqy{HIwX>PfSe^!9i~vMS-w#!@z9? z2v#*T4)n&M=mQ4Te1&$V(y&N5={EU{6Yd)YxB1EudlUTJ&&W)*ca#+%PyNe3(Fpn0V(V!^e}b)e(5o)0sZLQqTyOSQ@y?5_C`f(TM|hY=E!mI>*M#0e&jex6Ep$$kn`{U?%mmidc zHIK$lk`De|3$o?~n?+DNDbz*;H6lV3_~6Al$O0ow1}als5KM5DmI4GX2JkYRz6fFr zAZv*DWRBVkD?8coJ*pQy*PGdGjmEeBz|B@34{ffCCHtug47FOcdGlPj%b|cpu(nU^ zB%;m9fPxICD6K&^36)2q$A()qgBrBtL2cl=JRt)xk}62}%C!k#aBFMj-QiY>Ah;reRxU2@z%8V6VKJLMA$wsx0D=hgk}eG zZ0Q9jo(QrfOiaH-sf(}RE&}?W*~gItJw zHL3;n#6EnRE`RN@e!!bSYgw7TD08lZJRxJc=z(I)5^ z7Q@*;^+oMS6aLIToTB^`PI2sv(jj$i5)dIiZgC)A>R0?F=#+CBv*$UcSE4j*i~uAM z4cVz5qtT{rc&;`6zaH?ft#oDtQ>niGNSvBmP9gdl__f+&T=DH!F9g&<6hzQV5=(eP zzGQ7NuL5i88ng3B3TLRk6Hth*fT+?1r8xpsG5|8YT@s}}Y1U8!`Pp%`hm&dt`;$;c z9vcu%@Ve;q(M!rk5Is7u5|8Zzzn!LX5+pp0wf91!@?*U6pIO=^CQ^kd9C)tfr48LF z!=0xq8UBiTkhBfj73r}MXmU_LJsrPp<_b8=U?7H2`Gjt*{X-4Lr^ede;2p|er)VI*1OJ3f;viM z4H_v=2(PAj*TXHbZzRf3rRmaSr8Y6Rrb}S9N2yco>+cq7z+H(SHi@ea9 z9PMKiFg9>2LLHuT#mUpXXI!5zQJPNOt7GQ zA<8-Bv3+Y-T-ZiytJ8h!CIyOAM9^T=!7pKlCb?!o#d{dcVX4wJs^T#*3`Q63?y6qw z0i2|@dK)!V6ZGU{P5wr#M1|P6>gd%D=kLsID3)6IOMFcya>BXfY~hZcIlZm&4D1U* z_B~NO-UhvbKDdY`e4hZ;Qqgr%1!!;T5a?{HDnsj(<$&5O0@pod{Ns1vUoy@GGK}zE z%Q}qzj{vM7qFeCg{Zh>F%i5`Rds|alR%w>>GnKmWim_4%`B#5P9E2bN%$VyMNs1xU zBO1v`iOt&|+_tjQB`((cz~XS$-*H)C_>W@jg=#!o3GgJ^bW4uj=f^kIY2M8_ar3hB zBS3kaGJam9;Dm>ikBkS033Taz6A^uIlVX*st#OX3^#X2!h_@e&Uz6k5kr%uu#m<-D z=fG^)ri02PoSwaCMNmWOZN7kD)Lh5(QI*aM(PonV1JHhST9k=B~vhY1%L8ZP3T=9LyV&=?>wQEcw89MZ)3zRfqPL+&__N zxbRO)kI&I=E!kOjvAOYm8N3;{K&dFOeROs&eopSTGioozdQtCddxaja1tg=~P9l{+ z*x`=4(sRHLkKzgyPCp;fTTsb$4JiXlxdQ5!=zKVAHW3MURm+=E8kQgZ!Ty6 z-#^x@x$6X0!Djn25@UdQ?2r_uB8K$;)zYU*Lb*nZ`WWF)jpkQxUJ$oh^~K96uXMRO ze}&jbWaS6^oX=xYcoz_P=i(5vaje-d1isngis2(!y5y%qmC*Y;EjD(-`#>v{#5?-TLo!>>Eq98 z6Cp-)#9`{ydm8mWxR;*?COpL}+w4+m!~bKTjhWRYXVqO7q51rW$4GdXDgM~_%<;XE zUGMcm_Kw1Cjuxum#QapvIh$0w)4#NkRd~f~A`EA7%;D1IV6DMB=4fLPppTz2z6q?9 zAsZ?QU1FyQC}!Fi-%w{|5k6Yr@#=)FRx4zq7Ylb+s8XJ#bY~mhoCx0~VGal<4%P3N zV%GOwuJ58K(j@)E3c9)yV8y@QJ6Y+1<;a=LW3j4vtv-`g_49T^{0kpd&4%v!NC!nT*vcR8%JdDvb#i1GLti>jC1tb zobg@npF(a@jzwQmX~2nvmE%wUtG0rin1y{i({uH-M!!TQP*aI@8wQfq$+o%#A~cpM zIV8iq^wW@&t=`{!S#?(RDFxqWH`W%M<`i-K1F*M~LQ?Md-og+dft=;YHx(Bcc7HS4 zs0fJU9R*9kl2xksV08TXu?@aghO?k0g?i!J{^BxO+oFSx7O*gfiTJ~(zr%9`hIk~W z4O!ki(j59Lr_KFGqbr)?H-kr|2d!*e>?==WQ2FJPl<{?PEXL9 zm{bCc&=0)U$}t9h0?MQhS6TmGvpnU42w#$fB}l3pOS5I)at7WVJ3%3#=^|>}R4`j} zO`u9X>5(Pp2G-bd;^VVhX>!ruuRqTH&tAU$doymk&u-*nh4_KGnaGnH&zz5x`h^`U zWlVK@Cm`?Kaz;7sAI))?dCb#Wo)Le=)tlG1t1G%COSHSor?BVQDH4O5CGsEd94Ed- z)ZjDpy|^~^{j3%H)U{Q+hiVSHWIyUCGC5Ie9N`WXMrympaTVHq>&khiuApk-D_{Ed%w+DEp4(1z`InqE1$k^; z=fGzs!(ry@o0p&6O#1qURQ{;M+&$$RmEMp1t^Fva3gS*YM}`^IGhy!Tlbn5_4vhmU zYvY$va7vJ00~IjJ3KF{%7@pkgq2B1{d~Ny4Z6cN9I^0;=-u2&!a_Dc~tx2rUM*`sI zA__3Xog~8pgMTG9P~7AA`+_j4twH|&(eeEk6+cRu8joby`cQYP+r${Uy(MAkz^}Q+ zSL#cjh^@#7&@z5MIT_%pJPtO{E|q5YB15d&8p7NwKN|+n8F2wfQp}5*Gymbo;y|uJvC=og8w~tiyc2gTff<83}l$q1%2w#8NK^8 zqZ2D<{7iM7)>gq)H#S^H2a{WHzUI%)H$-Bp?j04)F-rJg6mPal;4X0lz1LBoKDq*PHz9?@&!rgp_%Lyml1I3698Sic%q^{RACu}dgg4i6J)H@^Dr4(WX zLr@r@DnC4Po)BY$kK!7Wntlc7u+RQFaj3NWZ_1G!J*!q3?*4OsQ667=ZZH@fT?|1A z;wrq&GvXtE+F^9sW_4 z)13Dxbxyx%zH-Tba94xyC&pBUZodh zJ0%*nv|hB&xEQ)rzn=#ccwzMbz+vLH+}2ALXodNs_lrIwAXg$FdL8M zKgJX=+P3DK7<{2Mdw^_n#0=Zu11Z3D*c)5d)S`@(krCGXyU<_jkolAY-aa|UOR3hh z#ODgtiQg`l4unVAoHiSrdb;7{qii4_l(j*CxY((nysz zf8@p$8+S))G|GoJSO-&B{u_ZKXRQ;Jr^59kmJ_z26YhHnCaY-;GQ<6`IyNakYj^x< ziCGtykzh8>f;EZFC@lq2}*v$17W*^u|KFm`CMD%6nNmx;G5n+$pyBsy1-CHDg-zL7UE&%|grlExL(|98MM{O7}YD5wF!mDCd`mOWa=!eAsYMIWfbujvv z6RF(xfcIV+DM9-#u;c5v>E3k4^r;_$=kfC9sNFpigOoF+~0kW zYocL$eINk`l8(!xBz>B4sm{g2)%dn%{IP(>fX;1EnY;mOfFy(4-VCjdqtxV~PwP3I zzptFvp_A}FYt&Pw5?@R^Aowi2T(oa#c(tDx##$aioOzJVW1NSn;C+e}Lv-IfiQH1u z8+2b-&Hs+Dd#Ln6eG+3G8Ctsm3%YLO%NSv3sNmcb7<1s+@M{)@la ze|=_g(D{5=R=iMHrm6nz3gb0D&sn^xCGLO)HiJ$IU9mEO#G#(GPX|wQQu9A0CgmZWrD3&Pvin>|&mJ0VUiN?{2?(pp)8d zL%2slxy!mJCCv1$B@yq8a#Ibz*hDvwAVfD$lA{{`%e9pDuV))k7pS+!1{U zzpwR!I)`j@Oh<3-ykP#&_0kwXa~S^NL-``@;KvoZTf~S&Di_QLt04BfTu$v4^NQ%G z0_v%3W^1MpNsHp1{aSvY5eg$7xG3@ZfFH8k==m#bn-L;6bh04hWdC@d$7$|FU(>}!bFKox4# z(G;-I67m>Pykh!3)mT(+MXO^hci%h2wxIIHDvplmiVnvJ6UDTefL$R~7`RuoL|pR! zUCCWx!xlJsyI1UT)ASy`3ewjR!oBYITUNl4@2oC_#hJEspcpd0RI=~>x`R=~dSn<} zhXzse;xW9OHjup+crb1Fh-{e}h?6xYvIlTwuj*+InIItBx z=M|7C9Ud8ERG}rRu*Z_&!pmTAK}dBgUn`pEAG&zULv-s;%pQ5(7QF{WYXkUJ#lLuL z-D9P|>49rFp7;pk+gg=**cOmr?J%V>@EazEp3{-r@!aN4q_q<2c`6Fb0h94a-pBnL zWT49o`o8}xVf6fwKfV^#4ZfFxl(l;L*%DtKox~HWG<-9CejEm?=Vmb7;wIp0C*bQz z^^r`Z{WD$1J*2!q@MlEER+fiR>Vt@Ix1KUBF;nq8pfGG;xF@*N{e+bmMkZ8nsdYB) z`xw>e(NoOTBq2@A&357C(zqJ{xG#S%m_^3TBWA45=AUj&BO)s><$=R+&tjMXo`t3X z&*Ou|*KLbhSDaojy|oi|HW0mtR=Yt$%N=vak1BO5Qea!aUcO^o9L>uNM2wN(p~G;q z71wPJbIlZyTNXJXOn3l^W8cBTM=_BVOhx7$^zgOAA8y>&9v_<5=Sq)CrvrgMDEB2^ zq|W-2#DVE=u`B1q8{ggCgG;l}+YGE|wYgK&?7h8hijTfACMsb-!qZe9|#f8!ZfpsWn`o zW)^vBg6Vss%wa1x6^-gIene|oohL(P@Nek=045NC0%7u;;5^lCkF5$liF#jSq3(>^ zo6acuch;MMB|RCLDh%t5i(rUW=Ph#6@oI)NfWL4IXj0ujf5R}B3}tOP)p5-CFGM*O z$q3}pqj-e`N{jGvF4HuTfHWX7aa1NtKMGBnU?%}Z8BfdiS4X7+28$eO6qk;+l4srs z3xjlm9CIQGq2r>=N@B7#qS1j-mnm58+GuWvA$9`L2`s0H5XnMrRupKoTOOKu@-M(d zBm9S1fQVVA@thO-?D)oKQN4f;x_sNPS}gr&-B+aJ2QG~a-ro@G=^SmqpxFbBwPXUM z=c293yj_sB6^M@?5cS%2^WI!=zF>9cDC`Pl-7@`*ev?Wtz;`krxP{T##E{{ig zGPp@GH}oB1t`3>XH~6QyGh_Ut$`JEF10jmd2iW+sBbJIeQHBi#wOsn}rtbhCg0A1g z4LE!-g+{tbe|h;koJ>S&M=>WA&a=rEOBa!S4$n;@D(M+1qG?;W7gi|~Moy`l5v zGzJot_A-v?r<6t5c-{^SsY*V$Hr7e!r3O{Bt>(Vo%YeFZ?vkl z>hh8P1SSS7BJoiEqt_g%VjcQL$cnOL0@ud<;Z}*lFE=EW;+)pOO{F4JE6SB!0OJWn z&!Ypk9>2DE{2B)UZfIV%&{S2|Hy6)Ku(r&@^V0YRG;oQvu>AP&HoD8XucO<`?!WeV z52FgXtxZP?EX~V&P`ht)KU90A(Ege9s=r@qZ;Cg}1qp3V5+8XmkyjPu1w!h9#a@o? zzR6^68o~EoXuO%ZS=ZhcRYLh}BUhdog(?>46v;Me*!0tw$Q0>Ra-bt=+mzW8Gc92` ztp}Mpfh^$jvRVEv+o*$W(=!WG^wDYeSth&#vVt>}Avit9=B+sDkrrkA;-Ow59lTMU zAZ5K3eFvZ<=ypqEocq5(xP%Tq4qo)VbVJlUlL;h*8O$`a*;xp~|G_ssV=qK}(I7G4K?PeyA}a&kD5X+`H2NKrci ztqb|6o#0dn`S|Tu$dk&4t^-^v7mzr1h{dMR5ZWYgY=?}>w&pdp@p8rB3<)Ubn~p79 zV$Xx8)I6&fbMoUeOi-s?As9&Q@XKfLie$*WS>D?am%%+brBO(gVR#{6K|eabX|Kk9 z5i^h`O%ZU@iLNi2Zy*jFO&06zGicf>g~UtSDOssL1xg42z%kh1Un5?Y@LcIa!h3E8 z$@j@$l$O&z&~#1(;CV6cjw2)f{6eV^VX1^`R4SKR5q0IlQ-%zAB>5G>hugI6XwzYb z2X{%N zx^Q3}M!`g0*6@kUsN+Yr9nI#aq=3&XqImbS8ABPo=0HcfFf#>!=tG&IvY-I7O!@8I z$m|&K(Fl3Rh?@}gE@pS;HjKtCASo)IXE$uEdz`}wS@j?}c5Xzk9(hQr$s0+2_qLEs zFt@MwK}A~vKu0rRiJ(t#>py(DeZcE56PY+6GP#*Fiu}(;msd(a^_=3aBd}mJFa-xx z<`IsLyu$fUepuaP8DcHydQsRxuY^a9F z2(pNR0)QUK(f2S7#pP5{xkDh-Rt!-iK~%`!)@J8h@xHACXNUyfjL1++OD6dFa3T{b zX8XX)VY%1*cRea#2hGI-F0eWm!|pf;K~~ z#h`G^Ql&6}d3K=;x%%KwxlK!^y?95)i2~J$?@$*Y^gqB|?hI%_dk-0r=|UHws`8fud{wE%^#RWk)U1 zp-BhiziWbi#}G@d;mSJa0C1KEE!b&BD=U>2o4dgC0A3FLZ{5_Zanv8{xj*U0zJZDK zy<>nJhyPoEE3+XimR3N`UD)6tST=pv_ui6cs}CMr&D%cz#~Ka2KJynl4}enjB(He# zTzQswPBCS7+r8g$g72o3vYm!e;8jkxcsGA@Sq2YTAk4ggD_z}3rwO5!i>Tpa-v|I& z)zILNnmq)qVY+3M=7_?+^rBA<{5|#mZI*++G+)UaP7Kp7O9Z!`QVI_f?I9c=>${Tu z*Ieq3j|hEusBs{%fdb6Pms2sW*>4{$!*>4oXF#vzp6YPco08|uj_=x27!=Y-`(UuVLJylU z(c82-&(7`ammbOFbq)Wg&WEoKl>d&u`|{VSj}wOdy9_R0HJ<9;f1~{Dt}7QmN=t3g z7T1@)rj6Y=SUULfvP*vJKuhVL*!xRspO4F*wYx01ewR(%`*Cyqi}+6xVf0SJ|2$23 zKQF9&KDc{%%}&{upW6qhU9eKU$2$xP=evGJFcqu`_1PCI9oMI$?ZEBqy5O-|xpo@u zez|JaVjLHJ31wVq*2FNbvI3jsJ+@aDjjQcPT}<|_dd@JZaed!oQtPp_Xu|habTzG8 zt5alJA7p*SbYE!Iz`=c&H z1Rt{gM<72u5o{J7sb&>9xK+&2|JqZneIfa-zt2AZGtV#Xx4pgJk(br(##orT^RQ^; zF;Ahl_UGT5Hz+c1f%KF?h>HxUG=EM0qP|DdZoA&)+)s*yi6g1WmotBx*Bri*@0i|q zB<8=@uY^8YU%p=6pkLim4idm zZr+sJku65IN*9+rP61R_ixi^k35~4&@aixmerTw`RDTAlt5=LCx zV|rW`T5)OEXKe}ql0XUzpI$Xj&0s3$i`92p_61qC566$$@vr6g0+rZe!0|{i1(DaN0=;G}d&-v+Ej8%^qiqaE_z1A8~$#t&M=3&#r)ei*z z`p|^7{r@SOY~QuLj-y>_zY29E*8LN^sT%RCrQLH$bO8$Dz*cjI6;$DKN8}vgpaIvf zZ=|^U<%2OH2m5~A%8iPSZ|u#2Ba{Wl&N$BQc?52pCKnp1L8v)*-*whH5Lkn{3_*C6 z5u-bftFcxhg=*zQ$~!78!XLzs+4fA8tvh@9V?1qtFX?@VQ)7|I`c}zE#FjRN&UZMk zhn>ySe#bVwkOB$By!GyWu5SFM9|I4u4zvO93X>-KmyzQ0!#-ozx_dsHwY@aIv?5^G z33kV6xTt?BujR3${x&eIPWIYSZ~-{+#2GW`6%pxpZ|@?y``+!0SrbYAvcz$us4S%3 zj@#L)IyTbPkdbTi^~p6QyQl&uo8T9VFAmTaBoXE;6k_f4?eFL>2mP>Gwo&Lq9VSon zy%acFUQeG1aGuK?N3PyZ^cPc$?gQafoo&^sKP=k?AJ3lo=BXKS^Y@PrhIiMb9Nc^l zm5@^FYDdcW_8K1~kAzsf;!M|gB>Q;m@Lu}ZZ|-%zM1`lvKu-ml9-_zpnmM>rRq>hS zF}->Jq4}}@l4pdzYVI;=er+Rq>r>pe<(D+YvXZBtDP_R*$#JJyv9HTL=t#u^^E+A9 zU$^y#H`=7er4RjeUr2qBc~j)wRnOWR&cv-u-?KcwdZq&=3;ltiSv`XOy^ix(2-)Y$ zxinPD_w!sV8+X3()b|y+XycH%XFCf;?2&MtCydfLco60HMz1Ah=ib+SW-*-X;0>83 zjEnE>z8O~|A7)$dT2vlA8o)8GS2!&&V4v2QdHu>HtK1+Dt{U#e7D-{2PQewPqC6by zOagAZi@_K9Yck4R8i(6C?`sJ3l0m{(g);TrBDhX5CI`oskb_p&d^aq9Y2t7Chevta zTwB?gYWTBf$kF+BpXT5_1#QL~KgNBw&~;Ne>Tr(Ra}t%m7; zqz{<>@WykQ@mJlwZ&zn<2xG(X&eh+w3k7^S171bYSY3Ne5@@+R%=7qcbmqUFuJT{CU*j*zwJ~p1E)JqC@27d_ zToK;v2)jVfmvG!hhSFpV(yG7H@$km=t`m!+ng^(A+6qX=lapW+&8Bm|Y8$8^<>KOT z69Xt~$ZIODHanyb;|=#UI?_2_>VBaj`c%96j(vAZf)dO|U3qSFC}q{Bgk$oanh#$d ztn+G$EC1BJRmHzfF&5pT{l*vN{ppLEFm@cJE8an;Vpb|>L+9!rjfKHv>r(I6ho6jEEF;`w zM7lg$c=+Juw7=UQGtvyCwy*=HKerfwD!Ph&bTL8qrhr3S5~18WCY53XPlg`~=6U+5 z1{2Pkl0>6-vi|fR$nPWsszF!nlKE}Pj7-0{38xC?uAA|KK`m zR6{RGSUZdUyhU+EZ7u<&GX@}SgL@U;*+X%or%ylm!!e3}*{9V<_IIi`sY&IV7#RGe zVKvU9o$10bZG5WwS!{pfPw(GCtycf(xN-jfn3!QcQ_UO*5xsAC@#Pl zpIidh{s!@1nE|PEc2dW2WDhO2C~C*KTkA-O`tE;nHoI5l$c>go_nqB^t94*O-sbcH z%fvXZ5KE(Fy&Mym`&|&C&%SF?=4N!h7u;JP0qr^gG*{} z^xXCe_O6KB8(j3x>bC89C}z8j$*E`aT#x&c*pp|HPs1UbJt8}ZZeyu{;+Ni?)4$WQ zexRJ>)FI*1h0SXnU3Kn&mN6G%Y^yx&(MudGJO!CdqAwBp7kMiSy}`M4AC+}{mPW;v z=m19i);`G>FM`?L^xC@>T33QxUx0OTCc|2hp z^1z5+fNp(edUlX~&>pj$@pAeM^2+|hti7pz6A#7m#eh>ebyeZCDWw%1VlO`cdEzq* ze+XS}0WVkjML#g`s)CU^UYWl2i-|>{By1|CyGXC&x87I5W`1G|;B4D_kXEf0+b%eN#}=xWJDw=Iz2 zWu*im#D7ga*&SGMdaaK~H$7;W?_IVdRVGoZ%yYToyzLwt_eBa5O_oe{L6n$K4prmF zG)61Q=4cL9z$-c&5O2ndy#aPrRK;c)t{JbW=H$KYg060k(p-un*dDJVLfwq>pehg* zrl~Rsa3UdFkE5GJDf1P^!g5S7}c3UVPj9PD#N0D%Hw5-J?DAiL%v z;SyxN#NsGr?dHd3V)+TpIr;|1cQvB{FW!*OA_6qG zh*Un2fWNGLI1Zach@GV-zTzt%8_IDYDBk~yyKmxg%hKVRy<#JP_6I#vJfzbSGG2k# zlmHIk7A1;NBVMtSsx&d9q9afqyU+Pb-&~nsE>;Ua`_*PN1#2#`!pd+Up9}|$#9=&W z1cNrQ0tH$pO0jQcJr(N7C9FAO>|0`)`3}rYdf8zyn#<>5zqw2a2uJb01&WgI8(>6!v__1-JSIwz}6)QEQn{0v@8rhk&Ux zp%U^R;eb8`;vk8XlhNbJw>%U+>%OXaNi95TrR$tVS#N$57pl+@N z5SIo>{})~N;?MN|$8rC&^Tup*p7RJ%suAVfoP{)pa;`a#$Vf;Bo6R^qoV6R8uN+*!Agm-EP-)yRO@H{ReJy>xOra*Zqn3Xnx@NPm{6Lg))NR z9a-S{WB-6KyjFx^GXJ^7GGJTDDngJ5W=uA0qL)T2A3q&jvdFL05JSL<&W(vm0qbgl zky*QZA9;8GQ|&EW+s)?qMW#*$#Ez8b4yx2F8={m5WeVil#PS>5%$RD*?ZJhUf>f~x z+XuF)B1|a-<@^2gt{(_z835B26lqBy&7PIJ^1*z&gwykA7j*&x(l_g>eZTIW7;foLgD| zZNgc((t>2$lBd}OZ4r-7!K&ZWIIuDfpoPL14-Ct@#!0 zz{#E5{*}YenBm=&y=O@1wPIj6`x2_OY0nJ^)SK`r0fGaNy-b6)XPhlo>JsbC(Z|)- z855FnFRYNQWEA1tc@^mlBuh+8Q4K0-Q#%@R4A!MECMX2u;&UQQICw80I^HPjBAl}( zATN}oB1?%P#CebXl2wkI6gOikTgfbDqxyrBE~jc59y0aG0_tA7~z)A zUqorh7f7HmF{JT+JG!)eW9T&{F$6_IXqHBZmlc{uYHgLPT{906wVE{>%vHa2_)I`h z0@wp8ue&Aszjn2@&Z{2J+k_~rPNG~K4Y1jB&DZbRJRh<}gz1pT>(n{Dq1v8RCiz5@ zQK@8KZ*y2`m`qxAdQ< zGi^^CkQV&SZF?_&N^=E^9IvaBz!fAAx*c)xCd5&KUb=ACqTKD;&GS}H#?&mw_1xPz ziynO)BAio6j3jdssq|m@;gfO4!f(=_O29ZhwgJG9Nlo)1M70)(&P60B?A!tLmJO~X zbf4FX?JzHMB<{iYjNa=p#IGQzmKO;>I-%-=iX!2LAN^(B-$UN;xF>JOw@NWpF9D4M zEyrI~t|wUREZwG4>J*czRyBO<+$x>?eF5Dg_+K*V_S95mnh$}ysUKxt0TaP0sdD9+ zSYzkiAW*ya5LdlA+@cv{BP^OXy-W3j_=?as>Ov|O@oQ#Hehn*`>zhhK9b3I_EHZ6x zVX4glCqI$yqbC400`g;81ox&!qEmOtR)KJHMw1w2M1^SP5BWrvD$<~-H2s6_M&nnp z^=u`rMWqjf8;caHfp|Rk2W}qw(BWRvtJM#`Gy`$rauCm(&JX%Ky>VMEraq!z(|%)i z(+VCE&y%Vl@>Cd;T%}RA?Z0X#6Mwa!8`_&)jN!l6Es2BJ{Q)pPZmrRiFBO1I3+ArZ z0a_YvR#Gu3x;ienawAx-Tnd$^T+5P$cY#Iz77|+fg#L@X4aedPR@dqMp3ne(-^#Sy zm1?|xo^@MONoCS#%S^Q8AT05+#dkOqk zK$mG_moey{K@h8mu00PBT)~OtPr4~@u#{vq;&&w-mDV4m%iZmoD`K2`2u?=8Axaf; zBTB#o{_|wwFjJdVel<7m&WRyx)K7eE3sk-Za?C*s(Sx0vD~c^vp2Dxz0)qc|nvhqLw0-mc=;QLsQx_|3;E|8kr#9DnZMLDqfNkL8EEtT84ZlY5Ok=1^kaEBGNzu z31vWS-)yI))&&V5Soqa{%vHJ<`FULNuv*Ia(I1G$5k>!Vit$evWsKGGza0ruIs_D_ zZCW0=$;PU+Co(Qwlb7nqMYljKBR+Z$*Pv+dTyj;N)XL1o$PD-5>1hLjf%1u6>WBru zPgJ)yhQ<49U!lY26eO_kr>rWOimg)oj#`T^TvY7GZy#>}j*NYQR!)(!cb^rtONtGg zb>`m$&u*GH&r1qGwquD->{>x?aP4<+Fg%)o;#rn`aNZIA4X-|lF#&CRQ{9^@(6kn- zjwp-Tk(rO5jdEWrsp#A|dFLm33co;>Gn>IE+AM)L4`4anGLD3?tU@=gT}zaA01=mi z&(DQJ>9mE)hL5-F7S>%Z`=m>&aT~p6ukI5N@L?K1NO5?&3Vm^Ri7FGCMomnUBB8Q6 zpYNvVD&a~K32{Sjp<{vPE=CC`JC4OzT+cNL(f>d)SDU(I;HvZGpl#!-^em|a1Js!) zYpVRebK-8SLil2;Ve=DRThK6GK5Oi&=Th#IsxRs88OmRW-^(ZU;`BYMtPfkL7M{2i zahr*-<0gf)#}7CCTa~Ky=6TM_wUu8%Q+ix9GvY4y4cUc@*dnuj6Zg?mvCc7TW^kEz_KER& zWMEs-B?655G7E0=G=1ZT#}R@&M8tb+Wk-(Zaf@~F>m%&W1zw7KR`9ZR17J{gm$!RU zFBhjMs#vjHbIfU5IdS1F49{Lnlyu&m+=zzZ)hJ*!jGgK$_fKy_sMqG|$F2w?mQ7w_6BY~SZ;1G zBX0vYpP_XbRYx0^SNRXmo|t1Qax3aOs<@SjZD1>#(vzBa`pMsOA8MXr=LYn0qzeOT zfM!MOV-1^TJkpogo~IV_H~-AwwwGz}vh5EkPi0p$*3AeZYVNt>^4Y8#)V8_;+coF# z_ve#z&bbBzTwqK3JPI7=U9Iknt4N$zhi8l-SHN+oFWy{$w zMd2&!wep5e>lT{1#MO*Hws_cQI8d#)MLyZ`2z9F9LRQ~atJgmrsT`2mff&EZ*}Je& zoa0k><|yLGrSh$?G-i6)HfM9A<2m$JX)Vpn$V+oWxl;Q%-v{j>Fy2wQ&T&LqcK)*yIS0oJciC;0im=h&k2Cz^u7thU^EvYd^rw65c&_5P z*0Yv5#+&G2*<|<1i&$iZ^NB&OO`OKLQ|Cft#B|x#&BWD!lms)1kNJd}c>Xo!n7@B% z-ifs+wSouijjIMoPaH4JMb?jute&+s5{QK37E&z+--026IA=q=Oyc<2?=|9^H_?;F4*q|WQ@ zCcC~5X}AR+(XzN?rQDG-_x5b<&4ep&u8vzTQ6NwN^t}xkb|`HU1chcI93@sbDxA^z zjfvI&dUqscd1g10=g*hR`&;|50i;N0~ z*Q{cTzb>Y4s0HL*Vy42a1JNI~s2(%D1h$2 zZlauPSQ!HDK2hje8!tR)-mZikQ_5 zI5m0o$REjoV_R9tp(0g1Ys5vHX)z@7S(+75Q~^Vdpqytu>fK)%@!yzk%8uwKRhCvg zp=oxg9^RQy|E6z4&9K7$htIU%Qc|qnp2VH+Zx94`6(p}7!oU9NqIdh=fWv%b$)T|+ zommrYrSUIMb&s7O#{DLN&>W|24> zlx6*em#>~xs^>19;>e`{}= zxfpgB2s!JD&5y?W98G-4;BGANS4gSo)d@@}|1*E~_}jV6yFZ#eLS|p%ezdvh%t<&< z&Ifh3NUX6D3A?KL0AEAK!&3q)YC)J+q!yX!u!;XU zA~XK7j_$3f)LjYQxc5&h{?GI1%TgxK=vCxLrILK@XBD}Z4?OzV7|A?%5C9+HCsxTg zfxKjyNrjVW5r1&kl3sk}e-1}HKk>}sgL6CYi8!sP#q!Za@N*;A=;Jaky67x0TeslO z;e($<>&D)TvwP@-OB4AYeM5G`WMBWXYt<#F5!oe@7DouZ_+WJpU;CuV@4B3e*U!tC zvs}}+f_K5UV7Vf<8y&jX^w>{ookaJ|lac>GZ{6!xYaKs3;X|(XPQP11nzgsO$C21X ze`_WyYwwA$VuU-(xa_i;(y6As&BNPLnw_leO3nox8bo%p*BvrHFtmMFM90iMa+4n} ztH?@sd2Fap>Qv%+dFtvrw1>uvv4p54j^ehL-`|>FD^su(!s!Hp&f)1R`!!^*{k=Bx z8+uD`#OqDF9*y^WR(ca+I|eqy!9jW1=7)DLni2=;?wiLZ_GXUtT86cH*uP{IpE|jq z`3%$xx#kDL276R&$Q0DlpK*ivi9p_g7k7Q)1RqI6?Oi|oUp1=9~ z{u%Qnp6D0vk0;tJp=!3#>`pDwNGk{CnB~<;nkj1SK9O96B^UeX6!6p zO*Z%WD+Kc5@$C|hC)u4mqvxa2`*QjEuZ?_vk}YSDP*1&p3N8-Bl86+LxhSBeOPIG)1oFXDy(;A0iHpKcIf5+(d4d;I~ z=da#)D=&bbT*gZp?eDb(Oc|9a7f&RR5i)lsCj<*>#7_TsXAu`ycQ!}JjigZyK7@m0 zs$&IIlbNp|^~f33Wx5_eUkJ1=qnwveRn}U0)+Y4Mi(H95&xgPd|Hm@Ni?|FzBZGi+ zk=Eo4a_+xEG^cXu#P&TPMJREOuI4yW!L2(Mg3Od7d!r;(cRP(LJCt|)wy~n3>4)kf z$mpo%i&6e2^+o6%_JBUvlG4F`6b05m=@rPR&OA>BeEXPUm=q&Bh>Qe7S_#~f&v7KO zwWZe)BA~qpXb-$IV28fus`|QXs~vxcExDZ|TGcq>eNy7ByW|}Q_TMw7GRbSNeME*a z;ZB3_Sk@g`>8#6kD#w}(RWZ3Jp7*h{y!ecazB^Xi-qPDfT%%Y4g|OhJ%RI|tW~>9- z+Gd!DK}f(@UTpKD$D&7>Vq@>~++Z5VQ=p=gpSNAeaggL{nn0jb=377CVf)J;RH_k6 zyq;EreCp%rZ`<=ES{$GnwuF*UIi8+;Idk;T)8a2heCb6)vLN!F%xyh=IU-%~NmNcSeCGgv$3+9X5HUx>L^E>x(>SLOt#|3Af}k>( zy?!;cB3v@e+K0-Z@G=^av`#2Cn5DX8h%u=-tR;_eL)&!b=12iZvksolRAqY0+^8Im z$+a8yPrEVOiD<<7LhfFMzv8;CeW0aHy=w}bN6ehQ>s0LHWA?$GFRj}|tb^Ds@tB4D zSxB9Atk^vj;@dm~BC`8PrCvRc929uT!AP1U7lCHU3GRvNoK4Y6 z2;adSWV$=Cwss;Sr9}*B(blKN*Vm#_#<=k_2ve~Bl>kV_^LV3edKb^UU)1dl=6|!{ zhV9^oUjkIdU?6y#ICe^{ke9aZf{7|BQHt;-K%pWXG!5WLy69&*T^!KcsAzjlE<0;Y z^63%7Xki&lDI`wr3l$$lcxo z9XAua_d8%Ume+iLXLuGjsz7%jp)YI+zU^Q1t9fNOH1;8w{xNr4^|SRuQ^D(pPh;vK zfV!ANo8jJXEu*rz^sMvA-w@$ToU6^OTVeTk?=vgrC$lcKDz*tod81{E#|tj)^Vy5?-cA`V+Wuw7%JLZ5kc9n~6DGT#FZsI({3L!uZE*v#o)4u$Qe+x^3LfZO7F z6y(wR)oD~7XWfeh`5lYo77^sCi-sF z0j%x6)0D$})F|6XznB{*)HG{4J0U;q)IZG@fs=~L;T7CuYgEe((==;I(jX}T-7PqP zJfOte`8Xz@8twInSzDOrrhIcB+3rvlDwTO=!`gztYu;(}*q|ftctUQwj#{Yn7$}7^ z=%%2loV`MEs6o_bE+RzX+xxeEivK6e&WsjW86I=q%%2X$6rPGd#zzBS@ba{f+zRru!aARi>>Hw3>w@a5?#Cpy3r*ac!xRv(>@g$TtPO<0CGySj3 zO%!C7U|<)7sY~W1ch2O9h4(YGllaKGV9@nNc51~vX&Ob!K{hhEviNUYx=9|sIm*-; zm3;)2LQh`Y&)urStyH9+>rck+V6vMn7A<%=qFe|S)ODc@5jTy&OY!{Nf6k8G%-tp6 z?jywQE#4alKcPy7#oD1xgMWIOz~I&ZbP1&opb`l@`mR;^t!1Ei#Ht0K^21?@G9cOb%L>6-c1SVzeHOY$ElJ&(ai<|i~hX^%l&do7lo{*t* z23Q+KOQZ^bU;3`gSIc zxDO!b?tGtA`sF~p^L_>&TDM`PW&5&n1v5v;g!7qD5$j(tP0iKGf@;n%m!tmd@92$cRmj5Oa;5*kN+2eobc6f=-8T|wxlkL>aJa$0(9V0^ZYVnI|h?RhCuTT zeL5B`;&I`f46O(YkU%yaZT9!bz3}n^_V_6m^k1!J1iDzokYQPR{1bggqn3>?NFc9! z-D%jnBO)GGMK%xVAa7NQ9lX0HmwoJ9-1>-6*;Vg%{|MxT`+c&ZI@tA3CyBkp(u!AU1HoxH92<7nl>@ST?Rs{r@A7 z%@Tu}t9S;stIG>*SDMS;QS-wo!2jJF8v_9F5|{`6Kb2xR6xMR`{;_qtMcj4!kn3J{ zB#fT_H{aKIJ!N9>luM@Xn;RLQUw0RJJkfPL{44G2)Qc-0oR6$5r9vr-dI0}_N^!?* zF9cScHW4^izX2Q=wA%M$KExwI|3V~KCC7B8y?b~jU;t-qf8g8Pn+LpodfRK|mY2Vs z+^#s>;QKEt9y1NB54iB-tLl94&bY8H$3o*zQ-fu1s3+`Rv|W0b^>uE%@!)kmmz>|y z2^SbC*H!c{D~_<9Q}u0#84oo}BDVeapkiyWyY}?Ey>A{j?HIVGbL*5<^4!P#pt>!G z|Gv&AQYWmE{+AVRrvswnTdRHU)n6r6w7eCu?WW`|rCGHa-aVjva?_g!Pg2J_@cYk3 zd?>M0RM|0_h24a%aaA;P;v3gBXFiDPM!OV6hpbbsW<)5eKeaMGeN`z8cp89rgze;s zcgd!w@aq9>#%Lz)ee)_87!lZ!YXv1dgE*p;icfp{eORtYe7n6px5t z{V&_(-9>$}HG9b2SQl)q_FniS%V*(TuWf7ZyF77Ncf*rfaqxRXiQ`-+snPG0yLXkV z?3j>Ge$^3xcZhlEf_M0o9{Li9M{1dU^8^;H}KT9G!%DcAPCk_sy z2Il7CIzAm6Y=6So2xqDcAM3?A zjC_iDDS|J^%10dknr%eta42P%vblTpOOvgQ_14crYl|#)vcBFpx_Mgg2bca-!&@2= zIk)PC){{FrKWAa<0C4!4`t9g7r-j2}Uzyp*5^$52g}UK+B5LSM6DTrE!PmD=v!D&L zg|~G}JHOa$NY<^~M%S`rYiw;N?T+itulwbDM0s6XlLl$TLUE=dO`EOpM8F*znyAf4TEBj2u!iEZk;Dog(EYZ= zv+t+g_;P?s3X&qs&+Fqd`q*x&0lS?t>PrqurgT^6?nIFgX}jn|DB|}SW_0%YEK!v! z$NK)r?9B`Qvs$lqIrObXjk&^y1k-HGeA<3`klpZ~Dcwa8&tVRt@a)uQwnH>)^(jy(_ z%u71qQ}S_C5a}SH?B*v<-koQY5&CFnuzfBU!)3wmtV8E}nBGZIo7)<3nSIf2EtU#D zB&qmOY*EIqtclI_U+?+3@4qC3p;oE#jYKF}1>) z_i4Ub;@V8sxt|s$hlF0_*-t`BGCQaAHY{+BMFj4Ve!K#GCLa9SsSeOwf=yrT!1FVG z@zma+IpKYKu+X*{dPi^j7`Ee!-%*8dug2jrw5FqCVFa43Ve+Tn=3;{Kp=lTQb6o>! z?;!Yp51KMh4_o6Q91V!VMpInYv*t!}X1*$Ilef7U(!zWct2NCC z>~Gqm;x(6dplTs7r5dg?-GbWfHPyvhIvRY3LbTbUwM*LU@oLL#`k92X zqiYrKjhS+kb>gl5)`=2-M{9--Em$@#;NzAi)mqVSO{|A`n-@ET)`7+$8z!~rjU8IP z-}~*-l)A}XY3)0X^YEguD5QcAg35Br_NqEgZ&{L=%>;XdZTgAR7}=@4=?>Qt{_J@C z@96x#)-;>8;UeeFYz^I&Z)E0#d@*)sF|~fN z3yvo?gD^9hO)NUG<6bJqxwUx?7Yeg6Z%4jtN1tC%R>n{)^vXpOPgocO6~yz02}gz*1x)E#90J z+;YB<0K4>T5SwFN9>fy%YX3LZZ`B0a#n`FAYm%4iJKq-uEevTqHs+H5P81eCa89ir z>&4rXQ&tT+DLmNk`ep1pUP77D1l?*Y;R3G8@WN44YlwqL>~y-&L+%Z79lPL6Sqmphw3b;q^Rblh)oJa3PwsUc#30d2>Qyr9_tJ4z1loGD(JTu z+%F$$IIbe2YyVJ>myh(>z3Vn{T-I;1fM3lAy=DR*@_aXBt+WmAA?IdBs!EHoT&2kf z^00k55qkCBp}Yr^nEJ(otzbbcf>ue*@3gp%ilR*FK<5nifg1MnszNbJVSt?6A&_g3 zVjzb0&_MeRfxe6>e@!3Rd~0W<*%^5UFn-- z=aRLzuSFe z-?p@g4-}Nk$%L3_DNIHKz!Odo!i6hB6j}f+GGZGHT`a_OK|+p|Q(g(w-V4{QU-aF* zi7=*Y4pmgCk+pzICq#!z@PM#=1_^3{d<`LB3}Cv3;A1M%kIp!g30zHtPi$jJ9~DuR$`tvt0`&lScf zj6nkSCPDs;5K|=fU`?Zee4impx!SX6niMKWf~big8f1bRl^|NegVnSf`2Gx_J^WV- z-f5vN72Z&ARl~RtS4}(CR)^uEKd9!W(>q6~P*@8GIxLt*gBb(_pdr*`P%L_s`MFtX zCp~O}v0L2}dz+D4BSJGtJ~E0A6F~PhW>hm#0RT)(2&j>ZWKw~uP=MP?AhrNT%xnXX z)g4Uvwv3z?EqbA4?qQbR^%Fbir$Q}9@Zc13E&yz_F847n(g)C9x$-?^jq)9N(!nfM zYXt-fyF7zAB}N^jpwbAZ(!iQn=piE@w-BHx2B0W`Se!ZzbprQu1qc?zS$d?X1@rZ~ zmMMyU|C&bHdyUPA-A`G{$sPP<2L6K-X4rHRWzGY+WlJH(b5wqiqTNV02u2@!OInY( zjs-hX?9}v!LyW8b=6mma4W3})jzP?)#Yni zFsUNMZV@7!f!Ha5SxKR9#sT;oM`>%3@ye+PjdBgi4tp9cZ4wRjQtaj0hI?4n=-V7DArZw8xeZ zj5*)f)l@$#*i#8vI|m_3pt%hB5#i4Kv~AE*d&wGu90^{tDrIV(^@P zR`av9lN1~YbA~&<#|L%#8pw=O&?W>(+zO#7`+Tz(L8%3jv4nWQ^jGY}LH(4s%(?H1 zBdBn8*h74wEc_SMi!gKEV(1m30D==kiouUH(C}^DO7DId*|kcfn?uA9Sqs>l(t3#4FkW;4YT0W6F28 zU>nAY>5!7VS)q~4iGg|{uOjzPMb=?9;r5&-cvs3u#Re2~u~U|wM*Q;*lb_5TyD|LmtOl~tN|1X{+VxwRa>8hQaR5u(-fogb67b-7(D^D5al@Q-M& z)|89xhfvmPDG4B|WQ6zEee<0P6Aav+r@PW3tL`h2qnw*lzF)qQ*QwB&??Ba0>UT9g zqqJaxd(@Tph=HxDj7gC|p12Nza$Efk2Lk=y05r4WWz2l?=aGeT4SlE3?RZ&p)y z%;^;ueU$4>7$0rmQ5_Mmtg5r#O;l^d4|q19gEUX@)MYi%RO15%4xigxV@W zmK1YMoIb5}?Y?dM1mV~#$sQ!Hq(g!!mq6vorGxVKWFmxiL*q@M#qm{2Cs*A*C;N35 z)}uVT)6OEc*7{ICrW71m1C@77(vQx^3ni0NG?!zYlIDm9Zm!E^*R=Ra@nmq895q*%0 zbxV-rQecb5ybESTg=JW-03%-V830VamqvrAa_2K83y9OpQTM-$jXxK)pF{?HB1LDq z-PZt$vLx2RF)Yn#&rqe>j~&s^C<!@U)HLLIrNPfcebrCaQ!wXf{vYm@|1xinJ*YG(>q)3QSyByF;K2Eg z)_fBJ>bynl$&6-n;Nz%Nqu|smI6^3+vcR>K21U|}l68n00&vLyo%mwS zZ7IH6vO07kzTZh{b)C|&>AP#6dMO9?E7Nh;_wQadB8)Mgpd`>riBFbY#RIt#T=uy! zs-9SQpdt(gleXvh5b?8*&O}rfO=x{xz(;OWb3PmPQ6}!OioCG8OZhJoKg(2-NsD2M zpo04Z2d4W1xqh1hAh|%bI(_qrYXunYK`K;Ba%$Lt7?gn6{;lTmv{f<0Ao3f2TrhT3 z?Ui@3WgA$2QU~@Q0*|8fs^4S#e&ZoxSob!pm)1zrjBvJ4VT6#h)EVPXh3r}x&n?Xl zr%K=-5-VH`U=BRRm2Od&Sk(zgs7y+w{P0^K=X{( z*#h6Q?IVfM2u;X#Z7n4Rf|#%6m8Or@)n-A}JR;N>JGULOQ$N(}{+CO6%%JnH>FfN( z>q_w&Bt$hyUL?jkt-cLCovuDs5HyFO$s`bnt`@!v?%qZX>|MV&x!Nsb*kD*P`$q3$ z>?SAu=_Q7Ob{e)%#K^pSUYkVlAYhs#p!iP-CgQ4)3L3YrosryO+?;v(2k$POA#m+G znfk%4SQ*7g-%07sqq}XVTU8B>VN*C_WUBgg;^^~<^K<{EjSmY9dn8ZB8A>vy!mx0X zSBx?i0`}{4)u?dk>h~Wf)+n8L8KP)n>uZ3!qg}O2+05S|yAD4h(uGCJXZjMBR$c|r z&|fp<`$z>(^07V4t~wEBH+bN&Mt5lrc2H#QeMT#0*V?J@Q5s93-|^hq*6WI&ufxhi zq)gWkWhvn!I0pgybPls$_SNU>q`ccHxusqNOazhJ+96SVX-RldNpYQnSZvn)a>Dn^ zFMYzf!Y|{^e3>L3WGxa0zd~hiX(SZ?`y<@|`*VWABPM8hU@A}XrCE#J3}nyPbwi>B zR_BW<$((S%PAN5G`!jFC7|eP>Xf314?c7aRHiN!uLegl+G*NQ9=Mk9{QzwC97@xO% z0gTAV&$AeB)!D52m*J6m(WPT57meEI77v$)j0$vXr1&c7PxD#8KwOhWK>g+*WfT>G8_c{_*8)PATLv7gZz)CtTB&N!NU?dl~Td) z@TjuRvrzRuu`c}fp+8zbQZzQkiyQrJa-~`}`(&e6*{iR-y`A^#_wY#Ldmai{fBOhR z>qHb(ug*I4rDejDu3gG#(XsXczhbz?&QQX~XE1dN*EscS;F=v~p|T9HCY}%OX^^!f ze|*0#yensRtgCSI6%a7S{QUIm`nnz#LiKBn`{|dF$meNZhc#8_c89uiWGj+7mx0GM z+pLtbIxlEWa$%11=%{1)BWJ5SvVN?n7ZJgzxyG$(=cmwXY;W1=fS()I+|K*6vheCd z42y^Bd2?4*Ik6k5EQq;R@cqm8?yW`EpT}JYzG+mz`h+Bm&PKYTLAlppyszBPzx183 zH`i}oul{f8``W~oe`Ict{@J#iw>E>ihZgyy{7XqKtVjqWxc~jy*!6)~iaW)=Y&TPxOi(&|F6Z^KM-6vnm{)6h zB4(fab8ChO+jD3ROo5Z~jgI?2d>T`hbw~bA#D@-L+*32d7!J|^eR|iuv1ow}w<2fm z)|r;y{wx-76CJw|7Vv6}O>j5T#)j7_ZTzVhuj~9lulcV&UN2E*gV)c#{OH=Y<>@MV z7)B00ePXvt!(NS}r5fC4wg(Gh5t+wTRGUnH0Puz?pE_|%PK&m?cbs*&Nj1CLfnJl- z4Be)GcrtQ2BN!aLDtFdSvsSewjvm&4GT6IDr$Fh&_1<&d%Ig zd>x`bIp(71{(aB-r)E4LY%xvh>;{B`!f97U*~{{H97C^{$G zogR8S@0%zAKre~lD&bjm2z4(a0PHP&etah9@B1~V5J6W{b=sY-xXJ`!x9_in`U7#N zA`g)zZ*m+rSVB($e!rUhd~DDsa|p`Fan7xWi|;uzb#tHJyeX$l;HbG;efny>lp(A0 zPDc|+Q|gH{Ct%4~5BHm$A|p}2Wg4hgI$Nea$LBfBE8^4B*><`wA6tpQ--gX-Ni!FQ zkugg!yTxur<^jFP*J`I{e@|&BM9SHYb{AKVPmwx*)h1d90A1}~?K$QE_()K^zjI3G z%OKYNaVhV{AsR!?8UP$6?9K3A?TXT&xWzjB!IlQ?SCYq@rh|_rh$jG|XZ44cdn{N5 z4SQ$B+raLz+ti# z1swYd=r2KZPekH;`+LiOcA^}2cHoalV7l)K1Dl;kj_#$bLczu;y7$5BWNq+Xb&0pi zcc9wi`*bYERLfdYt0A>%xu^t!J+r`{)$l!=Tl*NhbELq z7^u}BO8bM~M<1WqB#ASi}t@QGW$rToMd?4Bdr}M12JU1nH>4tKHPd7Ol94& zRPRAgzvaC;!nxnkZqJ@J1@ATF?54svKZHh(lTP>cU!2nU%17A`O&Ea>)#WwtShFwp z@imj*`1OIj?>(gos{x6ySLHYYD}dQ~nkwgb@qZJa)-{s);!wklpNjc}Bb?E-s;$l& zP7EL2Kf3DlClbo$Vm$6z)0Fl{Cd$`E!~5~f)W-J{rrCc>@oAb5b-!5iz9;EJTXj^= zC6$R#Jp>Zk9Bx}_=P9$4vF@^up>;aE(NAv4oiJL@QtNH*-~3V$pGHAiyj^l{mn3f6 zSA(kUnCER-JdaO(+n`(7?ctC+r(i`C!nh9eWo!Il_VX-7Sr+|B*4Jx7lA)$l5=!F;@V&e znN=u`$Y;t!ayiCAxeH-Fi=@!9c_&iCgB-YzKC)r&ej|TH{lO@8u?T5ZpV~$DbU9dn z9nc85`Sx42hu$I8)sFLi_-v7i?kSFk{c97x-A-_lP*oMBNrBlcIw=mFD@#*U!g2#w z=?AG!I)%$j*I~9V0b5$6&jznzFUJ;{hzI*OKZTSWko4-kw+Y_zH5I>H^s##$ ziEFBW={y=_)g>hb-;NbgX-mA9o6Kq4z{M`~^3yGwLNzjkgFan*(p=X}vV#|M!+VKH zbCS+%s^6TZ_xM+bsE;M=1L^k`L0>v_sQ5&EgZ5ie%4Q;@L5$c;N0Ihguzr^Wisnds z%+N#f$&Mo=!Ip?k+4?#&=)I~DC6bkRN8=&|QfZ@*ga zqRzZ0&-UT)n`Byp<`aQCISbrZR8isHyg)%?>-jn83jIr=4|jX+`VpTt8;Mon?%ZOuIgEn-!2qFx-6FOZzT0@(4Ov;2_8LAhHh4HQ#QT%yWjmoh5^Uk z|HFo@B6(~5s}a^H|C_+d`WW+1pwy$2TJB}~=v1AluA`|&q^=p+r9^9q> z)!E6A^z-$0Y?Je>{|^h}prgqhE{`Z99u9B)Lf@BvTt2ZqPj7)k&0;H!G1cYlk}ZyM z=*L2T@t}5mT`&Gj8hVw*-ERSaGMN(ruDxd=Ng9aIgU74 zCA%w-Sw(9uP9%VDY`n8H)V@w`EWqVHP!0g4*coLH0!Ox%070|>k=fT>t2ig3`R^+! z{FWx87-s|l;>4^L*BAK#YSku)-PTBAQT49qg0w+y9EghYkNdZD>-)j&E1+t0VDGqE z(ArI&RQ^vpK5cMwV8)5^WH5Z|7^kz7r88=vgh- z8##t{rs4uR5#i0XaTQ2u0g@)nql*7kww_ejDhdRoXhEnpE*-##n7KVnx=)9r^?K0~ z?>D2^IZ;Q!ynAn;C5F%3%;=QS$GEH8>h}waVh7>wW1OFLc@Y2-WTRuHh>#`DHU``o zVC#_~FgidSXR>||u+gV;W9~Vc=x}HnetrFH^xcHALGB;`L&JD%ZZZk=pkhN+0cszS zt3LrJbts3L<`{_Rb37#+z!KpLz|Eu(Wh(P=~C$GCI}hn&cSF_@c8ZMOUH z2kdM4Sr32E%i+gz9VmlTSM=z&lk2xW&TB@S(mNy@uRIX=X3=?XD!GvoIPCYOdrqP& z%|e7VI?)Hc7DSF`s!FJJ+C1Su*Y zSh3SoP{d%th-mise|Bb{*_qv)9o{j+OeSPblJB|h&n=%;M^Z*r5f9)sg7`o|->VgP zxN)C`Hta4TO>Fd(0ytMQ~k);X>)NE@R&^5 zNkG<<4|F=XrAv7YgDeCS;wC`M&TymdXx_W4`RWrQoaC!21aK{nVXk@(W&RG1=m_#~ zJcGB-VdDc%u{IiEZ_kURaO1mhNi)KK&Z)PL9}TWYwL2X4uzq3C_Yz4=9VrrWcVP}} znjMr40)PM(4j}1*!(mijXcQ~K)q7*8MOIC5g;WDMDcR|JAG}cT=gG95y z=Sage01#oI2<#aE_m;wcP3g)L_aPHVysbl=00vKw$ZDK@w*SUsmJ=FJKWJRcDhR9K z5>6E{j)g)Fh|oxytXM0GwPFkozBru(91vceuL0vyZJ!HVe>5_jg|r5hR?*}A$1AQ4 zgruzs?=KaY?zy5{dDc6ri!kR2Qq-_<2znzjx&@p9K$^lr6TF|c&JvPkoU8N~y^t}M zHH$;R>V>rxR39u53ONFVm2XK=9J|hd24Nd@j6NjN8c3f6( z%?mN1P%{ALXp43waf(EpMN)WV7gBBZ#ec7hq6c{9RztrYKG^?)m&|yIeW|+=Xg)l~ zTBMH*9v8^9z0p)D$5aOq3Gm|DYnUzk21hjv10E-MmPSYI5jRH|*kt|I-PX%n1ptos z03sGJkVgH-kZ@!Nn@5bYoB(AR{FAUdrv>$0cqV=3e2U0Wnh}ynEovHK0TR|KF_#rB zUifpMcfjJb$RWlFQ1eF6MNzXu8}g}ZShcT{gmrCuo;eY*2-y*&A?*osjrln=QFy2I zIT93j!(;fLp6I^c#XFRb+}Of0kZ?aN)1EN=wl1TNhrda4+@Lq693w-XDM4j!=l8dc ze~#v@dSA=4MAiLzq%~YZoeILC0o^d9)NAL zJ`Hq&`MagaEY{mSOve-nQt2l7;ycY4DYC#m&chj-+0rmQ$AXC2t2{4-$MFN)FU{5P zQqeC;oFd9suXES63K}lS6zQD%*oP&u){s_aU*j==dZzSWCY&U4X=~R^9I1{Sco+CS z{xM1Qy)|of3ofyj2U_J;$B|iCq1)nlD|cXG29V$cK+esxyLgG5F&09`&KfRHM#o$I zCM0*!lEk$|W7WyD#N0RUm^a_MyTa&HWXXE{jOqr(zPA?TJb79R?~vmGhU|3C<%A;R zcsw02XMoQTTZIWeR{s3~@#j5H5YfpEiz5NlGDnqObNH^^&41xlm-WPt}9-Yhr zHFl&G6QU{rfNE&g4Dx#D{MW_7D?aHzLcfsd5GW)4Qy=(#%1>eOb^;tNDQgA2{(Lp2 zv^)i35}rwhnNp-hR4A0hnpR*zNPyWm)QSLi6u=1MtbaLcON2Ya5c`&nTX!$#FDi>% zWGrBV94w);5U^zx5Lxg5mVyjsMgV}W!nMRg1sRLL3bgiK`&8XZ$A8#8lpjH4Q?{|! zd$H9R>2f3*0woq|fOW7f+Z-rVsAl1$|7K?jG{2N7GR$|n6?{S%p}!Rcu#H)4@LmLg z44^?>n8@;Ufsz48krxz=o23fMqqf;MRooeg8QY zZUj(mN%-3Lyp}9owy44Fs8h!?+Nz|5fq+ekTZ6Ddk-|@+16 z=C|P7EEdntAIkZey^03qqw4lP$X&~XY7?N~3x1`P1iWR2&dHL2J-Z(Khw?sB4c*)Ih#WbF*w89;S;`{NAlYrW+QA8xCs;tpJ&(+V?1%^-u{)$ zfurI_|M9}eFk>_bL9ZwIl53Z}a3Gn^1iy)N{XmPyRcf6S_ukH_t-Gzp%KM zm(Dh2vCVB^kplyL|LvtH?4NjRw!3rh=>SwZjb|~yHU++uX;AV2d#nAvoWFmHnE7-5 zxwHZl{cEJeZvi&{=Be4uAU`+m1Hls^P-5kZ07AZ4Q{W}5`lb|+Y`FK~s zR3Fzecm8ch{QJSeH45h1_exfyLQ`hHt{SYiNVFfU4xGA`3Ey&LId_!gm0_0jKT7dK zo_oR4_xEKV{HmrE6Vz(In?7yZZu0k4%h$J^CnlN?#%_P|@#)3nXU$uZD68(VpArq3_i zeV=)FI{3e|KlY1rFFL`j_>Y53I@y0{XVhQErSBiPhgz?lxN4jAO7TX;8{J4dddWwB z`M}8~i;86%QsJdaORVb^HR5XvC1;z`BIQk>QoLe2Q=g}i+@;Ug$pf=u{R6iD?@DoO z-h3I6@PAKzKmI?YzK~@Y%~%~weFbaxBDcJ_m^^lQ_iuIcy8nTLgFDY32j$=CC#`({ zw>OXdmMwhhzW`nkj@oWYpOlVbiqJi!NQ{EDmrDXBVnXr%cHB-(;F(IhnkMP zdT8dGx0rnM^Q>z9tp|U<|GKs{n{}sQe{k!Lp;~@(5QnQD@qVsmGO46}_rAH$tzDV# zhns?*4X*-?ji)w$b>_^M^_lumi;Gd3StenU!wplNEa>fJEHp zxr?v|8P(?yEB!GGQ~oY8hU;q&pt;2$D?st!`_ly+h)v2Ih1R@WDAQ$ou+M*$Ml(>uRc7zFU8Ip7`gY^%gh~LVIzTqq6;V{l;IU0i*hAx2eL=cU|M` zq_fXUi@H(~HG8vPtUk2eFK-ba;QHrLDHaU%>kq3t+t2P1`Y*kj@;3u8wcA=>EyZg#j6=l`&3$o` zKC7dj5`8J%;)wSYTV2b!ltD`DORuOsut@u%KGg?~i(R|lo-lYHT%mU6{EN@s{#a=$ z%DEIGFhS{d6_ePdl|_W~>$eAt>q}z}n02yH7z*)tzQwiqzH6dXDsOtI!|X!k+`Mjk`sW`{Z*o!% zuMJS9e2=*e54H_iypBC|5mDGu;j~D|oV@J*p{yy1>?`jWcFLYI>~eN%kALLyds($Y zC!45J{G|M0=Kbl;F;Eabl89Zr*RS0iX8n>GYm{-qG*M6RDCbCp(+?S~3X<2a8;I-f zQmuGsXZ_sYZ*<=L#oC?U>%EPI{RSmw7mfT&%-V@3^WS&nmyNGKx(Rl5#`KcW$(IcL zbg+y4>nuDa_kP+3U@p{bwcx)*~xsstOhgvjEY}*y=h8N29 ze@B1IJ4}rp@ziu%^4uhZlG16Xs z>|JB&;H<(QszPo4^pu7%5tuXfxf^<>&~u>L({@Z5KmYo}-oN8~4ahe9-aD}>XHwj? z=U99v02<3;n)Jb=(c8KM%Rd~5gj!F^OOuQ?3unbT!yX~7iYn7~H52}@huem@5b*Xg zxav%>P?}mdr2{^BY7+*2^Jh68x{~&7bmbLWiXv-63V{oF>dY^C@{OCJzqUi zJvox-xgq9G8mCA5ld#y)lZ($So!N`rQy%c5vS_vS#faJ85EI{wl4wVm)?2V{o~yiu zpN*^gQO&WcY&ULGpAQ$t0%-@G?F zzmS@E(M$k>M@BKRf+-g%GZQ``!uhUmS2k)GTL!4LdNG_EYkTz zHn#I!07KpoY(hYM#1m<#gM8pIfzeh!K)+Z*BQ>71_}yoJZ%;*@(RoW0WN6t0!mqh@W%K?`@idZ1kQ)b4(JFzU^Mqgp;ydzwk5+;yeVn54t05pM}7 zySdwha>*(`uLP2deUYZ2a-73RG`^r(IfD^fOLZ$L#ZhgpLQLuD6@Nm|Yc5#88+S4G;7h$O!i9=qOPl-JoytV6Kxk|K7@wY8TL+>6zG1|R9Z2H=F49{ zbH#UG;okMp`P1TDQQjO%gBWbvx6_nWh^~?l8pRunh&#Bl( zb<7PyemjZk3inWlVD1xA$QP_T#uZM86f%V{IRyYWbSN9h%v}9g zwCAXMRbh~a0Wb8%5beyw z9dcHToPq6J+Oma}-px$NZl@{w{6yM`At(X_-1LMUDOyEB_;;d$Y!r>A zloVptJtXXx=qDBx6^$3AeoXXSBH&#{cq_nsjKc8`ZLrDa5JS=3g_QAIZ6-+{y^$PkjC@My?^YBhBRXB8CW>0H3 zgH`Ueu3-KD&ZF$;#>oP>qDN70nP+e>ImwFEwQ-Ie-xk%9@OuR zHd!C-y&Nr^)%sAruL2du+3xMvEDs)Kk{i1C@esOM(){>uMpAfK(#sm;-&ZNT31gTG|uBp`=`h{1bL0K%!kT7lROjPw~cpXIGo1-ddY-i-P zZqkS7Nzm#GO3%2gm!yN$WP(xnLDJ)Yi1c<_1!pm!K`U#O-v%&Jyf(PXo}$oCDn9dk z+lxc$ee~3}+DHMc66Lxn@+bb=csr($Q%6whB4F;*oSuw0Ln}MvB-|TeLRu$gHE4ta z|9E4CW11=~$chojULjRW`Qisj+81$D?SeLI;B2vB>!!T~f2B)`%0MXv+bGIZ+lGBk zI7oIlcB;Qulk2>>Pvj)*AO-W$_DV1T(ywtn^aWrBpl>p-FFq{T zn4?d~c4(^dMYZGGrlKD^5LjDpp!KWZB4pS%{CxmBYit4y#GQYNg=Xvmry$(6)5+A+ zE?t@ftD%up_v4?GmW}pmENab;;1WlpQwsP0=&_emR4o@ezfnSf6vESLU=^TnD=d5v z@OAE$K=pCP?kRQa1Sy5?laNC`-HvbEcEJmGDyya@TJL}rVTlk% zLVz?(55^U6k|?~5mRw%IH(cm=M?GkH6wAGbN%v7YDN?Xwfc^HlGto^*F`OB$Xk-}2 zY+3PKWR|tLJGTM9GUEIidA|0eMSNMCEqoM58?1XuRJ;1{L115@i@5d4>M97Trz zM7b*$0c#~_6>F_wDSnTMFQ#tqs=|cOvAx5Iij@HZCqe)Ib_iAoV-XZiP>4)x%(VXf zNZ0$b5*)=D{^)vtWrO}#0%f&_Yec?!^D09BGF~U|B&`k5rlJ}NN^(iO zeOrffey)o=AB(oV*+o^714!MGp|J_TK!n5|jlVeJ1#aV3{_1c3VR$oVpb_QVl)JrU zMOO8IS>-jOaWCBgfUSMXbNgnQ_$y_{TP1bebu4Y}gdNEc>|4744k4s*Q zb_>aDgiT@>!!r9A?TKFGK{ zrZ56Kv^89gIJR@*{QLNq@5I=9OC55dqL5H`RO6qUKcgk;b3oXcY<60APpxG&nie~Ep?=3wv)_SuN>C@t%4JN%>1>H6b9 z5Xo`(kCM?~V(z)&iisDW^EGxA_QDJClL1&2KWtZ_7We1idXRT!LD>Pvw;eTG0oBI% z9(4Mc@^5s9L|~Jk>Wu#93s1d32%j>pid{WZ`a0D>{}|ijqf})}S@-X8yi`cM^d56* zVONsHU2t${8$oe^AC)v%3l}^Q-^IWxTOt_(?|dB%(0&HcmVXsyEsW6(%8my2U#|83 zuH|aI;8Fhp%da$6%8VYgxvL=p&zq6W0A{4w?0!Sz| z<{&YhLU%f&KX_?!v!MK?t^q3FF(-$d!}I@rcMK{mDv!2H*#)J0`9@CLO- zfEf#Qf~s_ffc1*gU-nENW`I{8#bXlK-_LsKQLv0C#}(>M6B$#?b5rM!AOG@dJV