From aaef24ffa665d09e4beb28b3acb9354bf87ec6be Mon Sep 17 00:00:00 2001 From: Zixu Zhang Date: Mon, 17 Apr 2023 20:49:16 -0400 Subject: [PATCH] add lab4 --- ROS_Core/src/Labs/Lab4/CMakeLists.txt | 123 +++++ ROS_Core/src/Labs/Lab4/README.md | 1 - ROS_Core/src/Labs/Lab4/asset/loop.png | Bin 0 -> 62316 bytes ROS_Core/src/Labs/Lab4/asset/rqt_truck.png | Bin 0 -> 153600 bytes ROS_Core/src/Labs/Lab4/cfg/controller.cfg | 11 + ROS_Core/src/Labs/Lab4/data/data_example.pkl | Bin 0 -> 166563 bytes ROS_Core/src/Labs/Lab4/launch/lab4.launch | 21 + .../src/Labs/Lab4/models/model_example.pt | Bin 0 -> 81493 bytes ROS_Core/src/Labs/Lab4/models/pwm.sav | Bin 0 -> 71764 bytes ROS_Core/src/Labs/Lab4/package.xml | 20 + ROS_Core/src/Labs/Lab4/readme.md | 73 +++ .../src/Labs/Lab4/scripts/imitation_learn.py | 430 ++++++++++++++++++ .../src/Labs/Lab4/scripts/learning_node.py | 11 + .../src/Labs/Lab4/scripts/neural_network.py | 107 +++++ .../src/Labs/Lab4/scripts/offline_train.ipynb | 194 ++++++++ .../src/Labs/Lab4/scripts/utils/__init__.py | 4 + .../Labs/Lab4/scripts/utils/generate_pwm.py | 72 +++ .../Lab4/scripts/utils/realtime_buffer.py | 48 ++ .../src/Labs/Lab4/scripts/utils/ref_path.py | 280 ++++++++++++ .../Labs/Lab4/scripts/utils/ros_utility.py | 27 ++ 20 files changed, 1421 insertions(+), 1 deletion(-) create mode 100644 ROS_Core/src/Labs/Lab4/CMakeLists.txt delete mode 100644 ROS_Core/src/Labs/Lab4/README.md create mode 100644 ROS_Core/src/Labs/Lab4/asset/loop.png create mode 100644 ROS_Core/src/Labs/Lab4/asset/rqt_truck.png create mode 100644 ROS_Core/src/Labs/Lab4/cfg/controller.cfg create mode 100644 ROS_Core/src/Labs/Lab4/data/data_example.pkl create mode 100644 ROS_Core/src/Labs/Lab4/launch/lab4.launch create mode 100644 ROS_Core/src/Labs/Lab4/models/model_example.pt create mode 100644 ROS_Core/src/Labs/Lab4/models/pwm.sav create mode 100644 ROS_Core/src/Labs/Lab4/package.xml create mode 100644 ROS_Core/src/Labs/Lab4/readme.md create mode 100644 ROS_Core/src/Labs/Lab4/scripts/imitation_learn.py create mode 100755 ROS_Core/src/Labs/Lab4/scripts/learning_node.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/neural_network.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/offline_train.ipynb create mode 100644 ROS_Core/src/Labs/Lab4/scripts/utils/__init__.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/utils/generate_pwm.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/utils/realtime_buffer.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/utils/ref_path.py create mode 100644 ROS_Core/src/Labs/Lab4/scripts/utils/ros_utility.py diff --git a/ROS_Core/src/Labs/Lab4/CMakeLists.txt b/ROS_Core/src/Labs/Lab4/CMakeLists.txt new file mode 100644 index 0000000..67d1558 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/CMakeLists.txt @@ -0,0 +1,123 @@ +cmake_minimum_required(VERSION 3.0.2) +project(racecar_learning) + + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + dynamic_reconfigure + rospy + std_msgs + nav_msgs + racecar_msgs +) + +# Uncomment this if the package has a setup.py. This macro ensures +# modules and global scripts declared therein get installed +# See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +generate_dynamic_reconfigure_options( + cfg/controller.cfg +) + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + CATKIN_DEPENDS + rospy + std_msgs + racecar_msgs + nav_msgs + dynamic_reconfigure +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +install(PROGRAMS + scripts/imitation_learning_node.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + diff --git a/ROS_Core/src/Labs/Lab4/README.md b/ROS_Core/src/Labs/Lab4/README.md deleted file mode 100644 index 4fa5fd4..0000000 --- a/ROS_Core/src/Labs/Lab4/README.md +++ /dev/null @@ -1 +0,0 @@ -# Lab 4: Imitation Learning \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/asset/loop.png b/ROS_Core/src/Labs/Lab4/asset/loop.png new file mode 100644 index 0000000000000000000000000000000000000000..07dcc38839d3a6bf15cf7c353398c0845d522e79 GIT binary patch literal 62316 zcmd?RWl&sQ7pMs#KnNDxJ-E9=kO0Bm-QA&SJi$GoDbN}aEcF55@Uv0Ci_rd#X*Ivge(KP8CeZz?4Tk*xxENa$w&;!% z(Y*J7Ve;o)AxB61TVkK1utMQP{YSotn5h($MxmNn z+iU!{J?9Q~B$$XkOGFeA=^z$z-ub%m2~Sp$eTJ|>meLPAfw(gP z;^5#&NJ+u9aFcF+#%~EKcW@uzMd3Hrbc6y7~V~IwEJ=_m=1`&HMc0yX3$`+5do6i2F`=QR{3=;o zvbwCnaM6+vt@osRSwrjb8ulBCl^@;c9yW~1Vc28o3AAObpFO`oBN>mQo@|vTKR9TDiqvnPk z%)I7us(~P=_NP0%VSZhszR)w-ri{l^h%B5`nXS}wfGP|c?CUFPG}eFT`^d_nJVd67 z-H-^QHN8E5zHa99dY24G^uf1?8P{pwm0D#rbK%5xy<|sKT)aAa2)d@n@A-1Eo}E5L zXfD9~G5UHY*cF|3{|E_pC1ZnABqK7q?=hGCRH9YpyKw*Y?)YGBl57w`(8~)=(ga$M zd5^VA?^**7)-hI*v7w4}tMJccUxA5wx0Mfev*_p3a+b>WTmx@SiJ5$gh2Jn<2)nRr zW8M6|8r7H@|DENPf+YXK{@^b(VgZA4B0d^vs9lLwA~X70^cbfJ`PW@pE#_xh=T zf#yu<8Mk4JR@{xRJ8xP@ByXG{=c6!0%F$*g8$pIIsA?HCAnVKshG`u1TH`KMbkO1x|}!WJ-@T_$P_c)i;8!lkUlEAInX%b8i;I7N| zO5Q*6Flnod0~kDW0gcnl8OSogCL~k0Fc)P?=^>*nJf=H&o~P9*Rn7-7cDnV6(%S01 zSmT+35$OmlUdol0`nqylx#ce-w{0>&qe+xBB#&6=+mA-g%>h~tzI_hQ(Pm_2!WX|`MwsplC^0}l|$Ag@y5@MW@iX^tt9i)Z7} zUm2cFroMijbG5%-Lz5{T>#V&6+zrg;xKBa7llB|mw5dZV-3c7JLiMw4@{h_NvN}0a z@c1)8ZFrTxT$9au`ptj=N1c7MP3?tXTXe2)VzNU7TK?^UqUy9|+Tnor4wY}TDe`;_ zGv(52%V)2ib2GN%)1zP}%aZ8haSqR?^&f#N<~}!HRII}U)8e~uWt;F z^;x~@PJ9^jF~3Q$*@lkX*}!GEpl6E?vIEfg*+Zl142QoYV-0*%y996=A-)9^(95Hl zLCt^YF7sD;kwt<1JyQy`D5?pb@<_@aAFUK~s)EAR;J#eR+AqdBkZkj$e7IB=`_m+P z(q*vZIPcCsB;PH*-cNx$lgBWQ_WZb2cmMdBh8(&xc*U%x+{z_sK0(FDCCquxy!+)L z6Qs*OWw>fhRe#rsNuqEttZ~5OD?=ARo$5HI@niaN3tX#bxW-SBQoF~{a3wi1mH6U) z@hz)F`)7a5ykWmcfVy17hGAfh%cC|^eyU|*y&yTcvv5mBf980vkE{ddvD_;Bt^7jS zQu5*7@y4E5;9kNUrLdSe>VEDqkFdG3aqeE?O$;I=+{*fHz9_}{wL0kf9E<)D5jf?s z2)3+0XY_6H#z9DQ$`qbI-Fx(h6PRse)GMFw4bXghbA#Ep%TLMR!?YS0j4h+FZSFr; z8DIq;oJzE?;&8EU*U35gd9$Q3rpC~~Vxx>5^i|$+rf@uCy}QE9k*+i5DH9|}ZiHE6 zs&rp+hf}o@U#B9n^cj?ne?eI+w=-SpKej^gPME(74Sm5`G)Y)p-DvI;4;%}8CK~h7 zOLtSKia9J3`VFA^-G!}E&v^(-Swv1A2NQXaz8cBdS;pdPCcu)30wXC|si~|GoLk{S zu?i>D_gj@#7-gWGGQH39iKmDGF45;`D(5TfU3vQ#BzX_dGz0|?Y!4O!DtS`RLDeT! z%dV2`Xh-LVck+EdnjB%^1ZINY6(zH}tTV+`kPWFjn#@etqLeGpgNbiyctm=!ecvc) zcI_N#TD`Gz-;w*dWY> z3~b<61*7>0ZyH*U^b&8}3ztuqi-{byR{Lket@d{DlZ2h;ERR?0wSb8CGu4AExy;dS z^^vHiyD%0ys4o|7auBZZHlI^o=aU84j(LfT?>H#DPBtE!ENE7Cd7tWOgO-$2TnNCX z`igujXziK1Hq2L+FMh#_iKVC2Ku~#ln!7A z6tJmfXHkpU_G(Oab^bQa%^m%>{hUnAyOVn-fCn@=;JT;Uq!!rx&feZo{LJ`r+Hcxp z{7+khr1(ykam;6+RwW|ib?<7sm-XTYVi5PzwlNg>f}g@pFiBi1j!oywarqLy3e)LF zh{Ji$xq>w>>zjUFpGm%W6kJikZe%pYQ?#gXo#a^W#}Qskf9EJP8))Hcple+2@|NAP z=y@Tn8*i}9*U@p$P%-wF2!kWmwFa-S4QJt?883MC`EHhc9lQq>+o;rZ?zoJ_%F}TT zh+YldSbiHj8Jhep1kq5fDX&v-!MpG2vF)e@`W|H;FzJIsU<{qROBBCJCq;s3_aa8x zJa%kGjj(-R`N_C2?A5#`Ys|OgTh-+m4F>DexjOsjK-kqxV};{QhJXDCNxg74!}ZJ| zvyWj`*5^JxV~je_>F-Q$Zj>t|>a3S$1SS6QDaD;p+>zv(s+F|M7PPezk{p!0?e8e3n04ZI0yJI!k%OJ&B{J`fD%$7NGwt?n!qx zTD0qB7}X>NHi^shB^FaJUnPHc7{upY;^RBdOvw08WgFxDDUTNh03mifO!w-|L&J@o zPxrF38M0Cs|MiN=zpR>=kN4;E{xFK3vTXbJAYcsmuP@wt_TS1v*J%IK1+hyL318 zhDqQq`Q&wKv;17YQxkC)_U)hk?%3}xX3k)fWRTL((7aioZd<=QOFZQGMN8>oT~O?J zeo3TJuDf~Cp6$_g!lZvD9Mo~{g!FIks$t8HaV>OrF&YfPVdo5SNfL~gFLmB?%UUQ68WzddzNCHv3R#p<$? zD)*jOOg%=iyS^AB4#=Nvm8cJR6oUr{*{hu>B|fyMzl`^Fo6+t=<33vQJbAej@ef>% zk*FM>C*wW!U5X=S7~hVwwRU)7tkg3WZVxF%>NyL>U)mcF*K{bl^)tz5@b*j*fmn0( z*KJpS&uTt;O>ZMDDMj7;@sAGqL>&6Ld{l@Ai44<%t<+B$dS=y*mu?2opI-Qr+GkK> zGg}P)S(wk9yh$1M9(8nPBS}%uR=k-eR^xU?V++?bEFJ?Uo3{VwqEs>%tF(EY1;6Ux<-ZqU2>ix@uvgZR@`G9uQ5sZP|m~< zs5^@pVz?OlL4G7-rmgZke8Dbnog(9bnvOS2GG*bgHSJ1YdZ&vV&bO=0Xmy^E-9NXs zWIA*p6fQJsAkZ8{E|oC|O5FCCEwSAdXr>X^WuHmXQg`Y`Qir&1Ovh0Yjwea|d&ZpJ zOHqMc@UmlM=W7|LphUGQGD+qEFePE|dn#LWl`YtcztaQ5zEopJ*sKiMW-Y##oM_!~ zQ>YyR+wTRi#%t9cW0J9=q?nW&(W@mBd_jZq9!fu;Dk@1Q*c91397xYsu@lsPK7(D) zgXviZCV!u6tFBk_*Gd0o>)UX7it__!s^V?9@o>;3qs2YIN9?F_oDkfO zCTD32Q@*H7$H)wexVp|=C>k_K;+jO-DLfMUuV%?-9EelF$tK5SJc{jVLR4x^p-^kC zFr3@yULuYdnoIuydoCMOR_as3eJ$8-_?V=Q>Bf#$*NEEJ&cZgCz?tcBj?2hxa9WgF z|6o=46+BX|05=6ZDB@TZO1lDde1l3^y;82VoLXUS^w@T`SuVrv^NCRM8JE{DN$_6! zZCatbIhrc<`w;HS=;6$JEL!~R{D0#GJEgkQ`?F!{FrF@ZdC94-3mxJFa8*Y8k1mfA z(FGpK%>2FR`1s$}s}pIr%zymO^L{*qW2tL^|mJ5qk#RQ6gIBPTmEpe!7jrpIR#7RlG#CUSsuP(;r#fB1{n%9Ea zJ-op<4ysiEhJX8NuyuT_L$a8*?%lLE{%=qvRG_ii=gVgU0}!S`htsx%dj*|dao@YU zFzS~4I=zO~i52R9o<$|*JpR`z#S-S3|HpPXg9aUI)_?u__5W1=BZ>6M|5N?LF!T%+ zkC~4Q@%(EbcAyJ|{ulb6ZMAfPCGtP@oS8h|pHqMS9JsMz=oLbKcyW12=CI!S@cg{O zj~V-!E#qIKmv0JwdkqW;QK`4pA|#w;VQ#2dvd!Ri2@ZfqRW4Sh^a`Pf`|_`;GW{kc z^#P(v`b^o3sx(iCqVs!fxm5nB(#mJ>7@aGM$4zSJ{2gZ;Wmi`h4-b!Fo%ShFxT*h~ zbzfJPh+HM*f>O51Uj-TqpHO~D$vu_%&nGmr|I3!?!4KL7v#C`kR)=s)teA1=3{66iI?$74fxh$C>A_ihen66n;z2T1%@*Eb<% zbH}>gCOJ(1fj0@Jg|(^Kh)Dw>8KupUrubN9NMGy7MZ3fIHSiu?p{Phclka4`jljRN z^Gm(mO41a|XAH=Qx{9)WKX%qk2+1r}o1GHIu0|crmHZv8L=5p*Zx{wNE~m9>^9+SV za)5M^q}Pbujs<7}}Ca#|TMoxw9= zOJzxw#dj8f|12*%X3lP2!@KDqIC1pG?slZg(&RscGpe@bJDutKeiW6}^TyIEB)jBf zr6C57-CQwW3hj?tiA0rg-^0uG1h3|deYYk(TzMHVMOXwJ86M(XseX0Mki?H}%GL1=2V9FPk+Xxs>T zLIdkY!+ugpXBq3(!(RKYp6Jy1((*OsdM)l8R@3kOfB&Z0o5)s3X3{%Ys2~vwL4n{9Gg+)coy4RUzGPcy+!ua_qO#NOI)m925`CSr#}Q&_>=<5K zP38`rHQtO!HN+bjFrlID-Ck)J{{4d_K{9sB=0>>_pG!J{p994(HlXb6_P`{?=Ne{X zwH1TgTmhQ&Zc)Vh1Uu(t!L)e7%GTC4d?wY1EB*4~Vq-Ie#Qgqj?fv`rP)-123atw;abB3F8lk{#}H?O>ahQ7e^P8jJlZPpLY+ zpy!R@c7GHmooeV@cHq0Y2$+t61~ zAhENtp-HHLemA(hpg-U5;daTGw_UKFUgzNdWIbyZ3`5Hluc6pK*@!?l5ga zC1euH9>-|{7s|>N<*2K`5loG%Bgo%A4GBjKu$wO{yBlzB?rn+2YR9l&oleyDYo|paEGU(WP&5zP!WbET+y^Vdq!{xoE%?l^-$v!pX#&{o z)Vt6@QPFyhF848gqqnHm>Y9?Q@4C-NU-q$h@fW*-Feuso2d%fhytj0^`b^ltHBm=& zNdQJ?>crvX?K_7P-w=P>W$~4{%+ahXGLVCiNJ0ts*?3lh&1%HHzDHy@;2FFw9Mo@e z#p1X0DcnLOBdlPKV-iogK(qhv?lFsXaq`YY zvW@Pul8?-e$1mUF`f~4=+NNi3XKeNAIpu-o>CqOd426|pYOE4=+7hqKq&yq9qT<1{*cps%01F96kWCQf-@arLE_P%Gz;m&>ILfuw za4zqh0Cm6U2DO@vU^lxScFz{894=Owh=Oc{g@u=Et$H9z>2SJ0CXU%Pj((_eSCZG0 z<88n`j5Z^EAw&|yC(|-f@A7g$hH|#lTclT-!RNxwsWGp4;{6k{_k#iY4hmywob0#H znF}jLKWCSl-ejWYy7e-K&%$y_49rhfFWjO@Xq1twZF{vb(?yfp)G5FfN_7X>|Su0#q8Cg6x0|rCM>th zI)EiG^J-TwS%~hh!K%p{^tfN+w*nRV5`XWBVq(`W;@xIMkiJl1b{j|Q>MAt&=I3IW z$;;5+Kx(8;0QsR-_nF9IRk+?ic*}V7aqB*26|(YvqaA0DxU2C4L%WY686HpKq{hoV z=U!m2YqHcT-(kW5l(J24G~1suJ~uc!IpvrPpvY$Mgt_dGLr>=Tc&V3acAcklnH8Tf zP!`=D&B-|NQD$Xjc|V^voGexaXxCX&ww|4x$xr2erPZt?WnyB&WYA<;s*O>wj)L{g z%?8j*w1UZDvOVLtqO{q(`*=HtpBe_Lgv{aN`Rfbaj;Bfy;Em<0Uh3>Q>}EsZ+>WO` z7YR`$MOL}#za9u35y1&Pe$F&_$)eX#zj9tFGY{o#p5Btrj}+wuI(+t$X~`J!xic(`$=KlIJ%N-~|=9~Pe{SM!Oi zOh>@1Emw`>rfB=)9zmgergS2m+5xCT`1R?Qf{yMedV1Arp$LIszl{9d#?8C-h!YWJ z@QO=s#!GDSGQ2WBslWDZGmHBv(6%$|on*ii(^9r{Gp+{Y8iUMelp!)CVosSxktv;*8G^-~667$?Fj62shK zc%e)b8mgO@$AO0kpF7tm;L8!fI|!>tMVfCqg*llBM<$8E2;$<6X7I+NQ%XC&JUDfC zcQ3XA*>RZldq+khe*Ge?w_h8H%iH}g3n1<2$U-fj@k=}m{qIw-h}fo$ysp**Fr9OD zB&@%HMAq={(Qy|exw$389t8Mse3Fn6C>ipS0m8oTLWMd@q2-D(7JmjKzbk%z*e8^$ z@9%i9?N(3gc*c7rzKkyECAwD3*~ZPXG7RQ8D$k2Qx*Gh|fH#$cR!65sx>5W{xXK>? zJ%;O-M8R;a_bYe#z=TapZ7hNUSCLX4+$^H4M2CWVzk%++LQ8z`mFamo(#w?;{=jbA zw&C#Vc|w5!xS-uYxq`m5DCt6Us(*`+z z%Ho~cytruLxLz^QO7Uz>)8+N_!xjY+hnpF)(?F+iTgBEYy~7dWgKCkTjo%d?G?jz( zY{@$uW~y10FkX+Oywj9#H!fO(quKGO>oER0h*>0`dPWaB;$B38_cgDi6^M^lV^L05 zCV>}4Cm-QH>^;BLc{q)oMsnZXPt6`)A_Mj`yXb{YqHX*NTc;DYn4A)$0zyd2^zp^+ z*)B)2w8nINR%QzI__YBZ;j{z+TN8N2WuSHe5`>+?v9t@9%|ZPi(Im20X%=&lb){FO zYvG>2Xr~j^LRq|wjIHIN0**{y zm(3nsKTBv(YX;7^pXiJ^Nmbr9W?Ga_ggJ@t*Ac9U!_AL|j+V;8LRT+=+1zS<0gmqN z^N}JX@RhrX-CuD1LgtO`0VZ2%YvLfon_SS~{vp)7%;@P-Bw)UNqefl+#H)jvVxqm% zLB~^N8jrj}Z(uMv`4YywN_a98nUv&tBDeSN+4e%(v;k7^j1Sny9~ zgZ4n+I~bTI_fvd`EN@Qch{>jNML~d)=_VJ8b&u_+&%3lR<7EdGoegbu{Z z(B3ZWJOC6}w~Ns-NE*ZJe54I|*)rW@ghpQUMh>q{9l{r~CxY+sCs*;9z$`JsI;h+H z6Sa3fL7$I>8Uf6}BLSHuRVLER5)||C<%J8U_Y@vPV))UfQ+YDLX&ll7Jsc9Fy+JBdBv{D$v`sxho*=ol zFnWR79-}_p+(yAs5hl*?-3g+`QMTXYYe%_&wqaSYFTC~$1X-|9*^&-4-1ozTA|O*P zX}ssYtG+K4&U~lbG_#?`oY+jybP?|tbhXqkC+i|S-b;0B`Fv;dQoV&byux**TQ}wX zs_LRo=M}pYpufFbLjTwn%UpP{Eo-+BhERvX!urXO1V?7nsB2I(1E6=2a zJoPCvt@gO1_AVlktM`kZYo#nc&kE#;bBk z!zz1SNp&A5MauX%b7jMYup=)zla^KEC0XGdar~udrdZB(c--Aj?Aw7ub z4PI*3p1~h&_^j`kN2dt}tE$S&n7QzhINiOL5;T?>X?^!TkN(ucJU$x;7BlE4HV~Jw zAZ1HXWdAu2Bnx_N*>5v{@bfIeN?~qmU+O;Yq9y9kZ{=yHXP3Y>K1X>xZKC#sLXv);yUgmD2}u z1m^zmU2jjtf05oN#Mpi65Y5{=XFJX|Z{0|HXnW!Cvg6Y8S@YMF_ge}PG2qx(h>e*n zw}DbgDkm#-!@2r2R3YP=BfX$O>mhkKfI>vBPzRkLf9vX#=m6$LUk_@NdW(LXWT}1tvW5{ zI=I?OoB~ev_efS)@f`HN*2Q|v?29S0!vaeHW5(nMjSZ?#!{h9zHMyMxBTLHiHu*xKv72mA?XoYw4%{b#>W{<|%j9#jT&|^E zYXQLjvYg6&dDxB_x??Pa@^s_vTl`w`ySkC3&6n|=AD+_+_8mOI9jEbRd>< zvgIKP3t)fodS!Tw#>1^c?o2daVSBJ2OHI<4^&%Y>mRV-YOPHSEM~qfEuqYZo+VupFuN~ ze1_C^!D-itSRwlCgLxam^R#Mk`}N)AVXr-x!%}}Cmc!)9D@khID}8vW?og9T5bpBf zKqD~9F+&v5d76dBc2#H(C7%zZ^)_fW@O3DTlGo#cl-pr_2NF(z#7?iTCxlfBWm5w^ z%^;^KOj_kYl_L4g-QB*f0Qe@y&3C}7og9cC1|TG$#BDV-h-*KyB0_D;n7@$ed-GNv z;4deHcewKWjz+AJ6|1<=ThYV9LN{OZmP30(>>E5Eg+KF0%}1JY6lcQR(9p03uUMBp zUmft+XZQ8^YGh|G>u=yfPhImKVYU#nKW~Vjlzv~@pVoS4nhj_g20m#y+-m9e46y!j+XpJmOaL*)FNrRJI4`oaB2FCDI2s}k&425Uo|?8{dhs5!~ke&%ma zqy)J8Gd#Xg{L#Pwaqx3wW{Wj{zK<>SBg1a)M8vi){nzJ#4P4``zyUMSj=Nv#;w~TO zhh<654Bv3U9PFbNEEZBh920?uzVFxYSzeZ2T+^B}ges`D;t-FiSe=)Qeju|)Z|*n# z1e1_^yq}P4nLapODs7z)B9^z&s^;{!Kc@uWjj=?2hSt>=$Pi*j#c;XiQ zRlJ)m($W~tJfj+Qj*6`;M{iEQTtrwRB&2(&cXZjN#|SVz%t4AOe-yg0iy)fmK{GgV z|MR`Ryl#NqN_!@yOfuVL8-j<2hvVheS1P%z(MlsR;KSyu5XRxibmq(`$8j6w<(jgj zq~z6J+gb)i-Jz@W&Rw1|k)vZ}+!a(O99KHVSby2p_8vgphRmPd-oC*=_D5PD(8QI*aiv)hDb;pvdVsq4-S<$<1#TH zD3E`p_G2lM_p%Qli`3xBqx|v>`_#JEpu@p%<|(X}NGCW3;4NO$t4DmTp65Blda??P zCnJhqkSt!%bJEqdzfa&yA48x3Pzy;^;w?rVwKlqL(HJEbS?UerZ; z4r^jHauL9(Z6BocE;0D4nm-#0n0GWE9;XfN>W@oF=Dy>|qwEYk`q0MDCx)Jqw!DQG zPDfxV`wA;)m=nDuI~VD-tPEAwp)!oux>i(RY+0{-#i*n9WoAw zG}wuYOh1|sQC7b8tiQ6VdhnfEG~)ob%=jjV$0IwM*L^Q9_FFH4x*iG;fA5{)xRd+gZNuY{JoT#eue6<28)zkRkIWLXULqi5XAj>eW3R(G9dbx<|31 z34T6j@F*0Tc`h>_`}y)&xLtV!L#jy#LFQQ?TUEj(?%BZAm4jaWrFSs4LOEAlS0@;Y z-ZvMLci@mF0}Vz(oQXP31_XdKhCFSq&7#>2< z{0g>npm0oZL8I$n6oE%#nG~7@sWDE3My4Fi{uEb`=G&pbxWqsky3;NlntyUKju9DI zDp5VviXEsu6B5v`aR9XkF5I223_vnOOYJ^h{U2!;lEX~&OucW*9$c>|%#(M|H zog1#SNv0sX*w|=FtHa(g%n)WXuM;=Qb2V48M3lwVXXHd%;qT zR4&N)y;_LOdRlwk! zr8D!pg{`Xw&F;v4cP5PgLo|3GD0{gtCxH*ne8vgbkma}O=Y7!y54gR4K?KV*P0k+u zE24dg@seS~28l_6+1sZL#E@)@U+IvI(AcwB(e2 z@u{ctqZ5WE0VdY5gyR>kYC&c~lFsSJ0GjOn-^TMl#Tb0da1F#!O&?5Bfr?+hrE%Sw z_MIf^a{5c&VIEoqs3CT_f|AI;qzs~|=f6v8ckzfpqMMsu9;lrcY< zSL*47>0;t}<=WyJ{N&;tXvC~;+!rEae-A)GA^*2WmlCJ)ozlQw)y@~v z+dru@S{*)EHziWB+EE{BwBuhe%ayW4Q42V_eV(REz)Tfs1I@>9pN0z^{CX{yKS!OZ zl4S_t%VvcTOxa!FQlWZ;3i`dq3oZ~H>fW1=X7UcbPW1H!-BY!uvnVrnZgfptcr@5+ z;TPjnd+c-6jCp=H1<1I_%Xtdz4_9)zrEY77C>;ys_sAfoqCI|8;7$`u7z&;%{%{J) zkQuug0*LK?Kc6)1M65m6$?A??$EnSW(ZLRPre;^y6hNI|J?Q=CWu9Hjtuk98fJ%{;?$-H22Nl>ZM7{FLb+ z9joB+to|h&V(JYO`e2i9%M&jtSq;l;E%o_;qW!}MH>Ljb4$dEGVRXf3&-~#4MAPmx zpf}H+9-k_{Y<>+t6Y$mQ{)FeFqCYjrBTdL;`FiJNy0I}i_iF9L7$om~(?coIu^ziz zvBIK-bft>lU35)Cw&Y{F@7~I0k4C}gYH=$@%#%zj#(3REgyyu>8^)nOjV^2N55t2A ztMl@SyI3||Fr+|HnWaUDXyn17!q|n)ga@l&bFnG%4}yK`7^*{**(`=zsx_-oU6WGt z0%m)K64f^Zdt~KoW^NK3NXQtHRjIL@A`eC(8eXcgpfzY0c)Z%pQ!Q3z(5!^=^Yf!q zmD)X%{WHx+%y-!ZumA#8U95vsojAOv?XRr+Im>&lRsOL3*3fyopcii+e*BH=2gH1y z00;aU^*Xn9BFA=Q zB51Q!U|8HpMr!CKCks~yrJoaii8sX+ha{wW(!&dEzOa>Kf;$_HH_J+TaFyOtTj&o4 zWhKUWM(cj494K<0;e}xyi~;;2bEv*7qQj{zhn7%=TNdT2+DrwI_!5b}%C7M_|JwTv zY<-yqTk6>m!r7~y@Ft_`cy)IiKi1yAe+y;VG_Ky%H9}Hp@%-+!cXw`pfv>Wew}MmT z+mlqY6Z@5xq@$h*sdzF*AKJ#r>j4kjM~5Q_eJ1(I4Pi$?ePa3kTG`Q&132Gr^?|L`4 zeRjN4YEbA@a`JwpUbcht#-UTCRsRJmSm2i1SIGP$R%!5g-^w+=>bb;zO8w{ug25O! zANDQ_T?6iMr=~G3a>2C?jTikhwXehBo0^eHDpZpN zP(PVZZ&!4#p_wo5&p=hZF|a1?uK7#;$!E>2-iNb(W(0{_4I*V8_p4^cB>0`&+3-I- z`8=XP)JPlg0aHA@1h~YUsc+w8WNDGS5`lkJg49ReZ)Y~4sWzq@b!9mC_|3cHI1b4A zm;?mrrhJt8`ucyVh7b~89;5Y09=|sMwLhwxCrd34cVOsx=Ur+0_12+ZA^}h-oHp2y zoKC8gJY~agwG!;V2**sJ9L&~PJ_J2s9Xsp=$f|gjP6ixpbOqS1x2DEX%1{aH->f#d za9GcVhGWq$^9#i4+7vxP*_GezdX2!>(o7DnZ%Q%Mx}R!WFO)|?vXX8w-wXC(%g0>% zTa?Vt%SYO_4h{w((1YdNAGP2;gSRn`d0&!+h$glBF4tjEXS#a{Ma56MBgxbZ47*9W z_i@R|8a`4T(8ft|Go$$I=17n*Lhl0iwiu6olXDP0r}e?RXQowYMQF-G^02>&hrj%c z18AImVs)2@6b36$`3z;tOHPmATj((0M7tbEOEDPW;oZ?;4u zW^r-x^Gq>tKNE0qbtS#sR4@b!4^Pk9CUd%6x4ob3C!c~H%hMnMI}uMElSu&qh?<0X zS{kQa7E=PPVlx~kB#+f{fev*Jp!IdK&>cQVMy%AJBP)(_=3x6Tc=c_zc%^%tY|u|P zDa!>P;@@u7hDzDbH@WNw9(ujLs6l|FRq_2UaQpM2Uq*rC(7(*B)R{`7M+22a? z{bYZkEOK(xN+jwcR#sLmZ6(N7tEu(2-`Ur|_K&AlSmcd+mN7IGgsh(RIm;P6M4J|A zR&7DH^1^z~s>UDnvi=~%eMmt2Pn%d%#R2Y^Kql&0w2)0|(RJ6_)Z@k(fbKJ{h^SI{)C0~waIzc(a~{ml8q}pirr$| z@#bI(sY3FE^MAF%|6hpi|9@8~=><>vcfIc=vW0wveZBH2Y#+ zgI6+_cEJw;je5mU6UW9cl=BfcR_W{BQ`JoK*E8!ii$XvrWglTaKKz;`S%_#GONt*(Qy&0k5ebG7ia-Z+g}aj_G01_uSig-Aatx4R%SKm6Ytn$A z`%=*|8G%WRUi^o=PFwH)_Q2IRQAtUO)x&Fl^X5`HoPdkl+rF_e&J~kJ zNOov^e0*mpo?7f06wb?!PA0`0I}}+P?T|hut~mLq3PMFi9Wbt{^aH<{o(ujSQf~Kt zq*X8FdA>UxyQ@}NE`kWLjFhH>4>sgr6MK4$jRp;QCm=51>Euz->A`L>; zIc;_WAzI&aVjjr6bMqDWub_u_bO=Mnl>y;YBp2=tHuiCny|V>U>%^HT%gf6fo14)I z2{TU3R#wU;(suL#^GlHCOduQyZ96r2oEk(pKI>4*OF?qdvXHaX38B((I4148FN%sk zGbx7J>{lB_Afcu|=Pk|sYm|}U;msOkf_VN$V8u=VoQbOx=O1&niEJ$&_LXoi1xBCMVa*;fKr$Wy4uQ7LU`9z6hNC zqd*Q;PPMUSNFp85Pa}xJ^NNj)U5)|J($R%ONYbP6Vj{}+_&!5z6S*K_&KjQLmDf&)1m@;d2R3QC6(OiMB#HnI0h1kJ=-oWf}?89N;h_Oap_rE zSy?w)1+aNVdU|*iJ~T%}u>b7=B$O-;!6r34nv~Ti;8|I#nvNEmG^&riFGx>YRy~BE zJnq*JpdtyllUPmq*-ZM8_$3n(#^C{y3%036FQhhSTF%;~nwMU6f4rz5kfIN(EXRLY zfFX&dgc~3b2;pc@d56ZvkV!~Dx>X>^xmUVCI+4fqfF+(v4%&I)^7H^#qfCnd8)9Cd zFK$K`X^POPTcVX}mLlWh5g)H{MuUI9O{}lMH@L0e{{TRN(zl7-YQHQfJRy*Y@;OQS{gkRYO-X69+?v}s^EA?)ha~j~h zIk9(8?ZmTT=S$WD3jzH!h(+eL0u5=YYj|t65Sp>Pm1NX(ZytJ%F1!7izvJ3%q`wNg z0~7=KcLb5q(eM1}TW-^$I`ZmDZahinzeYzzIXxY+(VcNNxMkM&9CvB=E*e+izV-M$ zxU6uY6~}O^Y2fAd|z9C|wmN zEe`efam*qO*Z>ioU}X_m=v@M-^OWrDfz{QFxt`zBIfjPD#@$CopLkKysnC>o)#bwk zl`+uD#`mvt>gwi>j66g+@EKv%tTW?93&9N#)$JtKt(j`1<$mXY2?g z506E6uVgk$#j;Y%pNS*8KSy>G^kOms)_TYK=;&erEE(v)z)b$DY7AyHG_`KXCGNkM z{Nwqq(1(5<^Ob1kBMBR-NUAD*6%!_R#({J!8KWy9DrQgyGWo|Ji@tyHmx~FtWx|gl zkClR~TGOW<+SmxzlsJv3=xFln2^~SCTy%G@Bzoc)iufVNaOT(%4jn-#a<-7nAI0Uz zYVfdfGk>!1sgD<76tFLDFxVeM_*?7vL=-o{99cR{Y(@@RxPUSKUU% zP{)}c!3v0sDePRoY)0ld2l%|oU~npGw{e>N+V^meoPhQ)P=+!qqK6aFS(e4m-uB(6 zqM`qTs<)1cvishL2a!-g1nE>l1q4C5QAb2tm>H06rMuH2L_oR(6eMPbkd{V~E{UPL zdnAUA_YBYH`&;W>i+^GayB(J?GoUP$hS-#vTpgPFEsAYIMK_37p(ELdYn5`o_8w)|Abj z-{sMKsz2X7bZ*5SD0fubkM<96FGi!*e4PvOR|VlrV-04^g>H~uqMQFCsnq_Q<3B^A>?nVp1`Lb z$U$fH4zuU>ruFJVrFu~o9}JVIEw#7VfZN&#!0K)#hgV5^+=Tqgn(*WGm#P18g|2)5 zo7bu6c+DZV{p8P}W1l6IY`v#`Q$6~H-7r5zuMJWZN*GSEViQJm;MaBV`xW-YPf+nD z@>ihJJS#ZP{5QjzKDU|QpK5_!?gvirtyIJ6;(G&q8^wcW+7wxsR1e&b7Y3xt9{qP#vDt$AbhF} z!V`=MwBH{XtU(~I<%Rm;h8?<(jz%9tx>_HNX`IeYUzV#E4x3`>Mo2HNR|fykNo-(a zGpw#ExKI)xPI!UACKaqLudnAFJrOLjEFI-}9S{JxBCpVrhC^=Br@Q?>U00|Um$c7) z{IRwBylJmMs>rogH_ay%FWX5f>{OvTXGhPVI5TlBXUgh4Ar@xl_dQFEQ5?_ivplOz zNb8yF4Q?Tze%DYkl`AXX#y%+ylrT@ddp^uA{Ds{?0pIsR*6$*!jf51o4P`d_CbsL6 z=0q#1N22qVw7rwe(X`(?+^|1MbZSCXna~uyY62c5KNd*{Q>4g^ovzCr{u+VHX`m8D z_V?GmM!@)7)HC<#jS7$a zBOLw||9vMxJyozf1J+|Jh7Fd6)99$xS=%ZrV9H-O@Rc=!&;88T)2=7!TPe*!Wpy;o zIlXT*L8yl^f0~JHs7?AZ}0%ZNXBB-vO zo*@`RMm46-ZPX?rO^0#M$h(eSqvHt=1c`w?xc1?31Vx3Z_X99-A;B+HmGYdL`s0>3 zS3{}yn$z9XlRI=iTh`7bXAhAtWjKdSN&1d3x@DQBq%!}^Nqe4tBv4Yp1gsp^^$j5f zd!%>BEG;cp#ecY{);GYOw$7~oz1(JP%2*g@ zqbwog;)akB1&@Jfz+)JME?;_ssu2Em1T@Km{3k??+9G9|JDj>>t*xX$W}N;_Kl0t} zeHM|t$`simC@pP^69~yw0B8TYW$+zE1kY4Otb@Fjgi!SlL|9iur}jzhRN4F!)T{bl zE#2Vu#pmG+U`Va4idHF%cb{`ot&c0u3*hfwTtHbJ)@4nF1>eX1Q7&ahuUN-vzX;fV zw@s1f&gWHUyz~7?yeP~;n)TI^A$#ylvKD)Aaj~^G7>{xRZ>+W=y-KQjzwp7SKRWmk z|G(MWEZ|X}!A@jSL?#TT)`8iGyfEG2#8R?sgtndm8}ED%jmm!a?%lz1W@N09_Kjb# z1z|(g{=X9wfL}em`Iw+~XD91iZfJD$?_qmSS-eYr{;>C{q&wYJnn)=OJC=|DT-@9H z%g##id0(vI*6qPMiR< zWz!=rYr(;zhJ}RQ<@fjh9L9V=mY4Sp?R9nvyKZi~~$(kveT^gNxbUhd{h{oBD>-{fpb8 zoiG``$yk>tVOH;d-8%|iibTWG$QOuuQP}ThMQAtPyl9~IMaVxq{&(n`CG!u)o8FE- z>dG{s&(33`rs>;oae)MS_{labRZ9sY$2nj_TZ+#}CO2Q2@urp48CvG^pu2Z% zW31d{E`sG?_jKRp=*;?(dq?5P)dHic_bKPQ>dI#)p7-AO^6Bve4brKl6KgybchC@F zlU2EN&{UA!ckVDb{$5Y)W55Hwa@r@$`Aj>*HCa^{S-ows%_AWvwn9O}in23azee)bz zs$T19mvg+ae^OUGLJ&i4P~_dTS=(e)SLnOHxfCUJJGLuk6<)W|$>dODf+ki9g3D)1BSb18RIBsLllhOahe<|; z(3a*k2o&cmBwKrG#0TMzWwAljPiNZM>3|Zz3c645x^8cCHe;Dc+zE1|)Co5r{xl8VkTrWY*K6_w4bp)&_u@r!-qfkE?dsu( zQj^eK6^%$Y_ap41s-mpF;@NAS)@z776424C38t5_avRt5MDn^c!|#6e&OGrhkHaF{ zG#Hzd+D@(KRy5|xtqdMVUIup5y;L>5QOFg?P1)?~YedYQmPM~DiLpn%;^X~|#=61s zw;%=!RbxCWe3G9@9EqC#dF|}UE!Y#h{++5lMg-Byl}fDYYQn8KsSF8X27}JFoYsvj zK9;IHQ!kw!aoCM5k9%n&m9%a5`p>>2Q*v4Or%%Hu!u^2(YIp3U9Z+nq$?>X*Dy%7w z_3gujR4@4De(*}w{_m-g-(YD)MS^+=HG;1W1r&)-iX?UAow7IbiwW%~&PpzQjO*u> zpUUwgHxTj|IeD%Q>Tf6hwW_qZ)|M*lf9TJNdp|%&u>vQ7In^Abfem@&X5p^u;eB@E zCB5Cs0V11_!3L{Z==B(-Eb#7?ywQgW&AYu5A1>`>_0w;xX%$CwUu!>C`$IyC2!b07 z^-fHL_x8S6Uc=3@tFvvw)Es8jnsx^_&g&yg$oaqWUKbYZ}_tv8AK? z)J0y=F<)eSXpi^Lt1ykXGDPr7O;LazR`=l(&7TyRIEQU>TN)RE6e5jr%lC1bF0LLP zgr9fz;ST^S4ESG1=XGd5`g-Z>%l8VT4D7e|FwF8?r9%q-td|a>f3ujzsE{B5Uv3tz!h;G$hP^LsugF*S!`-rkQbenp4Mo@=Y>Z}@)pQ$Np> zF}VDX`)>kP$l+_n!ks%&ZPY`{hDP^{LEvh?$&;Lnn!=VMkyp%;O727yd-LQRepIXL zdD`cB6w1IX^TMa8T>ASZW5u#0w$tTj2#PmA5`mSt@$Q{Z9M%EV_vY@k_&g!I_oUgD z>QbC*Fg@f%ZxJDd;o;LSd?#i_y1I3f1M)@Ix&r5Qvd59HHjhel-y&I%Ul#RFH1g;* zY*J_S)TDz$-EtRhmz}H`a+TjJ$uQ9rXSQ63ZEYR~&dF_n*%!=90?VvaP%_@HPMt#` zxuBY&W3)P8jItU{o(Q#IF^iYK6?k^$uT@y&d)0xqlovyR`toJ4#-fh}lPizK`ny4#(?~JzXQ@`Qzua%AgC;kCVW?;e*`Fa)c5tV>XYtRCGn9}lcgl!_{TH@d!0_^h0$V(7Lq6lLkn?ye- zn<4|~2s$C&{y3kkwdBaVAER z;f6PJ4&w_S`K=s^a!6V+%}bDxQEu{)TyMVrM73$J!233)Ciy>gsyrOX$!h!{CF@{ShfG(cE&T-J|!jPiH*&gL4e_!AiF1GcK=v;rnIt>!M~nuX8*UMfhqw@1w}GR zo#WxPpKmbx`0y68p=qoZQw)LFpEDa0L7(P-WW_bao^b>eASJ{Go!yWsrfqrU!{figQE_|714tL$9}^4w@?omfFuw!Y8K2w za&nP}hlgAN-^)8$BD$uWd%d1@=?5iT8hlyn?`S~*>H1tYoX9YwE;;o_Y z;eF+&lRwV*Dy*WQtWPk~|IoEvp-$68`@h;ng)6{$E z52ano4n%Kzc&&_m*zJ`3W2(;1d>xEp7C`rqueNC3qU$(g(Xi9Nxl1U=U1-OKJd$vk zTZV0Ns@ff=2Qv&iH#pgMiJGlXEp`tuH@}PzjUIpd%(bQ-+UgI26|mMLJ^r-86l@4@ z)wl^S5@Oo4-HFM2L*NZ+<_nfaO)$LbNbum$`EB0Q%iF7E=?N>sG@2O`SSzuh^fi@hCx6%0m*{0o3t^i zB|(3bo5^orvB8FO)axT7Bh`!#N1k$Ot~<}gYFrEpKGs!d6tNPIij9+ zmp*@S=xp7f^ZamERSN0m@UjGG@ZJ4=G2gV;!m9@qLbF>xi;uIUzqa2&<*3WOIA?T6 zhwxat7heNbw_TQ#lO06_wv9V$mHdTds)A_s9xV&+NP3SMtnVx|L-(q<3$Pf_=^JvH zEU*$e^i{BuaJ!pY&+pUn+V#&8&-y>l(#-n!g8@t?BKWa*Vw@Dw{&Fa7&7oR42Ri3> z$<*>A_u@785>5wVm=IQm-J0y;ZPxi#wSOeF7=D%drhe_`HHw2~z5qIk`whVNxiJb- z0%U}TzNZdnPe1h9?W-MDEwr#67h4Tcmav+uV`+K})bi4<0*KOF8+cUTKi!pY=lXo5qi)n0{+}^6Ujzo}T~EQezr%d6cfId$ID71l(tj zNhV9-xtgba{8QV|r_jAWj!MvWJkDAiV^Cg@EGn5gq^cUZ+WUGMVDJg$sbMi26V*dE z_j{NePGlfE*&kBiGT>ySXXfl(&3F+#acOmW`qpErlwQgx7oeP@sAj`^?kevH$g8k{Q&Ff>#_Q<&Hu+ec~TiV*$7-Q6CeOe1ss#>zK-RXfwcjq za&YL@>MVKUwoim7l{)i6;ONXuLV)NfpMee@MMubzZc^S{ zC@a_!X!h!epxsgIWRL$|iJR(5euZ_rz>9jkg~JHkHN%uX9KrN!@$mtehs(~okZCCO zsyix;>LT+Jl_@exibRmz3|Ho)DxWxqalN3NCt*PgWj=~sZ&tL|_qaNo ziXwOcbZOL0Q;^*KD2BwCmZ<~XWIeJA(5YHFZZMhJMA=Z+n%W!F14~?N2+TyBiycKJwcB1cxcAU<#I=WFOZn8{<&mWn^L0IU zySv53eTL)}1yV%gY;~cnhWHn{tgiHRaMvz|C}a+o+cDMcl@)SVXD0?7{(ZO8UQihg z9k(H-_B{7BVTQZEju>eS6psCd>86m-&P z{PX91-)1eMF!LJmyLkPfHlWl8khR4Xu}(r;Z?5O;QALe_VS``^_hwP6Hv9A1vf`Zw zZT0R#@t3+R@xv1|v%zUrRaJfMFlCO@UABO@JsY!wdz4h8d! zjK&Pp%XDn{r%##;?~8hvE~!-x9iA+C%mOC7xXa=@c;wb`buYLnEe$}DNE<2IQ~&k6 z8Qr16sec19HW=)(4>t9eS)?BW$@LRn5akc+2sB-+Q{z`w$?+T9k;XZM;uvU_h&b#IX(T%L^vc^E`VIhdGQfRP;(f7Srt`A2oAf?)00%KEzN#;I{UpI-Ube7nrumW}qfj_fl7 zvhn(m{FFOIMU{cJh|T^kzkQsswKZz?Ku=FkP{xlS;ein`u9cf<$v#MPhria7=lv`h(OH!$&IW@WQyUQ6|Svo=p+ z=zj(TBjqwdxsp(F%Fy$}mrZNGPWJ>yX8AuWkPe|^R3K!5gd^Gy%^L5I1W9vp+J z^^4)!j|A;>ct^_fZMv2YtwV?2H8nk@zDjg<2EU*!`2M9Y0Eu-}VAtmXtr6z7YvH!z zcjA&CJ{!I)V#n^#=aPJcC|NjuR?t5BZuWJE2c= z%Ts^E@M~f1CLu(6ce*Betu61wD=IaBt*Le%^tB#m1qV(N+y|w}y{hOc2FGY&`UT;{ z4!UF2vTS>ut*P0l)pyrp(PjQnsbCI~q@pnDp9A^185`1i z2mCI*-Wml^yl?iex?4wC;SPH>vF`&FANUA$Xvl?)3b9p%<6stMoT5*yKdomgTINY{v1g0|BTX5V zk3^-R^dGclD>}ELWIHCY)Q;z++G6Skci7kPp=s0xGB3@!N9&a$CzWQ;U6%=DBKsyH z{fmv3b1E?H?;qa=Q7pR;i1OLhhYjvco6-$Emxya$<(@u6CFp^~p`Ofp8ZVOxZptWz zi+NL0g}#rz^BBd*QN*ojb}?bU|9$`pF0yB+}S#altLd!tFwf*DG8v=B& zh8W<-uF{1o#KG0!DjRUja$CN+c7IPu7qEHsSL+a3k2xisfaB~ z0M=HsdhgO^>Zmf*oEQidyE8S|R(N<6OvKxncO)`BuUXO5`)5i;>}~ewaNr7rFt@GC z=b!|mQ3~qzcXqaJmfSaosaIyHm;w0Xvsz9*D={TE@J{EQZ0|$WVih@6C|toZ5R4UmHjW$_S5Ab-ntJ)z;*U=T${In#Sh^DYY4{hFw?aBOMA0oUfN*Kr-GK^ zJx~#lLF7=^-?GY0*~@q_lwPXP%cez%$RQ2PKoABz@k}J96 zc45j+T}A7w+$n%#&DZq5wVRnQijjc1R>4Q;pEtoQ#Dp@vtJM4I{*LPgg}k=-?>)dJ zopBrOOXDPCS6sq zYrsWD=a7FsJz(i~+l`D=PMz$)FE`7@qj@Z~nZQw}y4d;d7E4>c9errGt4T%Mg0rG> zvXUya8@LNlXhBBCXl|7t6*>oZ6XTks*P&8YHe)QxyWl&nYw1RoeGv?R%jUD26(Q)H z@Xsv&nkI7|4yHTXFtBIfgVvB%H{joccbVc!1uZY1G|I^I{qJXXyqdjVKjnbC(V7jV z7mT@(5z+2XfdSIgzw2D9W&(BV$~t+c;)DzmLs~<@)1*7wy6!kvegWAT5=SjFPMWd# zpGm{I3YIRMMYW$k5kG&x+NVqqhev_X7ndV{QQwR3GdKUUYVtW8&=C3yZ!>cES@e+i z7iO8JFjs^rWNM~x0Onr$$H1fI#yJp7&Og6cBBd?Q@m;s%48cA+4S7RxeFwZGK(&uYfdlt%`qcXIdxl@_Hl4%Qv=?^`r`6>B_@no1iQ-hTAvM7l z`>Bi>m<;GHXqhvrv0in%Ec7;xE=lm|kwLop=&qr$6%hta5cfYNo%=}6%jTwRzl*^N zwF(#oN48>zFSCU^mL}~~fg**IGV0ZZLPjGKiGB8BOwGRMq<^MU;t|Y5M$(a!ljB)h zJ=KY{-0Fw#VK)*u>ID^LB^_SLl3%|rS$@;>9`$bkT7py!kJlPZ3Ucond0tvOWn@c~BIjq7 zJ6UPkd2(?q8tP}ZHzA(?cQYUsUp_yaa08;voif_7ij+3>VMrp6Rx2x=_Pobg_J|5{ z(nL`){p#F}iHVCciudB=p^@WEyZ?-c9C3^F@BMuyzK!551$T$xjc^53tIw_%Vx?;> z@3&U#rp(B7I!}^gz@X`JAy4d0cxescJp7l5@IBU`^$OLJ;C;bRQ`-Q<%9057RlIB8 zXX~>KI(NmDam95M&?2H914)_JkxlPey?ui(3S@jh?ksCag_G*bC~wqD0=LpaisL>j zq>aX#S=s6ibgpeY(4Ig803~9)<@qH%iW9_JAh_tONMzVpi<#tneq+LyKvbEXeaRH4 z&S$f*2N_bZ^@UZgEl=hmozB?6qwNBNzKSGDL+S5xTT_z@qgHj$dH)N6y<&geq4#wx zMysv!YOcH!8w?_z*rg;>s3F^x03_tgd%R)?W`x<`jkL=m-~-$WUf$T?v#Xu8w7))$ zz@rD#0skc_L4G`b^4^u7LS6fK>P)*w*Og!3YdK(zqs$~EbYdhy1b_V?i`sPsJZ|&RJW)h&J#JmN{i5Xx#jjOjm ztBPAlI(T@90VZagK_o^ChhNTqK0SdVi)$cR+;?d;EZ7xbfo!aPp5q7t+=XNMCWIRA zAG9Q=rj~h=n%{I!?5_4Z-V;G*+`M@+F)>j?m>r>>uUU5;^GW8_)YQ+S(uq%V31ov99eS>MRZk5u(phxn;?eW*664Ld0oNCm25aG|vm}Cuom+JhoXrmxcLmn+& zn-BuK@PMA7+$0^cP&o%jx}XhQbF+Y`X!)Yx;nm|8?j9Z-H%MWudFFX(x;>p%b;X1z zoq+b0TIhH1!l+=t1`zjt=i=_XTi~6&Qvk;alM!ZSW@Z;&Nli@D5t>eZgVFL40Q*at z>ti{8xgE^V$%lbmGvdOR%t>3R!N6qTI%w|bY^!A~HbEAbfYCY@u&GWmt9V7cUZ_!7 zI0$l**{;})Wu3^qJ-5E@XBUJ|;0zUyx=x;*oqg!*IgMcx2taA zaEb?TPfy(byCh-N#(@E%78(1s(Zad(JCAjS>S!XRH78OilR(4h2vEn-mvZ7``D(_& zp@m}&&DPPv7Adjm!umspqMDz~uZbz5S`YjphgGmyyb{k^@t=hbq5)_%>;3)@fHZtwbOUn@M17<_m5 zRj~c{%9ula)~aUvFP&z6n4yVpFwN`*(+ z+^#uw58GbDj#pkA0bNOJbWR2Wp2~(s`k1Z&h%PjHp7c|u*>!5`{!c6XMSKB z?`<8QzP7V#`fyDPGEl<`^0**vTvSw4g+k-outv9;TWw^?XB9{eWi=J7oHylMCxzWEMcpyw>(PS?Yl@Ke)#Z#$%a^qeftjn z_!ifKOp9KHJ-!tjg2EzHpFgLjE!u>hrUHdj5N2E$)nfXnkV#7Xu1{7RFr%KFA9yw{ zNqA@Iu*8+^?GEyB=iFwe!<$+5v5!!8!0rd(sprfGI+dx#Ci2129ys`SUv-n_+#kc- zhnH4?&#k|{8r{dtEj981K;q=-!6CU+U?7oz;)xHl0a+k|RSr&jk$w9FWq&bB{9!Qr zg7!Nk&CeRCoZlBE{ji#+er@OZ$T7@yGp;h9jI!4mSSVK7s~->(?Z2=1%BBPT9rMRj z5QM#EuV07!Dpde#2^@JiOGm!NI`@U0RUENg1VM$8eI`aLNy|q9EF=OSz(j~}d}EZ~ z;1{B~!yh`T`>@Ez~a{{k9w?i>->tCuegSGl1FTo{Ai z==0yjeL;he!^0pcGNn{BR5*e*EBCWUN0kEn3(Cr> z(4%_ku*pNIwJpGjG&UNkggTa)y$)}g%Q_Wdc)R`#rhdNXa9*(K5`wJF@%CPoZ2{!v zfBNr_Q>mgPfWdDq0zE}P0m|4ZydwdI& z5fU1flrgyajXiMiXi?^GO~HX5AD{A*oC3m%9V9O47rvp!gcX?_n`=3G_UEADhpddygvg zR-DqyzJu4`oq)@A-Lk}UX4h&xDd`u0nee&0@&0!pNb?9*4#hj$i3M}uZ^5AYAMiYt zQAH2F$cDcgxxbg7N{840Ukd=*Vc)A~Y}nzX`7EgJ91ujGtf@T(z!JLgFf2{_kTaT1h@`&s>2@^}X~JGj^SK1E)} z$D`jX{UE)L;{hJp_;pY0r`uA2XJ(`Tl<0qr&@Cp~jw`I?n}Y`aN?-M;(XX zZwQh#{#anFU%(9bt&}3;2EZbL?RqWTew@ze9+suWu8U6?d#RPJsR18q3Tsrn__-^J z=jJch*RK_y3rr-anW6H#Xno%6W=VffmYC4KJOK8Z7#4XvZEG_zHTLH>HzgdOlW@Wz z*fvb&Fxv*K+L>!K+ak+wcMND4efCPjshxqG^J-rP*T!+=typ>`3nK=I_8(_@i;RO z@bXF8W*)#T%=Ghve6(@uB1M9f+gc$~P4%@kYI9==5HD0%uThSWgXu|(f;uYTt|4~z zMXD%e2v=E5Q8^!ttr2q^6_m$WYGq~L0(|woKz`|QPuhbBDR(E z9>2}opd!5|)(MnJDUEb1z`j_J41jEv`#(4*&=oOlIx?Svet?=fc%Ll}5)zWfiOR`g z{K6v%q9CBZ6gf?gXn7EnTAnvSsBNF`{@NGD`t$dUz}sKb(S>1OL6HzMWE{hpTTwv= zK0>1BoEMjBAGspAx3q%~Pg7a>%5|LAY8~hR(gmVu%A}9@bGHFgzP6{TZdTDV~@?|{?QJ}rKZ1j|5b=-;b? z1}*;76)90PCrzhmDtF?9o41Sirvj!{ZwrUur5Ddq@tWMyc-;gN=1ZWMaIav)9KmtP zTAbPa#PBoXy(T1EOjb9PG~zLP)aNsTC(^7&&T71k;K3wEN8dXcZvZqB%oCuNb6CIX ztHkdPGUdD(WMuYrWnzOI)4?mqhk$76<6$3Ca=>%GtU(t2M*eF-vtWjEsV`p|X-*kc z97j&UBfs^c2OOZVCr-%(oSm06KWjJ&N7j@-{6{94nVHeF5M~VLIZT?{5(lteP*4!q z*!M6VA_zFxN}DW2n9g6eh*61=TW$J)^+%qb*(8-*^*{GQTeTy!JxV8d^>Rk<3(*ufqY{A|ix+`0$c7(ud(>%N z1(l4C4|}SqC=pMI#K2%_!;%ne2Xe{8c?@1yWNV==x^A7>OYLW_`@Ud~@ZRoutITC}Ca3AgJ1>ZsTx4HURQ=?9RZu3GdJg2P|U@DiAHR(G}6} z%MsOT@Xa;r>*bhy}LLq+|m z-O3Op0enzY2!IJmD$Rl=#OrE{F3+$v$*8-OFJ$n6dwWQ}h51by3i#R;ZT3O!_`;&R zEa%r?GI1+$A;=okTPvWn@6)=d2pE7Oty#3uDG#XVQmqXB6D(AG321bKK3w8zg$LHq z3f>RQk7jp2>E09e3*|)_CxPi>FMA6s@Rj-YF%Yn~;xG3(itFndz3g#C0M4?g=p74N z_QZ%i9QT!MQ|mIVcSv9{>UL7G5P?@RJ3!EZKV-EZz#cWdJ4phxOurz%X5E5tv=Qxr&Q@OG~;=TG#H8> z}OOe{`&DNGV0SZknyE$feUzZ(q~0mcjPYt-8-VYxYal9Uom`@qZ4{RPGVh{4A@ zURsx6hbgK>Qx^AW8z*ahl;P2s$Q%UnXF)sz*XKQkQ*W_-gnVB-UXWY~IDSE?n9Mmv` zmX#J0T4Oh^*9CK3hP_yDYp=B?$r!!ABM4MC-vYMe1*Sma6jb7LvXD}aT*t@XaSlzh zFu-?sxz$qv2(mudjYpzBz!A1d4(gwnAnoc*L_9KRQ!>G{9V>j)xJsS#DY>>8R)gGs zEI`vqnhUH9i9?~B-R@*$%N%KN!{$spX)89xc)p;nB@BntMQm~J=G=qlC?Z<$= z#89)g!;Or;M3%i^?$JsU5b$tcj%Xg?IRRZv1OMf=VrR|-G6!Y&=mgVXLm-mSaXXs{nqm>i2mgMKigS=A(9Gn6GBp>}m)BYAr$3=i93m zVZh$f?0yO@WoBXrfYq`=Iv$Pva_vJbk$}{w!M(2@{;a2SbAS+&^?d}yVcBRVMn)d^ zU5h+DS$+Vcd=<}*lx?3*nL4QedzW@DHC`VeS74x|b8qJVxB%5b4t{HT&ON+N4uGfq z!2jNUTcxP|-6zm&;{`Bv1yh#EI#*p?uD0jUI9DS{16?gtu_jN*^a4&pD|GnxQ{s_+ zAEI9PNXME6P*A|1SM?$@N2q?F=uWOEqowr13%l3HY%9&~xw62jYK@;ZGAkX`?k}m7 z-k1u2IGHTlCZuIflZmq}ZIag$e3AehJ5cXccZMreo-%!AiJ^u7$c@>djsxp!1DL_> z1%Ta#&+MdqvtqpTMqZTwgWWImKKWll$w+czR3vu+u8C2NK*Xrr0SG<43YxR}QQvE$ z^w`bX4nUa)nN^`Rji>a0IQiCuzOND4iL%N(P8l>aHkLmW32oK=Upy-yF8&%cB-dO! zxO?Xg%AYXTicwNhl84nrWyndI+8G}6J%6Zh4hR?ko6DcZ!9t+yS;njLwMO~3-qw8j zd-rz)!@du|KY``|78xfzwe2&KNAc2JTeXSy;RDu(0ebh?xB2nDtZ;gdHm(RTT#Xu; ztbx9il&rE$l)?19ZLCQ71E}|<98XZWp8;{c*Jp##vfQDMiyON7h zGjbb~guUP++7y2CQ2G4e=Ku=13?6JQYR~lq$~p3%F2%=Ly>+rHsSnq@wfolr|@vNn=Lp$oK%l^;(miBDJ<39;-D0ro{R^161GxfDUEehdO(>J9tZH1 zo5SBe>Q0(y!=7pDKB?*}HK@M)3-qd*&aap(?(!Tr2CfQ7Kz$wlHPk6GWXi%b4dBZK zj3%YZ1*FcQPOO^z zR0BR1<8J5m+`yf|ZwPDe?-#g9mXX$;t6^aH=MY6cwKXpGo_=BS|5XfEO~YRHSu7P@2m5(?dGZU=6^VJ1@<_$*##Nr_h9Ys8(*Ob3yE*Hi=p z*IH}Z+f8;GaykzGX)pPGT%hPiK_ca5#xIKD?kQ7RXzLsyHO0U&c{E(WL6 z_433YU*MgU?-tT3l!K4q;0ZAdT|3}r&lGDC@;d67)ld;FN-9yK_^HHl{iTP34g|&vK zhJ8?II38lt1z*XdXJHZ9I9cd-*bt!6zG&Zp?-i<4P%#+K4n98Mwmx`U?V+q}1nteu z`m#$Xp!7D&wtb-QpBCXdw+qEU**l~m8u>R#g%}KP#qTJqBVj9SKd*61qqTG?98}39 z3?{S6n4G%Yr1T;IdXtjiN6((1ydY_agsAxuXG#dZCdrf@op~o za$n!>KV9Cfj-mNGR9CY4-4g)PX*RaVC%(Bqce=veU(mQx12w0?%kL$}oajn`Ob7KW z>>m?AD)kEruyn_|(TpH=DQzgzl?R}F;FQCpD{lMi)vv;*6}n)g);BQ1`I{7h|0}db zmW!UaY14InneV|rmkT^MczIc%BIW)>*E*kN?nAW|_+5IkWbd=MODGfipH6c@$RWO0 z3#XjP0pa1{7-o$Ghnpps?}C@UbSpy#=MWE}P&6p`08CqeFGM+4>H|t|!^sb*M{aTk zPr2qpmlTF-suC(|@@z}{nM*IF zT&xV^rTp=S_MV}py1<02*emO~OlLr@c!u5EX`GtH803@7buwk^iF=)V$4_z}sMR=f zrXQeo6I5{`m)seP%3V?Us#ayN8!XS;|Ve>0X)xNw&kVeu&4c*aUp)Hp&@zA_^QdRtrj*t znag_Z3(oPv%K(O7US4)oZTt?{`(Gs8+G!tsN%h9)p*2%`mQ+VHtw5Y5US~$Kr>Zt< zEULG7v^lt91u*B|)w1bX{mD-;yP!@gKKxCH;)Qc@-NnTv5uZDww>j!dqa6on z6&u!9^u+x7Kff9SN<3=l2dl9vsa}|#AgV}QgTy-USuukOZ?-YXorAxfbh7KI&<cVv$r%u>d>YYa&PjU~uxj&75mDJ@`Tj63)G7LC%livDslRWi_uK4Lz zWI!jtz~n)UQRGcpo^@gN67s^(gC{4_iye~!LnuwR-7b%#f4@c$E0|v81b)zW!gj3u z$*NcAsv9aR3-(63+=ec2Htj1UUL~E6A_^P7F`=(zd|#@(=3&)IjT+fE-kHg4C}%(T zw4{ByBhOo4-_-G787cX5(CzGu47Yil)UjZF#!7?fRRXAA6XKzHc-fw0SyU}AfOO?S82c#YRhy>eURF>}xhd5;Q-xaiG|edGRSFX^); z^npr`8-$6#bsCUN4jkC54_b;W0e5&PE<(&_(9Xf(0jNW>KEy7c)Xe7ytnEv zYDoFY&dIo8zTqE*5 zm=yLuDp+Rq9_ia6O-+dQGU_i=tBtxr63_GAOZr?2oeI) z-3$yVEh#0fBA`;z-3>!`hk|s2w1`L!J#^eNet++M-}~47`>u6atcByuoaa2}*=O(1 z{_K7Bb~jUV6V zQru(SL-!m+Usk0LmEVz0Vu?5rbdgS7jqq_FGwHR_;u`O##2Z(*uD z3k!PJy$%4UtFjJOhvINFR`IYghm{O=aG|fV-^LHd)R!FVmfkoHIFEqjcVyA^@$uj@ z)8=&$WHtktA^Epdp6^L@hDKmpk9kr6<@H(W9#d_LT4|n_6MOP#e7Bu?LGY*42o#|E2+n=tLSx5DAQb~Z zmapBX-lFKQfwa@HL4-AIU}?MuI86plDynwxUu>J@OElAZfFh)5=6!_qPG=jiDUq!C zAZ+JeSUm%R-jt$2ptjJ?j>8(&)=ve-Gz}pX$WB4$MopwQHau7GH_(r zjS_rDS*w86=3f-z2~u?qWKn{=+{&#pDXAFQS^2==AGiChRDVnVJ3csZ34r0PCCB(p zI{4pTt-e%7H`Bh=glXv3Exg-XhpyI+mGwo61N$j3lFv?9E@&5pu{xg;;bA`^OfMoH zh)DhoNImpf?tf_?5A}Zw$?^g6v_c-$e<-$0t6n=?arL6A%IE&n9coYnilx3r&!W_> zeJJnEkJW==-ho3O{|EGm^v`lM9R6u9sccY8h?sa<`8mz18~0~$x)mgQOrV+@O0vMM z{tKC2PnG(3pSQv?ta*M`7m+!%A`kiIY9SIoj?SmAA1L;fYj6@zlLD3&tf?k&n(}RI z0H$WD)SUpMCg=^w%Xr)AE%z-8!&%7AGCCxVxb&vhCav0S!Qxp*;KMxPX%JaTOL1z_-O(&bu`uFX0Ny;q7 zc|?nqW;1Bk8-ZrMsT@G|c<Z$awb zSs(kW;2+y)UQ!!0pO%)9vD4U7E%;g;Pyq&i1_sX@S^I2s8*C)kJONf`n##P(&m7Il zv+9AtO&`F8g11fMtb@_zyy)vjVWAOqqUs`CZ$5;3sr}!ndjDm^{g|xV)@-S!q+dCB z8<;J0dg(is`wehk08|v~*A7M>+#}Zem$v-+%ck;xi53GRr^~n0loUQY`KDa!pDjN6 z^NXBE0zQBZ){_Js%>Qxw-;40Wl3&}~6BwP(Ocm1v+G^SayyEB7G#g01n>Mrxs&y`b zJP!Pn)vJYPatz>GXju0A9tiXWKchpu zd;NEQ8f3v<1$Cp7;6PO3{uezF5*hhNQ721;e!&JDmMGO9QovXEy%nJ{Sj|F(PYilO zgJ;JI9HQ#)zG>Q^m|o?88Qr8jclzWbz^q60l$~=eeW*l0{-D~@6B;@5b(ciiY@)ZS zl@nNW4|t3{_K{MayJy!wy{pM znBD$%F!iDCd2RcKN%5zl_5U(={}AENcvAS=9_VK@gl+om{nufwkW| zWc)6?y}PUHHJPf>`8oRu!fzsAca>vFta;i7b6uO^8* z8=ondm^4CEvpV6IQ-YcyDRrg>SW@J~lF&^#I&$%7f67#`-xQDN`(APLtoHYxyTa=^ z;#ZPY9$EfP_G(GGb?cUF4MU)M%Kl}q{k31Z+Fk8 zyr!)Bi6LcaL!e8F5VMeH3KUEeph4I5QX%eV7z_rhvermxxjM70RCp$?lfgR&#waW- z)HF2Q*2%BjuMlElVp_PFZpxQV$^P5i+&uPXZdu7p=!ck?@`?S*Bg|lS^kDV#_LT~2 zJhijb6?)XbnfP%3NAX>GA5<2R<;~> zKi~`FY}k9Ks$giJRNVU+4jS7far5vDaA1kYbLn$J0sdfepgz15$MpUg2;%1Ft7>U! z73Sv$ul+LX|N8*H^-H_E+p3iVI|@Fl6M1|a_rp%4Lf2VK3fJTXU%n7!ts1ml%BCw`tb8{#@-0>Fl;uUrf$O#B0AZRfYVDO2&msn|>dC;)T$S7(dH)=A@^m6d|r+^&jN4MrM$Q296Ih6cmoX$>qkR@AJ1u@A4RrG3(Bg6~mUVL`!O z&5ZO1oMVEC%*OSF+il(f8jzaV+HeMFO&<@40jio$UYX_9Rcv49_J4kLKuW73w?uhP z!dPNR)Vj456cq9h0WCZC7M}{)%^W($l9fe9M!NZ7#q}{Y&Tn7-7U#aMTW4!H#w^3^ zU?Extt&ug0U0FZ+J(}L%-w(DKxpiY1^8)0cO{KUm6oB$nBY!@hm6)lb?5H;2rHuDh+E@=#D*+eXW(_#R;*|C1Y}dn!`@Sw928?yU%GabG>G_HzG{n3Tll{AzWRn-Wn5By@qo zlA+uc!TeQFn*XQJ`TNc_^N~GYHk-|b&5;h<8@BDul1fDknrW+0aj4@hDSw7A!H%uF zrrMV5<)EhJb7Skzx?0-WxuAz}{%t+@I;-xVzctnGOZ2Buu%wX?)tUOiuEGWb4(d1k zT%M>2ooZ13rHoK!?Nj-Ywf?c;gLyBE0IlR{9O$VIC<8ssBt;U}w}LDTs`;`51m5l5 zEqZ=NM#lWQI^C6(m5Ny;>*L2|-bLxtK+k|*i^1dqhn7=mfq9pxX(m^jo<8fyY>idk z1cRIYx{`u8kQfC<$nD)D@KNw=XF`jl4$r&At};MoMOS~_sIiT;^$2_ITxKVs*j(gJ z5)fn5-^ORXy*~?2-yFxo3H-?=(1UDDc=6Q>*7>NEaTyPsH!`LZoY;0Lx4$(Yav9U2R)}Y;B>;p~;>*57= zUocnng+5Nb7HA}axZZV#Kuh!)@`$JRyD;tzMIxr-~;vpzvg3PKeY z1>e5OfaXNo&C;7J|9#GBVq$`RQHIeSW46u-tf>?!W?}V77$;La?2A_8F(o1oBD#gP zQ*WQspzTz6_q~doS47^}nzqK?1t`68ubtmHdnVH$wEA@xNzm5<>EbSth-(H1Mo=r@ z<^Sbw_`=;XepdXmnGBNn2yXZ(4hG+aZY%Hpa3MZjERixsfMQ*PAH6dLMnPfW=Lkwu zm*r3cw6%QTbqmS>>kh^DuDkTw*D7R^@{xF3F6TUOc*V-XQa<-n1H!`rCampli1zsY zzBBC8`)^k4;BA**J{WW}K+8k1OD;nH?NAAr+IhN}Ez7(IL)u;oZFWXrlqn&cUb4{=@V@r*W{e3*FbOoqlZ*=TCQ#G7uLr!;@8A z1tvQ=`WQVp&!AxE7I#O-lH=|Q3({L)f^M(ltD2f;V>2CST%$G!V6cx`na&qq+p1 zHv(4OyLA_$V_ciO{jF|vRJ~H63@j7tj@0wA7PJ|PVy39PknV8im9Cxd=#bcPe){C* zhZ1u3jgb%&U1e`N%**S`%lcujb?Vl9~G+csT(9*vOyd3=fTJ zRrptJ&KExL+Rgkb+wnTtB}N-!0RAu+q-|}*_;_E3{+JR~E#IYqH`YkoPSFV7dt1GqmsS-Y%OwgvV2_10rckh2 zjg^@S7MYkB$^U(lsTP*Lvi!=Q_JC;x4iJ(4Vn!i|16kmn45e5Jf_84_I8}H7E|@Pd=w@u zwnu|(wi2Q3Pvqlya&98Q2+<2XI#;Mvz$1tMg&?To1JDQH=P5OiRfrDrRQWFsGy-(> zx4O*Chm{Io8{L&8fTS4EkJhqsTB6}{YildQo)#KT?Oeh;wG@Un!4Ad4nB408U%3DU z4S|OdI}BoCV%f8cbxvlowS?#^vG_l37uW*-`U(s=-ETfVoR%;aNQyO(3JT^2iWUO! zBmxT>2}I9`=$(y?O+N<)^#1d|mnNUTd>KH$3`0-tpJ0QjMb6uUode-DU|5iWf&CYX z3JbX#10tLn=Plx(Hf%5|arhT4YaF9{fok_UwuEDuz+1h7E-jI&B|ayNV2FrbWb&+6{2yAp#-jz26af!^_d$^g_` zNqznF*4_7y#u05#n6cVk>lnVx0nUN=5437F(C(TnL$YZuR>j4{6qJ=cWt_d?zwool z8Xyi}oX{W9M0T~C%<8zhR_`AiNLJXHd6NN~(a-C?ZGh0L?Aqc63IW_xW?=Wd87JMU zRLrNdpoNsN+f9gw8$C&00Y7`Un;557N|}t-S92mJvzGY{N28v%+7vnB`q1l^jh81L zVrydq7B{`Hq(mDOU;a^}0t{Fsz}41E9r^xlLRY)kDCzNnMH?uk-}v4S7qbi z(0=*yjH)dsRH1BS0zEjq%T*{$Mwxq&;%VThdfjO$W*oTqhl9Y?pN$BA$O1 z=V1DEO_`$T2>&)O+n;kT$rmr)0cVsEX=Hx`df(29$c^MR+weq-*mtXEICOIKaL<>Y z7o7513^?MFm6_S|p-dQDvH?8TV9@s&ip;*axG39N9e<_-jJrvHJk>L*u(GY9>})Bw z#uSbg=zYgYM;~j)=}P8+#qHC$T&Nhp8M-HM&rmQ)ZT&_=Yinzh<{w;L>D*s9{jE$D z1795m+|23k?~mBQ@<*XXXCN|eEIOu~Zwu}PdX98Xa=(83_;JKHp?nCl(-PNTS4t4) z7ir1lcSm<5A1ttQ{$>AKSoh0E{^Gg?3Z>)x6r)Kyf8&81KL)m(t^nc6HQv85!ahOUf#+mt+TNs)I_VO2L7?-GpE0V7Wr8z^Z+Sk|D+2R0w?Xf}Rc6p2ecZ(0e z#E}rkTjJ{a9>4|>&R%uQSL<+>qBLz9ho7*qX=rK1FzLU9bU$c`(RRJ^>$%GfNdSG& z#+GP_jG6Im&CT5nGW}3K9`b7bwkq_OOO&j5(uP$|k3wIo(aG`WQC#f(Gm3W@x`Y57 z{Y;ps)`^_6cmH`jO}wm%;qq$5xM4RD8JQhE$rxyt24WBp=0_~HB#NsDF%;MjdE7)Pg*tbAHGTrT7v2D}^gm68( z3t>N4BJpSG-Bn2x+f#}6(N|GuOdd0LYh8y8npSNHSJ zXDA>Mxb#X&p}?Bth{^#BR zS*>t+8gmrRhb*4pP44T3f~m3kIUs-3_|#ONMde3t%4^`FxW07KpIZ2?P$|(+x((jh z1g+iUNK&f}FIT*lHk|7<|3g}RM#GqE25;ZiGwONnGf3)~DGgk46N|fKt$+zVrwIqD zsANa^5+=v@NZHhYm53r_aH8AFsJt)&d}%dSJu+e2{IS^64zxrdO|f2-(YyKnw!wT`)(wsHa}lBCnqO& zVktZf?gi(F+j46J&lNx+#_H-a>E7>8iP%FpKl$!{pp}j6?d^TI?elY9cPz{{6;u2v zkOr6D<-Pp;{Krqso|4T8YnDE@xcaHVQh`}mTGD}@q@iIdBbt-&@&f>=v0G;5JC89x zL%>-}_Z@&;JddU=Q60BAtw6H4MKsydtcj{h<6aL9CXN;^Okq(C%97(j^5DC}$B<l{S+_urS5sArUNO#N4&d%=E z9{o(V9|I+>m*x&(_hsLzzz5A_T zug2rE%E?p;z_U>i;C}gr6>N1C!V`1kzK)m|6g0@`LAnLm89~KhGf4&Op532bTbSkd zDn)fY16~%uv*s2Sy&%E^Cx8wUTiZ1=!Tsz4pi`E8yTmrBe5!X@CDh@Fv-QGRf|Uph z@K!NNNw#hjJ{H(x+mFQezdvb)I)JMs72MS&4Zv1oYs}9lVproxx6OCBG!as=IGOXH z@n8uko|FWaPCL1wv8>RRN<;Y1Z+#dHV2#}(f0EM6moH7`Eg3_^_{iz2TUr*j)S-YM zpbOswaGBjGFb?3{U1`P}UpTB*8q|6FeIU`Cw{_{6=_7Z(0h;Z^n+6Y)L{)CM05M01JgSnw=pns9T6B={T~}6 zp<(;92<5UjdJ-H@SHRr$M~)y!65I~97DT@+d^)ly{~CaR7M&r1A_dO0FXCGdlQD^b zXaSU_XeSbyeKWFQ*{yNKtx*dGWBrtVi|#~duy=OW*v7ldx9SlW$%^Zzp%-*D=v&dy z*0!*jGVE!Z)F?oBO#_2u)isVHrdGvoc@dM~`)*f3R#p{|i__-VfY94)LZmjQ#7r4u z&n^Vc7(bnixIyFv&6yBHL6zf3*_D z0`#p0V`)as#^%sy;J(gM%1sn|fTf?@G znY^x^Dy5bwO&JQQhF`GN&tHO)%JRy}+rOv3TKB~wW-82!7_Gm5j-ljvBm?@Nse)rl zK- zk%eV%BJ!~61qDUL@nW-OKHozkImyFCfuOa}<5|(=3e2SQ{FI)kGuv6R&cktqgcsAP ztrZp0HlY6xy)aG4!3%ZuNVlz%_y3O@0LdE94H|DH&CNZR8*Omqd!%z$54ht0eBAMI zUUTzMo8tzALA?PmRe)}LTFz~&Tdz*(JK&b`)V2A{Z`Sv2L_>qpOid`4V&oxeiXW&Z z8$j~H8r=}tH5@L~-Gm1;ND<&6F6nNj00lnvRpV|I^2^A^F)9cKI2l#TF}TNoTd2I< z=4hj{`H;~o91X#+4`9sC;k4NS0WYZBebN5wh^MF^NJ8kSNGtmY%#50W!RrLMNT5Ki z?=i6h4Sjz;;pJ zl=R)jWlkVc0CTBr!aybHD6ue@x)>-7r^&@^Y;MLRB&=Vy?zCPe{P=dfr#@Rj++zDT zHa6Dn+&ie#sZISJ3ya-63ee16cYdabEb3@zXoTB7apTwDFEg?GaN+DMeSC6}YG~OZ zl#L~64e)ksQ}UzZa{#AqUCm^51;}FqcLlAEiUH6D6lkoq2m-h~zP>F5WK%5|sM#x{ z_0lhjY)rpT4%~TQMpzRXjy#*E%?Zf5N}?;&)S}h5U}Dh0$xM7l(Y>^Mz`~YnO?aQ# zn2eOv)yq%C=~ZCZfv*MBJ#^F-UK*diM+nG z0OS?`byH|7E0)ew$r(lM`dxQwTsQMJ)DQU0hsiN86%m?n5C&Rt6g;DPc-DcJ|Mr=% z%Tj{yVK=T48xC=%z>ECK?!SMxwczj+BeRgRvxT)yGHmssr7>C`_&x&Gjn}O;kk{dPj;uvZ>N}jmhXQWit9pB2(TZgU^yl5XcQJ3Z9jtDDWpp5l`C~^P zLsG?La+>kqNz>}jz?I-?TPDc>VtnFhgdiWwfKfoJMX^nn zHZ(MJJJ~Jmb_d-;PkEDjMrSj`c( zaCRN-F74)1`!J3=j=sBQLZR9Ql^+TiLmvnX9@6kb#b_XLldUEdhRier@euTkB12Xz z@baPe4(OT0_MqX#nBAm&`}mTh70^bxlTe!{uxcbMAYP%lSwK4S`4*jK@eGVrj}63C z5xEwF8w72M;1kinG5^}P!rgeMPanh(E)n0P!Nf?k?bu_A$rP>maE3`OHgPgT#@00f zs0P{>+e|(3^o<=5&trFbttUlLn?qM|Z6r!m`0vns76^X4)ptgy115XTLD8AcgR7r3SV-Y5ou6rWKM z0N#qXawYXVZRA;RKGxC&4lOX@H6#H$iPTkMs)UQ<`aZzw(>5F0wiA#=;{*e|M6p z+NZ#EXE`f6#xJsk48TSmOm{RIOOxUy*z2Qjg>f~l4{#2*#5)E z<1@J0J$Q(~uq7><+hwCyId*rXBamxR1N`$&sC|E1-VR4Pp&M)BE~E{Y#63&U{B3vJ zb+DBf3;Lc?;=dc$@$qS1iN(&EAPIgBgeUOj%!x(;dpafkghi#^w&{=8xPdwa>}~SY zlCLcvg)SnHUWB8uO3#{SN{Rikmb^x`&v(RK!PrZ)zvmvL?Z`(mA{VsCc3W=#%^=>G zR9|j>)&Gs1+Jj2Qj2!u+Fzx%-VPU*BU-XqIGOC)I3_u#hBb_nf@}D-8if}j`C&&S@ z9=lOgQBjMK_p$!CF)PIj$FcKseQmvs02HCkPOaQb%cd>9%J%%5Ec*BdnATj^TL%_! zJ>98Q;{~n9X~3M;R*&Na!PmD1_o>hA);4y`u}45INJ3M;R8=D8*H35?S2l_6=30I! z*|iTLp=3ak91;ZJBk90$54N93STs93_>yHRu)U&FZaAR#Tli-I5^h)d-QO;=*$LnmMd zK4xbh7|j@e`sT0VG}5iI52R&OC1b8da?P6XhP=RmPKMS@?%r%4UvVzT%J(A?)mbavs!8#c7G@x^8zAMVQHqIBKgLWhk zUOch&o8{7x!kC2b-PC=_^qInKNXX1Re*#kc=-~9s`Pv zCkM_Z}TaIbcfY)=Zr$vW<7COJN|n2}PC+U4WQSG&p-EN$^Yxmo~Xrt4Q?oC*xjh zS@G9^Ey1H$)Ygpad+At;9WH{U=bpZg7oB&lNO;z_wUnD zx?ZTW^6?F1%Xfs|jPU;nwh__&keB$$t!6qP8HcGycrS7UldYPtAY~7Z%OxxeC<`Y z75%ZlaR31-%Od3yLajV(EaiD{?E2i^C~fiQ&-|;)^P=){`t;S~@r^m^MeUsua>T~F z=dF1VX%FHre-fe_d0Z{JsOL%{u)y=4g=iMYyW$Hr)=W8o=^3r(8xs9f7vqLUr;HcJ z4$kimUQn>j&o76>c8SB9HPqFcuI=sZxA#x4n%sP>CoJVyu89>f(0ub}ZOyisi<{bT zk*>wn#A%y_dmZK;M2Z-)>gaqJ{~dLV{(d~D{QHVC3y@FaTOcU-Pvd|+rYj0TrU83; zMyjgD&P-4-`Ym-pQ#X;ZpfMf?2Y>xTNc?ehT%1BC8>jyznDLXIb(caASpks?ZA~cn zAxJ<1p>7=z;cf>y2}C<$Eez@ab&OU+9i(JrecJjH#bf)BRA0`VFj=yZjHyP*xASNOwZ+-Qf1&}ek>qPz2 zr*P;n#J(ANsBVc7bDI__3jszFeh(?>NulCyawB;GL#X*hts$h=zV6~F zY5n%?vw0tkHf(8u1+Y8b12q5`Y;ny!JGsjN2j47Gw%E;@S$n>ERw&qBnrs0~PJ+eX zAJD&2OnGAkAhf#{slWk%Tnyli*S2p%FDwGo_wWnBa{*~i;1}6YJXA43iL9C21uRth(R`e~siCE1oq0#j@t^%CUAzL>SJGzyeT z3JgS03Y2Wpk+L?wU34QmY=}%rncrLn}?Ratq!% zAHtgeU7c^#>PyM}hptlL)8o#d@L<3kY2Ijhn_A<0ypy+`mLt>uB=@%VrI&?8n5L;| zCg5{$%)QvOHQmpzt-eO_NQaA_8u0j+itty@?4n5PZ#KWM)>V*j_EsauUV6v-+Vef)JCe#<9UpU!%^Al)vld zLrT9|RgiDC#JBmexEK?kW=kD59_}m}fd&tNzCAjBhK0#OfL=$U2Z03Cg{aLbHfClStQ#j} z^q~DhH8^C2Pc1aQa|tX0`crU90sCap(?9oo&erqL!eBHcr>r~)Dhu-2&k433gQOjp zni_El{NJbFuMJBQ;-88Fi9mn(zegw53~DS<@>;2;UE@O#!T8Wnw~~Xsy)RpK40x(e z(sgs7-bdOMJ|zA`PEPKb_Gm>aO?QAS1fBE<=pL;sLeMX9m(BlVVsIyR%zfc4bF?dZ ze8`j>WND#)#<>21bQK61Rt8y!=rnNizF0#Mhm+kUc|hInE_He}tNf4n0Nbk88HhjD z!<3Ugkv{dku!zCXSL)qRRS+WAhaYUKeU`}u*sbu2NDi$c>b> zu_Y)eE{>i>PJ&V-)n?rUN=f_(m2o+QdYd0?9g#td?$;ZON`jUZn)?FF}#IBoWgm6nIvBb_0M_0v~Vj`KymO6|NymZ@)DBlHU z^w9pT{djp8rEg&R`b9ui0dLZJb~l_x1O~hgAgT10ews?1q4LuWRqz5nW-4*u3Uyd`w!*p`Zl#({j zCq3*{y?=ogHbxs6-&L%Zs%~6f*0v63C9SSa%Jdx$rG<{*9>=bAIxrS!rHT4}xhk_s zE;&262Wwh$OQ|})$?okE({j_04?RB7-b2=8%D(U9QM9L>9>sfe>EvFKpH+USclgsM z3T~3)FDB+BkkRBEzQBs+w#yBh)5%h)l^taTaSWribF#G3Pb^p@WNA6mV$bEUjQk|i zZj@4@#|`$d2pCI8yxG|Nc2DKGabRu)N=KO@mt=WyZ|}2;yqf%bC&~A}m)(oZYqLc{ zXDSYE`odTv`xS+w6Mwg|p>E zyZZrPzO_pY5ul?wZP{c&DgFcgwRT+EanODSWH<1dbOiW+{-;C&wC(H=gU?o}fbLTP za@Oo=Z(xuNc28bjs;9hJS5;_UGC1B^9vO=|oD)?F2H&m%I}ebx>x05O(Va`fRn}uo zmHYhs{Dl=2>h`tzU=T_^8~I1wtGg%FEs1%<*WOCys4pWi`A#-w4ptc+o2G^T1;$n2*ddv3|y<82|JIVB!Bq zFS%2XWoM&<1djy-bUxq`5_FZI7ZjqmP&Bo58Nd$$!XWhO2hqyvDjP_+(@nxgzxyrN z-|{~VN~e2a|4ig;ElW}l7yS-hAOOqgfBb*Z%nGz^VVd^LRNGd+Syko}0HJevO<+RQ zoSiGW!l-TCSh&8J33Kl)tUm}l|Ix|iAi5y%_0usyM^0K=c+$e$+=aF*+b3t+sS>U0 ztIL?EC^I(}HPGl?8yufrmK?*Tn*ADjtZXc}%|O=O^wwihihn_P?MrlYv>6lo=DJf= za$pZo??CT8sq71ep=}CVX%mRUbA2)suGm|+d8gaw&+m8v!kwfaU0%3LZSiAIGtTAL zK)>S;QzH9&0$U=6l|Q-`hp3vizlOKcOMo=U|DMFWCwgn?_9pV#R)N_Widg=Lpr;h` z^$up05d6-Ltw8(qfLWKbK=c3Q7}g9~5OeN(Jmh#ftMQLmFVO4RM7$7Oy@e@diO ze3w~y`u5vrq zIkJ`EUmfP|`W9URbGd3nfLn$T)u`vY9sJnn%Mn8_f6}m6Yqn@9MEn#&&p2 zOPkkJ)h;hjT^eP763%~4BeZBgejq^lSnN&N?|VVk{o}UPRehXVwd)hJ%2NSLpX3ES zsw@ol;wOE5eq{-XToFHk;lX$ps%{Hnw-O20W zSm+!ks^V8Nx3E%E%%t1hblA(6#dnbE`T|kHS$Ll&qsPblo^y-13W%S3q3+!*j*z=B z(N3YimAC0~?8G7u#86&7Q93N8c$#c63s8-I$*zKhy}On60*|R&U*Fk%PYULKb5Y9-uo6QPcu8E z-I_Bu{ou^A(MJOAMsXx!`{bn8HBx>;oXc$;{0pTAgKwp$-J6O6&yHO-e^_d|Tp3O5 zHJPrt=@*XB-oB-I*H166H0`>>Tal(rB`po_M113m{dKBSPeqDz=(f*>C-s}Q6r=T( zP2Y4Qgs`59M`9J~gP3)H>(J!0;|X8)YXQ&Izx55fD_jkyr{Psjoz5}W+q|LMnb+N` zDn=RaTeruCu66RdCJ5K^&EwXKg|!RkSDeVY#g1kjcV6eDo(8*lIGpObD=Mx3sc}g$ zqD*FJJUc3Y`=;h8w!GA$EQoSAsrHSaj-JPPX(ZY$Na)gvC^b5XQEtsr`)F=^c)Civ zSun=G`FG4=auaSjFUqwXAIEsP%AG^)*ss5-5O2Kf{cg8>kS{?m;ZGm)U|6v2a70b= zV7&18_6Xy8=G22Mx|$G&T!u6a;qZN z7p;cjDI&U;-Gd`J2VJ(tkNuWt`pM%84!`nKi)}jQ$VRqk*&!`^g;5gED(>=Htx3V1 z7xreVZDK^D7(++obPO|jER{7qnPnVXF+M~`MC{HF<#}%04F7BBk;=^^SKV+ept7+m zoI37si(rbrQ|9sUk0?H$ke&NS8=$(K0WI96l%sdQxjC;P`+~$U3QmPBo^FoL*T4+xB;6;C^8K!sN0kj*7jDmTt(zT* z@GY2?x3n0dR8mXZF(zqmHk^Cee7kwJM`~#sCZg~OcTO*7HO*l%p|#0SCXd<1aj>TW znb*A*8bmY399f0D$=<|i*y{P4Cgq@+i<0ZPew1ZedZ*B3u4!JX*WojBxLXoO(sRY0 ztiS6=Ny?KmGWXZ9cFY=tu9j>M57&FWSJ|8Gn$!|wt*3RCqmR{sW+#;=57*nDRWQ%* z<{n>GoRutRGmx!GE?*ujU@EBrnZnCw}`eoiH^e=GDL#Fmt;f&osu>3;bEkqsAq2k8d?3%LDSAH+%8v0q;_h15h6g&o8HiO!jrDxotuo(YUv4d-`1OoTl}0 z^Uj_!UltpOSDarsOT} zAMko6!w*W{YNnR9G&&eX8D9HY+HPcI@p(o{PDM|y=`TiVb563mU&=hd^31^+DV)@n zqYjfszzRTi7b0KNe1j2r86*ip=6v2;E^wFY^O@=O8gS6G&?k|bY0;}Mf<+^`)+9#T zX9`iYxlD^xOeirstchiJINw>Qjk6vo7aL=$>2<61as1(;M9Z|E#CmD8M@7wLUnRXl zm78_j4{>dOQPVfz-X-9OPf5g#+AQ^0zPu+UektS`0Y-Mm#gHf z?@~hq4{TD-PY*oT<`JM;XA$dlxh}1W$V;9v&sO%k+Aid#Nbz$k@zB*tI}`~WqR6^AHZ+n#iqGBRWv6!@P?8!|$`uqcar}2N zr*;-qd~^+aEGTG1_cX;Q$|py_*EPE<<+_TJNzMzkWY^8Qic4taQ&eT9mZ3gar*{l@ z{`@!DBRQAGFYIbJcBs~D-oO^AtC=5N>05;B=NxIFC}OaBRVnI{@M>N}$o}x-*`)~C z`Z=@m)bUn#;Yq31nS7)T?Kq*sTe#<&j9jJE;+}4fap6e*>+?q`zFXKUVM0=Gqb%1e za7EXC``i^ZA%Am*aGPq)>b`20mvrv7s$)cY$&i-%6ir(uXVN2Sgf($22S&F)>!4b) z|73+tniO4U*gE)WDlF<3A=p#w#Kaq8*AfyBsytRa*{{FA9Spo0lv}U$;m5S$HVbuX zxG@(Jeg!sOYdWR#*<*gqFY-ioV<$_zR0s#)MYfzxDz?XR>Xi#V7o46YXGPmbkK_vH zE0l+fjzX^t91Buk+cYB6JBNm!b*4_tseSsal8~K5$uTNspSsZJpwR*nRGyc>E#dj^ zKeRL!_(t*j=p!PT3eJ|jP%{?`My@CNacd#7VphT?Lc{p-;_C3?&Y~X=ym2W4^ zXSZ~g&+^qQzs`kkONoc&=WXBbS*~n-E=wh1YfZC@BZhJV*UlS3Dg+ay*R|4{3zuR_ zdJVFrpqSv%%gdDvo!KMe`!Z|Mv{c2GaKGW8G(SYF5~uajWvSevZ%*lvtdZSJ_Fp9x z+r1K_d{d1N+9Ga+lk<*=zNgNX)S7PAQzi65C&p=g!GB&cZQk}NR}i7O-sSp5u9OBV zHSgn>jTAM|F6im*9}BVm;A8KlkCmq~^-6ArEU!4qFOR9uwrX!V?l7r1&SknYv$VBboFVTirZ-tMCnL{1?Z4rB zws@v!w|Z1Y(w=9O_$@V#IpKw!r=n5Lq4CLx(Dk^3%TU!4$oMNU+j)?#f8`r0!B1<+ zNOf?o?m8E$ve{gnwmv4XJ*LK1GNwXv;&Oc{9Jhh;ohrKUD_uvB*^j254~=yQ9Lw5_ zyt(aHlK57|)*N|b!uO)#%6D%`J~G?xdQ@ewNd*xnT0&?mI$~Sm-R#_>a_I3Pds6GH zldx20U@oY-X)^2DpjuKzWc{2p?0QO~z5NukJvw{Y-bdWBv{_Au{YhJvp@6(&L?){Rp?m9C$ z=g#D0&)!R5L;FDL>nE(G&>3mfhcu+NXN~76BAEt?CRkO1fV%$6lS#>K6hhayNp4uo zo4`XD=XbtSzk#Nu*npIA;a4Q-MgjTwQI%owS+qMWqv26imoZyfR8dbN&ai_=^|+O= z1!X6`hiVK%mrKSPfQFT)p-k~CxR2@XQ>K;8VsO7kD;bH*vG2)hBq2BPCqFblZwv9ED8TBc|kO4L0;UEOobMM(#Ekt+`J`ts&D|_ zFdc-RHmtVBKU7F}`=Y_h#?50AWa1YR;ghe1cZ?G@%OtH7?mk3H`Zm|VzglX(@k`)% zvxQWw-o}!^hmmb$1rYO$!Ma7oZ;)MyV%^Y$1RQW#5Lczqr|}w}vtNI9ap)TSQJLg+ zf!6@LFo8hVC6jb}1t5Sd4&p~j#6ENFzJb>aL?o5=zsnZpRc4Ay`cdmEzM(=`1!*TgdmHUSF$NDYM*dsEm-!v#}X~GZ_OHsK1n#l8d$c8KQ z@RiA2$A!L)*WS?HHg>slW5FLM{Jy=se(@Vk6?W&e60hr;CV=hX;8fa5lmzN$$jBq4 zVQMkLW@ZqF(&B{tUDX}tINs^#W!JKt#|YUXhJ36Vey?9nq!#}?SF^!HABwK-HJ!Tu z29RyTq&eaS0I2j3liHnyh;8!*?VS(f?XwmZ!2Z8nz0?z&;vCO0kyTzT;DP!T=kTUO zKVzq01Ot66VkEwcGMqHF8pLN5S2gaDmsV;Yq4@?tIEHW=K4Gg=dr*Mq zHwNdbhr}!?^do;Oj~VW3O-%G>Ye)k@ows$sGei_HyzWF=wQ(PB+XO!{IZA-@5C?Z0 z9$BXx9WM-WeYGEZk@>FF+Nxbuxqyj&KBu!&&#k}9R7}_o=u)VSQPoZx&NulnokzHi zs;Y~PicINDb3=Dii^L$4J^fTo&O_HJG@o6@=Crp9Q?NOXK6@S#5?Hz2C&=lWg^yzcAG`|t;Sx7yB zMex)8^y634*^vx*JveR}zhZl)Qj9y@4DC$kMQ@5cla}$tLzWcZd%6T}ZF8#Esob8e z*72CrdNjd}aYda94hPH||GZ1)n}?_tv0tUrIgUZbdd{=$V7YmFbCB1=mJAW!Fpnt`<-AG?b>Qeo4$= z8i(?QOUKQzu#6uea^8}cfcI5GEQ# z?p&U1EM)=*h*p0|M+q!@!DmaRcj{#)*3p;XlGAnc1$b_6f;Uw3$ajaO>`LoT^z#EEB63^C!ncjJSyh)A*<^YAxqj7A^(GuTtF8Obu*f+yIE$(1}H}S8Sn7C3R>XAiujS1iZQo;xp~Evjin#O0G9AN;1KnZ%^b6Um1-v5 z+52qY1f!yn3(MC}`1~?=|De}Jqk=SDFo(#co(qKDZc&vTxeF>3V|PF4mdy%PU6UYT zFq&QHPXU5rl@V)N5yS{yXgN0``Nev9XGxH$+{Y=KIFmjXj zY6}LX%D8*yF49&QlTW`R`M&8cifvc%g!Hu$CrJ#2B+IQ+Q<%{_hvij&xI7`NusLpS zuOGV~XEzncjKNRqG@Iy~*eI=}B)f`jaH zOO#4IM}HP#w0L1dnKPSP20jyS;NgMqiMD{*T5Nx7X!vrt4wHwk59*-j8k1cvWbTJs z!tR31Z`!_9QWmxlhS&qrpg4tMB$F7_jwrU>kJCb8)fp?6gFex-w-Inw0! z_ZX3wo{mlAc=_gwaT@pQ3Jn!(i<6$8?)vpfr zHQ3f$mVyFj7Gnu0Mc&0Ie86W^qCziSQ0wbWgFyxYAg62ptIw?hta!ClUoST3%`_#I zpA(=V0BEL~08%g)MjB9VAhnQ;GBeIZDxShN==^Pz*KbC+TFJnP7%2?PqI+y#GqnQ2T)C284HAwB^)0Qs)w9&0~Ack9I0h62H`>%G!CoJhT_?g-j%UL(It>_-+ zv2y^qKW}UtZNDPYpklRZX=@Wnv@Z@rIykz6D(*Q7a+O!%JWw@}1x?&E^Ip`zlP@6j zFF#qI-7EYgU?SIi+DUwx-qt=nLVm#9JNWJ+#dWQ=AN9^pX1N>|(39dz=9J}rV6nOL zDz1kLu9^H)4PK;sk1vzu^3{@PN}VKKsiCFtVEn`5y6_-2Kpckr z99`+=h1pUEFxTFh*fu?R~-5e7!&&k#UT#s=Oo2*pM*kCbyy8#6q`q zYGIm9QgrwHN%g0|777oK)38Kl(x9UT#a#u(4=#@xK5Ke15=dzc{ajM|LZucqHiGxi z>6@l{zUix`GIH%ykY0WCa{7kNnfE57WInL2(dRC^z_hxN$=aJNzFXr>Dl_d0gxyq= z|6|MYq9aG*Fh0&@*^!+=wa9|g?t-!WVK_t-VR5|wJKM+zLk<0G%q4QppE{3E+PQ*2 zj#G#;wN6N7*Tq~tvEo}W8jrYha`Ifx`>5JxG59vhPtsplyOs$QrJj1*DPFtMZ`bxj zFuCuA&@U@L%m;~}3W2guA@5wUG6r%Cii#|=WawKBj9bgW*%m$tmNV2!5oal4hU32m znn*RnZ{$z5La#e|7RMq2$qnlQ#uYCky$2P*rf*fN3g(5XtU7l(ljf5!i%gVOY3gaF zDQ!~|+DXGG)^(;P)a3@tcvw*+Mco*r&R>q|#cjokl@WE_Tjc$*-V z&#im1jCkFv@p`ihkD^N#ct$uIPfIHt0)xpB0>=HH3eU082W^IKb1^AwQC41@^Ft2= zlToN^X-(S;i|>iovimVh3>D$l%)N~v+Y<3fz43B~NsZFU5v;`i5LDf+A|+HT)>`Lg zcIXu{pwI8$zjh{NE3p>5a{BB`+Rt)0O&+*(oqhn^81;>a__~*j-!b5S?lQ{2kBX}T zsJ7gB@ONYBO<3ASA9^|%k>l3-*J35Ic@AwMd0#oLH5lvCcvK@}qU_d6$Ci`v`asEQ z*L&;s#Zr%Jk~nN41O(zF_8Fol@NHrVC~@w>@e-BEJ5gXe&RdYOONbJK9c=D{O4Z7M zzLD)o%ge9T;B*x?GMIal&~hgn0fWk$w+4Hd`E)uk%6ZHmna8_2b2+|vGRuvNgbN17 z`cPaoHS7nfZm&IAEC8aAG20zPAs${+2(JwrL!=5x?&8 zBE6ifJgjL9`=Ma?9n*c*yxAjQ>3xXV-Ixh4f7OxbBAF)#;}2^N z-}Y(kv9pWV(xEF^iuFlUw-WiX+Vnez9>l!z8rH|%`VD0y4Y`92mAgylV|Y#ROolDq z0ikZM7uX|jmFnh|0=OySQV>=UB!gh1TxGx%&p6 zK-Ka?g`RWEn)=3@SA_Ld;@bN5l;={$**b8PV;m2(Gv7srNuj+H1Rl=R^P z<&*1~h?q%fAmuNDs3u{NuP1RZgkug$CVsjWmIt?22v%T!am-zmJuPjX3g(tBd_8!q z#Z*;jc`W2^^6}zYvRa%7(73#}o*X%q)Doez~d6%pT)tNIQEr#^mzf1mL<`8_Gum+<&d zL|sYgdZe_A4W8xfATfRaVxMGC&?oCUbZgcpOu^!znU5o(Nhvg#VBN+YJv|{&QBh#c zhaIT_I@Eux?x$|4iOgyAN=EiVWiVs7f<41xhKJzCVB|^ak~$`WmV{HD_a$K#M$O>6u|1YM-)D5f6dsZW zUSVfvw`W*w&aF3=wwc8{_hBLx0@QTE$oz{v9V@q|s9F zZ`}Xa2fC9aKYH*WfB=mpNH93%_vvi(CJIKjm}MGP*^LYQ7X-_04<{ySYX9(X3IfRO zao7QE2tn4~1$*Y)*wj>PO#3fDSwsWg%S%gW0$GT8Iqh^J91b9eHh(FX`4`l0{a;Kw zk>dz5!P2j4Gd4TJGZ|pA{El*-y@46N?fZX2+Y!6j(0s-iE}Y@c4_b&1?>Y#`j$&WzbtV-?8grP#x#&T>Ea%p39GE+IlZb)@EopvjFlEPdc3Wl1D|~D8dCd?ZJKemjN23k zO4F1a%{Iw){>>5RVUH0q>wP2%Kn8I6Q+U}e=*x3htGT$bgD$EU?tc_4l-&q4J&gWr z#PjWVAoZ%%_M0f~zth%!QV?YQj3Y-xs77~v=%i>qC))Z-S&wW>v=e1+fM!S$G4s>Q zNRoD++qp{~QjFTH_u{JL%im1|VyoX>edC}BEAkQY2J1o{+U!AVebj0i8$ILb3|(GZ zE^GX|{*x~aCFfd?2E1#UaQ7%FDaFObUsr=U?Zo!_8k?NIVC04EB>gp-&R%G0{{6aE z9IZmk2dDWwIXoHt#IAik_B!YxdkgTPhor-`vTYY9j>`5XT3Sw8FYCu_Bl=B}_|vGZzSO|`cz*AePR6i2xl(|6+>Pstq> zG)kqsWE1*kynAW>1OVn~5iO+SuCQMj`q&xS zaQ^c%NhoK0SqNgtqYG4Y>A({y;}k%LgRY&Ii%g1%L}~E_l_Ng_vLpC&)GvmS#M*!N zcU@{_N;MQmQ{t;)sgCysFV@7l5#t`+;$WHXfQp)o@ zQe;9L!WC)E7&4mp*uTenfuQRb$e2)@IgP60ai{A{^Z z1P2&jXFavh3%md5p_%mQ09f?w_L{4WX)lr0)p;v3kbX1DH6-JTJBkyles+2NDqCp? zD4uA`yv2O7v-Lc2V}GDQ*p&pGx7|GlMmbVo@`P8Os$RsDity3@^J7|Eyl!dBbtm?2 zevFxZo^;8o%9SYWL=CyG{ar-_x6WY04P(H0LNvueY}JpOg6;xsN1|0Iw=7zbY4z2< z7Pqo1cQmoxXZ~&C-m)Z^3N~r%@B?cZ;{(dlcP(@p)h4Rm&=D9YgJbbXG_QFk@iEz; zP)^nr=6e_I${${GkF@^EA{X_{sc_27G}d`L*HahaL-Vqy-`dJ51PX@*3h9bdKS*lkw&*{)Tx4faON zqs_h0M}*(ev9ce4msjz-6ZYlL(@R>wVqhdD`_G0zrIJOsepLy9 z;H*kLg5D!T4G-e&Ns$&)^n-a<^&=}>Hb$g%b05U}0-wk%($P25Tt_YAckR|lzX*L- zXXW+LZ7ZFfE|O+}Hec_`_W~&?%R(A?zxV{gR6UIeH!ovZI2kRnEdnD#m8|huIAo= z_aSa&^t~{F&*p1*xO(}ADSLZ+RRW=*LN;>h)xVU?GhSi6+BAk~?DcT6d%`I0xv$qX|lHreaXb@a~@!|ysC+F&>ugR(u@W1kE2JRRiKfycc{V(;eT*f8l sHGY{Y5_>rHUp4h_e*cGi-6xP(VOHuwtTuazH@f7C=CtV(%c{TAW;Q3g13}?c_xG zfyzd(_TRo(8YqhyN=gEezdgSL0tH3{0{x@Q+aC}x9T3RdGs4@OKF9EU0z#t#l2joh_{Y=m5m&%>MRhVPLO==WJnaX~*u&Met`2_P6IhnrR5|{_J9J z#zmkkDT60qWov-POifEoOTZ0sO(%U?RA`~EbRz?0{I0;(BO?u6Ki`DD@(jT;OgjFIoNX% z5d1OGzg|D_v^O#QdnQY}zsPzckmiqHXy~YEY5v!+H)8*V-+zp9*0KIM=ufJCPR98M zD0XRE6N5K&|3HeHj`L6O|Izk0a-46_*#&G3bnLBc6|Ahxx&J9UPMUxA_-imH%^&3c z8~HzZ`)BJLbGf13M*b2MH`Jx)+(K4hn(l##SnN=eic6BWEXP;W$ zc{dt9;Q1%nXnd&;f`Wp;2w2_(o#4LjfV2P-Zv?gpJSB>ag% z2q4itVEa4W@yQqC&6MFSlgTmE*C+Z!Oso+Z9;)hfxiieAV)4bd?zRhqTG3^OJDUrg zLykP6tQ3F7R=1`=sp;krg_8?XRaJQoy;Nu@@wW=<4Gc!Vburb~*O$9Xt*%V)J;t}j zMz@7XF*~x6$#86jPoXtW*>j{9@%lIEMTS_gxdZ6{qH1nbRT@wDpR0;YchQD#d)c9Qzi=3%*@Q3 zgWHc|>g%(0nSDr9N@ch(N@OPrlm)0Ks^4+{A?y5+TV3?ZfM9lUCk+Puk3(U| zX8lf2KCAO$*kGbzLThQQDt#y4#K(bUXPx=Nr?wwy67K^jsz$k-TgV9sW zm4JpOgE-jTBwS9Ec+-+fSwE^kn1x2s8uHVV6$X6#4s8^D;s0atO7e#KJUrZAj}#@) zGn*E$W6&EPk^(+2@eR`u5_Za5>v8`dgQeaEFU-v;3=}2$;Zqp*Wt5gG(76Z)^6gsD z>gy$;{Z`h%0`GJ3^NMsc9RmmC2YTPArXUlbLnyDh>iezUW$>Dy_I()yOcE6M)LSC_68YqJhZ;}K33FS5ur-Ju3y5$1aBg7Z5WY9j-iC>)#N^q*CeuSB%u09o=NTv@Eg1`6Wlzn{C0z*X_n;cS{EpMStstGD9uMQCegRK4|~@0~{(WIb->tA?X% zrH6BMg~Tmb3qX`{pw*L+_8>(&_x^iGoGyk-`E}kos@Sc7jD4`wc1|MHUY1 zx|0Hb#|_f>_8=6b2-FHdxiaXZz57l~M(f~F-N$OCNAWJGza{Sg3_TZD?tc)Wnwi;T0`jYm28d8*-d(N_?iA z!hbn$Z%+_OtckHnVxhLKZqey!Ht=4g5^KuwCo8F*=-Tf3F^SLra`O_OwATZ@znGrc zM1$0RqKE^JLjVpd0zJRar^yOwqre()$#krPKifVNuAm}3He&e2XxcRIm;eyH&wD%C z6IgYpilY7skak+E6EjQY9}Y!+f_KIMr!-&RIF2d;6cONM5TqYzg{HA=_n3tg4l-zp zCo+JC(q!}=c4WG~D-!kU)~7+WF8}BoirQBYLPlCqvCZi8|bEMyILh(HWb~Bm~7}|KupA2MB!>PU88kbG7w% zZ+bAIsE#}{FH9<9vxAHDR*D}O3BlVa^+{w#_eI;~x z*`Mf1(2RXvavsY3Qusb+{CgShD}=a{RekvLduCV;WK~%*?L&G;Zpx*WSd&~%DAgQx zQ3tx+078r5`-2M0e_wjE0p3sea4)nluaBK*+#~(L&5uAKAM;2P4Sq!y8Ppkv!SfrD zV*r{(%;=v&34;*e_a*~F7~8dQXWIk z*?!um4CMEHN91_*It+{^%J4M;z6fi(;P7Z7bE^H(h>sr-oGb~CHkhBdofyi@p4j`K zESVOw7ca5Lzw1bXIVXs)okM3==LmKQ@pL`+SueGI46L9)vpMOq@m~=~<|!C4sRE?bdU>XTN%lg3z#YmLaA~~rk2?)wqu}8MJuC?nwY&BlL(;+?@u@0!z(9Rv zM(!w*R=%*NbZg?-@!z>!p8|;lrW!AGLaVk=#{_r`boLAT#MX<{qdDS`z@2oLS-5?` z0Ne$G6)G}MYxW%76OLD?kKA5dh(OZXbvc{Yr)gm`Qp4a?iFAJvHde_0mRK$rAS=V9p zGG}2fpARN<`g(CJ(5OxV;E9ie7JTIP7;6B4D!`xlrevcFMJET(i6GRw9kNrWbNe2r z)UE5<&uG*RRV=e9<)J_46qG|A#@{(_O4!@UUZ*jprcT3WEAj}JI=%Kh0ei||%M#&s zUA5{}lHK~(p}wG3pGm{O%eDX^i_TrLJxI=lDo3ycZ(Ijqp>103PoC17T_Lx5VI;&h z{Apf!KcW@veu0a4Oh?_wgjy;RUV7V!TxXcufYi#3%W06S4kCQhRS}i^yi;+21n7?) zk^7egOZRplY;JpUySlC(YQ|3#7K^WNx)ughLe#Hz9k8)M8btE#-FM`pk2e(E?Wox4 zda8+_i53TGF-@5+DH6%ynJo71vAeL?@+YvlBwfd+b3>TL)S#)tKO*C{D8Qd6CXc{v zG=ecBoB73`g|hpPSp+~@7?cgunJz3EXS{h6B8{GJ-`oQugka}BM^u@5vlx1nqBc*O zSLRlcfEHF30cL``6Ivf#mbrBJxm57#~|b*y7KO%`i_3OqEKxFj z9z)0%vv~40FMK+k$J%ho4TUTWm}|xh%CMP_#U}cMcV<3BfKI>c$r5c2y<{g}ZlKoj z7{?lSk+9!34K>Cl-AWTqFqr+ha!Ff2G)Jzmg$rFnY->F@*PgRTeIxxU4 z6t&VSmDAMy;yft|NNq(`oC!qfMYVYNL9^p~og%(O#|~$g9rf^IRVwLrX6cE1&mbJ` zK+~#Rcy{UZC=<|w-S=>6gCm*8F~k zHJKRp=}A#AQo0IW!3$>}g-l7|up;~Sy&(4Cg-RW4Mkgy*#k%7PZ$~#C=(+whL9s%> z@LayNUt{R4In4YM$?;JJ3K4srNI`0OD0Z9TZn%=}9a}G#QFo4%`y|Jq#I1%lu}sV) zG&? zetPuqg=cr=v-2(mF{!*oz(Ij*NJ~ll+K$a!C$)A3TBDs*`(#jN%jjN0C#;F|%flAVk5e85mb~viDOv{32~{I-aN?6>V6B`8olz~mNg`9AT{G`+ zp5CumZhe)f3BU@8MniDD2A)WLk}Y;bsh`)sCO&6)$+Lp*WpLx}s9oY|nlzwOvw(MrrR2N(g|{%iOhaxBNdtRyoAfqd!UAcSvU~ywg2Tj(WUUP z^LOD8>=c9zAjPS$xz;VuWj@ZuG&r`edHP^nO7!bV>+Nrio()Dns!ZatW*!a=-{sW6 zIjI1MHoD4V7o%WVg;oPmM$m8t( zR&RWP@UmA6b)xOS+%0ig#BLUXbdO!7eRvSb@t_u-d84Y%aIN0eThR~{&1g{l zvSf$4(0|dQ;7>U$6TZ*C#TIf;*j-D#=HP-Z-!ay7z~L{~k5ELF|5R<9brTRp0E>2u z-Q|&e3wiB|Vb_%5Ns{MFO?CRMhe&_rPv*+(fZKn()gh;}D~TyOPQ~FP?hyGIFYtau z?h_5>S4c$$L}#j3MH+A9;2ei`X0pYc+c~z^9szIPp_d&?Nq!SZxiH1;=qi}Yw)?cU zXu$@oR>Y?8 zd{%tl<*z;D+b&gH0rve2dS-zrtN$ zVc$ksOk*c?g&?wSM%p3e>+t#83RUec$j!wO{6Jri1nl!Qb#okd`ss^#70N#u<^ZI2 z@gC%d@d~2UD@a#i85|uch>Q@Pt}lFx`{bGUtG%aPvRH~+Mto9n;)+pu%)abx z%Ni~wsr2ZCFn=;)q2`>rtabThR)_y6hC}e|NQBiH2}h%kVDy`YIw=e(sPjPzLnPKcIN(Rh$Vf3_UCa??LjIESK+Aj zc0<_AExzXq%CsRQ4F>VxJKnr&*{PYXlVWG$9gVr3oT#Gx^w*|Brd=JJa(!n#nE}3_ zz)-kLa*289^l-RloLGj24$U~=B6;N2a!oN5zlcD@^|R?n0YE@sg%`)9&T6g9)q3s+ zu%%_K3RxE;IF2R8F(n>FgaAFJT7m62t4tS3=wk}q?k#VZ()F2O$Bq5;kq@b1AOR7dy^HrsDcRq@af)3|&h}HY(k;jB>8n0>M z;s(CZLhcZGLo00Qm{K=0bSp=9q&p?_aIi;LdF#;mG!1QRXjXHIINv%c0`lPIFyyOOZ}Oeu`&m6bJkf13-aw|bYwA- z3Xg9OQ#i!)xb~KLn(yyk3ehl;-nLB!>b%J#d932as8pdbsV3sQyii|0g_0qLx?Yw) zfz%ci6@%1KtMF+UA=FPhbd_@Z=mYM1JoU$B=6(!)`L2S_?;x?OUbI=afGb4^v(;T%!!8`GXLFVf#2n5vuZWg1q7g==Zb8prPglrvrux_lMa7mls0I7ocSv^ zt1agPv()0E^i-`$Wqde~E?K0yJ{0$ZN1;#&5FHylq{eCB0rYjgV^Aa+k@uU6+O*wF zt3}ZTatK{;bXF~Mk)ulHXKSF67mo7I;4S;5W=GKdP^kHNWmcA6J1TW+{n3~b@BAA_ z)5R29J;GMy6z`9h!dcOFGty0zspEHPG-nUF>&hRJ3y715)%}vQg{Yizme~UQNKWx& zxmxpxg;q3B&rBx3JP+DF4c3RLIVoHc=WO;&(~e6;r8+7a2c1xPb%dlvIanI4T!ht& zENva{bN~_wX98MFY4tZq(5Kp&4vn5rtu3curb`_+o$-CPQYR#)EuSAlY_#A_>d!_| z)!p`~z|_RbK@pzHSUzM^B#1~2-O$~ba|bI&a2tGj#^2?~a6a7kcx9votNOzxWyAo9 z44CecpS;sQZb%+o@jIUhfUq!_sU^L=QA(00$O*yh8^MTt3t}!U{C@_Xw~np0D~q;P zQhWzV9s`9)7m`G9erwN%A3zl1GOxcQZt15zui#={ghjf{S6}EF%e_X3!@SYuCK&9W# z8bBz5XGP(3bu%*ILOXGC+}OdG>}1;zvIfhBmjO%(GI*`P<;rM!(I)HGJ%y#x=@;=} zp6roTx5Uh%z9@NhX|;`Xk!*fiyJQnTe~c|V>u=~%r4E4E=HyyW^oV@tID-)k4-tUp zwpJt>XLAZBwFH2T2CSV&KeK*ImM2km&Y0{vrEPW6Q1}8tT1*u$#r@7?77g2Mi#@|p zN|wc7+br86MYX{An}&|T#MYVLomtGgieiA+&K8VOjb)*Vuvl#q`g2!bIpqB?)tvn& zVvaNFsw?mO150}l+RYP1bI$Y}F|rZr!j~__1j4Qle=Gwr|M|c2JQqlFPhG-nLj0b+ zxz7`vHPU%4q2VG30TAYZdr>|OvU& zWRfoYXrba(ZN%}jToRH9gdJ#b>m+gO)4}<;4JXuv`qZL_cVJ)og=s^6=yrb`#>%4! zNqFb^>or~hfG93yB_erF*6PmpUD;v&9dI(u@(dHr==y#ApdgX_kc9Cqj zjhaF?gls4U_L`oI4u|!uYqh1ly~Q2m-_tq3+c1USRRfUufns!Wg~c&j$f zK{eFM-QZjM?t=W@vX1 zv;3vWd}p`z18{pgYED9wH>39$m|aA*2mBjw1{F5v!o1qFAjJ(ytIHM|dN5inz8}3k3fSdf5VSWn5aQg+;pz1Be62 z`yCILrNf_HW!Cyz0dp9c_v~Nlk>86{7+zWod*We#iAUUrPZCPmTFt+Co+M(Y^#AF( zGw>^pDygz2py9Jd^86?lITi58^KTBJTvw~H9S2DY$**wUVUN&m82W*^EZpL&s`5JMW&Q(KwFIs zXr=q!p4?908bed)oozmW?y1wAeZLEr)r?`X*vWkddj~lLm6av5w*|vnJqg~NZcuy239xO=EQJ*;a2^& zr9@n=ZZ0j+*QxNocEGVY-Uh_gAJ4FSb9I6Sgd&6eC@O>`G`_qNoIK&wqP-q9`zzak z(vgsmu(Hi{$VG>fASl_GFMd+5F7o58VWXVvbX*(NXb@Hjm6`Knc-1)!fs~mG<4na` z*EXW!cFw^k`-G@t1i!XAol<$K%erwDfo96cA9Znc0W9~nU7Q&XvL=~FtaZGxuBZzt zO{C#Vj}OneBMF9r?~Jn}u`%A|QNEnjnsa4_3Q=7s5QXXOFFmY0HYfUu9A8me6V#Fh zTSB=dDv5l*)auIs`P%tF1!+yj33ov-#X@xfLg2xXt@lOmW(pa#jPJ~&8T(Z;7<3EX z=0%?s>#6uhc{9p}6;}J|q>=7+oPR2>Wx6fBwO#MGInPCq?bN}Jjv2&@oZfeB_AqL% zPpI-nWnC`AO;RT6ABjW=>>t_9*&HFyKcZHAuklMuqcW%Lez)weEV$Yhakwk3z1miM zwut+>v5~Dm9G&cPATPs%+A&9w@Zp743JjS_$G`#<6Vptmh*#K@6K54#U@x;&neLQg z=x z2&ImvK!ZNpa%UeN{F(zGnLcwX4S2p6{VM^L)}E#y?yTI8U|hWI_Z^|Ql22k7PjXay zkC=e|BB6xy6rJ2^TFWM|uRJ$atn=X-9-V+;hwraylQ$dGue8U3$PpBg#Ur`~$?1$; zR~B1sW%z7=BQf_1E7G#Mf`I0vwXGsgxGHuW(i~NUph3-Y?zw8RMatcaNo_(P%AfIx z4C%7U`Lp1#MS>?8bC&xq%X25j8{($tS&#3;8H$f^#^o5zYFl|>vaS1zww9EDEql)B|0pZc zLIRUnKhATBG_Oa8r&BksI+u`IycGr$Uo*CL#;87H*Q9l3lrp27{0hPTt%Ufi4u$tt zKFl~c2crnTlJLz>Je>I;uFwdclM;z7K6Ovx5lGrP=R#|&X3lT;zl)-8t;iz0P-U$S zgHRso@@H9UP*`2V`qwIm+w>(!*=7kmwJ0q4Ok2mzSA`KTCNL^?E5Q=4hwZVy7W%JB z&@b@bAHG=1-IUmoFC>Ty08+yFLF-KjS}~LL1CDK&S@CwtnH(zOSqSv%a{nsj{1;K5 zYrK)|mnnq@KNlmnmzsR@xrn#DQy!F+3U8N0;8WdC4cey{%v0Nt(A`gw$hfL0P;gRV zj{FbK{(aEQ;ElME_?`@N9i_3X3MA*B>AYWV_3wUvkRw6To>97AqJsEKLH>(IAAWH3 zYO2^^l7CYDH!ZYjKz_A(Rfb~!HTYi&1%;wLRx3l0{)=UQ5B`NuyFCcZLh?v5@m~eK z|A8;5f;ZnHe~2^4Z;=I_d{1j^#%>lb_^+A&2`57a_^tX+yz&0`$o_wlDaHJwW9R<8 zFgd0Fv;EI|A*Ryv;(uS)F}p1 zh7el77WOy)Q&fM0M3#S(ye1lrESN~f}y+OK>-!wVVTSDr$^R$0?n+HQK#^wLe(vh4ko4HNO-=rVwBF^|BAiDdW!0Vk^aV0& z`zW-F8OPbgEexPvG|=>)F>x9elyOj+$umtw zk?bE<)$Z)a;g%$rZ<&`nqtkZJiC!RH7M-S-DAcwdOpb$aP}VVJup<_3e_$ec{kW;f zA=otke_&&+BxZAw2$Upa#>i9j7~367q8XRJ4I=f(ZB6HftH<9 zQrB5^=zDry&u!Dbd4=8cZMXZUgfn=7i$S82JNYot6zrY6Z}z^E3>eh#&e$Lu!dLxB zA}`OX3u9AIzh$3`Ee{_!VJ67LDh!c6!@Izc5)5|OC8xYA~;mDV{}74%M|9-Gst7n71iQ_PjR1o zpy4-hhCyz-dCVzW^A(y>$TvLJSx`i1ZKBe;(z5d#4^>y+>a6Z($Xf!VUL+=PIO&3j zvL?v&z0C7>6P!fpaTm9toX6X6|D`nECm=hx)fV&!kjyOs{GB9@HRl6YE{)KMvY|y* z&k+KfW`?t((eAkUFDl;sn{Aywhl6J~6@kW-lT{kvjkqzv;Yl)}yh# zAhKYnXLx9mi0&gUmb2TwapOf(;s+&K<&eD50_5hv(C`^!$`|>z^b4>hw(oGOl27Pu zsZiZZEIk?LA**A9rG0D{UFJRva~D>u+6gU$qr!!r<$aT?C;x3N_NcYXI+-1;#KS8p3Bc8DyqIy zX3dfd^GR&kal5ic9nEIZ+uuQ-*u(!~?~d})P$3>wE#@0@(bgA0o*WmeFDMmpCiW;bwcvTcGb7Gfg(CYv=hEe&B99Tjjd2so zZ#SRPtrQ`r-J91i6(FhH+Wb^7sR`+Jt4pY+&9WflMbDqMXw4rk0G#q~p(Iz!2ih|l z{h$Dc{auyW!hyZCtVOPNpKm=GT89e-J8H7`uBHpuuo7w>2o7sBog-{DoK zp##4quoTUhhVHJW`WobC+er?WYE6f+%=X@$joP_H9nzrhY2oz)8ByhlcD zUO}yC9O`BwJI*a1SFqr|NWH~~3&W&er9fuA5#!o^jK1~WURZ_9dHPznCh4`$gyK)< z_IAFY>{u*O{GNZzk`O6TnjXnOikQxCJ5*@KEY&jqi-kjYuOXKkSp_D-kE&e?OoW*GCB2)lQRnrhtX zC~D6A zOT9|xRgby*Y2NG4+h4G3a5!G?u%6RD`T`IZCb=7%;l)=h{UT4@qh2is*09ws87223Pu%dlxaCG*# zmkgF^-1%yaRpnMIoDj`WX?_a6ByAU{1nx#8sNUVLQEa`JPDMGf5xu2=ySxa=$95WN zrg4SAiSAc5gO==Ux|8%Q5%>x8kz%)1a-|g!^D+dJo_ z^E~(_88Au%i^4Zw7X4c$`e=d-ja9{KW?7^9Me^2%%OgW%UDNlTrfn(F6>+Htn#^+7 zMk14(4@s7V#GGwtCEh>0$EggG(7om zc@+ND`@Lo9*?A8(`f?*d?6Lqt)MZ;#m-uOUZ*I51x$Gj6@)CoQu4eaeH#+kbi+caN z9~lAS=MHV!`kIk~>USQjn$A|BGm$uv@x$E(GXq5sf}7vy%C!%CNR{uMdJ`^qmh#@-=xaYZ$=mS4*uc3om6z-T>Ap@Vv551jlf?6N?K?*M4y7>eA-K8E zDBrJ4qeczkQEpiwf4pk?dwn*pwm8@oz*p)SO{n)%SsLn1j{P(lOT!e)j^XIr1t8{!;wQGk_M_IVHy7 z4wb-&_7Tj{lOsD^=nVk3;lrvSqX3QmT|ppTx;3)heI6bz}A-u2-^|CoT}cwL^cM zB&zXjettcM3)<*HO&l`_jGP4HsT^+0BiPn5m9L$HskoL1FVS?moOo7=M&k?#aFZhz zO4Tz6-*eZVC{>yg>K)Hj;Ww`kVGdi}_{1i~=9y$h{%2L6v+LqW=4TS!>uvpdCagfM zSM-pKBW+vyT8jm0SCX*`C0vDpm2dJKuZpGk0S{aGQfmq$Cr4C=j@fjrX*Ug$SEswM zK#YkHzFTdpBLvY7ZVN_$riJLsW&d=Dxp zRLI4&VR*2qR!_cMA!_*EtjYH5ow@gyK#OsUHB9uW+OIZmcA$x%e7%t#N)xok%mf8( z@&E#VPW%bvAsy!f-}Hw9rX)hFT%ZQ!iAg&UWai^fdgGA0bXzIe%Ips+C8;auT#&FG z6n>9cHEoQlQ~u(*VASb@AFC2ozJsPezo5T(c0=~uGdT!>L6}0Pg-w7bewA=Gi7;4% zI&_DCVK>w%Rzs7Nn|<(Ke{dkvH^YC3p(iiTMYmxn#-kJJEIjJVinj}|5DzbbZ6a@} zFsP`m3<^`KDA1F)-(v!^YMo-8eK*up?Kp|)`NzbZ$FYW`mUuUi6TKd`MVb84oQ@6PdXw_n)PHlD4 zDkAX$exz8->CN%tKo$8^p`Ux`APw5`O~Ppea2n5#kqDAX+i8d9OV65;tJ_M$ZSL{W z(s2{swp8}L`E+(YRNaBXmpk*`PZCG>G_8e`D4>DOz8y52et5g?E4TJ$V&kKhOrW#O zE#S8xa{eB(z!BU$X}d7lZ_dN4Z9tykzqgSB?-ISnYR|!r$hM+XJ@9aNMw%BR^kg{f zOOhyle5L4w5ROpTLRQpU;={twVlWCStV2ZnE<772z;^5hA{3Dd&8jFGfSpDU8WE5h zZ#Rcx!F>-Y(p26dZMU--CD~hP8?S66Ef{gqc|Jcyw|7)-aAzn55x6+Gj^LO8Qb{0XS!>rg0GY>&8InVdnG!GIlR!rNmX~SK7Y7vJj z%8S|O$`ABH;gY3GPcBn~T+2nm7Z?RO#J)7o{CKZ#5h=B$d%|gW7Y+)&h;A4r^rzr` zj@U5gQF&$oe=bZ1D~MI!hZ3!tk_Jm3ktlk31I_#=HQ6V^$UWu^5_M+k&Lk8Ho9pM2 zd+XD(o`KE{sc^VaJ#DL+v%K_U9}li@br<9`W~!dl`>@KLG2x+)6f7W}JqA{|uD?(Q! z24@sPU~mi~OQvRKrpfjRTy~o38SYKNvDqDC-O3Za=vFDNSC?JRM52?Z#z|$sHkHAE zuRGzo2^i7$*9w5zVjCo*@RvA+%HY5QnQltf+n-lD2e>ZW>J!}Jz1^jlt}M->*!S*NZtqU- z93{;0vsj{>bRT}`1ybi3-?KS%?S69-VtdN~##SoF@1Dpj_BD?xK*-7GdgsOqJsmYy zUvmvBLf~bDBFjpkJ?}T}WF8rv*Q2F>)ErtdaK!X1kn2{R`WzWUa`_^$JT^^b%Ol+o zN^x(G*F9e)vtl?RERneu0}!|cQjm?z;0Zz^scB;{HVZ5NR&IOyY`5D5ixAPQT+`!? z_9TR_qg?e6>)ad&pdhxBezM{v8BW1Fn8z7LRc!olcnK%gSgw-DcIrf3!gFv$QWZFQTVTM= zrHuJP4wY$&f2migl2m~9bTzDMf$-4aLWa`lMb?UqGS4ZzznKg4*i3?JLDa`$b)KBacB9@AA^_tPEJ z)*l|~qJ1yLg2RJ{PZ_J`t^RPOM@oi-KSKXbrT@uTQVkFTX5+BWezZC=#B>DL%&2ht zQTvOQ#xDvQI6;Sx@j5#jE%Q#YUZ&I@aG^Ut!a6Htlz!CE>Tkw^76UgSlvojbh zSJ>y@FNArVygcAf%NsInjIQq}C}B-x&9TN(VSu!&JMawRetvAg>NSMvoQ2HBGjtzTN3MLQ@q{W&lhD)Unz713V>oO< zfnD3fa2g@RKxZJdu@Z8(%F(udMOXt(Fd`bl?kCAJ`UB%S`UYR%%unS`b2K@qF;9w4MlY z#@Pi3L)68T@}ZjKJ>+X*m}EX-H@eF(@%cshon6$G;bw$t4Ro@fGJ{447sJA0b4~^~g#1PSSmW1T8 z{`_6AVVYjqr5Dr(4fM3D`BGeG5xviWBl@J8pen3CtGSAhkGr=-4YZ?~-6SxeN~0z8?aE6J@UI9*Vj zM3xG*&O53r@5VZiI`Em+)K(z&r3q}dkJto*$6Ie|R=N|cz)|ZGb#v>Ap1BQM8)3Lm zS9@@ArMkV}PHj;hp2*Y$N%61d3RLX$AYNIZhT>=>^-I3>^l!7W0q2)nm;OPu4f)#hup{u&u6G1G_N^hbt~j z0pHDnLkQ-acDHXU9=1lETe=bJ0dT%vE@nC1LhCof@4CY7j3R8(XunsPa)Z=dftw#J zkAgmKP`$R?HL6)q7GU_Ug)#@XdAvvK+!U0VhN}^w>{1#Cc9B|-=j*K0KbLG~yfX5C z;ljXHllKp_}_TILXT2)2G#`{y2Ag6=t2Q$9bashS$6!!pdG;Og;&M zLy`UJjhg7X^TG2~L(tUVnr>}7S#@-_g{!c>*%h%TJQ+qU%CrE`iFz!oGYLo4ad-QUy7G6;r+@FpaOkyczX>?awz9M8!qV{5+IjY0 zeSI$^oLyI`3}%T2Ymww2pS2`uCww?sr+r(#IaY3fqAZl&;qy#lO<0QI>h&GuQLz>3 z^+?B~VG`rUCD&6+yQiSlSg{{N77b2sbi{+zjskf5@VcvMwWK%tSSuqpaiLZpjidTy zOZ*B&9-q{b^2cM9)NZ(W*%&CaV_EOiEIWP|JIw1#1JEUEY5R*?`W~ABq2uc{Q{y!G z{6b2WefjRLc5f~2x#j4mv*^_yAeWU05^m%$J5T$ z$-r#47@)b{)vkalv=6AnK}s#VX9xbLbauQbX@lcU-$>lDUoSkAIUGJ<%yG4EPv+Yk zhj10u+~M|6%}03U*UUbwY%gz{ne)^GSBbpBQ~9Y!BYM6!8r2Ze52Y}5+>4^C+R-!K zDM4kkC>(pwPqOGM<_YL#{luPvMdJm8bu@wwuc_O(oJ7cBH6tEo;uEfa-_M}v1obcH(8R1z5VBaz`b zkl#?;fc_(*Ag0lFv|9)*sFotv)i0OYO_}U(tOWpWzna_Kt$OK3U7@wuc}z_{C#)5H zN_@_4ofS4!7SqJ73K|CR-RJUD9>rEy(H~5+w1tRX9YY?0Hc&HuBL}}amTtJ8YqJeI z`$sj~XM&_Xx;FPT8MR!9<+aEEeOSe@Ix?dXhNQq&dimMTu3M~=#w{)@y2ZR(sFB7e zxo_RRcSq|j1zFJxK)Yr9kxX_7wH%RMnZb*NS{f|5Nzslx5-zl^m2`vUE z-Vs!po2jxozB0n{JYV6Lq`=6lJai`Tt8!1Vu+_m1z8z1_ZVY}@SE zw$rg~+qP95cRIG+aR(ivlj_*EZKr~rXP@;uYprMPeg1*-YF>3+RkLQ@v&KE}{fsg3 zVk0rL`_A|i!Ht1dzK%#s!n2mC-|Y3f2Z}bk2Wa)RHLBF`^Ozq*Ukwe~eQ>YcL=UEM zjG29K#mcHRlH|=qXxXuq8NgeBn5dJ-lpoNxmUyD!IAq|y#W4%9x`nlnXR?fU3 z`jpxPClBe6v!>c?%k%5Lw?3PUXiK;J^RX|I42EIW`CH7Z(^s)BhAY|B0_mXg>iI zWUAqS|NB?siS}-Je?))##wyyJ0sZew_Ron#LmTN#t_o^eTfLW4EUN##H1?mr08cbz zmJ$yvN%#N#ue;nUXJ=T1^ zHpBXP1jF1jtl(F}4~}TNI)sQ-9y|WZw9=Y@aV|vzB*k^M9<;hLv3v> z90G#crs3H+EZgvBoK7$9EIbsR@uiJ-rO53ojfd?H0EZmg)H3t7^}W$>ak}fbNX{9T zIRX!*S-tJ1B~gzHs`jOz)&gCHnlC5Hwb&!~Jo?tT-kD$8K2i*(CesuX1%>!CAhDyP zgG4M+!@!6gs%z*y7BrF(0_~8yzLi1{e)O%Hm%K(G&D?p0&Vf+(cduW{oR}_9HA83& z!Mdt5X2S}vJ|6WAni592cSyf7Q<9xwsiVD5H|ZN_abo*o-krC_yqQ%v;X^8;+*Q_a z^>w7nbr(h{hZmgg8x}r(B@(-@k57Tqdb`a`3H(SZL%Q=8U5_B*3JWxaxP(MQ@JG;> zFJF3xhv`7E7<4kULUkII7$qjV*So;$=lS6W0 zAp&v=k>crRlCTKlr4x6*XK`tbjC2SM1qfhDK(4z=zsCFQk6=T=!rBk&)Vmlxyqh}5 z|J|5y-rahZ3FtaQI)U;pc1*UrV!njB2A0EZP@C;0xdgQGV_iN}hCkeQHa!1zWZZCr z7t-7N6ScRqX3Uc}WUN1FCYla|$5nuQ64P0-f0hcD)9r@pte~4HW_W5U^XOOq*BVVJ z=$_%?J>pjW>S1)Z{#Z%RN-M3!h4~Vu8n8x&YXWHf`N$Y4^jI%&% zA1;lWs^tE{?UVUtAHr3l# zp;eQ0qYqxgHPv$a5`Y9!L0DQTys+Qg>bU-p2vjEg`#rQo`q5>7PU*FY9EqIez~eKx zNjVbkSn;v+n}{uwJpEC96#<#Qy&SZ;`{Rjljl7<4gZPp8MPv~Vd?J(bVaCjPcPwvQ z2c%4t=RY48@7`Qpk|$TJ|9G|>KAz3P5DuA0Y8}*3Qk97Hi_L=Rt|Z{d)TG!j@fm05^4+gvFpas|ro+eXA1 zb$`2+vVRkH+mo^EZQ)&%IZ?m9z8-ni`l*v-J?98aAWrRbqjSkNR?*gMEfSRL^QmN! z6*HrAJ{Ho~577`}sZ5wjhqj)~i)`VSE5#)nm73BZZ%bRpV%xn^+j#x*6opy((1|vsh>v_(aUs8B{P&2;SqAwUP#p6S^ z?~Wv9Unw4rj2KT#`~~PqIJ9%bCQ+KV z4(w1F&{aGeTSJR;u_4|Jt`#6fB%_mBMHofsAzE5p9>t2D2(_tUge=mSp&d4#%!CYb ziR&-2wOy~q6d70jV3H4=)$`EQ<}oL^QTwAVjRs46^-~X-^VUW!LRWuHT}~B`9`dHb zr6Br(lPU$kvIwf<8hK?R%Ow6z7|0GDh_k(Ia0VV8Z9KCrT)sezpK+|hj*@i>coQwO zf*`DM5{BYFn!Itqv@`+l-^i1QD=9sBSwj%~Hiinp6ydbvi- zaH9YhI~N(UUWRg5&TBNRN=oHo1HT}p4@#K9rxx<{reRErfNX{VUTDl9Ws!~|Tn zL?M?>-k|6MARa%R0>Oka#PHacu*{&h7yP#!`#%d4BV#GK%jT8$ZLYgl+W^ucpX(i^ zj!by)kLN>D$Q?9hJprw8kpIJ(ZPVtO6MvrX27E##moag<1Y7apH}gnRh@1P9<3S=cGCo*9x+D{6gYRVN&3Aet79fk1w8tc+PJ#q4vm5xIYD=jIq(=To0vtohL^^rexQvKEG_@OW zz`y0BlJkv`Xe8+InyZQCL&gI27Q3neoWF>T@~>LAM~JUvkh9;dfKiix01L3ywfl{J z^jad0>yUEAu9vDdOGVsyPV1<*sEYl!q`!b^)Av8Jca2QpsJre2NM3DlsgVf* zwWG!orC-7bI=ls=0)6qW!5y!zmz@5RBs!X@t3had;bF4ZGDzNGoOt#mS@AymrYr)& zGam|w;jo@udgX1cyw5#eA~Mm==9?_eh5oxEwCDzCk)tT8A{#K25tz2A_+i+xwRX4H z(Wly}*zFNuyLS1oTV}^Mzr|b z>_d|^hPSD1RqPacHMD0$EU8NR`04%N-TJ$d^Xl=+^z@YtnH-%5Y@>?}BCb(f?K)jR zfmw~#5$FKRq0@$D!TQI>zOi9Bf?{uKjflxp@x4l+ju;lB9$|4ynU?m@BRbp_*TX`M z{%)$aQQv7@Pr{;+KQc?#-H+>&dge?eDSq?wuJ@YT66@z#WfAm}BJ=WTU#LUeH@^ zP~rV2v~FGfguZ1ZEgm*(;F8KYg>^Z$bn@d`J>s?Ov&%dL9K_cS=N$ncp$+b!U628pG z?AFnCS~7%h5Je&X99)1{E-Vo(qzZp#J=iujzBOQKEoms4WVaUh#r`xGnEUJ%U7Doo zaTj=8m1pqE8w}k|Z?N3N_i5|cssu2Yyi|`*H|feUuKPgk25rP;o2p)^usMQSYD0FQ z-8kIBuKg3)9IRQE!@XgIBDT$O%?2)#Y4s`c%{0kjpdPLtL?^lDS$}$)pS@kOZ+rw% z3Hx-{pi6}UH=;RB(-9y~j1Vci37jAu#_v0Df}nPV{gA+8$cf(`IBuDnFA_!uXiS$N zNxm&}kgzBSLr~J1yrL@*ag%_|ZVSc%yVErV^QOA5T>6DIQ36bJ_EDPwZ^(8FRgu%h z(xx+evfK@9<8Sn;?I|~N^mi@3d|FYNk0lKxEtr_?ToM3Wnw>hK#ce`0;(7T)sikep zj2kU&F5hL?C684jd{;Y&!rdj-DoQ=ntcX$&3*`oo@H!}zcC8(k|Mt=7h%}>V4Lqgu z7nr+N@{yKU9gtzQy4OtqF4Wei(-jekNCb*-JmzkcbB!zlLP5#KZ3w)qNF%Ogyp)3Y4*}mFl#c? zT*0??yziDcPZf8abjfcTw)B)!Y<8t|8^0Zu!Ky3qf(c}P0j>UyRA)3;^~hgjyU4?8 zxr`nGO8+`;H@M~LiTeI}WBJQ@1$y&LK4#Ef6Nt@)KKDF0Fx~PdpV9IHSKIN@&p{0) zw(LQUeun-cbT=h2#L$cs+`IVuSguC5sSNs0QS7uXn$xS?6X2vu7t z<_v+19#%#I%S)CLkbF5U)x`DX?pR6(0oi0mJrl)W^yqIr*n;I$Jg^>aZLxKI{7mN7Z+@gynvU?*9<^@@bK19wp- z%G-)oWGjG>K$|XtOoU~QKAjXZ-#H>}K8)?CX^_`{pIgZQLBc>VT0QJVAAhLCJaA?H z&k8ZH!S#`@cxm^rws1C9q-av#{b~&ujJKM#z!)tUB+Tn`gWyH{I|MxUgaDYenq+wT zC&&mDr5BS*GkjL&{Tyb8?WQPWzJ*VSes`Z`el`CB3BZb^t~|K=)JkvA-$J`*%SW(F z+RCZ3jPw1OsWy|PKM3CG1dvp2z4O!U!ifZKBpcO`^fW3__!Vz37N-wD8XTfot&M-d zd5ZBWfYNJzhijY@SjT35c}$LrN|)*%$+QBm;Shj1L(T&*<|D%?=0vrI z#sE*y?^ZCq=Grs|NAHYHKk2Pvp98AW>o{b3um>wfLsr~R$)oQ=an>{f7v+sGKd1-z zQsEKYBlz(Z=_!E03D+^PVf10U_rOx;mk+WR$y$VM;7H&8j9n++6~|dK2knk`aA@A- zm}CS2WRH{T;nkjNj_@NYOlf_IM=MP;M*^nYx&Y11*MXkTJWF>+tJr?=wVlPh za)$h`Y{^ednv|1;nrt?54Lh*0m$sbuTr|&zv*o9E(B&*Nu4fM%*73}jjFKjgo4sMF z3@D*xj7JvT#y?Awe%-G(@~@w7<4$I45DYUsG42lV9UvajK5e=svb^`Th*MUgF2e*( z`24Nx)5=}!-17;3+6FL*BeK3ikvc39W(%e%2jS0FenyJiPS?L)Y?Zy;{d07!eUh$s z=hfA)XL)H#b5?3|N|Kr!x4SYLT8#tmH7SSKcSSiA;u8kOeKy}fkHBx}lyUGQPhFoO z?=UF0M*1fDzxbnn+17HQXaT~irGk)`zqZ>ol5c?oh0E@HAP5~V1vQmkL$&8Ewqlb9 zHm(yXvp3*Cb|j8CrW?hljUr2PBG%d1E^4a)YnKfCe5b~Gs@xGf0_#rVUC_uyeVgb> zAgO1%~8E-1LReYzV-EX`ab6-lua z#42wPB-Lg6rv6ni<6* z;SD`;QZ{wo4GyO~KJCK_0dr?;cgL%^U8{>y;4H;Dqrnqz-==4kDrpBCucsgD3POj! zp5UwzT_yy=#Oehkd{_l1el5-_j?KcG%wawk4xz7O?sKlwmNu&f*M>IEIJvusZZr;x zp^QD)x~!L;TBd+GqvHZka;xlvWb$L+wPK!|cxm1oG8;jMUW~Z|rsz^m@$RpLWE;cJ zIcoNMXb`0(e&C%_hTIJF3_R8DD~NpyR6UNKygn!jzFymjfATso669h>POrGZ86#)94DQ+U?P2nIW`JWJ8JTZfHb=R8E{}YW2ZhF-H$O2SosNpi_ehC`&+^^S z0J=Y$+%bue#}OKy6&WYz92mAoW+bgQ9nCJAgtcKlhrGC@xt79y0QIYRfLi;ihk?Dc zXhJeGdI*Le#uz&(NWD^x3Nmc=c(n0&i%7uhXOeU)z)96k32#8yp0@Z=pG6nf)7%D( zIx2`Pf+oPS3s-Y>9JCyCVg1vjiTObL4n88ohe(9q@_^`=z0q72`7=6&jp8<;gTBTfzA&I{skqOW_f^whnazFH zrOE9lLNq8hPv3V(!XV>u-dM{(bD1quj2iHIzS$ps6Lvp{L(fk~72wqxPf$>jlUCG$ z0aAmDgp!TY)F13Qo)!B#%raFEC>?dz6B9{C%;&tN?mvS-#ZvJEQL7od8573VtEHpk ze}A~9FT)sth-Mw6gRsMmXj&p{rCu6+-4rzJ^rj@^1ALs zAkQ5J#y!fl_xg$yXmtj={%E7utin4bs-8>mT?)!WjKbXhllXHsX9

Hy^bRDYu0F zf%)dL^TpxQ)*B_m#ry&H-+zxEtI54F<=|0l z4~!+G>QOLP6 z-t#;q&1$QbDzJJH3)j6{d8zl{3eK&TofM~WVP_C8R2N=@PF6Qt2Y{>cZ#Cy(?jsHQ z4Hn=;!q{0F@?IJu}>Am-O@f+T^QPn?ufNfdLj z0C8g{wX*-z`DN*f;6?Rv?8Y!<@|&S)Q!a(Brv9G$&stlh;P7AGPv)HFoxcnL&Ic|x zD?6mdslZ!;vuZm`SH8AFwjrgfP1pAGDs|zMJD)WW>YG>mX}V`L+uZi$%!fP^9L0r| zDkR}7U~upq5x2!%TSRZi+A(58BDnUcsvUPV>))^AV(PBsdwlXZP5V9o@S9A&q(krA1mF9}B^M<(u(;(`Wi z1_XZxM+tw(`D?!J2vd~3r5;5hN%K(Vk*OmMDx65(<1af22M`KVjFKjgqPHw>g1TP@ zqQUp}fJ&r(%dgI;3#p*Y)7&@5BL1+m&JPdho}0HPm#=` z$=k686n4#-J+?>j7o#0L4K*)UFIO7E+j=_0DtrmRw`iP0=1KPw3?lhuHJ{PUs--)Oqsk?f&w^+dY3T{FDZw%okq2$2`ikgzv@!^?RWE+9o>7uL6YL z?q+R=)E3TDO8-em|06m5evZ)gOp#t*HF)>Pe){?Va*mS)!dVp;6}cW5Q1l9UJfTta zr`{@;66(`@2CqeJ2g?(_dp#HGxME`d8qR4ZY(!qU0o0--qLBpYi=nY#p)kkr?u+IK z2huB5!w>s;oE8Rw;j#x|Wd)DXc(W;g6?{106nr?LI(q_XkL3tMH));q*IjxJY$8T& zl|vU#eUYs;KLKzQy4)36tMXng?@>5tGfRw%nPpe;NJ0YE3ZVQR>_VnH7R;B4_94!f zQN?7b&a!VA@Lb8Zl8kK9saJUc>g6`Sy);7<`WAl8G#B&Q34Y^EXi$V?<8FRU*XWsh z*T^mi!P##w>a1_YmIlE4m23T454=ul^F62Trzk?htV`)Zw-?>V^ThEXVb9u`_kB%- zHO>#6@U5=H?nPK>Uz7;vUop!*+1Bk&o(k;^H`xM^27wvIDL{q5q7bo~m}n^= zNbyepcDHuH;N&>kV%T^^Gjp->h;l42A76O`a-)+?n~p5LAOE7Pr~J89{gxwh{#lyg zHp;aADc!!B1Kk=?kb@V;8p%BPX}y~vBC9Qq9KFPbxs0bt(j;u6D69RyK2H%C?qTaDhcww$()oSdI4pUXattuilaE{;py zWwLvzOJvm+5473k?@jqDLYSwM+GnG(27h8ERGt+N17qjzX-1QOCfDS?I8m6r;MRLH z5H>9IOpIh^2wn|+><{_xa zIuoBI)#S6g68mHns|U@+zSAUBuL}6b2BC=bfUB8id+p-!i5B_Oqzx)kVOB;c8tE@K zK^MOd<8FKXam1KO^U!<*vV9UhYqIW;5$=MnYiN?QzN4~Tyc2M`_%l17MJ_HA)=S8U zj!tdGT>kkTa-@4|(Rn574P3mA>_=|qO4R1vwi1T4!^lXPTQG3JMX=X6_AtUz*?_o{#EZ`n*UZ*B15pKhL~=38NK3pqS3xRo1HX$%v+Z_ zg5D4fQC6k5MkJYmPgcGkC3Q(kYf zFBW%Z2>Ck@V?6yOq`tz(po2I(G@l6=rs}BDqJ#E8)Me6Uw^*6c61A!&rXMWgoWmOo z`N_llIWe?O8C_6+6ZTRMPVOi$xDMd;JD?w_gdd&BZ3&1=`^Zj|^iO&|8p3P#B3i+) zSuKH!h)h=CgLN8E%LGJz1-!o#Y`h*)3#O1WE$$;`T<>%owU{yzfL1he_W!rt12xQi zBA`-e^+rCYLLN*GcE5qHWTdgp3f#4U^$YFUdC)4m(}(lctWrPozxBOIn?Bb@<6TKn zo@K7VSk!3OQTxfbr#eQZVXMP5d8)n|6&K{zjHF`QST}8GRM@j{2HOjz)n$cmvfN92 zK&&+px*w2ejlTN)e3VdPovJh?e855*siZRvurH#7pZ%KXW$z<)WZt?;%! zxYMf`4NuG>@9&@}DAGtrTK0K$V~j0sJ(E{VMTgkVRj9()kU3b4{TZWfA3lmP7t}h1 zFNTwTDrAVStLET@G$!N@*KU!8)E8%p(kh@#T4c%%@t|xZjiCPY8_ljmEA}Gb?0uM_ zOyJm~qdt>g4Z{&1sd%<3x2REE+|vKRsn>{AZC zM^flM!<87rVI1dXzBvglf{@SGM0MM*f`(aQ??$mKCTZ zqx^hcxsK@z6qND{qo|XptCJweZ9y?6;vOX8LQ+v)b>Z#i?x0FKOi=&3NCma{-tRL1 z>;&tB{d@WN3UYEf38^W?YD{w0-21r%zguwZ0cO_g4JjTDQw~yv>rPC+CX@%jebZZK zPd&=QsH>9Ud88uw+?{H5OBy?Nft9yA)9j{kVNyMLW; zgs#8rL99>}t_dkx5K`G3VBW5H5fV+Twxo~Fj#82kn+;T7WFQGJs{;hu!4G8KJrryVfZNvbC1h`qm|TVCKOpBgO^rYR}( z#OaGZ3*>GVWMt@u_7tz96J|u-U2r6bBJyu z(4h*DkVUTwFvT$XzJP!2^1Gjbmh`|sD2=L&Q1ci>-_oP$NAB)cTw=4CB10q-Ya7w- z%Y-9@7rWzLj0{(%5G6 zAhzq3b}0%?@-n;O4HHEkIGfMkaD@8m@l{O#g5msRcE6-KpEYqpq@8-a5dH2tQ%Jf! z=S)YL4HZ@o2-ix+_A!rPmz3P-RNobI=91;37EgQl6XL# zbDn&dW{|S7TZzCnp>eXcSsQACA^*&A$N}%3=kRH$%iMBzJtM#Ay`cT|UO8`dU4{qUp85)=c@8_Zbrc3Z+eB2kG z|6ygzmA%87)uyj2EE_f%7QevSMZdlh;^E!C zhG(!^GrX_6;)Dxmh(q7Me9SmnZ`F#PO)@0xj5HI{zlIX7VTYVgl?dh$yusoGO_O?( z(ndkj)Z(o|x`9k|68)q!2dJ3=*=Ar!*(xnIWFuH8y|<)eeXY(OzntV+0ym3;+&75S z1kZ>6?zEV_QFo&|UwR)qGWwr>9aGKg{9X<;m8{vhdO1^koil;r4&=bf7i@vKoVyum z5w16}mNAba=p~iz?%qJqi02BTy+58;4xF@nlvej+xY88a`aAj<0ifVitD&uS9R5LW zx6fW%K^j*+HAk0Miy|XE68X?Y68h1f-(b5DkVAYYl9R)MdWV&Ixs1q_yMrI8Qc@xQ z17JR%_!=$>l&f6K=YgV1rE`C)=~`+LB7j_7x(_TjiW=OgI-2U{?auH(0F^2Aj~r6> z8ZGI>O8n@~$$aPTR_Vq0+P(`+-7IKMtrj9T1^-sak-a7tRggiyx7TpKRHl%!k6Gzy z728D##FV>fHfeu(df_a@TQ?@)L|bDv>Rj@1TwF=bOoG9PLBVJL1I8TpCTG*fKNdX| z$1D<-^eKE3H1NW6AL(&PAcx7f%VolS_sE9tdoqpFLM|NJ&tBvU{jqGS087-@48z{8 zKqB!?TBV=;m~-wzsh`*#4uT)-_>RiLtW%Evu@U1Z+8i1jpIqhn;|shU6xvZKZ0(GuJeWd!hR?-uZ`p1ZYa-@% z^dgLs($=~Jk3-(wrzvxnwKi8NW4w!y`^Ml8(B=n{wyWRCUh~Ll)*>E|!L$gar_Ww? zK(2;E0;0Yrp%zzMd?;q$XFELhFh6)BBt8Jl9F_jWt;ucJAN!O>kjmoiX*V(c3M}F; z5`(BWV_$W**KAexqX2|k6kdTq9;%>+v5#YRU7*rK>7`J@$o`uY>7*dzWWWSo-O_6= zXxtBT>y#fJz(v-gZLGBxd!EX$`rpw2$xsCb7kg~#w>BUx^)HLqJnJjd^v^t}kgxE2#h3>m* zKK?ftmSI03NU|^H0*I812-9l^o}6xLEJe1;lZDvYB;`8Ju-$g+=rSg8ONAW9^SA9c z2CwjAUZ5ZQGg=8~+U+D@%wFZ2rtZQGGdS-!JanI_tCn`V9_UAVTR!m=CxjL1FKzTd zO`bjE9Vo*}#MHbNfYTBj43%go25k}+prwMKmuqt+>|CIHXY_t@D>82pu|B)(+%S9(FS)fWNMp|OXygxei=^^{==)Ee8P>CcYs7WGMy8D}q0wlHly> z-u>KVH0A-rY3i#~!LWAlu}R73A`y4UJ*yMVdZ>pM27Tt^?Y!9#1XY0r#V@M4X=Yh| zSa{trl|O%N?omziy_Vh5gXWC}6ztG3Fw9cEiYioy_m&x#AFxHRL4CC%8(1vRtz`y0 zyNMS`Bsod)Yc%gp8g;O{CCos|oX=-2aJS?-sX*8p;&NH@A`3fA)m6E#VYIk8P<4-g z*BXun@dZ^Nt}ps2xVW`{4kI93gxbZ#yyHWJ9&i3k;;!OR72rH|X+#3ZM0v-xci~Im z4LH~n{2nhH6%wR%x zaN$c-J%%t#4&M3m*47e%ykw>uJ?d`<%@go{Dvv>_M4lb(y>LIb?u#f)$D|lxD%t$EA6#RuIecA^SpFl{NuTi+sI)_a4=N1K9ic zo9uLw4M$q+jv#UgviSkE0`Ar%IrDk2u#?*gJyWj_ad!rJ4tCr9HapI?{;2p3`%>_j z&()K<5cp2-CqGXA__8G9RKe>(1oQENMtzYVQfTba*TbS6hN+{7`@Pn(<(gG{U&il# ze^Kr2+ODTm`x;o`?OO0>z-GCGnLd3C@$!pGCYmov_F>|{DJ2f2oUB@*vGd$?B-Uy8 zA}ApIfrEO{yQ}#v5_7X^DRl69;Hg}tTofbCnsAZ1Z+R!N zuu`=QmLy=?at?Hk?4T!vk@z-AY}~U+IDcD~(^4VdQSZ^GCdm_wZ#cqN%j2s&9rX12 zCNi}%h|SCKfiLJ|M{I=8hL)Qp81hO$RxLZkOu8C5PFP#)kk3t9KGxTFlB#=e#^Q9o z8LNKHq-x+OuRu?Gzc6_{qYZl(rNCTmI(2%^db|8}>0TH0Zt|W>*k2Dk$|Bj7v6jRj za`P}(`aUU8g)+I>@^Blf5(=N+i}q9w`G9v7Cycdy>q)K&#>vAEgWA=NYRLBstyP@t zxecYHX^u2M3cTa^R>W2knJn<*i;ktBLGIn@{!2$OmASH=H{mT>2^NDEBmP)}LGDq2 zxuATM6RU&+goQgkf3TEjwlKFq+MMyJymk>+z}Okz%pn(tBMoh_e9NbpFg&4>25fOR zqrIS+;{>Mc3!nQfc)DZIDrpR=z}SZR2O_0=7_oOk73{}$tP{Lb zcglM09E^}+g}ys1`~t_^hXY7M_JKFUG{}Iu$|X+iXV%a~s8CkJ{?0PriD%gK?x7jR zFLV-qpfiWx$HUUF0?q%DNRuV1uQvVwggyFhLlG|xJ=Xc%&l{AXS_6Fg;QNm@_5-6f z#}~c*R%m_y-3mdf;O`g0o~d8}Xjz ztt;G4q1>v?iK#exJyWEe6XWGYm&Jcy_eh_b-e26}iP%#j>`%rcP$5z{hh%-zyB5^G z_ZPnN!+T$M!C~>J4BLTLE9*M!rgIjFu|@PQdi!4a`Q#c%&N@{CMc%Zxsh!1Em0t?7dymn;a|Uad zn=?;I8mR5cNF{OodBBf1YxBxW);qs#Yoc|2>^d)XQg2cyDCk~>i?o>E6?qkS{H+5i zM$uC(W_5iw5A%pR&7Pbjc1^g3`dT5ub5ul|T||i5M$%n{fvRt}_)EtTP_~wIb8qqr zA9Xx0!7U`g-OJ#y!i*Jb`jJV9+iiXqP)YzPy2VS%jI@D5CXlQ&;Wj;SX#_=rQL(Z- z=4}uJHpJ57hW}*$n~aONH_<6s4l)7)J6Liz&au-TziBc)QG;O)XPhg=`0BVPf0I*G z@R%}yt}oYDt^C&rc}g+j(yO1R9&j!G&4YR-a3VVUEO&M+ulVN?W^O`6iO1~8;U;oSkc-{(|(i5RIg+o&c1KLLad+V&*%;(o8x8H?=l zf8yhS_*Jb|o^odR&E+5?YozT)xBU@|N1;hnAhPNCQiD12qrcwUmIT>Jqs1`B?f^g% z>1!V={#-65;mH+)Z7LP$e^{h0_X$Ch+%(DMjYbcIZz zFnutFi3|1LlsLP~#?Et6{`&QJvgo21hC}uF4f(p0K;Vn(i?j9P5$`6~nKlUpc&@MD z%YhBMpjfq8GtXvvwm-u8!8v5`@~P`F3-G(vfaELwJ{2!GdXyo1)1z(^n^GHRFSci$ zPMq7=)w%Z&tH^Ur2x!oR&OVsE!U)_wdte#mL<|xFvq&S)8!Wn(S*zkGg)_uZ2 zh+Q0xgeDYV-_u_Y>Q%_~_S(6$%44Oi$$Au|7Uc{jTE#=!I&dWmX`fMdDVgD=nuXm7 z)h_ z5RG>v49~M#WU%7;-dK+8V9u4wLqA05y-5;WPj(gP1)oR_2+tIha?7EjYT6KhW5RUC zsXPsDE7>n(*`@j}fp@{_q}hgEJU%#%Vc?fn=HA{>+_h`PqMCXUs*oR#NC z;Ja;)Y6OWkL6GrN=c=i ziEI;!e0Gi$MLr1TJAm|^yDV`xnuOa~@E21|Vc_yJ+a_R9fo~Z{xus!4u%Cw|+uUQf+7u+D7J#v;1)Y=6reg+@Fbo z>qU71A6EmY!)$rJ#IwWpB(n#fpvd}Xa>LPrFC6v=X_VcmY@^L7VG{SLc^xsFesMVT zkz=~<{A|hN!(U=&>FX>8so7Z$3;$Ql{-4Y`6brhM=15%bxse)StrY=H#x3gQQ!|@~ z(-f_jfXxo7$ss4LG8LbJLuY&nfA!-x&%qdBD`PZ8Hf7IkqUd*8ae$V77Uz!f7v#OJm$cEo#0B=L@W6>t((I6RGnUB7|!s8e946ey- zi*Oy2?ppTBRZdUR91Vv>C79xq96X{rlSAIHyd%n7{d^R{(3+CWflWaDhlkK-*WNUk z6V%SZ!?oaS(umLKLdb@Jb%)nE;{^PpE4x6Rh`WAU?qSkyR9#4N{!{ma5T}em<%H-T&pN)H0Kb}zw2Yqp!g&L5e%*b`)r(jH} zL_d1yGaX&K?%eaX0OlW{BZ^j$Xi1VF^10pSA4s0VsUBxp`c528xQ_Y!_PAkBtBY!C zS6rLO=z8Jb;}SzYuCm-&D%4NkN<$S|^19%m5vDaIF~TKsCI~nYoXf1wVm9yBHljR$ zg`0~x|Fs}SI$6qb&VD%gmw%FK6U8LJ$nKM{a946{Q(78#6+QPgo>}}|8~fS$V>o7C zGyPMy32AEFb=ZaG;Qcm-otnq6D<>`iGwt{azum!U)+B9_Cvkc+6Yz+8>uqOO8@?F# zEL=L8`tSI}{|1zQK=7N{YW@0+hv<9Wya;3U)l@Bt_WLY0*%+Avh02#ba!IlRG83{r zvOiP?WLV^1#*=9hp?{ivz~MZ#^NTTI=4R)R{WZ#frVM`pF!O~`hN&zl%19oGsr0qu zr-g*XZbeKi(&PusfU#Ot$oqU{mE7tVo*EzCeI^hPYb(7`_G1PD^H8T#)2Ao_gkU#*r3{poPdMO>Q%- z3?Z^GX&-JLb77iiEZyE@ls2#n7sAKAOwDh3IF@Pd5WEvjgLL$>4%!ITBkaZ$!qak- zcf&{N*(CG@&E;0liZlaoX!aRXNP+OFL$A}1GZvlH`Xv&q#m)01j5s=nJj{d>d=rk* z?nC|%Byi+&oX-%PxXm{0mDs%mi3L8Be<>f$b#iDg1RxVy-Gv|KB)C2-3!?Z=77L#- z0E1VD^^L!R(o1&Cu^;rm@ulO5Eet+T&+NZAgf7qkka>|r^YyW zdlvK{bR%>Ow*Xa%Pm*+Q=h=i}?hq23_$u!(Ij|wB@qZEaj!}|zS+{Ui+O}<0+Er=W zMx`^-wzJZewrxk+s4 zjB8F1tK;#jw`nOxYz;0|SKbvH+0V0_o~zf?DsT|#eN!!^6Uspo%@$My2Sa-P(alF< zs$Hiaz9W!mcoU9JELpO6Nsc*nI&HyA?E8C91&O?!aI}K-kG{SOID-r~lQkpNq=7MQ z`z~k8#@e)=i``d}Sh8!_w5baXTr~u`a?dTy7dtI1XSMtkd>dTOPRTIbCQrXbv*h?$ zEk2>3_MGUMq*10G2O&E_JAS@t3)EF2QCeQ~(f0~9 zq!}LiGgR+zU|9P&iLD5OF1Q5=|2F13T09lgNTK1pfH&lTZy%j8K<{_GH2& z)eZv&qF92Hf`?@}72YD;4eUh?(MZ3}NYu$af2K_zKa z!9!4%(G%EvznX#<9oQ9E({_K@HMf9SCDvlD!A~g5B&SLycDBt{CU8^{;$B@b8~V2E zH0*&%_~mlF+j4HT@itx#9(v2Iq7Lt-;g3VFL(f^;Cns}SDP$M@zvDDf5lyx?ESn-g zD@)}J)hta#Qj+W6$$A&Qysv@K;dl`)TYE_}jGF$LtE>%ntls}+M*iP;-=*qT9t=bw z=vFmaBKbGmW>*~?%jMy$af5wZpr|os!}BH*dAKX)gtL85!uv1GSJ>}V;d?gV{*b2N zKPUf7xnC%;JoggRVkrfrsc)VX5WzX5xnNL-7#QgCmw z{|(~*=MYyrVVc%Eb>cGr^3(r^hju|tG)g47ytWzXW=_qQ#3k~nFnE(_EGA; zZ{lC5!THz~)-~KS3Qm_736Z${+r{_lCV9V=+lxi&$|DM_Zd2|2chaWOQ&L4E+ zWawqZ<@IJM-JqK;TQlOb?=L?F1Q@ipT#N!TR%<2xfBr6Af#}CoQy>|CQrj#f&dMAn zYKVh^_BeUygx%1GM6L2BK>!fu&%j_A0Tmc7CS+q-(U$ui-Kw>2;0gR)vlBD}GqUe< zlW-ZigS#teCcni|z~kx@@`WDKl^YBRL-DU?G$H>qvF&U-g+im5O=g5dpL1MrSD#;U z+b>rV9I&7lxF4$=Yw=NkGsfJmHC12!?tJzp6!GiU=ceOGmsT$gWgkz$Hjswnymyzq zd9L(MJG`96iEYV6H|=&WgqRwGUlGtkj#hy&gCk>*x&+OeXPK}+nqi6cDtjz6u!3Ht zNILb93!=-Whvw8x6i_dY4A0@sq~yyW{8l1iFF9-Q&kqp0&R)BPzo!MiGE8lKS2v_+ zloF%2r)=^dWoW`PgjEri7MJOR#1IA9s-VpiT{TsU6`A<(@g&ZVRQl*E*>bqFq66Yb z4{X6QAESn_EbQ2k#u7FNM7cw?zkM*%i$E1{O5E1eowu*zwghh%W(N%CxYyw z7Egaz$bVj}GK`uK=HAr{Z>w~BuM6H3SRdGcJk@Bo`D%jKT8}zddD=JjN1oi`*oyqy zK0A`z64J+PgBJ#6_XI5z`HhN53J9BgjXdA(^>7@V9sRd=f#=wSpS8qJpL>wymhvgN z3^Q;`o!+Y6n?q4oJRQVF+K-Z(tmiL(q}S}+gpia9zvhmx3wu_6?+45!ke#oLio2^t zk>^K-NpuDGDkL|uq4=Cd_KdAqDg#O@~juQeQ`zaUKsHW==(Q zergkcS!xPs4uGWGsnz=v$CTK$b7|4kXEH%#OO*?gf}~T(oLdT1IA6)72?T)@Rh8VU zHd%^+28Xh=2_D=@g5OH6=EXaxqJ{kGKNzZ{#&K|QxI!zC=* zo(}HuIN^0A&?xgwyIOzFz=3o=w)-Jn0`aSS1>KGYgF)MYf39&R^u-%>Y(as!tNhLY z>+Jxb-AZ1${PLbJ1^K^(*p3y6j7peYxWg-+|@Y_PkkS@d#; z$GG@xM~<8nzw9!BeQ=O~SwYJedQ6_$-8(1Mj+J#Yn(#nbuQD5n8sc{L1gXn|$&Fsd ze$}E(`RCVuIVG}#0<(Esr8*!@RSt}^SUbY5;GKADhn;lPKQ2IKsXDI|DD<=8Ui@;L zo)|TjY#bW4#quFNtb3%+Mt?;@#5#kwfGg*08shIgXmJ;)$SQMXl7L10&s8n>#`7rl zt6^cc^Jkw&%Lf-uf|iwJtI?Fi!_dA*V9Qk}S#_xpZnbtHSpV*$fM9wbR&(gdz&PtW zHGwkpSs8zTq2Hde)n+=I%EB8YKxI|)VPtTt?pUiyhc5w4Nr_7+or>-V^&*L|rW+k8 zsfu&^22D8&iX4n}Ok#z`fMZ!ByvOBGVK3g_#> zztVs_Ed1F_J!t~ri~a=(C+w#15z1(-HZJ|eN*oR{SfZny1+q1$_4E2K$G~oK6@`yW z(ZloOzM6-MuxaMMn}5sO(a~jLrW1?4w7a{}fZuH@Xwvl2ZQen@In;$F~cjDgF(9hosbov;F2De~C@l zSJ_zA{WePAO0WXf=yLX7 zg%#2A2cz~`{T$$CI&-byL9aTq;AcS)#(WCwi}>W%&7{#)u)K5d3bB75Ry7K~OP8lQ zP?8W72^!hm3evF?L=JR9=Amati1GSaTi^+?<(l#ldS1H{JU%s<_`4TWaex(YkP0&U zykK%V+J$fVIw|{y+xIq8i((dcSc%A*o#b z5LUB_F_%9%d~FWa2|4gfIIe@M+*+6g7ajrbh!HUt9Fw*!DU|}6mHEH=L^+N{oi)xz zUOXLfTn<)>4{~rjRkY9&tyBbKy0c%3^xEs%CjIVPvg6K|{=2m#F7(wMi~~QihY^?b z@&+g_OwFQcae1Eu*>>sl@dfPJSfI(c$v>P!&R}3bVff8`AZJFUciA5NB-<`!oGPW$ zK2Z)%)YbEP*n98(4Ih%xN?6*{vGfa9S0mB$ybo>=sHCZz)--1Ud+Pi@*rWyn|lY^}6sNEaP?@!TKb*r?_F~RwleN#!K zm&XMVxPk{G?^M;bYm{1*DP@tFo=+=T1d~$uxQCo|lQp(m0Uh8n?$sCV- z;H@tRXIs$A>Y=|41pU0zmM}3~l@jz^3nxWpi<^9<-14Dw6m*D-GoLPp3zVilYOx~F zCOkrUutuH;`Azmt-<9&1bpz^j$J2x?YyIPA+ZVaKSw1?lEL?t{RYDmW_Y&AS1BF_l zzZyJ!h1y@@PwoOy_A}CZT}4VVCJC zGzy;;wz>aW*C=Mq`!VSnPjjff7<{(Uh&#rp)8d%uNLrQySU%*EO09S-OT`~|8FC%$ zQVkN?1T$*n?hIKZNw5d2HeN6a7}*9|C^@DK1cNSS;#sT75ie}p*@nW^HEIEk{Xkmf z`Zw=3thvB|ptvuatwo?QdcFXRVtSFk&2uy4yEYck^$_8@9L791j}1N&wqjtdjRx&x zM~yp092W~A7i;5bIVQH!_DIpHRc^SKBr?zW4>dkiZY{a5D?zo`Ck9C|pIHg~_~AEv zt1vf)8|P>~v%wDCcNzw5ffC(h7ox1v9v;ZF3Y*MC{{7IHm~_HWo9eHC6~q0 zCM<A2|`n}Hd4AKTydUoit0#y7T5aE%?BR`!f8bsmhicYmH|vcDJ$ z4WMt9hgXeu_!U#}V5YmDe%F6dK9k2=^x(~?`uej?#y_Sw08r~^_g)|C=tge zo&Ej~Wc<&CTI-Z~s6PpWN@|_qxTSCNcGfnuP<((n57(SCObJ_#yTp9Pbm3!TOffXw zakk-PJ_*J?ZzsNU??Sc0jB4WsR}7n5IuI&6l-$#h34Um*ZEl_WyN{)<@aeMuXFvO2 zY5qUz5@(J0YSyj#Lk1kUfxrtZI+Jqf-Whs_UOv=Ex*s*o8$j<03c{6&?^X0gq}6YF zWz0}RdP7jnzfsv})rui9l>q6l7bDKyXC-BjOg=s#R@csTjEpH{>l}*4&XzS? zZC)k%15}(PPVzso@N0t({MBp?JjZ^CzsfgYp%GT=`O{2FkdTT_dBSA&{**evtcHnq z4f=#E!H3Ih%W$(-x_rqcnf}1>b!d=c_`7I>1b!X?;$*SV=KwFLz_0E`2Y_#Q)K|c& z+yH`C9GS0mu%uPrU)s>j3Z{=4@Y7J7&d~EKcL5Efz=17O{nv?X%c(0o@;0^Vl{~dy zTIDL#-bT}PF@n~&7?)1!BclT*md!zRLIIDZp8~h~XE#s!R~Bt8`?T2TR2FpJ(I0s4GqOlrERJn{{~M zCcH-CTNe?m>c{Ce@M)0p41vYciauPcFg<)1s|d6tn+itAZ76|_Gs~*F!g;O zj~kK=SAJc)+?VUMd8ck#Z_56r&i{6~euZl|%qG|t=0{6y1XIp~7Rj%BUwg-GdF1&dt#w|N*Y$-fVSJY`)>{d^`i;lj%K_C$k7duc~dQ^E-evO3%v{m zV>!*g8bO()_AC7F*`9mP2-sBlwc81!be4m9F&mfrj&!_i5mFN`0$<-n5_~v=NY|F? zQfihzsgv$!Zg-_}hGza{eD>Dx@FTjl>ZrUgXNfu`^&NnNa^tzflvqXeP0pWBtG-!RbUY*%#$9ZX%Km+-3 z?z&?sVEsHf4Vvhk;`Nq#C7)FCpIgUru zCG*%yx!i`5b0G&YY{SSFZs=}j8i8hPb{cIL?btk|b5W)@JDJY>+ zPQhw&Z8NoE+uu8W7i~X+J1-_9hy2JKK+HBdGYv^mNF1_QRY-_oZ%vRhC84Em4rCZa z!q^pRbOE{dR#&WRX#IE zeL#&597|a|i|bcwVO?e$ zQ7dg$_D@tBQ01j(4h_WLWGX$qmcPYT5QGbL-RsOBGRy@xqrgmMz z9teN+4zBXLY~pNCf6%RB8(KHlqw7^mFX9LI5TV_vJ&KC2FLMHyYvOq#qb^|8K>hDp z@V`oqo9l|-Wr_k-!vYq2%^)~x`YG7)Bh+kyY`8kqo1Fkl$}`tGTL<`N4x{ZY#7Sxd ztkfULYfMmS(H{Yefyo}FmKx{vPOyC7pEV1OJy~iFFw?B=HqIH#7UNqo|RTr}1vPhN|u5@u2m#8w(=>M+p z`H&5ApPqGx4w=$IJUy`JENq8rd23QNLdkG3SfEveW>^zQcYX|b6y4*d=}Nitmi0Jm zQd(IoGJf$96mB!NTA^)}-FYnVqQcY`+G_U5o6uO7jE-ADx2p51;A3wx%pIBkYFp=W z4YhT?Kd76A2ME7G6xGfNbIz$JmBC9OU-2VN+CE+P9LBK6yr%~h{yRtYu16(LvB(d} zWzQ_zUo7*rChBo%eFpcF1e!RbLN|-#=IIZ2zkRsqVdr6e@kNW_ri#5J%w`rH)oa^Y=)sI9!Z0=6o2ahH`Inh6lo z*BU~8e4EHAb_|hQYd!%2y)vt}-Oe`3Z^4uHC{fj)bfAUQLbCA6~7K@N#+*aCbgY>b}~ush)C1Cabrw zD`~gRd@MzO>bha9jJ`By#-QarCug7T%@5seBeRxin%59E!gHCc)M3l4Vc6ILl6}DJ7s&DdwW5p7w7Ews8L4Y z{DZK3sdRESB=ghShqbMW%a9S@!RoYGsJXE*is%dNw765uPX7a}djlWM(j z#V~v#7hW300w5)`_4TcHuNi%}_eyhg!^d6E1CG?~c3bdS(-nI%v}yC6_sGC^O(j zP&7#8$je)U;^}n|L^YRv^itLVw+jdwCQDVBUpvkPJl_Th9L-A&M@{S`FYkr4-xX~; zZM#6UStumVV!JsVZa4)e2)o(66W{#jka?Oxbv+8Z8Xhu1uL8j^ zNRX53&&(3$i00myZ$u~82!-mFQ$Djl*uHZ*j876y0vGjn)3Ae5bVhm3C!g0UKMuh8sIUDO?hx=svA!l_QCr z8aR>?XSdxW6Ombiji06_sPBuoicU0kwiBwoeom#t`UP>GDokpDl<8`L9%hlCw;uW?NFdp5(_Ge4!n4>DC@#H?ggEu5a34?UF0EM8~_REW^Tz|A! zR=-q%k^oHeakgwI{bH>TMWKzWShJxL^YCDK*KC&TmuAa6=a`B`cku*(-ArAj)Q|Ne z7CUtS!$uL~G1fweQ)YeV#^Z}zxr&XBqhv#6{m776RI6$y0g`B^%ty|Unb?btGDK@LAMc7oUHEZ){aQ`Av=#7-ShBt-XW%2# zyE^i{gR(Vu2?88&W-7H*s{Kb`T-K5JVUA%pzJ0u+UuWR8c?1=IWE?-Hq50hTO=AW3 zuPc6=47AlIV>sHa&h$bRpK9I0aTGG&9IZqVYE4aAU2o!pzRDzNbyYRhq_#kxk(eNQ z&wl|j1o3RI_?TqNX;k%*n5l24ni37O9{VNDg;3vJN6?kL#`PScyyVuUMkq*#Qnyn! z82j<|qo>ssI&}5pQbvX@X`lPKHO6AASl~N3XJv(GDL92$)eeHAsjgTB)ea^5!H)p5 z*nMrSw0U{?w3#=zXv~xv!QOdXKsVkR5KmmP23Vq%h2FpD-2!yFi+^Mo83&AK-uHo{ zNd^K{_gZxYY<#y_Td_R8o|sAxsMWm>07*@4*%%Q0rBp=9tOJ;KQxd5R&|`O2)c{vr zxLQ-j&mz)pWFRlzPhb}^ukdM6x}p(!E}kDEbeSh_EY`bc0Z)(=xj{O^F6c8Y%3ZeT zgY~B)mep?g?pNLuX0uk@7=r=NMq4#@W>#yLxGzi}FBi;~TQsM9b_feb_N00S=yi?u zLbskrfZNhjBfGu|A=s<6K0+p&G5+*6SJ+G#T{W{wWI5gsUUyZ*`afwgjQ7^E7<<|o zA=u$PUpB-pg)zsY{@A(0e+o)OEyNm+^vG;D(jhoriXh%Nt}>xWg$)i+&s6Jql`MAf zY4UFem%=QczuVEMcItr2oa)9%B#;XeHI1N}U5{gwXY%0tM4Jaib=)tz;5!t(MQKs_ zQ@+fJ-FAk$xu&tS01kft@$v4{ZuyN%jcG68(2>S@dB7^2c}+Wi$`i_x)U%1K3?&kl zC>n`@Ke=~x?%E{yMV1lI&s6svfmROL57fck%}CaskDlr2mE;yteD$~O4$*tc8|waB zI|{A~f$Ei0kIG{_5n7czA>xA%deuW&(3kKL7L2;q7lW>z!em!x=FDrpU;%zFsUSX$ zAkc%JttDrW#Jjcdq>OTbW)1U-z^txXY`v|tC8?T&M~(E(uaA(JqEm`0ll3~3x2H?c zbJs_daqi#A-oy^@z^U*%0~HmJ4a7&43u zq-Wd`4Y$=|XP5>Ws+I*Lzh8wsI(KX0@qTI!WS|t!=kn;fzI?Kz1a&4k9`x^%nIFCV zS}^2vMCx6>##gLh$aUN!KyZv^$++l_+z)g7g~vM=1D8ys3)S;^Lq|pq?R3gG%ZrXi z6pg@&k@$6F1&F%Q=@2QZ=x0+*sL->sd?+7)`nK1koxF3ez2guCE!O1NChKhL1sEzNUde-%rcBowTkj! z+~BuVi;E|97*C}@(3mDcbWs!Vm}KW~3^OwjE3T)RBVuSURu^V9oD((zU0(2QgmGQ2 z*F*+;a?5dk0(so;$1qbWqk`}PVwqO04nTvaZ*Oy{qY9KHq(R+HTjZR*gUzXVd|zZc z2Dac?F`|W|^f(&|Hkuq>ZVSIQ9B_LImFBr0twQm%!6~gPMh%4sbQP{(h>>}P_V$Ml z))>rw)VL5_Dxm4%eH6IFej$d&C;ooeo-|oDt#z2~pX*PB@tUXpU8Ed}hN_)|disa^ z1wM+qFPb3t(cZ_pE<_Sz5_y{@o{`| zJXB=+8xRERML#X`RDS@@`3K9_Gq2#S5#tb~-->YScNSf1bWoHFZ@wJdz=2{Fms(Pz z#dAC>uWCc)cNsF9_e`Ow4EGY6<{ZNUlHu(qzSi!>To5^E48@z-ZvK|V-Ow|&)j1K2om$92^&S6h2 zAR62?_D(+UXy?{PMT^)+bbtD$Np$|KgbHTky`<0r1w6cZ8uRB!_siFy8S)I3*Y7%xR| zgQhQn@@;oN=`wkcWu%G+@D%;;4URXvAMZw`Bi`$|WZyPHb#mXO#Ekm-Uy5(W^^%!$ zAWK^{iP%!Cs_T7iI&0NAUkKQ%*8K>%+jCt`1DwjbZBDdUull=^>c{4_!bzDeA72)| z1<=Vo`Fqj{H$+#i?}v?lqj+H!MThv~L9r+$g;~L@61>b_xT9dY(Q5lWPATKfVMSG1u=c}W^Q%gm zKU=_N?E^+&;?w|UbaZk^8%KjJn?SPB>%6`rZ>BjYVaUZ-zd-#6$X6m!5 zZ?+KoaGt(d3{?Xq^4afY4opQ!EgZ}Kw>BqNoj)QstusWW6^~%+>xS+uHI1#f496Tj zeKOm^PGoyJR|<2zk?$Hca1750dVz5!W>x8(waH~7++Zvf z)p5R@%GpxjdTxX}=;Mv={hBhUaTe;e;Z>+!3e)O|3bx4JY_@}cl_gBPyHmhBfHYrC z&CQa)dlbovD}b*Q{ssEuL|BL79c!PVJ>E{agHc;I%=n;0FA@J&PDR5+q*GjpI!6(q zZY?pg+YyhMPCxFM-W!S(!n%;NcNJIT4YDfzqTrrp&RMk|Rf?{!$40lAT$1=}CAfM{ z3ndOUcfxihQZs|lR0ywT93tI77!S9`%(&52EUe>LL(i{nbTi5Zt%KNEE)YajhJIZX z=Z5y*)N1-fAY2Y97>C8gi`Nveri}GhUf2z+8KrI^)FsPQudH4_3-w0^lezNV^B<<- z=K2F!ID4;1Z>Lc|)6HLMYG-}rTXc)|5G*KGHy=S^NESSZt!PC}-FM%>v{byJ_EK~8 zHYjZORFqAEyZ4+jhLIKl1pA~hmD6^InH*63~3$@Pdsjal}`k`Lvj5}hmWUXQfm*3NN&)ZchFu%YMNZG)=0bSSPeBBxoyL{3Jc z53|bY$K5eM*3FFd>I||?K;vt`%&cj-*1cfkt=cFXY<=+zNTl0Ol6TgAkg3(Uj?>$3 z{O*kiX!uetjg5>Da}-y+-ju2~^L7FcdI4;vC5ElCmuDK%58@ej>ZglsYHm*L)4s@N zF%|kQXj(wqNk5pw^)lyuGCk~qmRz?Ri{aFdl$l>ci~?Nh=AR*OBB1R* zFf5hvfl!pP6}`$EqL<dw;(zb1b2|vJ7a4! z2N{1RL2n_>{_}uVO;T1vn}w0O%V)?kJMvhx9e?S>1o;wPHKZVMcdc&uT8kV0_l3gE zH_;Iei+oomNCuo}4$Sl}Qv5+TA>f{88fjabaxa;Jf+)`E9Q+#XNs@MrCfi(d?XmCr z+MS!aT18lxr@A_oU{>@6$(!gf#=jGbe=nZE@5CgZlsd?I%Z2e`kxv8!v`gd7O- zQWH}k^-UF5*A#VDfe@qny(te0335qZWQtX0C^kGl!T~{8Xv4l9JD{jyf~7iqTqQg-73U1xCI8fLGOL9dU)dEz%gbVdAo6TSps(bbho4v3Lwud8z5cyU! zEg;1qK~hI0#`>KzY@1xJr19?YW>;dkgdi z+)}8M&_@q&!@Wmor)RwB@(KMbDkS+hgF2M+qm#EWRR7$Z<3*!bV>jPcn>RHBz2>ht zLeBsQ&4<2-AN)&F#0gi%SAq!xgAs&t~YP z_<~7^#cjVw;Cp^2rsRmkYm2z=ga{yR?Uy;&y)Gb|F@3PqA9H|^iouCQi)Jo^RN4Es zP*f_{d2u^glvD6QiwWPN_K_D(5=T$BryZ%cRI=2VBx*Hlu%JoVB#AN~g{M48SLk)Z z&0)}HP1GC)NL{|2V_`(zbPreI9i8xNT~tT3VXm!Uq)nTMJ;BqNS@p1vuHaC71i;rXqwiHE!0U3A0Voi;RvccBiO; zW}39VQ7Eix&i8VYczgDWmu_G`;D7AK;}88N(b%=eT=HhI?$=(#44bBKPVw5L_Jd-?G#EwU$ z?EehbM^4u3vTWVy9!1`snh3V+DsD z6%&TJ4_>ZuA{Nw~GqH&PAW*cf}ZEgO`6hz>+XVC!ZbTNj;u856kT8@+&a~>G5XWzbg6euvu-g3auSSX z>o?vZt`fBypk96ZNjz${APTGaX203Kr{44c%W9T1MkE$VjHT!SQJAUcNB+_&3`*Ft zBns%sjog(ud#4F@8l8tvg%j_cBBw=T+%4@8lGnSqW)&Jr^6A^Ed#nCAKk?`_#Ez$a z%k}0JwC(h=)m~L(q%Gy*J|#d&jZRFNxS7O7TW$Pdz6uvA)2WfBDyndNAV=ApJ!i^e zcb?FY{B~2N-gE_~>LumF!XNlRYqK>{MVTYjY&EXXk`wxXxH*yK)0>JPVz+f~)OX@z zie(e))$(XT7ZPAp3CSISPQ4QJUmG&PE~c;ZS)3;Ho%BZsgYGav0r|;|pQ`lVIH}vW z6f@UVwP>feA2sxZ9(I>e&DY5xEh#mpQ9)ce$X%N1?$I*CK4tZ$1Vz@91JFXl%S?^t zw<8xluDJ;YszEnrWS~RslyhWz&7~mXiY#R-Em(fIv9xPnyBD~4-gyMLNnr#ap3S}_ovu2^p`gj)!aCKSwB`lRT*i~9~|;v_1BNu^LRzVA%MoU zgsp%cicrof8(UQ+=$(`?XV2etz#B0^t==6hD`t0P6XdY&Ge7~XD43XVZ=@$Y0HDIw*R*$RTi(tOZ%YBmbc#xeD(_htrS?bsUiyE$}9r z^LE<0c=f=}i_J@>q(08s&-)x#V_08L`6;~b#B>I9@-tPK>jSi;C>aVOKUQ$ z2DLdREW>Sk%-oY)(yXf9|JnIsLqtDW%NXZ9E9)%yJp)!7i zooDd(#6ZC|&3S-Vc~8TAwvXQuwD~%zZPiqB3Xp!Hj5jyGnlOV-DntBM_pMZ{uH)9i z%_x{}xOTZI0Cv_GGfq{oZzO_LE)iUa9PE#;K)P#GfRV}rUSh|>HOw=I8)Z@J7(Y{ZkZ6q znrN&Lc>M{-*PUZk!J%B)>IO0`l>41D4$J`#V5yQ|%oLWh<2Xbm;Gm1A7WB zfvEgA^Kg(80$m)m6IuX3OPm*WLHG5YfAZ8xu+x$V;9|?^irL zXn!Oz4)6~cg%x&H0?}#Wi-N?U3cim%OiC`v;a)RyWv5-x+OD^u3@%g*2Gs1>x{Pu2 zX5*B?-HPzV$wpF2CQ#(eGh!z(=z!{uQwR&zTo-=_jyV6BYHHZQ_I$-n zw?-hv!f}_4^_gTLaZ#^<%$3@8wuiIYGb0p{?vZnPj-3ccvNvPZQSJR^#%429Hq%qUt#m4Ft@3{6OQ{zm?zQ6jK$TAtNV0ElIT+hMd;!~Scn(3+n#*I3=J#+n!Wa0 zTcxSXP(s|uXlEAc7#nER(dfeRt-qo3eRi1JxIYhMj6UtY6^JrAT!^e=Vum>BNS5@c z-&}se#8cq`}<}km`u^uRXnL~0ricB zONCp|cv{`adQc<7-{79Q=O9J>BS>DG9IwvSoctAWDxBbv^XVVxgf;q>s^~i$XT9|U z+*7g_x_r2k>16>>RR?#P8<~VPM z+W;oOWpa*vip-76)IxR2g&eJ<_v8Ye`!634nWxdq)i>}(6X|x zIPeW7mBW9EHJL0!398WgYmE&SIZdJYk2rA(>_b$F^xss3^2i?4=)O+8>@E91wJg?A z=Dpi#*o5|Pksc(_-R}+Oa7N$e6K22f3f7(EHFe^_I>&L_Oo5RGt1_oy6bxWCWRys_;uK1{qw<6lKX6!iXkJ2CT`#Z8=LiH zX0=LJcB6`2u3dxwF9I%+9GJGY@AU9yWbd-a z*5KYCljWEMUMt?Ou0grqzvBg~h|{+0`cSP_Jw!rXw8nMx)W=2UAP{RjU1LC~%LHjG zO~jq(L+b;H@bvhh-}qPkz+e*OKg(3C%BD0dV1$S{;i0cq2k?ZyY@F91#5VqjmrOOe z*^+m>oP06-#=dXcT?_8{l28zS$Lj3U3Bwa0E@rhK{&i1=aWLOZoH;Eh6xzJU}y9|zQ7>CBbe6!eNXe?&~e7Fso)>CR~8qFd0HCheFn=g zuJSZRrMt$X{UPnnpuLeOVs!FJ8(RX*wkOC@F(($LB7_hX z4Jcy<2~-a!CT&rZAkm~sI^DoHG?|{t9dWpyXX|FyJ(mjfKcR*7I&ls1NHVeWErPO7aa-H2CQx_@Viw*9uT8YnM#v15@e5}*|5$?Tk` zt+B1JnEmoXQWgtKqe4?iN1)RT_1;qVy~Vvt2>Iz^ds`$!7taUtgwi{B?5Ef&?!Bjr%~l~i z6XDqZU3C9v5ZwWbg+C-li}^uYlAbji#Zx-5Eqkg`%J{Yh*X%pXnu(;%(>dP~#Ic_C z#(ey{FwXHz?iTR$jbEc4(c2&tXONtf;t~eowH?jlqI9^{@xeFu8<{FAxANU3kl!~Vruj?zB0A48>ND{2&jTw;|5a47l^q`ei0kXVVp%u)Y$%N;r z791!rI`y=6rtLnZAf%Z2T$u__d4JiwEcD7*Gv+8#o5GwR`DM30AfZTYYusRCv9+i$ zP!fI<>g@*IV)KBwr`Huk{jQOh$LOYU%uZJ3lq8$nZ2Rr}(K`}Vi!yH~>gcjq9;b5u z%GFcA*Q&mIvcYSzw5=2gwu+;Avx*1n@>yG3oB1n1Rqn@;B>JXFQdsijOVbMxNT|8U z)$#tr6pzxI5Hc=HV99MIoaMB5Hf4zUV)Ay3j~#WQPQK6xe4oD2mHUjKo%`OyqM*+z zBcRv^!=ZuP;2c?yWLqT(C<0yo;>p!Q+FAi5w~41^c2#n6l~!K^e+ z#^&z5w1D$_614}h%N$&0S<1~6@$2mXp0xJ}vT>VbwxNWn`alTj=CYeMBC*JPGc^B4 zkD3#UtU%>naZNGsCr%~aJE7*RX27$G&Tpijp}Hd+n-yUhOeT&ZuPg@?iBV>uVs9SV z2Gq2|{7u26A6DIaxdB(A3*w{erEJyC#nX>ZsRJDQ9Uxk%)WP^slAQ*X)=y@ z;$vf@3aQD-QwKM{BZ_63S>85$DVeFy6ZD@pQA*}h@oC^y9~g*oG;xpRmu{&dOJ$G& z0(j~nQTk50PTAmN=QFv%A=gC;$^*G2hUFzs-(U*CM|@!+_`(<=2R9|M(LnL(RIA0IMhb37k$ z61h9SW3)y)4o-Js7_8l+UUvGxV{VV>UmQbUuxCtFS~5}s711kzmO3YQY zBA|ty+oLM4T&ctlYigbSLU=BO8T3 zVUCPHH=LghU}ouynNbA16a4pZKl-shZa6*JpcBW>(H5GRpQG_2YO3ykfV$9Du%|4f z2X-!K?93cVRUf>fNLgr5n!mF=7_+F5?yO>BvH0u)&lzQz6x|~*g%@R= zNu|>Y`HbL-ZUoUFid`UcRA81|oSt_(Ch~vydJC>Nw=GySA-HSf5Zv9}Ew~1EcMb0D z1b2cH+})vZ4esvl4zKrpuzK~kq^j1ORc(_4ow9dKH-lu0-fl2HtK!S8 zS`f2W?zm-Y?ZI*Y-!0_uMm#p*I-N8iQ`1-jd4{o!Pw%Xjmj6c znk_8$4&CnR!&ve1Mb0HDPDMBYYPYA&hth|dy}fpd}DikNzKG^D<2 z6=yXHDeA>_+F%8(?2ymUriTvL!EERuBa|LYWgFjpzSc(NV@Xj^blk>#FyEbtXJ%^~ zgU|Ehm-owk5x#iVhQkf3I)D4vapXMH6~Z%7r;mI$uT_;)Md14mO=n$S^%<(W({bjz zFF8PLW`x~Yc^JIkyHGlXezLsESd&=#zyHzyrMV2@f1b|+1y>gpie+^sg~bR25vg98 zkJBy`m$IpK=%CLhn?{6~%3v-zglCpk(ihr8FB6-px~97p@2RM#XB5qt%xf>E{HZ>i zN@+%Si`(V0Q5-HF`RZK3g}Q(AoJq9qZjn`1X63~FE~z^*#mlb8XVbD-;CQF+WQjlK zEUFc$FOV9_C;08kk=%2ol()YgLP2&1&QZe&yf@K58?wRfVJQAg0i zSQzu6M8Mz*XKfa0lO_HFMV=py2_Zg*Y{NBLcS^%eK2rLxhyx^kI?8m%0rm(JWt=FE zFjbfOgwy(@d}Hqcc9Y_ZuHFz&YL=0WK13AAC@;`JJU%JIX%vn6NVm#);vIs(l_Hu& zN8AoRTmg<;6fBR<$VMtLX%b+xFe$hqo;-f6@(P^RRsVrY`Wy8|nfCxbB?3FT=mHnOa*D^=)WSHiRzgaqHzomUHjH5#z z(vT`&#z`jHbt%o?)_Nig5UZ#pcVCH@uDNdI8N6{@CPH20OFuEjm5~B$`Bz^HND?=^ zPe~YJ5W+@&)om=YpB+=K3TOzR6XO|y{GlVQLQYcm2Ndjmx?iACMEem6v$`IxAwcI} zbJ>?}e9Vc|XEiR{cFz`@VDb-P`maUmPV|e0m^^{J_JF&E@Mu)FWU@6J=H2?#K(osl z3S4aMPvniq={$LT$?BKNdt2j1nBcua2l=f<^K{;~#fousSYZj7yw;PHvl5w+d-SoP zCTdtwS((yBG(}Lo%G)q%l&$z#ZiqC41)1} zS@%Brok4*C``;>)ziquKGW&jp&;CE3!6Z>6oK)yce(zb7d6w^cWI6IzH#p9&7SK`@ z^&5ONG)S^DTBPXi3wQcMT)ZtT5YbaLGsjBUf$Q=hK5L50PCfY)A+lynd(-j z-d`y;!WFiXbq+(7&`WlHpJD+nzik7bLWen&%tS4KHR_L3{D_Sea@!VVvD0rL$gzvfVH9v<5HU-59(ZTN$;RREo~^A zg66)s!VFL=C@7#N7*kV&`0;#GnACy0Xt-6w*?~J7QU~L9VZdCPG99xK&ye(u=-(&k zhwL^0ZuB73m^l`6^Yh|~&Bi?z5>i#Ie^+Qr#DD|yd=ZF~gs>dq54(|L@R9_;?( z9kH(ek$3je8fgz1>E83h?IINL!{QcUZO@^@WyDH{k4QF3gS_ z+9G*Ac#Ai~_6xARfv*NK`GMiEAremNzFa(eprQ``L*K)s=s-qBM%c>>Y2WWf7T52?G)Phm{w8D=E$j&|0m;HqR=%jS&9L6-H8v#rXh4bSB_ zu;qn%)lVjOIDSXqWX1pMD#%9o+;Hf2X$hv5!@g-EZQ3Ei9Uh%j>54n7OsZZQ%VFwW zHqzm6)$^OKCow}#DU2sp>Xn)U*r|Dt)O@!0UD66L$bY)0` zau7O6*V1u~6Y#6>a1$q?&`&kK#?CAP`nKwQV8^!azIQ7J0 z|4hyMxPN(O5$IhXz)o5_iKnpJf_wPw&Yw0{A%R(Qeu^Y1CHrT!khbn^%_=6iVz15@ zPIrhTw1(<+w*JXk-{SWE1KzWxQFRdwq`|;f@H~DFt06Ki@h{)#W*l)*QD*w zFMT)`r)xZdfW*AQp;0y8S&^zMa%)MFoX1D-20`2^=!Tk_E4Rn5;I4L1+wO)G+r}}Z_#PG5sKh4~;n?5#YkgV$xh&e4=Y*YvIDKi;Jffv=g{&nPU zp1pZNjk7yf8fX0bTDjat)2FDv!K~U|$Ok%5B;qa9lOdBi?|!uM#R zmry5{M3ZB9Y+hE}c^H~0SrRAXf54KY`@~!W%P=*!l0}HYgI)}dt{6~qZbhqrrUk=n zzb~2FS5Kz-S@N}IwhF&LDz7SR=Fv3;_mQdxt^1GfWs&|MKVh4^e{@WpF3`P-hVnDo z0t^@@$HT8ASQ$9^)S>juM=dV_VAgFM@c~3hi`LP7u|T(g7*BOOgpAHST&=&?mI{*iX^1uR$TX43 z6?l1RKQ3aT@o%u>uiH5|+fVstUaIQ|!i(KcU87C1?dQGn&6P2t1>MHVF>Tb6z@aC7FOFdX=opVv$wpl+m>(pJ2wfc``N{cK*u}50fB#LoJ zhVBm}UjFbx9q$zrFFTsxwapX1e&$TB$gKur$8755r3QDX5GR`JAzSDzZZ&wimmwBO%VSsAUA06H;E8**&fep5Y?> zOe`S8`Py`5RMY5_e>|CFK8p4_jB-3elt4E)fBeJ z`L8$ybfl(=`gzZwqRw1)vHetcWt#YNw>Q)7*Qd6eE){S&aScDSNXypR8i zY#>i?2y8Oh`mq$wFkLaA&RRN!tp*4-qAx{v1n2WM<6zgz3@kwJn~0kD0i3St@vLrC z8TU6%#Ts@!+M-O=F_3+_LF_7Z8Gj7q#Ye)mD%TLE#cTA28vS(=0+i=woCBp&HB}L} zINzBO9whe?foOwxz!@m04W9VKd6l;%mvpfRy()}CM?kRD8)e;4sZ}~55MRLKGlv~` zoS-y8J*$v<_nHI*K|+HtnY{JldjiOXkW>Utu?Qp7=<0rivS4a_Ou_Q|IF0~b% zS!_TONPJ=Vz9o;0@gOPRtlCs%Iy~{YE^0m@5{xWb%#4n=p*8liW(3&IM{xD zV-pRsSos|}G(!Q?J^tH|#GP7nXS0}k z*|Ed)iphTU8K0J5jq%W-tTtL0!L3QeD^Qm-D1M+kISg-<2;xzP?z6CTUA9vDo z>g#W@P8m6lhH7Wu@+DDzL(8^8bUk{9Nk=nU=95_~4(4KN(@HC&ubiG4A!(VJ9eANx zw_r?mn2$#5Z_OJ#SgZ3lOZHZv2qj(@YVdr`l|w?c_l~nX>Fyl$V#QSa6wXZ^-e4N; zP~G_hxzX%{oF_kOK_nk;ID0+p>=FPo%7tb<7o5%Q0JGuSfn_HDJRKJ1fO!1+bj9WQ z9(p*{LKQ6GX8Dupy6-fK`LT%IR)};yGe#oaKMj2j+jG95$5SUup{0O~mTv5@C~uwQ ze*jMqE_()FtYZ&;Z^Ot8AZ!v-)>eakC?SMUGQpD4ubOQHUgT@*o9R^Ni3={er2ARp z5N`{c|DiX6{EV@7oU44dMY*RW6^?18CYarH3XzeX9Pn#sWzoSM=2ch@t059XQ(`3# zYxNM#I3p#J7~Pb-zl z=Cd4LXH;`@IhXNwwI46|c-Ej^4(mi(9bzqxtJ4vWa^&y%nI?9? z0O1I`Knh3xDB!HBFKf$q5HSiON7#tK@TjH=8P7!vMW(KFx=i#-efcad#<$s^!WOdO zBHk{AbyjYGu1I-Pw}5u(CkJk=WgXRv zF4nZ#+#>6u_A10mLfLTNU3e*nnUoOQ)^{b~fF!*#k52dA#3(f$;ZTma9I_r6$Uleh zHU~QzFBKTnL%m5{Zi}D4*zn!LN$op4rd}1OCtEdzA`w?+vY4XYc{uh2Gio*os&GAyPratGB3-Q%wj#-!NpRfvd!?Re8 zRMpABexiyow~Rgd64^aJ5;jmckvW+ok4k*?u%yw9;}+G+VSJ%}Xm}B`T)6VfV;B@g zUMaZVM7kOOqX<=g$zr1Vjdrp&ui`adKI!`zpEe9{#LZ_<3&;AFYT<^j+CN@mdjrlUv$RUu%|i<)}L$64BHK1f0`&!NYSBAz<*aKL#ZC#&|A0o znHmc-w2om|KPGN-@X_{J_!QK4_48-VtgCGOsJ=xA$8*eK7{?%zD9nQ)Iss9JK4nNG zrL&g1V=dBx1j#eZ+M}cYSd<7w>cMumu!Jx?D%d}m$6vQaHk<#fisR!bab~{ai)3GI z4O8DjM`kUE6CGYX)d%*G;B~Y>@Kn)@di_bD<FVL~xOIvPu$7Ne>Dta1*5nN?^nd8k|N#L3Y4*6=s+cHTszj#MUvr(4>LGt*_#S zr)&416t0;blXoA4qgrMbVL|lGtGsQ6x+y;iM?gY(54Sj7sv;886BrCQW> z-r@?5i`>M>d~f~5aiFnRH8GfkErl6AeJ&$5UE{wfnEywe^MkH-wF#_MdyFAhs}jo* z$5Y9nF8fu|w&-C%U>lMx0UOMw+HT}z;qTrmo{~-xJt2c)K8ji9Z`+_NB9#(xM9|T~ zTKWmm(?Cp%jpioRelc4UsSG!i@|>>4@IbX)6*F^2zSWTPhpiIOG|X->l-E5{875?{ z)k)J??POINN}2IeRZ0jw+_uzcgL4;-PjA zNcKigPTlV9-#(#Zauck=rOemd7SvLgi(Mr8_bbjE^=o)|gA4}+oYySyvxp{VcWK-> z_N4Gx;Y+9mb9FFuEJA_QZ2S%Bx+VL@tO;U+zT9(Woehk0IXhm%Xk*?}1nj}e4nwptG0C)+YWt9O>+782Undec2{ZQ9jA6AAUAUB2)t$9+R2A*ki5Wv zExf7g9XE2tfU4jLt?g7~VE6l-Qp~@Tg|FaIXkUkctE=#ZI%8L+xKNMmO~u0l*_G$U ztDJqF@l@qK!G3|9hh2z7)2>p*c^p|cyKGj?1mhK_SytlPwDPR;0pxsT$`erY=zv_t z;*TiMG-2=}=a)Yy-PZ{UQ=6Lf2eO-1nXb#6E~`U`=at5m4flSk*TBS6bBL67L@o!J zU8j9Rv#HQ-#eh4o>81M+EU2Zi_+0eI1mt;>gS6~o9i>#brdXeP<3zV!gxqE16Rz${ zO|U{wF(pfugoP@I+KmCDT@hF&02fz*PWSKM@HG_L+`Rf*$rqr+6g&`bY`P_#&4Z&_ z#!Vdb>32@I9Pw=u1lz>Jhjn9`yIi3;Lbr7=w>T$L;H zpk)&;g}Hp9U@^+f?1t9jQvr%)OR&xG{_^we;Jv=GYWP-=FtX@;m7K@{#AVa*SLXkd zvLwyEgR^O(tLR;%u|%|#539sm_Vu@ycR{mT$-RZzb5sfkXju!GRsiotABGV4Tzly} zC(@~(lkHu_a)fNAYowJEsZM^ot>a{zU0~-kwRjBt$TGF!b>czs5t6z@lIsZ!QxOGD z6T0t{?~@BQ4>w4Q|2y{I>=N#dAm?QeMvK6xVasnW16)!I`4S|TeDA?gmDZRp&}M)P z=S(j+_1L6Zh36{k?}&~-l6~kTds1^qRkm^=UHZLxAQ>% zqf>D%3$!G|?VDJ>YWZ@P1F&hB08lvq3_e#w`+m9^LQa){=;M7x8H+bOVu%4>a~qLc z3kX_bP5(_lzD)2t21vzT(RQ7pRFCdHpG=f<+gmk%vEd2Z<<$g_Ik_h6=r}=PPV*7p zM%)>~A0cY5kA;es(4c^$c}1y#{w2g&Fmz&Evi;64KLHfSzI6}r`t>VgRr;1rP(%d&Nz+HA)`)?f_|M}^!2hh7s<{3G*MZ1l# zUboW{`5#VZdsM88bp^PV^Y^_So=6yWOS_~qytd=Rz}JfKFA5FM(j~h2sKI>ZAtS1z zy(7!bZs5a|*w9|0c zRC&Hos39SuIUny7Zid?0| zS6wUgzoY}}(@WjfbX%MQ$tj&kCbcltmAy?-8H8e!tp6sB z|6ea{ZZ$Ar<}Zdh8+Z*9@xlb4e>-q{xrk^}_iG-p5f!Q!e6EOpq+>UnLOy#+56{qO8)0A)!2>HK@MR)T{fgNBffDi_46rp1J`^wZKPSBz zO!PJH49Wf|LsXw|-x*s02ktIT`6l-dD-&`qsz#ybB$gOdFA2k*!ANnVdXV*Ro5Pn{yKP=KV}BMTsQJ8oVoeuz$GsR=KCI>Tki= zYDE5l&Ls6e2m7iA13FEl8S14yenQuq>mbRAoz_^rD55(|Y%oIHBQ|33H6pc_bp;8S zRsqv?7EoS91?JCsyfKk+A9#wqp147}ZDQFaJi{NZpZ^mH{>9ufkr_v&_N}kkciy(P zwnFQMQ}WkvB`^oW?v@=?#w*S?H%~(xbsMG%MD(I??qJ&^cg>U?jSX|hGLdsi(*4T) zs#lSq2N+mV3@<8Ypgr-jP$a&iiFb%6T`kqukglo)1qTQ3(`x|!iO~JEkvFHDL8iCO z9(UASL+W`TD|=R=dJ+0>BTGcu4Du@8AMf5i=b>$FJRq$_Y%+@-8=|nNh?tU6(w%?T zn~I8RL{B{A7Q)KvY`C`N)Esuu_37F~r9u;j_CTok3- zrnif*`tbO?dvd$g7dmn`XwA#Vx3#}t6g27e`p6`g%^MENnW3bNx+Bz)!%LqT8Tsbw zR5_1^ifVtl$W(7RH?rH*hj3@$vggGxHk`4(D)H!JLg~Pzt!s@^-8}C*p>8r9N8E|PS;(#p})}J z`Q8ojgr^>=zp`6luve~yc0(CJ2CtCQmD2Rmh1w1cLnOMM6oCKZjP8z<_)1L;t6U`0 z^IN%ib9Xn0%V~eJFh!R-E~NGoIv!pWo7FreF%w)Z?H{!g1%KgdGAb~-$fmhcRgs;6 zXahUDs>PWCDYW+M5t_vYD@*{b`mek4p}b{=u2*3+bxcKT)2&^Q=VB_aJ2TjqFN%%U z8h>4gC7>{#%H{qa*rh2N<5@f$8=@3CJJ-FX@;Usiz_fPT@{aUOBSXW>bx8?@}#fyCh zKko}g0)?~{Ml4zl0p=YaxgYND2S9E67L?L4jWzlnhf_o{8SDskrsGPGmbEl~P*I)F z$27nn053K)xM6;Nek>N#sD0D?QSJExsRU%<);v=~#bqE6VmyOmFbsu+)itd>b0g2@ zyuc`7e7q})AzC9apU~Y5kc#)Yt3&z{Sin%dcaG@Ac+XM4%t8Qhqne~~cGHgD;Dj3! zH*-DuGz%S*@^W5~%L;oOWCGVjv?&LzbR@0Ag3sfOE#TFLmE-l!9c}O4J;p0A2*YX> z|Ia7y?nqfbV1!sCz+i7ANxzDPhll477VAmOZ*-%>vx&GhTfkTMYX1!s5~%oFiA;>v zv?h-485Dcxzf@;tv{Y*n@%0$=);p3!Lqm{Bi#%7Mg}LGVpcA5TiZM1=3hIEknG}ea z8d+HkOg$N@Fdxm%4>>lOo=-K)T25Z|*-uinJ=xodYWSW|S5ZOdGrUGef6uJP2J z*W=b)?AJW)iw3;_M_vU1sWhg_`6WBx6*~YD-v`*iVpV;$@7AuR$WUyp4@MPRy>;O| z^lCXqNSmydjKx-j6kW2sJ-NZLxqhbK0W!$Ao&Ey(fokSrse|8LUn{jg^MAZL z0TYzpG?^j;KxI5?LCCVx^KomZg{5-snV1f26nCX3W20t1)g#hxMfE9@Qh|^NQ`H82 z@YC!~E{+>oHHN{&F+a{%pMHbNsQ8Wc$I?bROMU`e1dBZCQHKvh&Wn>ss^f= zTMkNW^knfo7Z&jGhpNu#iY*MVDb^G~eRH1^t;^nFbV8HOE6mYpAfti~eRm^#(_9dR zkau-Uu8J5~+vrB(Isb~%lR7huQ3;eVirl{|IfK+V7L4 zDcR|cd?(DvDW5gj-=9gmXV&t$<6#H~3dM*#zddXuygO3JZ+pm{Ds;(B_L4R=7y=_S z1L#tKD=iF;8`zBce$(4?#5|r!*Nz5K?lqBo5nRTi*4E{ykx4tkEJ)-1#O$6`zMx!o zk5f*<1GB6!pw_rbyPHFYO**JiYfQJ1=f~-g{v;6{XJYX0aG)vy{C4V6diJ*V`Sspt zl0DME$o326;PYM&!y11t0TAzAEG46+Hhcd5K(}7Z3q22AXa=z{!Yw15e%cp1r0K}7 zhGk*vmIN-bTmw^8C&B(<(@_TZJg^b1iA4Fkya4?b_50xlY?aq7<_|qL@RM3L#hFoj zsqYIrqy80BH^mLjZX|UvURoZGh+Vf<(dTGp2BSde#gwW*ZVddZemkW1^goytZ8CkJ zs9-7ZAF{VX(i74D}fjSUQsQBDh~XHMoNmHM6YAa?;2X2 zcM9D&*RuEkb|34{mK&6HyA~Q4 zcu<0XqWAMAcB|329Mszkp&Ub2BbDpz$$H4;*M)G@B#wQre(+c_}HIReGy@DGt^giIV&B4(94=g|p^moHvk^IbuP zihJ)fR8udQhl;u;`W-*JDE&9M9$y%`qD0W%JT)pcd$YU_hrUnw+Cw!rb05PrDgLZ^ ze9r*7*$ZG<{7$Rt+AU?~lKcm!xFr1A9e_AkvzMB5>ZKePt|w%6mDsT{8{RQl`n{@B zm+g6&$q4kgqVJThj%9iw=%boN5znm3YtVD7QD_D{)~HW`Py&E0NheTrkIIgWwkR!3 z-Z^reQVlPF51P)&(jGbxZePNr6QQc3?;3HwGwUe_lkLsXoA#ka{}!{hT|p9f^|M;2 z#I`1u2Mp;JEd`S>y4e$O)GAEml~&r|v1EunWs-JEIG-)6j(TQxByp`b<@UdYKy|sr zH~N2pI_|*GKTPedK6{F`$N)sPz3dxqKPI_>ORL~=z*Lox=cqJ`+dV?o(Npx5Ua8PN z){=}EyM-i-x(33e-kk$x(;Q(l4l2a#FKX-$@=@$idLLXcvNL>!E#`1YgfegMF4i_TXtouPXj)yD zLUt0%LYO9B%_wK^&dSW&u(UY83!i*Wa=TEL2LSf5SSkeq0tt+E(!bpH347M>ZZB!6 zGyAd(bP0g}RXoz_t(5x@op;lnsGE53{p}@bu@;oSC+ja4*GJ%S+S3ezCh)wcseLsH z?zP3IsGbhjR-w$?0S%n!pWq5l#fAyuUzfSzw&}DQ zRkl5@TikKN-D~)AyzjB^PnQxD$>56cgagw+@bRxGVC)w+A-bs=$-y)Io^qKq=5M%< z+DWt;N;JM|G^=WrB3W)=yol5G=c`;|epai^HK>{*9XTDn6td}wM29tTPlJTMn@t-& zeIUY>Xid9aqcB8F@0rqQIrr_zwOyI+(qWJ-Kk7eT0MNk+6!O%A_8T;s^(Br7j^3}u z=XPEboO0!rmqWdV8=c-sLSdkKW~vvB(}VlE%~a*K*|V8fV|GiP*+!@4&!)4*@`PmC z;Gvuf6z9@+$8*ZyZg-8vcf(+8^7?}^oZyj~=KE4RoN~+$Hp*xlcD%g2iJYKr{c&Z) zotuFK3P<0a9`f=2x2vI_B;RsMl#3D1u_CHU-35s>d~8KmR^USN_W*OAufL^gpnb9Y zy3NzoMvF)_yI#=V9}5V|S$+)|EeN#r7*Rxf-u^+hW?}wieFLD3R)*&E#K8+_VY%S$ zB81}XEK}8j$5oGLIwX~FK3YO#KUttMIXNA>v%F09wNHnHuK3GtWz32ypEr`5ZfenA zbcLeWVV`=cjp(fOTQ;!3-L{1p%1*8_EJxrJ!VY9<$Z2C`76_9NLcD3q7(>_^VBG3& zQ3PTU`KlSu=JU1m-cQDFCPRZ)!DE;l8_-XXeH^px?en=7ksfIbw#t8Io(*T~gKc*1 zZwM*giF)v|gXz+LU~94u)O@wxYkeFT)pLGL|3X0^wI{$v_>MC4^f=1gMyMOId_&vh z&~-p4yt>dL`?Pj&v&?REu&mI+#q|-~u@ zX*iH6#(#9(@q49qPa>6aH3;#W?0f1?(A&~{u$!PnQm}3}$!nCDGR1TRE#)sJZmdB7 zBXVp&32r5BUy^CQ%Uy--nqdQExp*O+^yPa%Zd23&nZFOn7@nHt8V(xv-S^IXe0(B) zP1YFCh2K;Qj_Ow6h4|$d4aO2yh1K(Z>Zyr!4`^#z_mED5mhskB%UP9oyYw?kE=7|! z1)k8Z)`qgfCDMvtKkW$Y7t6i2yMgkv=_a)r6CkwLC!#clcKXk@haWiM`#U@z(C0yU zHj1JO*{mlZusbO5@tQx&=5nl3$l#E(&5w?Pl3TB(!vHtV`>WePK)qnM8g(oXv+1wLn>42H@YROPHKwFRnuexqJl|##dm~GCfT&s zb&HeUK~VafS1p@Dummz&Cx2%9A7Jls_OF}0xtjQu2`(`++Olpz$N)==De`P? zXXJ~Ul7JB$-L~|l3Jc>hTARy-)zrbgj9DfPW|>uPNHU#4V?~^$Qq#>Mz2MEXS>bMN$pu;iV*E(L7q%eIjmTOs~<2Awh$yq^ujLR!sL4| zx+?u$?@|<2Wd+_VxCuARAB#Y(Q=Lnfl+?a0*I_WRBUk3}RC*=H*HPZrC5Rj4?z=MH zxhMO38H~P))mTG0uSP*YQkoW`_E#dM6m*gvWDU-eW0V}=zKD4@|Hhxpl7+ZziDVNIg!MVA2`sZfq{B-&2 z%ijtI;`G2DUD+bjUQ1mc&ez~xo4yLb9d$OA1M+2T&<+k5VT#D#qZf;0ae*hQe7L*< zH`TxL<*YFy11~yXDz9I%b09S8jTK{dltB8G28!q7gT>qP-QBi!>8PS_Z8Yuab%D%l zJ8;kYaVxY$tEuvOCF#K|1vUWV17JES7eg^N$$dIJoE`cK-wlTA2~%s1g@siD9d_!X zRi;*PDl>lL<1?{+K;=_u#31fsnCmo_$^ zCurw`Lqe$6+jy_Ee}uolcox?}HJTEdm}1gvD}Z|gsJPUqJYSCoL`~%#0O1;JwXn7N5T%0jVhMiJg*9u-`` z>W_J5&a1C*3xmXT6rDv}4tfW1pFk{`Wr==IkmTd4?qbERtK!yZoc6VR%$FA4$&=F< ze6ViMY^*pdl@M;oE6W|^QxHgRIh|~?_1>-93?i|e!$l4oyC;574vlsjm3V`v?$!FU zC5qq5ZPtfY-26hJ2)SL3jUAtYiHx=sKh@?c-u01iKL2c@{(g+`x|qw=`75T&`pUii zN|glvCv#>$_=IJ+qikzlBXxb*Pn^;`nbzd~?X37!$y=uQj81=j(Mh%+qKzwky}e1i zh`JTi6Ff6}8&m!+ERfY>n@cw2_gSZrCQhaX>$Uit&AT+uFF3%H+aB=N;V2u$05Cq@ zw%K2b2=I7+VCsCe0}mFIB?Z`%hLKJ$i(F*)Cx$1-^* zF~DgW%tvDwGZ$~{xBJ5*C`X7{x;iH(H8a)w_p86ii`1J;oMPpl1ocej(xzJti0`rE z@p-5ij2e7WA2azGHHk*yBfewC@k7A?3isaG6lHRe)OAGYmT;we@*R&jXy^F&UfD-{ z*GvRJv4oZpyaED`W|_*3Nqn3w`03#`3sF5|3s`Xbr!Zrqt08~kBk!meD1i<8Feo2e zMZNsfwecA3RW(~eJ%(4>$#9^zkN6(vwDk@Mo0XS4by&y#{$a6fZJstMJDJUwbif>A zR_0lykEH!>q}9C9el>uLo%cF_$mr?H5C|uw6$Q;P? z!B95VjBOb`%h|YJDiIWI1cysFtpH^B=Zs?+ZJ~^mI$18?87=Inl{! zIXqsWKY&|b4(xBc$vPNe;P!0`7-0}L&lP2)MHM#|i{x`Eqxuh*`?kMsU_Ip>pvpZ!E=we%F;3z0ULPCWPIG;bGASY2v+6DOCt_!6*gF9~UX2{gKY9mNB zck^`VIl8vh)vQH z2%>xC5+m;jTmLNNw@btICw-H*f~1BfaC(V+hCB_+CqRnjG_fw!4==Z9>fdBG+3HXd zYAsw#J%x<*3Y&kZRuGFPn!Ntjm(-05UHwryh>y<6Y&L;MwzTbj$L!`U9AT0jmiEjk zFMxkHNeNcVFm{FXK{<9LI8l#hwz(K%qy<~x9J)o#NC)eU zPG&ZdX>ogDGw8u90QA-*siU8PT|pyZn5Tgq(sUy;t5d`TwP|&s+h8|e#~GIB{+Zml zW83k`&alO&RAI@gF&f0_W!}kXVLXon&rZ1u44^nc_I_B-=+^H%;<=Av*2ZPGPGt)5 z{dv>sNjo}m(krh?&(dWqvj92k?fh#RgAFN$WeuTRne1C4BP%}LzH(w=wr~@2J7gww zE|OJ@j{Er`dV3#?C1)6rei=!xQE5I_9?3u^=Ze#!aMW0V#jZxBRA>a=J7?wh%kMpm zkXP3ybUD5c)ZR_!iJU$NPpW}i)gK-3w|tfiVD`G>c zxUlt^d$ay5zr5_Hwx@oGOAlV%Ca@Ia&PHWt=kCBWLKwi#d+aAkyC2rgWq?5#^V1TS z5zW>)Y2%3cik<4GL1@)(-sOGZOt5+oV|k!S@SAf5jzYl`3ZvulrP)N4*2XcIJ-GX( zf2o3lFqMCj5O1+a6QaS;G_7+oT&ZC>(CUQyuh1n7T7C-U`6WYh-|$@Bh`Bo?-8M-E(?f9as<>cj;RexIIXBhg--L0p8D-@~ zjH?Yd(nj}Mcr#7%ew9~2-F)+(!s8^kEfVZpW>!6jbm3T(q;rF7Nuz6W*J)Auv(^m* zu4~jeted_AZ8i|k^x#pw*ke<{*#ec;vSX)ncmIxm>%zDlvr?Mpn<{6VP}Y#;Y! ztGU0X9gA4y^eL6`t9!lCfFA`qoY4%Kx_O<889JhU-Q=Qkk9qITyHit09UBJApI2sj~Jm37JG((W2ZB z>F2xOjjg@1$8*cqpSB!kd28NK0-=?i;l4u{{Oy^ITD|(00n;I!TB9kysn7ly%2n2T zMDuEJG$#*R`$S{$NO6kMin}C%dAg-7)l88 zH=#wmOdTk#>GUoeHYg`ehUYA=G(DVY=aczyb!-_9Pt&c;gRicwZTXQALx{V5HCWz= zR<01d#g!NJA#6~v73kW0FnF=G{HYY+C1^F{1ygcOKJ~{9_)Q*;F)0`vi=4M6S#M&K z8F?t;UaV**0;>TCIrn{eO_;x=hQ2+K-o0#PUCeJ~^aBQ43u9{;37!m_b3fn}HCn|KpmhS<=4!uI z#vnUmQZ$wK#}59<^&Eti>^`IL8F<7GSIC#sFqSq(70G!IykkiY$o4Ya8;!){Mj%z( ze;D=`u+?8daJQrrWXHEOIw5>irvy0>KXvBU`I|FiAS9%2g64ZA{5V6f)A4USNP0^Tfm%cC7B~&Yt1}MZ*?R^YBXy0MogU=_N+8?qky*10f&%bP$NPVi>5$k}J?D({+Sa&k_ITfw^3`Ip7yh5M#D$E5*;Njte)1wRul!L4}zJIOBOOj``D&w?PII>R~t zJ)^f;3bzx^bDwy&3yMzjG3%?5oiu??@UuUK(joGCbzzgd3B_Cr%3GosItIIoLHXK-YChYPb5_WMz1sSje& zJ6-MXC+{9@MiF-H6d=@F5mRz_*qKVHzeDy_HTDjcacqqiiCxN$ln-U|Ga2%CM$?#0 zZY_V=1N(I<={%Kpc1QPEc|Z#9!SR`ScO=r<0}og;AZg0| zz2#mfj>jGx(e4c#1CBvxT3hP!F@oWEQYXN*HjP-kcL6NeF;8@<{n2HK-DO5Ia$(f> z6~AxQr1IXXABPJO>cMO}IK38cTwb zgn)rd$R71N(JUjPMS9F^UzEwxeOi*nL$WFkXF(uQyys=ESj`S~y z8_Q*PzAsTcc~i49BQ^!=1Bg>C%3Z}>zuu>T$JpV+N z(J9cN>*wgWg<{Eeytw3J8d@P&DGg#ih|5X4SB8vPizTJ{vX2L zG9a#PNgECl+#$HTYjDyK+=2#ocXwz!NN|_nPJ+8b;|{^yU4pxQojY^poSV7xem}c+ z@7}f7s#R-M)l*L~p5eClgq6SDw-tgV?yq|HOn6D9k40-iRMJ1x%EEJEKQ(^j+jsvXO=9=f8Qy^--z<^P}f`5 z9l*Q0d%b}>!nk-rSUROmCgg_PDp&7sq^>D5wI1x>Z-0G_$Egvoq4BwefX6i7Tt>!o z1-lyP93-sQk-5BflF328sS&-Kw;6%%9hK5FVfLAZv6vHn58F3XUQ4BKU%Hb!->$we zr9KA^fBc(2C~J0eT-nTizYDV`A`1x*K~XD$B@ffat5Vf?ONV(Of$2^(Ru*U-O|s%5z=Z4)}LC1?T%r2Wb7WMKtiWkv*9Y?rsa(cy+$@#y~Q z9j~me*5M&osaB+skH3;tJTss4jTZAgT%M|YSZvpjYUE7tk5qqkCZd*8$kZeCVc2WU zLG4~DROZ7C1}9rgs`%fN*+vm)tSyAv7k&!Q6+rEk;iAP_v4(of?h3;rBcWGkoq!vC z&byRX7V1IBB*7~(5CSbGMzmj>hKx#}9k!TGwu^xb5V{hH_K_#xv@|9xGJ{TK;ra$_ zv`|CH+z#0*O6g1GXC^Z29)x{I;H`@Y^Rlbt!)()llVbNkw<}@{Mur9J;q8VeO^<+? zVp);hAcsM6*k%W~`}F=SVOH~%ITJ!o!Re^vVctlI(-F08>+n#`?Pp&&lihxvVw1cF z3RShUR*r1-?S%e|zqTgH^s14|Hp8vkb zX55WJw-zzjdWOrSSyO)2*?V=sAGX#M9l-tU5sPzF(4<^2j+2_jhBI&O%!IP-M_4o^}xt0BsJ+YO#h zf&22uu;aj*HMv{M<7hrafy|`vs}f7y6-gN$X0M|CE&8+8W2>6AT{)oI0o(ZT_#`Y1 z)MNiK_hixcBFr;FipuffbEqKmD4P_$C`I$Kr=H>@0+*>>WgW z&a8bJSQu>|&NR=zT`ET#4I~F-wyQqba48sgH_&V^Ffbsq^7OHX*YgoiZQ!OcFg5Y1 zXlW_&uiyP#0Rf#_h34RZ5L{4d&66s5vt-Mk80fbY`Lm-yRoP|Xn7e^nEhCocbLBex z-2rJk({o2+mxET)f%NUkp`KrO?Vko6z=;_!HIQZ#%g=Ll!D6eQAvGwq?X$uatGkEs zx0Fl5nxamG#ZX5CYE|NMV0X=??O@Kqs@bX4r$A!8Ld&4WU$tt>L?Y5Hn7~(cDdYKU z_)Eh>gtD(Id4?BE|7gLtw~W|+=$F%386y6Sa8E@!D<3)uFe&r`0k~x^+QHB-#VbcL z*L&=Rbizpa-_MAtOFEL#!;(irN*5+KDwb%@WH~YT1R7uA(zuR4_Q_f#6c|^|7v81{ zF5sS-7P9t&aEKJwUDVDvimu7m=;oD3jY7Wqqr#0z)&%DDvSk3wZfLVFHij1}J_f?z zZ4&e@864U~rf(E03!CmwL>-j#@TPl-dekk z%u61?@?T1^#Rn7>-EUNBe*>9N1L45g(J8dZ1^BH=gm#a(+!`O+qo;3zgJCsV+MXX> zTZ4hcz}M&7>=vl@gT!{v!3h;oqjr;cRHf07NY=})C@K;REWrKxUiU)g-9BC5S>?LwWMMGYpbq`s!mcyK{>OqzWa zi~vJ+L(qo200VglR11&ID}Bzjk*=tEOjNb;y9KH_gbTp{PL2!l4&5v7oqRP%M}%VbL_GQ%7r0}!5-u${m!$tJlC>B26DFcrb9o&lOn%n8 zxwrUK2vs&bk81q-DOwCSdJA5&enQ9(b5@)96N9pvzY)d*Xgl0@!Ol#7E$dk#?AsXR z_^=NH6V^h7%eyrVO;3`?d?4P^)qz2-pN~b2&&PzQVfh<8PS{J=XPxje!sH1z#!J~M z=Ojn5kGt<<9Joa(O90*vxFub*K*dTE{RO&Jr_$_x*OOhQADagbr2XKYLN(Ms^~8#CUUq&Zf1sHS01V6f)`D~PF6R0Dmy0l(AE$UE!t1w%%7RqqPoQ5KS|A6YA0ES+sAJ^Ikr$(aivsu5nJKK;Y;pa-Ps#s&CIDB7BDOjG{WcU@En zO2_m23$mAvbn=(o8ZHlK2756(j9@JE21|G@?eK_|zHW2*rQyr=Br%}1KLRgM;|GUm z@>{;2GjA8n4V3NNt_D*%GUN9eywR#SKx2f@NU?NpCBssIeg|loRv5&y=?1%;9D>lP zsIJHE-s-;hLL2!|Ta!wu?O(3AG&dcUx)e!S06pp?clO&_+#X0rdG)pHRq0;~8^@b_ zVL9%V*Qs$FjfwJi*ee)%?c10Agav5ebNOO|{-wdZ<`!%1ZD73aa3?I+THi24giS~n zq5MB1L+d8!`XtFo^~XgEj~o@PhQxI)cwjqi#Qw86lA(7#x=4k&OnPB_Yrb1W-!uKG zaQMxK%xu4|Eep0i+RCg^Cq<;4dH-i-m>d5EoH}IBy6jb3V$|Q8kYeLDPme(GdSlG9 zK2s?ha^IfubFpGx#Ocjg$=;vvX^IJ(YzFk#j1l!IJ@&5p3aA}4*%D3w;h zi6lr{SJ{abQTAqNxUoK+E;lu>&B|!i?q#gm0$V7xURO$5F{?zRDJvMTC=_6lEmngv z0$wq!Q(GxLI(m7G6wy0%bDNoRYQ7ghLOu2~z~O3J%c=?R5O@wdm1pqoh&b|V3UmL< zgF8`(2_<*oXkupl32#ai%G20;=XE=$mDwd5L7ko9o8|@L@wE|>e$S|7^Oz4yZ_0`k zp6a=&bKPxF7^9oYQ*WzuCxs&UpqEIZx}EiX8tD_nO)L`xRyDugheNxV%^p zjCI|!964D|@toE_NNrJ;jVhF^tEVm51eWa&JJ!EX0~$$G&UV~rdIB}XXAFOb}$y{Za|*A zMI?C65edNulcg(?0MGo{Not&u78qsvY&oN)QHN#4|V|0~H`T&vQv8geWp5 z?SDd(~sYf%WMJ{{{PuVK z$$9xrm-|xX!VZu|prXx)dA&waxH}|V>{U-fi^COlh@6Xy2{kxGPi@ZG=d4muAFF zlp-JX=+5|9``$B$%F;Bx6JhHT2nB=08llyg6-@A6HwVu6v~^j$Gty$xG0q4JUu7S} zJ!`cgXXkW{r&yXogRh*@OBE#s#^^?Y(OUT8u%;VP5$5^Au~EW>Z5NA%F4fHkN7qaR>Wz^@% zM_Dy4#>iT)e5oWPd{x}vLik)xZ=C6@zv|q!&9xh1l&{<7i5E=dnQnPB8yHWFm22_D z=5=Gua0}*!Qj=6-(O=!q^xIM-a@QG1-*d!T9!zd?sA#+5nSHvNl1COHtWh7iR8A=b z4S}Q(EeT3H_$u4ah<`G8T)Rf`eph2feo-to$;d-TZ~DnZ6r_(&W8vKg1k{U-_0 zNUj`WpYK~Y(HG1TuJo)R@zx{*T{8|zMf#>`Rmn*H5OxBO zC4wal{EdbF;P5@;E%{C*ZfxuKP>_%j1yWJO?AGb`Xw#8!1fpDTG)0Y97u+WfW6$S# zCVz0W`e$H1Bo+`r@7jUmE8<&&DDZDTa!F_Ih8&!cbqNW!I3N71vr;oEjOfw_BS9jM zvXfiphxwE9)80z;nFN-Tm|CxoqGEYjq%iN^?7+g zR4&`n6PaCXmtC-BCxjf#QwD@EuGCj;JsL8ApQ(aOJV%$UBjaFIXW@8twEYXY3ig~u z-$C4@nJ@GW0&n6M#`AU<9#2o8`}V+Rb?NfW+=0Sg%qR`oSp|J#z1UzH!jcJ6zdrKg z*U4-@3;W}4pOX7tQvt!pm*cz|RB6Q^BYvl~B!~Ir-@xz`lY#LJy-w8z>vg1F_NKF9=hLmD%j;`45Z3n0+TZT-_ zQ;VtBVHQUZVu3hObLuoH%#p%8#Q9|C{kEkXSTj83+wQ$9pr;Aa&@E+6Z>MTMVJlNk zW@DY)SlA=zqc>B9y82w$n-0r;oip!1(F*8$x4Zx7fgR-)~XW!&71dmPZkEDEKn z;%DozN(Pf35Be&>RaWABj4TZYAfQ7XMZcOhx-^69(z;wb&x zIJKI%#wQlyQY14S$*?6C>QriV?!EDr&l2dIVSLm|JnsX3ks@oMc(*gJV)xD0**fRT zevsAJrF}0)1=VFfR2{Ayt^Gyt+&rQC>r@-`)SmQbxkGmmdmlAV5fm!a3PS%Ro3)!_ z*;YI{*K_JZQZYnnK!VQbth+M?Z0x=L#^|_s6mo#BQcrLw@&|&Ct3Pju?bBl?yC~!L zM#py!7fDb^Tp6KAe5`wTjjqW3GuRRG`B<=aYh(JIyW>d!&~&WTH6Re|8(#dAnZKdW{=WDskAK?ho&J`R=h)`Oj!G*w(7hT8)TasykmNZUJQDrLFM#B% zxht<$>Y}X)#cXK@mV?XlHo#|&yeyM!mWUq<|zX6B+a2s;!+x99;&>m#JST;(s%xuq#66{x)$Q7pVKh9ntts)+H7OJG=zQD|Z-iuU4| zqf)Jls_tlN7p2A$%&v}8{fgPkr~`HXhBm@@Rq2>srhrE&aHKj@i8dcjnk?GG1e~G! zvPr$7RH+S|gWhV!bZ;w$IwPVM2;Krj{XV?#w3=>zbclBOV#0-3F8~`oh240SGsGuq zL>~1{1E$R})}ycl3Bil-)serUs@y5a&{V}&eU0bE*n4k2s)KhocfY(}d)KjwnM3|2 zpyj^Wjj`bzU_{JgyGPTXvMr3BW+Yy{)tI_vmXvkR9WCe~Ff6|kxENjoYF%U?i8k;8 zJyn zHrXr<9DxRj5YD3@r#LPhuvmW7hno|qGsko;Jq z!vc0PJELapKnmNGA?4KWBs{{%@$r`s|F)+l!?I|DJ^u`u>P?Y&|C*E$7Bl|?w2TaG zc}P5SD;whe2RrN^E}FY?2>hQHe|ihTNZR zKmTHM*V1uLQd^*b{u_2PKn`+1)3ZLJue2L`r-oI1rxOjv44SoMd5eXq)}n3mgkrls z<=G261U~abnH(3412`UA%5@=ofMC@CM76LpOniNo-1Rqt%3ND^bGdEBswQV|g=5$a z?01rt>^q05fDmJ3>S^gtoegEdr*(835mJ=f8(*#4^GLB{H`U;I z(SM$}4w@T?2RYV*Tk4?&dJy)*5U#Q5gmt#Q$fliN-Sz1{2(TQX_KFY>v%w7;6Ngu3 zvW=Hom8Quq5r)i#Lek=~mJ_F4JZ*4#I?(9d40YR#wCDznJP3OS+RS$ZDK~opqooEL6=lQ=&Zu5$D$Pg9ZQL_pXE?sHUp$DjJo%K& z4f9-DdB}}rJ5WahQp~aKtPEt7y_xSfWHYfvD4?(iOver##2o_Jujl*$8MO9w<`bJu zmrG$5))D(GA*jj8=v`?fV?s4~{Wz71ji!5{{s)SbJ2c7D?$xzatvh>;zt5hApk-eD z{z9pE>f(H8Z@$hfHltuN=?j75p9;0xPzYV{XdzcY(t z<4CFfBj$!K=4UADUMfzMkre>@O3waCV$ZQY<5_rj!(^{pgIMp&y9$CJAus<&+L7~9 zleY*FyYDi}FFLCzUv()fm%;c{sQ$oRwj7VFl2a_U`#r`pd_MfVN)+*6&O-kC>QRmb zh0k2Dx)gTpf+HS@r(^K$Tx}ZyObZOqPgB_-b zBC+8!)=D>G`FaQHbdG>#BN4f)rS6BW0-k2MmNaU9hI&-}W)4=ZwZ+2TvEW~9wdt;| z5jObf&uPO)cewyv88=+;(uy!Aj?4UqWAHzV41xm!-DdRtcFP=E_Plh+&Xt-pgTS}L zsiKjum^4UMYMQ_caI!d5{(RWlWY}aK>*mf>g713~&rW%^B-^~=y7jvi%GT>yE!Ekt zBba3h2Y$^E{`v%2dMwBCFZr)W^U(#*aS!z#HC-|TneW#$`!;;_vY z>yF4;B>bKoHS&%{cO%X&+1Jdcs9x8}O9Or!ox4Wn2Qq4i_5MlIt*?aVb&({QYo$k5 zr?Mo9jN!jVD%;*u{9ulQeO0&nbzbdeyFmT7z4;p+Liz(f)ay$zHS?a6lwU4-uV(vb zd@hQ&-?wCM<*VsUS}|Hat2vh2TsRRnx9x%0;Kt$ji4DFC%QPlqA`@XPxmYqT?IT58 zdy1#rc3WWJ{NFknD7h+bp$C zK+qHo2&P55_!L@;uuIYn&ge!y%~t5Gp+)RJ_+$5Cy*qeJ@HeCtqpB&$`yivODe|q% ziLUXS2f{oL)^5m%HQwP-|E~z6 zdagqEzM~Ucef*jPby1D9b%;d5Hz zYVVF^Smle|lGTcv>ExKOS3ta70=IP~u+wpo7}>7No?$&I;Zl<<>#~bL)aKw+@`De`Fe@ufvEhTtb zu)30zo2WqrcUaD}#7&rY7_2o`(3%yNSy_v|jBA?vvMD)@Vg^Y8Xk|P$P{|I;PkAnk z<6`Kc?KY?+0P9d)P1!A_OE851t^>G0+zhS(j2z}nx^Uu8u262x^@3=p4IkS{)kAQ{ za-$PgvNvv)h$gP9K3nPV6}*%1kMzjC6SEQvbLCU`lBX`Uk+PZpVebm;rCMB4*<25*SMSTQLT1mcV-}OsEaI|TU2a4H<22p_r`Ub60NxQiSk)Ru_o~Vd z6ti|G+rx|Q$mWA%p7KZ9FAkf5kPN38x2s;`16dky4axF_-K`fd*(GnC*28Dj#ld}{ znXfX2o0~tj^+eAFdl>0w%;lDqICA)&%!=6<$Q&7Ja>f%u=_&OK{N(I~B>|#Y`r8~Q z`2Hhp{5J(mYp9<*^lkytlv3a!6M9M^<@Go8Y&3~sWu`C9^gd;pbw8_3WEkdPvAB!m zv!cMmhnM8)94RDN8?_1=yhFrce*cBNX6FZ(C3?O@qo&Yc;d?JvSRfV$UFA0@J!Y|F zB&=ZE6l$^R`^!B72MY(ujbuo?xBbD$1o$%3cxsQE1)St!^iJ98GHfX)c#ZFU2IHv4 zHF%Ur^UNQ|_)oL#H@bGaMLN9VNHk59g!26){1aG6^WMm1Rb!c>`(5rT_ zUSzY%pz^~wAs&)MkFbb|#HDaQz|Uhh4rpcoj%x?oORz=F#$kQ+U=EwcdZmS#v}47q zwV3MD*T=SYSq9@fl?&KjY4`#4o3p9cmx2RB--j-S@X6>6br8c!K65So`Q zRp<%+j8oN8swwsN_g8Q8tUG51IGU_%UYk!B$FkuGeViq9_aW})6WvIJqzQ6I=mOWk za%i)p=)E@s%szR8o6f`FAl%i@Y4sbmZ2)R!8dv+rRm(K-t^-__RGKvQ_UC3Znv2JC z%DyfXR@$Du=o96|=#;9nHR$>kPQ}UpBarbod~6J^xXMPO&bOq7C-WF{Vir>qgL@Gz zdxnNdiw@>oOhR+pGxe>0=DwUic2n(_{6wg0FJgQ!db77NlF(S{tUldvoe6CVP~ ztO5p@5qqs4$Y#2DnRpJIl39fFQu=|8ByZ(xYz`RZPgw0;TZZL*WzV#7413uzb!`8qzJjf3 zexdcN-rkgM|4~K%GBmBG(Bzu6$UY{wRxpZT4F73E{ugHy>F+CNs$iNO&!fax;Qz(> z`(ON0niyykH+8MYO6LD@X#WzZHSxEIo+gxfe|__pRDVwc_)2RMv}mn26H5!0=0A?5 z|N9m@s`aBXyrn9mkOtFF7ylRW{l5+xAO@jqFtd!V213O<8>teo{nv&6#QyshGw3Kn z-T>_;M-SJSo_~4vjijVD;fO-j|I9=G>)}Pvv*kKR&acDE2Q#^4y@npC*4xYAE25+j zO<5FZg_Pj`6QYH%&=OW0!1;3^bjct$r*7Ugrzm0ldFkHub%p~WNn!En<*imgchgSv8o1+9Z17ySSE8B4rhqlA0v z)y}f;Iwu*aOp0DSB2zCGq@t|QViGM3a}g%wzl%UR1Q%LhW1J1(AV996lnAEJb6}-q zmm{_K2e6*>5Pn&G_Fa>5;m5&`X=kj5@+@Xp|NcJ}$o}S(i>sg>OP{mL%k2twYTd{O zD~p8=h!U2y{%aM!iZ zfF?d!**~1vJk@z}F!M%G{arEx@n3V~t_Z37i@3Ado-KydgfCyltZnAv42F5l6RAfo z;yvAFw`P!B5HwramP9X0mZdjqy@c%X=psCFyl5}p4xun2CpBWr2 z2>ntc6(zokEhOU7+u^l=>bW0J z(I7CKPY4#LJo5Q=xn*4Or^aWZS8~Z-AFF@;KS(bBURvm~>viZhr^Gt`v8U4#2g`Ud z^iqcT1MAV`DodO38cPn>sULnEO?>#I-7_kP3ws7_=1UMHXZKEgwstUv#{%D&NfT2? zqO8Zl%Wh*{5ZYtwhtbq+^(h0(KFM(k2Udn=#Mh;LaSi9 zTF-&{xlGUsm3flzikd@B&Kg(0+h8i&jtb$siftSo3$VNG#S7iM)29o3wc!8EbR2y( z7*8rD?u%72^H%T48TVH25s~7}7qFcJIbz3K7IG~{jX(_BA2pF{*gFDUDAjCaS_xMw zclC%i-YzD`vY-RFtmFJ*jNtRZk^en) z$CH}}|1NM6TP1u?3_H;$E&*>tuafcyw=YQ^j&(oP6fbj>7e`~HP1OKB@-xN$tj`F^ zB6^+l9feL0QYXVxs2(Wg&5{0ezu@pfVh7HVJ z11EO5?q%rnwjX@pTkgzW`Yx)F6`MQtpX}Gsm5hf2m+=fY`f`v{I2zfcJ2;W}PlLqV z?tiVy0X6b)SC9E1{RvPu59388(}qw{nTdKcT@b6T4G9T4TA7s-;Dpz&Nnr7cvN6@ z_G7JLanigcH`>@u(Dx^&dj#g^NzBBOw(tXjs7==h_s~l{3`%)S$0#o^wnAOH&!^YO zs)UU}?ivVr_Vr&H-K;sOZ!1ES?0mv(+(z%4BG)_V3jk4yPAaB7E#$Ci#XG7QH(zCXh3Y8L$=RrW+?C0QX+%X>3-)AFV~$DPLv|6KFZIk1o@%d zd)4>2CQvUI>?QEr>mht5;v<<_WeERFR^Vgr_!g$#HhRz(Ni2M|snW{TTLA+Bgj_9Lg-`$mBmd>yi56KX!0U_l+HOxumU zRVG&BDb737AK|ge5_uv`&SzWjS<78jHoltmt(n6F?Jh)$fuYerZ9JrI{i%CF`#1`Z&I!(7XjzJ2@zn z-lC@5S|GO?wAKv-Xz@$rsdPtI8CcR>F?W#oMjB9f) zV?9_(q@6vXdHPv{bC?V->b*Lfq>Q^}!dfp7`c?b%Q@`0ejFd?){~IbwnUB8Sk-Td9A z7g~xQ+Nd~9c*_{>W(otyaK(_vQ0XdO!^x94anA|zxjA)ss=9!S2 zul-3#lx*;ednShcbGG-FVXs;J?iFEL;y@30IdR|Wc;nvdPSY#92V$QVXk*JeBJ7AG zzW}KK8>oO2!md^T(@&?DarcT|iGeon_d|Vi3zHUWJ;$ga>ya>PhD(i6w7AO~!apN* za2J}1gKY)E@kr#AHh+c8Vmk8S-T%2$8MqMu-36Fy2kHFSW|+YJJkDvVmK zU06-!e6bX;${8Q9;!&15n!n;l^wipFR+^;aO6qQUkKk&)t(vKDs_8dqN=yuYcD8rr z5@%G%!^>K}v!4)X&3mgQ9-WBw^6m$zuM%wkkSTb}M$7x`RXbWHw5$>3!EhoVv3)8Q zZZBzbT{4Rhsq~?NAaixtEeWYRB~Tu{p zx%xLHC<`gr&U?1R9-|}~38aN(-9%By5^=v1UUPPERU?$EiOcCFRIG0$ zD)mSm>^--F#>xUM*C)M#+62T)#v?Q0{mczt-^cdVDcfrO#(k#>T6}+`B#QDKFAdoHFfr z0_!O01ze-0mhDl#l^8~RP zFTTdG6k5WT;s>17vxLc*>yZ&Hq8x@se5AJ_a9dGJV(Mm|u?y8{hp?oo`p_Uv(cu`F z&8RBBx)zxMo0;naUpLx88&+Z?`1%1mRh2QMX>S(Hwnc&unWFJ zv=AX8r8z-v} z1LkN1g5=m0BOi)!m&U3VF32msQ3+nGacZ~yxCy~ST^h`>{-cFJ1q?(5woO^m3h%m2 zi!6&VEjr=j1sfqZqkJ`~1d85~2{7k?>Wi=34v+0Gv2=j9bZ-t*2ygz!q!FK+=<8vB zLcGt*TMZ7oBR20O_?xDh6td_8ALdeP_9DJ0?~X@L7yjC<8FV8%`+@#*I9cz`2L&QN z$3yG$gE8#v>&pjhJ=;LJ#nY`-G4&DdXsYkw*qmDnO=ch3l3CV!zDo3IG~A9yiauv( zr}j%rHkO^ZtU&X8rEdW{K%uyh%u7izA$BJ(OO@V2#33}^XzJ#CikRxJ6ijbeU)bw$0z+llfV@39bcjo?f^Zff1Pu|1F!N?VZ z=ls%zn$CXR*8v*9=HvH)*AJcXufjtX8MRM;&JW@5`O!9e>gGzf{c9R`YA_3XVtG&ioy`=- z>sTbW@UzgjhG93bRn4XFzcb;_@i-a0+q6sc>Oe4GqYnvB{^GgVo>ELH9cJuWtJv3w zw+u(-6BSk*x8y;RXK$HNh&nm*f=}SaEx!JxDuw-&+xpvO>H|R(RuF#P_+D0ySJO0{ zP4y@;>p*uO!I?D#7u6CD ztcQaJx zR)L>pL@kN?q{LbxdFznnS-N5m>-K`YiZ18_*}^tL5Kp=5cjOrgvRb8B1G~WXSwh;a zL_cxqlE!*6?=KyWS0K(Bj(g$?_EazqCTdOYS=qYi73EKNdRT22hCk9SyHJ~QyVs@3 zFnqocfoq+G4zLGywcM$~*SA+0Z7t-f;4Ztp{qd;;bF!!swtwoTR~LWW4)KKhDX{U~ zgJHSn#&;Sr*XBucLD^^I<_MzUJ^i71sXK=?VWiR;c-XyXe<`~((_A11x!VdLMd4N_ zf~OuEvG7yR{K8R{t2K@Fk|(j1YDaXdTpDOwL5KM|z)#{wN3UGG_xVijgVu2r*+4Ajy>tCz_^8kQ?>0?d(1t43A=s&(m%C*u zw_~bnR_X{DrukoD+ITgw+@?!CJXy>{lNhT$=YG6%8rQvLr>^?F%x|DGi65{t1XsdB zsu1--YVsq%Y?^$670E( z^r~!?0NlaobUm@`ZAPqM8Io4{x;PUxVYSo)L+~vVC!ar1u(?JiQt0tZ6iU>Wb`Hly z5%XJ``JNR{S!PWT45wla#h3pvJfzU+X!iNGJiL^LuBp#6yic}6W0wxnc|ISS0e3hu zg)E&m4^lPH{A^IlzP^Q<#=?;ejvA-jllA&jVOb8tH$2ymiXJk;e55Wyhknx#-=UOXOAm$Y<)`^yz3R*#HwO%J4YQ&Z6q{na&yMt+i5n2P zKiQf301c2~T#19AEVZh?LH#T{yL7D|>F!>G$y>_zzT$}UM`nf0Bsdsv#ptp2^LS&{%>`EQbk^|fXuX}Y3_ zkk=G2t40O{Ff7N!$w;$@j1auaDX(8c+#DGuHXr2Oi_SyTJ-4F{GF60!yTj*Sw$vjY zBjc)mt4=Przr_5xhFJvf9kdS>jG^J_a&Sqay9uE4OZnkj4Y%1m-{e7_cQ@%(;R#78~!R5Q$OrQY^-}TH@_f4}1)F&vKQ+we> ztjynqyU9PkGn1;Wwvr{4qgJ_`@I1Aih8>QphrmjhlG|@#*0C{N?0&Lrn;NTtb`ccK z5+2IA6TCe4iEiQna@S7f^BK@o?ynH1xXN+P9B3H|wT!qb#eDkrupPKbA3V>sf@u`4 zPRC;_x*r`!be_fIx%!7GZA3ZvDc-idB@}p*;%E=ioU9k{ za=<}RhLL#s>O_oVD*%qG_(-fMS!mNxv3&s@$&uP9*OuI{)mLOj@=A-Im;Ho{)jNj$@Bh>C;5#Ic2yD^QT{}?yNM&&LB0%sY^H8z5 z3;$%%_3bY(10?(FbQ!gDrcdW=VI{3AO9Hq${Up6LjRj}-J(&aOH-*dzcv$H)t zWgG%C zh5D|(+8dvfwyqr+-4zT33pA|?g}Gxdw|Qc~qNaDRWUCKMUND$ASo6xvu?zY}Y2Vk7ejg`F=XHlmCRRtIP%%Nu5=5~3;S>G8EgPnLFOy9mVpj9v zo_gKA1aP7Z`+}-D9P`oDU@cWbQl}NAIr;%_Nex9DFGQSjJf@^y+WNtV^ziX* zJ7)b(#|P|mtcMC2PTOgrehmmnxV9qvY_kAYICnVDOAEZMwyQTysdwPOMglkfqN*l6 zY2)CjeMOVgsUiK;*?`8n&JUbnpFhpdh##T`uQ*+He;T*)^{4yGn^)##=r+QQHJ7`} zqtEH^VIdbHG`Ut>X(zFIQb6_`n(BV{FDu>r2Gf8oTIIp6x%Lzc`=^4;@nKEl#|iJ4IVK!O+Fu7b|^68OXJkmw4(QQA?K^35sm{MamB|&U?Gc=HI{A z;MiE%OFxltC_~9=cAz^6!h_OypX|2=vgX@f$rE$qc# zfg>hTq~Z~{hbF!fVE(_TP?q(HSXvcJ=%~JukcED;oN^s*Dn}Lx0e2}yxK|%YR zj(~;UvN#p`ANc?rj8MsEHjBx86BYCZ@y~2FvQp&q3u+8RJ9!!b;E=Jd1SmjokEKU3 zv4YYiZHuWTpv%3iMJyDLk4_sLt%(hgznoL4&4)F==RZpdVvrRQT~fQ- zl%DtkDiL4b*a@6>IQM6-_!Qpd@@@TD{w1VAxx=y`;o`41`#UB6uM|)PKRB61H0u|3 zcQWz`xM$yS{ClJ<;S+lI9>+GFqUGsttNRDG-+&jyG9~G+@U(2oZ-0jGi80PBCvHq0 zzhA}_h~j_~6DSaN=lm8lR@LCS@HhXRzA*=$Qy%^K3XPQOGr2Yj3NgcwlD~~eD|lE< z!1>;QN04_U4&Fdca8`P&mATdhFvuI7^K2 zCpb}M$jN%qDMXruf1-eY%M7CW?FaR;kMCT^!~M=++}+*bs@6LSdOa7!AtCsii~W|= zrHQiUuP6QWSa(TKiP#dD>%?81@GCP|ng$GTBaR>cozxV1PYo9JeY<_9&9U zN!ydSIQKur{`Wcer~M5p!V*eS{`c?yJ2&;WVl0FE#gw(=Q~qaw-2X^JiU1dCPVhEn z2kZa+TnIOCx1A$qy08Dhvi`4Ug2x~f5}c?MhcM<1`cuLF{r^EazZ04=(wp!QcI1_I zXw{E*AQ~}l>$5_jhllRT=nrHP#}YpHhBkqU3hA42mS3UPU*mG^UnAY`eqc!t{l{i_ zq;X&w3BLO=&EI^)7NHz^KG!Sc_yGEv)geAEZW7Dj?MN9)gy^tIBeqB=rdYQFi+kCP zo!(-{)(eZxeaksH$i1CCAz6}xiMgMiG_bWfEhs$$Qx6DgZPC2lSQ{L;G?j1Ieid*E@<03 zF?@^0p=j9iaLQGleusIq8{PLfx~RVy8#+2aN>XU>J!b~c6ZYM|@$ln?m+5F1MDjV) zJir?pr76NJ%-$Z`^!0ns0k@pbGdo5cb#e;);+G3RnYsq{i;bi{Fc3d(i?s^? z+^Y@nO|$GN67Q%K$ScC!oKZ||ksWGerqni-O#(t9a4SvR9 zUJsaAb99#N7N!zDy03p^)_)Ckv`wDp_QC}6I?=Z$;?D|kIs-} zmvR$E1DMWSS`7V6SPDO_Z9O2Nvgax;#SP7#K<V2t*5LT;n!&DL zFN^|LCG5J#FE~lnw6AiQL!wqDX;UhstK1E(EWG(r8Um^A^r)X`t9tmv!DoA?0p}xCfwBa4m9wLU&BkYV_ckSF@Q-=iMOC*sGW3hSMsN>tD0f%4~K~Z2KspK>h(> zh0oQjgv5v%TQBAH`7_?L*@kQ>P(QKqpr7f9)tl~w97@xTHjw7We7SJ(JIDJQ^Y~H1 zM-&t$l1N*-WT6w;?=c`2;<$qGsHXx;QvG$&QUSuJhhnE;fKZ}!>V${MSxF=|7u(}z zX_!S}gRI8Ohls>2*leBAxPe$|woN*cE}yScq-F=fclr;^%Lwh1g|Y&@tq-zbM1vFZ zWgezFUn6{&nN&_xWO)8{VhbGVn4R?e{Tysjm1!5OxdJsy^$*~~J(c)3Mh}HnOT?>3 zQ}mmct*%9lqL*X77wz0->)O&_at&p&SUtv`sAOooi_fCN9}(>b#;%*rKJlvP>b=*v z!)G4jlv0pAf&>Zz-J=Z|Rua-n(Xv|=|^7u$5@DWIJ-=q0Io|3z!^UTI}Uk|tO;iq3| zI_I(+JZ0gl?#Q#0b|>2mlSv#xhvt>r-H(eyKPFudM)`XYneEP>k&CB#5BrA8kWDNb z+ycW4uuqzn>QEbk_@`!E3VSiWHLvx)GBz2m%&iG ze=8p)E4C^geaf{SX1R2OJXDZU(CL--E8_-T?)e7UvsDLcVTxLOxlt+>AR+bsNgt9+ zuimJcC?FX{K(geVCFjs& zXvv|;IY$8j0VQW7H{CQjXF+lfO@;=MoO6c1*Y|&WFI{`BbDrm1or`_bPeFB$8a3t! z?|5t0oT<|vW4{T#b5GNBn?dH21O1A&ZmnGqsd4k|?ejVX-$1gJ4$-G375@=rlrwlA ziRa(W{CMQo$$~n_;VnsHlaKru-^dk0lb?v!x#@nUjhT#-t2gxCn{#P-MWO9dEFSkE`g&4 ztMMs{?Ri}Hp@Zk#ads(bVoaDmWygo#n~Z)xl;)*b?!N#8@EGlv}((!CMF6)>1d58WuYg$ETGQU}3(s2CwMhlgW zvButNot4hrN(^(I(;XfI}3~aAS;3`8~3;nJF|8$wy}9tU%lvv45yHbO0w;7cd9Ux_g-2D z3(&2tyaU8qzkybz^Ua_(nk*9_UiEGE6NrdK!S?465pqt6_4iyizi&T)@bA$q101o_ zyyp)mPW(u)Tjm1zS$|N$T2fy0Tv9NTE`;XgxEX0L;(gM-Velk$ZV_zKjx;N?Bg{(=( zJbP%V&8@w)4(Z4Eu}Ndm)FKU+*Xze;78-SA1epNYs=7gzJCp&<>raAI49g!=j|8ic zDbe&!LdW}nyMYMuvRDmk4g#B1Y$~$*`Jb6z;&Ar>sOd8 z(1mnpIQ-x&Wo$GKce2Wr=!qbB?KyThfH+g&XG|!liPD)E)V7+wYHhq|G*y?$z)CQS z=%2M|rbx2(DA;@6mw$xY?ut5JzD=t04KH&oLT!lc&UT79VkOMfRxqCgq58G7g<3LD zETMR;2Dx3CSsG;@a)%A^R}CJ%PNO)@h%}YHY%^uXvT&Tz?M5<_aD0W6+_<8gPQ+=wf*y%P3W zylPsG@N^a>roLGkwy1->OXvzj((1dnMP02^q3LdYg+|xT<=fP!!Y`4BtiG+>l9+D-4{wTg z^Ucktl>mpZOmMwPnSkEHM9c>d*~zi;>C19db9w!(?Kz5)X43$N7WYBL#QksOTm;m< z+C~X?6OJ-=l~;8Ghqj)p{ACaZS1K*%bQ!hUQtC)0N4a2MEJnY1jONcn>ffAIoCP>i z?9zu}rU?Xv?omkz+b}cTs5z`zpR;w`1Y5KpM3bqL&_(mmc2|fUF85iP$-z=tAyZY$ zv`rnpXP-cM+J(#4yrPkZXnTHcvGA+}C>F7943xuX0c@9CdX-c_v6kmvsLa$50 z-o<>x>zgq_I{ibS_1pBk3cVUZoE`s*3a*S`@x2H6xq?@o*a2#ZQ0MqygDZ_;4L8e_ zDmA%sIOGnIZ?u4BPWSMow6;YDbe>!xK6q^mo1Jy9Qo(zL!mYF4rx&vdkFOeFRwk=i zTAIT5h!DlxFkR;~qw>o%rZ$=VhU)(4o;jUW;62( zVF-J#=~tGX&x^6B9q7kWR4I0X3z75aCpbrIKHG>hihATT?lZnPG2-_9LGCQ&w_3qg=*_EOFfc zuBqs1n+G;x`k`K%jtG^JA73p_xWDvb7E+Ajmqbt4H81fIsXdO+DHk$JEkD;F&$=2s zCx(x8Va{*GQqt-uC5I2nUU+6b+2!+m;l(o1Hm86!+@MN>+E9K9aCx*3CGyWN1Qatf zy<2=ZfwEOfweOXtoEpPr6@AI^OwxUNWauFfIPGs;o#Mof?- zmw155H$t`$`Xp#*-^Fy!W8tap8LT6-N(n{IplorJJDQ}@b>rt;2u#m{@|VCvxJjDE zj(qP#?7>ZgL_8K+6FUwY{6$Dd&O+dZ?Ib^Z4fx{dz-UhS^d>!jP~t3GroBjG*+gR5 z!FZS^-f9a+p)(he*+RfmMc9QE{jC$9A}7Hwdy%bEeR9P4p%gIlx`NQDfxE4sAr9aD zu>QPKb6*gj^o~d)`bD7dxHzQ}LPXv+nZ%Ii2bEs|-3tv}8;@F|WwUF1Pt3lkuoq3i z%tl&kEn-#9hP($dpRsK66{IFVWsOj+%bgz*XW8hX#=ndC&rKZN+3#yETiFdZB(4qw z!r0edG@l<+^3Va5hlr-}PecO`Dc zuC!R$DW8T1DQfPHM2ZmZNjnX@Vx?e$9S~j5;Pb--F}ipr(icJgLPrk!)vBMU*v~K9 zg|U?OS&qX^XU94qqZHzh50B!ik?(%GC8*}TUw0its2Gj9>Q&?rHl5euwIYPIAXxg@ zHmP7gvhe}ShNs;b+;;m_;U@$s<6aq3+X5b+(?jRa(eG-X>;$PPeTvC*EG&sGs|7lJ zy0~e)JT+Q6zdYHD_n?nk|EP$T(Qx2Dg+E-mfW-{+4dByRpI@>t+9OwaMt&d02K@w0 zR2$H>xiM<`%9O;N$xdB3EFgklSu%0ELGRZo)JZ&d8E%$A8nqiBc zXtd#g&u^)~0qgDTr1{Pi9p0hscKdBG{iiL-XwFzExiXYm??ctPCin^FLCJgHpS>}7 zVPnrlXX((NaQiXH8=ML1XcexemL3;u(GOT#3|D?6d&)yZuhDOwcGNwXp0z6&RiYbu zG`9&J?4l3NKY=Nln zNs{COUtaktC@=dc5Sd7h8O&zw)hDV=Sg(vPMeZG6Wuap&>2kAd%oQ&4ZSpOMU!Hlk zN=qN@+&}Xfi0}Il*~TIy(=Xn(J&;U3xqKh+VZh|Hp;J<~#%1>L>refv-is#KC9yKM z=w@5-o4oOP@0?EVJhM*qYS+*{!BJZ(a-U!M`d*(8Fvk*57?WyI z3uO?ZH{WIP+N(>Bt?DLcB(0sh^(oK4GscTjxjHj8AF3eZXlwcc`fjVtfP1b3iJ_P9 zK)v?enFnRA@zCpx%fDH4?a9Bsm{<4qE;%)*#(K_XN_GA$fwAS#91~c0x6o9q(sxJ# z)j4gi6BAsde=k^AfBoFvE{)HH-W%Y(lX~wWpZAbs<}(I$KGwH96%b|3wv^o zEVR;Bonhspm%dl0AZ+*9;9SH0yyM)heooh{cyI1eY-&o0aVR$GYpb^gYdh(ov{wCi z?3&-260+0b)3?QkOESbYcQ0p0Ar8+TNWOI2W}Nh| zetY2)SJ$ICQ|lGnyfLd4{EQ4yR4JI|@(^cUk@=(gEO~9|@WR}>7Usc`pJ<}!zH%*!8O%qn+4ec7Io4-2 zG_{ho1)8&iCv8#oEqx=BR*Af&U<7p{zI}bn8xO~>Q0^>Zg^W1`=jrEOLKMpXP?z204*L)oGpDyO|MQrP()D&^G-dE3*HLCgmCla4 zZw7dmz+;LjzUfXjgJ9a!g(lztbPfC5|NBqe`qi;KtP=%HO~IEfgCkTi|MH&y@uOBMx+e#IebGOcgtmj~bG6L|yCYU3+LR<*2Bq1%tP0nBhrbJM zsUK8`UwU*Z)z8#9?F+A|>|DfOQ8do&ubHs;DnJGAG zG6ST`{)qj!R%3`Xheh~8Y>Z1$6+zsxRiaJ8ndR{Pet0RTHXlz`U9VeuPVDM|Tri32 z#3H04jzNuHFyUuJV+L(>+>kwb;%zolskd3+0{WVSoulq6M_`<Sh-eSAp-C-L|<(#@&5n1^ugfMNZS&{8Iepy(6B8{W;!F&59NGY-znvZ~~{m*Ym4@uTtm zFhxZF@X;6V2(0?mp=1%OcYQ&6N0Y_L-0o|RnLgOy)o+O9wE35je`XuxkpKkc3o-jK znB2RPA`vv$4GnOT47o@Yh*9VOEVbPSBB}>7IHM!#5i39i5*zgByzG*aapA70jiiRm z;3hpFRf~Y#r+kT5QHgo_gm5+|rHo8Y#R?YE@egHv{p}UuV9+G(+{57XCS3Ahy}F2u zsPAt~sC#n{cM#*aB&QZVeI3t-?vk4Q+=_5`7^2?zc!hU89sAv*pa< zq(ZBPEZ|NT2ISYLdf1X{K2xK5lz)1_rBY}85_hd$%JlAFmq#}Fj;`sv!)WIcR7sr6 znS(Kj4c`y`k~zmM73Kf&G)%t%Me<7nZ(w`qKSN|(({2P zO8uJ+^a0kAQ}9g#g5|8dLaNq}#cR&zCHs);`P1DjzJpBIs(P{Bsv7DMPB}=kl^dmv z+oz||j_BT6%!vHb67f{aY@EyPWBJsxaO1A_y$DeLUALLtLWAO#9*`3wb8X35rerX) z306+i>h0Ruw|Q5wTsxX%>=;RW+t;7BMWak6S`b)#5pi{vs_j0{@>KuGVW9oTHv4<2 zn)w=cIA^eYtrifvBMr~4*k1FN z@TtqjXW(iGr)Iqmmd2^ZMD&k@5jRbJ;`*d3I^-JZ&Zs@-I1e8n-}gM?j?A!s>n%9Q zRHzGy@OeM!J24fo2bz=Y;}`*?AM&!-%K=CG9q#9R-g32tz7fQsSF{3nRo5NPz{!P+ zpM8U)M^40EU(4r?)}>9u=8NxJbig6vOZ&L8^+v0yb9;=>ez*$Ln?8BV4Z3))fK?|ghBGmfQ+MPVnw#Uq)CS_fj7++MIz2d|Yl{SOI(@Ue z5%6gyl1mYBX{d}izWFh+J7H&*u|u_5{>F55y4ud&PD>T+8R=i}$tIagqG9`6_29}i z%7E_Ds(cp|Obn2Bo^5>ApK{nR>%V-0Slu8zy3nr8Gr_7V6@FV^@s6rx%1o^DZvIE? zm4wf9&1a$wFR^7W?9uSyAT1wAp@h>_P;*4e!NvMJ?epDj$-<#Z<1Sv~^~vXjZ%QI(}7=N|~8e-hiBdljhC?KQxGy_{f$KDbgxS$N;ad*GA&L!mshb44HFsoTi~?_>yQ1bqG~TI^2`QO zCr=d4w<0=0qryw=HV*WH1qK}orDv;q#8b8(Zv{v;wd}~p+U}E`988qjNbusXfH>%x z1oHFKQ&UTN5aTguc9y$F>`tK35KO<8cLRguOSd^hAw)Ih$>#i0>X%3MN2|Ms<;3}K zZLF`f$S#>i!;}lg5q3F3e)T1*XbO8I`3!~Qmn(|B7S&`Ir`jh;r*28;_y#kaGV`8M zE(2(!`AG~as!a$>>wKEp90hS=F#O{RAGul5hE4ixnKU9L^qwsS@ce$wceO%MAY^uV z6-SUqcBrYr;AM@MH=O9L7QTG{ZSQC^jk2%~$xsLiD-(jJPNqT%2VSY16X8RDG9E!a zz-ebQfv%4jfv`t`ZsABrJbmypCMlfd7Od2K%dZaX=elFpne+Q>#<#%r;NEUYiHdJ@ zU%IBpPEEyf#mRh|)2emrXNQ&bn#0Yx)}z>h3O4gTE7M~IljL=e*3;Sz*i8F`b|NX@dWx?YI4I_!&SDPkwA6!P0xpL}Izm;9y8SCuwxlTvwS^2_?!{QUqJ@cZ65^CBGF~XK7URfcgq3({s zLcICcDo(z7odX3QAWY+%C4&7$t@#ULcG?YMHaG@??7a}9Jxya!FKiL!rhQN$2`@dm z(h3`0t;zuF%zADX>S*M}Ov8RUZ0{Vv^wQ0B3&bYvO_Sm5x}+6K2}+0C8p)egMG&Rc znwcnJlC-VW(~_c;4R1Y!EC-*tWBsw8+`UUBDd;o=MgL_Wepa^E3Z4L0swwp?Kv&ut47Mpl_gW=u`nlGk5KIH2;^$AEbnuIO-V)Z4=@(NzJV7ffb?2Y30e`R~(w3RN+mXRjKN-Fk%6cwVSGr zNT7gwvSfD5bBZ>Sln!a6Kx?;^+$MC3~G((4A4dF$4y}f7GbEWrk ze+3Hn0??n7E=P|%?W){*d)GHzHe#Xs!V!6;3Aq2GY!!qB{Qkvtj$SY`;9!}y4tY4hye2VArUpOrMlbiS3_wVxjP zIvhH&Q7N4j0c$CfqDw6KbTT$unZKTapJ#S>~f z&_M@nxbQ3^18Tt*eW-@*=+kGH0~V4+$z`1oKBIVzs9k8t#dVcKF9!C_B9?-_uWVg| z!f<}o-PmV>71O}_v!=PGn{Lh2runy#+Xx-}{7!=XzFW=SU8@0vT}F9IM*$$W5V5@o7vhL`auUH%LdIaQi^fa;z6H z<4XU9E#C>d!1aXJH*4+WXw~#``=UTyU>=)ns#YWQuDM9w1qdHM@!O0wzy~afM(qj} zkG$a|EP>QdwHxluu^Nj~5m!;5HN2&o6PIL?DpbN{b;|EFuCg8AIRP0cChw7s&mc4{ zj>_EWr!Ul)5FGjnqdZ-P=q@zD5Z^{I5?^n*9r`tm>t&KE?+d;gABJchoEsTk0$0t` z(g%Pb%oI%^z{e}O8b(~g%|EI7#W_K7dm+2Um3(9+*F(L^2I#}*Qwj;Cf0_<0)b-6i zvr6Fx>!x!4toy=eai@)|$Hsjv2C89#Pd=D|IQjzhh3myr?`CqACw&058d6QSaMUI( z`ZsQ^phgtI%J;E#t6mdotWEL>H0c9A2 zSps6SkoaU{jhNjnVpm{#Hcr2gjzt60TSVs^Gkazd+|re&0(Iy+zUjkOXN+yZLGIXb z`|zC3MUs7q6YJlk%^wZb6D-tMm@ErJSq<4eH06z(zL@-dMfwdIE}P>Hwlx3Kb3I`| zWgOV}{7!)us9A`6YS|9DPeCBDJ3I+iN^rcq&g|d3T4Tj#A*oZ1HY)C0CV8Wsm}w%J z*k{+{^z@-2MThZP((fVZ^@!1+QOmS9u1>RBdgtuq1oob-I7)q0+QcZ==Jn_9z&{k* z2V&KJR9XGkS^%Vz2tV{sl?v&6fgYt)o1;}NCua^`=2j9_7ViM%WWSf@djWTOfNk3o2Qm-^=4C9B$#G}aKZ4Elz$l-5`*&>7DsKKnm~oTco7H_;AV1OXHj< z^y-N?>Sol4DMY2s?~-13msB>BEzFylY$R$&%DD%4 zD5I;NskmL@J!r5X0HMxo$r=*g%R8qlf1^1lFB{L1QJguI2lKn?@qMU$I2y$1A&qt* zH5evE{2xl}-&xD^$Q?gLo^bz(8eX_I+5X&b6%V#hsfLcTH(sV+^PJlOGmk+XaI#gc zQj(ad68y>bR^HUEV96|ZXS{=<((uZcY`#hR%2xJKY#t!v5TIVM;^etf$Jd*&{zZJ* z|2N;ck7^X=uf#!a?$N+3EZhPZQCUMS{{|>fOkW3w^Zn(k|N1lFElLC-i$*e=X`6Ke z;zLP^9h#c!$xVV=f^oHQ0mkpG<)2MvYY+;mjo?S6vEOK_KUoNWHUF#nYc| zvM72#u$ugP!9R+p6B(YM6Z?xv|9$!WulGcCaes{cqxk2P7F*B%!ixM!$+{~el|w(U z{3r4Dm`^HQ!aqy?`+C1OTmo;9$_1Ts{7$<3DV_%nV}?&cn(EKn{q2bS59LI?Q~pVO z8q%`quX3OMe$ju8*L_^1awn8R3jZWt5ouY)r=$NgF6c<*JfCFd|C9Ivq-Fm*?Ekj* zzep9NEBtrZ{~PVU1@iw5vHwQzf8xl0 zAN?27{S(ywe@F7)oox5>kAHMTG!^n6|AnRgH@C&WKzrT7Z-LX{s-WV+Nj{a z@w9R0(=f$W9PCvW3peo=ezKB~8m z4@1%qD8<+Cw-QaKq9%r(GAMsGr~$}%I3gsK0^OdL^X>xDDu&ZHs&90|LuIg z=tJo*Qbd64?x9M;=+S@ndcPhm&>(xG*+GmO(SIBF7rpKUXfcTlb7^Gy;*kHT%&$jC z8-In>q(8k3`c>+mI+W@7f3+zRx*-+#`_9rm71_Vo@lze6|0?xQIB!&SPjptx=aSd` z7gPRu`pG^QvVB@`m0ZXDd->n3kmt)TkDd1a)alnFqybTFn*JYs3peN8A{Eac--y2G#_2m=e!0ISpxdT;tI~XCSZNF2mmFvRH zan9;388actFGl^%171)+aSEyq=s%Ft)TsOJ`r|VW8Rp!J%?`dAiLr&P{DR)+D#h|d zalA@TGMxNjJp1qZjNMYks^6=AH4J5axka zV*_M>z?Jn1^+Vwt0HQIQ03VA%bM?4)-(5&hdylAz+bNMbG!CQ2)dQhKJkpQ{AsB*n zvFB>8&Pk}B7MgRI{NPK+;g7d_KaDt1kR6dwXju+CWSz**u z8310&%SF#)P9`)ht@gO22>c`x1Z3qNnh${=YafEUW8>jpm!X%}T`qhM?A~Q^UaO#Y zCHW9##*%WAZg5&~#<<#ih{YyB%YO3oUkSAT^?TgcPnLtK>wQ%S^#eM;%l^b%2yvgA zY+I2v_1 z;hQz@*2HR-bud>8OzSx*0Di0PpYeR2v{jgKj77&nv{k;V7$-&g z68Z&XG5GZuTffHLpDAo#1ch}~)Z{7hEj2`jD#*;Xj5z*!8Gw(&iiyY&amUNh$g02h41N&rt%LlsDth8$y}Fx< zg`G?tIO4h|j;X}CSTawJpB8K$A#}O%U93sa5vJ1!q$zDBW4f>gYosSSx+Q02hQgI+ z7Vqu2q|Y6v-qz~L=LOXyi}P@32-YhNFYtSe8y>&*8Glt0Q)|@#Nk^Qi_bnW8G$<*> zvot8rm-F&V{{s=WD@A!-I&xLm@yxUc%GbEf?y?~WFn_Lu23#+Z>=Ea4v>Xg2u3N7D zk?5hn9D*!IJ2ygyO!HDyKxUhXLD20w5g)$Rc7IQ7z0HK0u(ld?;DhS>rZHwrIc5VH z>e5r3rJuK`Gw5-MVYj09bv3_qse{KRFTZMI#vYEPl@!pMEN%gqUa+dp4qz<3J_)h1 z&iw2T)8}v)yd>s21>m!quZq^1gl#T9ei&jg@Rv9f`llghO3; zYNznic|3Y@@gQ1NvRNqAt|9MwmCKuT0E2jGx@Mcfd6~Xo_++kkljPReqCYI1ItB;U1=OrR{C#$zC{O^kq?yEmiAbOXJYMyMoo-lrIg6cQxX+YyNzmDh2SV-e_ zkQp|8A?i20$&;->>UzUbY7%bvvgiY|pffpb2K6|y>|;cuO6r3ea|V5#jsDA?FrSmr z57>OhQub6;aq8_4iRORGXBY6*sOwa8`7P7mcnH3YxXaYJ-jaxw&RQMfP?P1Rj&Fcw zz|3&H<_qea<|S;F!LnnLY_TLCbVu=-xA}0=d5uwKMCBagnbW&o+gdE74y|wD-_?2t zo`(3{s0rVgC~bZg$4((&H*{G00ma0}tmoRDtvo0`I^~m#`Fn~o;3Jxm{P1b#hR;m1 zPs5h^TE+uDhaLe71_QdLlP;P8kBWrRP~I5hnHB`jv@8h7@)~$lT52y07amjLZ;xc> zBjd5N4y3oUk_WPCjVgkvNr&Wz^I_z_}Ns-SCJrs1!W9RRSSR1>dj*s1>G6Z@*K{k~UK2+pT_qCTqA zk(sPar>i0Ua|Mxx%Dn$jKNkZ~+i<^nf88WESh{|ou{AV_iOR9q0?eF%e0Aft8U49; zr#h6Sl)`coYH)qL*W${TQ67(6Aai@E;wkgRiTl1lF&)5ie@JKYeL^!4uk15I>*473 zfg#$UxE4{RCc$HTcn>jK26t`m_tlpc-yU_zrc~a~F>nEB1{$@PQNQP`LQWJa*n0E) zvwZ5r?zwQi?`~Q@BO2yaT2+^cQH6>w9-&$Z#bn`XU>Py5Rgu{ZFOcdgIg`5_+Q}Yt zeA`OUOY+tdc3i^h49_sgBaTy9eJko9RiW*OHt4c7rTCYpDgOd;*^Ga9yI~ZgqHWW@ zgOWn=N!_X6Rk;wTLhk`)s8HNGut(ul@#u5A!f(d9R;|-E zIy@eqnn^h&w$}V|xu6qUeR=Hgg^OVrG|{Dl4N#XHBAUqDn}H!}whglX%;^GYMUO}y zo31d^)X)sEZ&A#|NwVR#E$@1TgBi-;5{)g?6W3x$;RD~NZfe=%Rv6tCRQD8>dn)~~IK&7F~_B98wxJ?J>mXxA}x0m3iWU13r zMW4$<%}f4%?(2#-QaD~S_x+GyX{9+eEHnQj@yV@Ti?vp^=t{pj>K!vYG-oojWUo_b zM-b1qqN!u19x%Hdk7|Y)EPooV?d?RD2x6NFnrWC6i0t2S6!kiNh-!26b6|~&e7jmJ zm%CFXT)^xyG}_E+zIO=F_36B++#yMl`B7Row~OnFw3%kLJ_)zPc$YM{q~zbjv5&bT zpRi|Us5C*1obOKh?T1N7gj8D|6%$!Kz~v9yuVPP#ZC0F!qCDwLYKd6 zkoKwLS>JeX#ubd{+-v~4ZKQd0Y9r@_{h*0VC*B{1i3MYYEa2DfmYh(W4NF0l`fw`h z3AVDUBYiY{@~4j|a#bP-b*7v$O+?;?E;!6gUY#!0+iOb5KUKcvp#1WF1XC;QRg#E1OS)XEiRlx78){plXz`Q zZds)VfJtAO)=;FD99cZ0Lpx`y{cD@?c}4Q*QMWs4aTpAR&o4z>QXnR zi~QDeE`v{O1_OIjg#wrt3Y(g}%YHwr43rV7^(7w~(#B>L>6+Co8g#4rO(Q{e|o$3o@XBH8q* z(Umbj&{Z{6{Z9%Y?+j5Ntr*I8hoj^1+Op8``m4K28(9iK>TO8*&%vz9up5_)ZC0|| zwMJW=!f_j4Va`61j@{3HeT4nLz18@1U`1$=-Vm5;OapvdL$MV>K>!*{V6P{b)U4}; zYgFvsoEXJ=o3VxN%heN$S6N87L{e~S2;bJrTyay3Mt*4S)v3>#saY>34|j(Y&OFCe`+)lQ4kq9)(p}n%4t`x~;c*2Y8nS~2 zY2u4pO>wDHGx%i(6*gFWyL}3IB3`e+{r9~h<>en#!p`vG<~oGcY{-&C9}`z6+C!Rf zXv0(aUGLvNh4e>u`3YP9Dja|91ovMdduRh^wsp+E*O?OeW6=NSA1^+OL|xgbzrMcK zkT6bH5B_`ThT&f2|HrfLv2XAZxQyhCWa8_Sf9kkLkP2}TKPmi$KlzPZ_{faBpAl*q z!M|@v{6#o0o>WFYd>0L^u80ft=l(W{=MGTL7g)85a0#WG9nw-NK7e8i|-{(bB6 z`S{BcoEe=2{Bb2D0&IQRdb4!zWf*dcsoiMh7e&9&Wq)*?-+AsM*XeaA_=NNKvCx{s zC^CGiBGf=i^7rnJ6p%0V@ecuAuJj@y5#Hpa1*yh%)~X(jhI)Ki&T2Uj8=%TB(>?)Bdjjascw~ zeAI^+yYR_S<|sz8q{)7>**%nu=kIf2v?rD%f3M3Ed!+Nb_R*`)8v3!cazofcG5lYF2 zHs*rq<0sLjH$(Oxgp)lta0&MvU24Mfqp2)bSxYj=5}%K1i(F-`=9KxO1R6LTqN)JiYpKV99(6p}_3|Yd79ur;38jnp7I`i3#L# zR;fRk)wjid9|L!3l&9|mC{#fzMH3l`!#jAjynAxOpyfp|+lpGQltb5vPgM_7R6gFH zepST&LxjU@GykU&1GGZu50*sFw-a|rHL}{ z0Q8(%poCLZ&o1Aq@K5VpSc&o27~h`+?4N}myKhy~-(Bj!W_SQ68C$805_@Tyr#tf^~u?`+QEX+Xtas()*w$W(xvEnDfM|M9qh7c8Hf^JX+6?Qo16 z@)c*v50*&pRK_%B)LuPTPOa{EHP}V|*R)5TEy9Q~lM?!^Qnu)O*fXdr>N9tPIZjQA zGjIv*p*dhCt}u?y%>llBoIqoD8o_rn;8%GZK?n!S8<@(+i!~FKL)~G;m+xdBkf+WyeX*?3T)r`g+;@Ww)$`n>jt zkV4&byxwHic-3<=`RJq~lA#ve>D zD2$<1>ph-UuapI0zi3fe6L0?TRP{|@RUV6(>%7{9fi9tFR6DW3LNhmoTH?iSx!&YA zV6%E={)+k=FVBmaGyNr5E5Suwm{1RCvVkl)Jbca8w9CzVaJbY;%Y3s?}yp<4P(~~NK3SLEvUSC+3)V}|(sAQ;4)8xo^=jrm`k*nv zPN6t?spb%$XF<23OZe%UG7=WhAWecsBQQ$<+x9s(FQ<->> z!e!djvzX(!qr>0@CYWqOXbl*U7x&1yZkdH-LzH1L;kiwD54Kh}A~N8Bqn(rTf^Rbk%1>s;ZY`SabF^HACRqI1lYN*Q7kf{NBxL z6Lbr&2JQ(eySYQhG0;#RJ{@NpT(5a5<%72xq&O|t{W zZrNsk05n21qR|)Z0?t}@GC7?^BsodTR1wZBbihd|kz2l+U3M31F0Hsv5p(b)E zFyl{`=t#0O#z7VG-6@B&$THk(QXB{MRy=^mv;k~m z$JY>2%}S?m@U2ox)ltgTK;phO}%Tf zbD)(?J8%!JVYA|_;RCAmj-wErI>b+yQ^t0}&U%#Q%FF}Y#}(=AR(%VQbh))E%D~2) znz5nj&&sC~(rBn;L+rlD8R;WKKU2PvSosTB7-3q3Q`y)dT z(%qgC+#JX%RvcAdKRD98t-)7a!yHJqlkA`mCFWqZE>HF`gvjO};>&Y@mLBeC*J!NS z5h}OdgYeV51+gSt@34smb1}pBT>BY(v0bcf^50=BEcIIZQmf3P1-$;R3_Hf13@$qIc<2giPLX4>VP)`V}?7@&P+OlgCGM zz=0E%BlvD-uXC5jkW6x)rZNF+Y$S54^41j>UJ+47`2;P%Yo5XZQmI&Sv4TSQ@3V(xErh`5hIjRdtNkAa;00t5S%>x-RErjFQ|Dj z9>svHGSYrCsMXJGnHKr4SVljGh?*bb=;s;)z&H#O?uJ9^@G*PoD zpB%&YF!rLAU6T74?ZeJf`bP6}Ak9@8a)~!ziD)x4Y90qjaNU84PGh@Nxm0I8W!k&} z0+dn@SGqI02V5(-RmfL*j111wC$q%Y6v(~eE?9REe)9n50T5c;HRmMc3dr3rXr8hC zlYUhQUH7RygZ0qv|0a8hbF(3TuXI9TEIL#^US<>Ga$~Yvveimp zr++eb5uxdFGeH)+_o=vkm))r;MH-ak#S9KTz4GbC>3YupjoVV$_K4Uj6>8neeCKoJ z+-e|r*F;=!E%e?PwPh$x$aJPsxYpz^WY@m$w@K}OHy&i7S`0a@JPgp{gq4>ps7O*EKeDj!AbwJ(Ah{wM2@f@(uJQfy1G@;**i)z`CI;%JG?PtsrMID-O z@QB$!idS3Z9+UR(LYm|IJ(D2>ong zJZNP422{VgiYvqB^q_-v;Jg4@;zo<3db@5NQ~zsQg)9z@vaPpwEUwIjPH#d%Q(Ig% zbM8k0*m&lB1aI3;Tgi9o@I_suqLWxYR!}bbpd3J*RcEd9femI>`5s9zRlXUkv+X!e zH7c{TuRK$E3Y)yd1x*=`4fPR_mi{-obn%Wq<;iQ;99FuYB8sj+W1Ry5v+km;&rs0D z^Ie{f?Q`B3t!g({n`IEBvGp7ejMqbudkX5<-W3}L$+u1jf9Y*((&{Vl&JJL4)<`vr zgqMmw;IvSdscVbu#|A76ST(xer_h?KC;EmU-})Fem6^&t^H0x?>xlHL;G1@a7-GuHiw%z1Lze}u1i+EIYoo4 z+#0T)Kl+BBaw%4VP8}YvdGR`jV{Nk}<=_Yn4to9^jM?k`f7pA=xTw1B4Vcc6kZv#l z0qKSzB@9B5ZjkPdp;KuA=@b>|?#@9vgrQTqh8h~)y)XPqz|2k>0>TiNCs1*i4B zS49Q5I{G9WqhBI%LK@Tpi*=u~u5rZZU-J9sOi1G`_eXrY824G$h<%p-`rZcZi^BRy zE9SO#8DZ|#=K~OrM#?WZk2)w(Mi>aDF7LbbO|Wn|r}A@Xe=HN4=!u##wU~dlx{Rh< z;@>1xAqUYN^CSjn1v>G9hq%t%7n|aDrl>cx$#eeC<-wBPIMZ<~Ro+XP6Pv)k0$#PN z9SSW@kdqQEQqeH*Ct4Dl!tN=#jd1Cf?U|P%-z_C1Jx=HjvQXDZ{z{tZdr=7QWQRM- zaFs}Sjc<(Un+#y(75IYGj@FsX`|7gfoH3~fB2|1X+G;v@`+Ty_ni4u)#&eAMk5s2{ zQ%)@Ly=(3tV|7|hix-q!L>Q;-Hjz*53;8$F2N zZzzCI2S|0X@Ltc2O!0M$pP%UW^D>C_j(pDT=jjhfj91VbKSJ-9@2+q<_6kQ%X}bJK z;YL-i0lOJV(Y$}MdJmGsfs2CwlHLlpirx4I4Orq#7Kca)DKAjn=3dKpVQZ#{pXc+~ zF|?T>6?F4ZPS_6RYuFdjvVUwY{X_34fwkm2W5I3g%L}i99QfzR3v+moAEtIlL2;5N zo>y;#eoIbENY$(L61B}YNp1BtC;NL3DNpAga3z4LY5!Vb;t$l76ku+44veX+G>d#v z8}cczQSmI;I&SNYWeOc-JcNCyfI4qv9@SfX9<9K=D9~(%q{GfwPP@tPOb+YN*=l@M zXIUF#3Jzn|J`_0=sa1g}c8Z{}s(phGJQQo5?+Y$9lK1;W3%I0f%F?`AxOIhNm zUDe}QqnPlzVb6j0v?{;%^r;?6uSvV|I=VMK_<* zSdD4(@Ou}qo3zB)Rg3nfur%B13K!iERoo~)-+6Fr#W!AH`=x;oVAizC^nocg#f5EF zKCnlSB%5Y6OVxgb57^sZA&EK{o2e~)bylkBHdFGSxw~M&D-9>>O5#>#`L0_p_XA`f zJEQ5(y(X!AWV<>~`PwBx@7%jUtWa02fO7oxJGO5wN8j0tbQ+&D#7(Go#2)easwlsU zfkhOxOq^oQTp=NF%pa6b&iy%LDpotW6YbXk^tM)Gw+);l!%)#>tk(SoO$ z!&bOA!`}sF3LKk%)K}WY@!NC*=h@}X0<0zJQ_x5GZE`HJQCJ>N z=c}UOBc6Q<+vk}0$l;l1OY3WseDEP8`b?HbJzZ@uDyQ12C!|Jd?Ghmcq?FRbM8@K#q2ZUv;8vHz#47(C z+0jOoILrbmx)eX#a9{-m|KtXKHZt!V#i(N-^^`(8YRsoM z;?%WLJN@>nPhVBXmFvmFk2=ukN*rUmyA1PR;Kij7NYFR7 zvfL>;ZRYQ6`ApPMW3ezr^=ca9;;Ikt8JQT5_AgoeAD1`x0a5jqkavK7F%ku)Xbqe8 zElydgqEP*4_`K96|v%9-^1OHMXssD>fz@t%vvrxqA3-S5jea!o z%Qx;nlz1@RGl3sD#g^mx(~ms9kKME;oPA&K!Q#rw3Z+Tk^^y!zaIt$N(rG9x4M+Hw zf;KqPPmZBmWjT&YO(_Go06MTZ{KTA&UM{p170cdN6p2>mFM6!M#=RIeP3{u#D?o&= zHXmuXTG}B0YhV6bgzD7s?+Pb_*sQO(+YJ5PO~5ipI<*H6@`4iwFvW>9(l5|96FLm9B%(S}WQ zlbZX_uhG2(D4N{|3mk*~+`duv&!SoPQK2`#_`|<0;d;Q(n1|SIQ2e?5PATB~GWaK_ zo?qmEe_bv%{VbY2ogL=+bNg?Df$xo%p03CI#ZmraY%ApFqQ?EYY_mVN|33%#|HA=p z&Gy+BKjqVM_+`$SB+ACb$L}e=Bp~?ooRUyd`IrfX zrrimCoOdRIQlU7+6`}4mx{_iFvQ1)1}h9|sd zWclL$Xa#VisIo+M5hj1VtL9(q`)?C>?ezgu_h$I>lmGM}KW|+0N5QcHmyT5R{jI5& zfT=DE)h`Erdlv`+bfbUo1@LbZ@QIbpxBVlFbrb&1>{)fd?91v%OUB<`?Y~TS&+?Pf z#82evD`88JjFN*vx>HJO7`CkqxF{UvnHQw z;hURFyVv=zA4$5b9uNS3hBRIoz$v2|WQzEBc-8EKJRT582Mh)~XPEmPZPoq+VzDy# z&*&Y{$-`)c9MPQC2fGee`(9>AAbXvRtG{b_FIXJOKqlS&Naf4o#z>CZq-rz@V)1=Qe(X`?)er| z`sQ1#fqety)D}c7$SI@ga9eFV7lw?Ap>e5RtRuATx;gqehu0wy8`KN@ZD3(^Qg2uh0tAipn#5;}{j54YR}hB5$rQwe=8TwF7uG!Wv`~ zR*0RcvjZqy8xo8iXr(JR(D?_$J(4` zgVcqZ6&S!%b+p{xgfnG&aXau6L|1V>skdK3@wwP!+HSW`IN2O8Afxr%U|?-Dv0EHS z64lVbYxmW2mm zN0T)zRnXxcc|gUf%@5k7z2=o2&FdMv7R}xMdhVS!9QJN_HdCaSc+{8m_l$Y4dm66Y6qo30wqk!5;*>&Ec z~Jn1{d32;g1hBn3`xuAJUKU(duWIvayDa3a0&gG$7JRi{t| zK9kT!UrjYT)g?l|I)QcO){fpbS%u=$MFE}OZ0ptD4@HKgB@pGg2)WkU9ZwsTiNDLd`MQD97p zSBFdsv$;)>Q>`XaqKh#{2-Tj?KxS=;Mj6UBtVAw_*P@W&aT==jM5axD<_a(}NOz~J zoKAHeHN`Oofx*#{6D?+mJ{n2MCpGp(L3a>RLia%V3NyMJY3hcf+IB03#H{Y55_r@%EUdpP zo3uIx+_%b8AD@aJL_IS}gWKXvF76}hx;JZ~8f_>X`oMki*fKKz?EKt+<+vOw2w7%S zTRI9%+<5k4EJs^y>{nN8t@ugOTraKm<0Skf?*!h)>g$^|_Ng~m;lMFEu{YI*^*4dt!cJ#vph}A-qM11VQeP2Gcmstp5aN$A=Oct;E zI9fECM2axeZ;Yv&KpKcwtGn^9-5bj>9p2r2Sja(vL&`?J?JYmZzk1NkAjhbbLG9yM zVm(#91Vk3M^Ur}!RB(+F^a!^+1H{iW`APlR^P9dTSb;w!2-qSOv$Nq?IaY9ziKyod04rlvG>JE9OQ2L0*5`21aWn))~Dm5T4l@v zC#ree{ThgguhpbnM~m1g(rcRR}OkzafSA?r*J$DYpcSfhAd zq{S!7_DKcMT#Fo3(-X_cqIP|znBE%q*plt>pvqC&zr~rh*D>-0T%~(Dlg{^QBm>;e z7b=z|(4mk4ie_3iDw8%1LA+0_s!?xn-No8A;xNvrjB0zNgyOo~iCsWLe(1QPrZ<|a zL}y45QZITy3w1TsP8ai@rtJ2+Y=7>Lf_|@`ZjL6SGkj%q+F062?{YH2RtQ2Fdbu%M zSJB7uNU*;>ibkZ+IAj+{u_oK@t1-B|%MKmJ%=PPGP3g6I&@Sd;C}!yHqC?)jU&;6* zC5ddCUMrq)4HO4bgMF=#>_PDTsRnL-CKDsOC7n7)nMp>}%InM1zz#7^(8{%4^Esmz zErt&0T+o$Wnm;3A7YMZ))z%cij=@10V2D;*?ola72O9rK1r7{WO$GrawyshD3e-)+ z;DL-Uk2g_o(lW^ujg=;Wyd7#+19*;F^vICdB?yR79S(q<7n+pNx1iY_RB8XY-+8Qf|BO; zZ0XQKRrt-AlDN$Yf`->ThQ!ndD6lsXaY095*yFmm3C~)$gOqfOo znDgvS)_j&EDr?f4;a&zz^RD*YGVe5L?T|rGf%x^YN?)VP_JsT9=fqOmIpN0Bd5GHN zRHKJe<27PtNm2mSty%=)#zRn~T98l$3Y|Rr5vK$%r5H8niD6(?`4Ukzmvpnj)h{ea z=IMYHJxLq_{~7KFSAjTvcG$;JWKd_+6}B-^l`ee8iRH z!cI+>n0+sh6H)o&T><$OSCWaLl6pu{ljljf)a#IR&@nkR&xWx^7g8isi_wzOg759M zTjTA`r5cAEhLsLe$5d7peFTjNDF8xH0$&%$MLSJ~0KKl^pIUYIh%S&HZ?3hp3cw>8 zRhAz}8oB!4nD^1P0_nc4K<;Z(;}M??x$TWXH{4|CRl{(s@f>&M+Qk%Zg%zxL0*-|c zMY!mkhBFNsY4j>5H6?4B_s&-Vh_bSAvsG#gz)~w8)b+|xGzRx)trBcO40Uun47~)2 z>^g}@-`2^+W}4jU^g?E>^&8+~+a0ZGU@tn4AB4vnBON%0Q?x*gsHQb5?VE1_!6@v3 zO{E3xvq(0|t$5A1D{LCVGy(sBNR!}ZQad~culOg$#aA!5V*3izn z!Crg{*Bxk4EuEs*F+wL~o_h30wD?V_Cv!z8CymC?WJo`P|6_er^v^z`&Gf!RD8$mX zzuZlvP5gzS1Bhxksruc@*DCqeB6M=za#)U&;UZ;fYk2nK4#o9$f_O>B4hh7KaqH^r z%6qW*R7JVNO1E0lH~Rj)rJm9-Fb4%EH-N2LSD?|_ZBu}c6vn&_IeL~`? zRT2!jYWnJVklqlOks&BezV;}`uJn~NvB5gpcO6CE2Z}?cdSJ&(f+hE5BT7-0d&Y#G zbN~ns-bJRb;m-)wGO@QvJli4bkkUHpG zXFm?qoJe;u?fK^V8FyQ!!c@U(e3l*63J*P2MxB0>uH*I`Xz&-ciZQ) zcSbD9Fyg3R`5y_^FwI06<`=XhIRQ9m0wI{5?Y`6=Tttv`O2O&0fiaP|YlENHYP|as zO|aGaRHHuDtbL5v)@p?LdC;(ik73jovvYq6%j4`1 zqt53VcHFx|=|KbfkcP@PIJ6iA1I1{bRrq3rgIv?0Gpp6^%iI{*Y&#~FcA0JWAvNWg zMFs7<(@XTZJm0GVjpx_JcsQeM3^{wUV!`a2PzEZ-7fA*ugU))Gk&^`wI@sd-bwrztA*Kw=qLj9H|XSLn3yBdQ0P)905*Y47NR`t=j8^ z(@AUNH5jChwC`#5$xy^P)#BjYZ$qqdwb3?-o+p7np>3POg8Se}#w8Y{d#KUKhzxe! z`pT1}g4Op_#gV1#Ii9*dYhdyX6o$HeKItR-Rbj2w>Nw!Q# zY*|I_@%>*@>8YAT_HNS&Y~o=I8w!Y8Wcs&*8Q5?Sr!jE=>$xSe&l*gDVCm1 z6=)pt#+9HOzPB?~p*HLW#1*&)ML)YvEvJ_tCPoP81qDty*(WC~s%B+gfm$2Dc~%}4 z2hUUms@(Kv8aFz+hgMm^WHm?vpJk9oWSPHRoLXHk6Khgjr zdPexPaMe}gw3B&O&4{84aV8((X+`r}it_rIqK34zV_U&Q1{_^L&eLSlEoW_09>G)I zh3e?eG!dldmO)KkFhx6NWY$m=3Y`X+V0AAFI!4Q4#EaIcZ%-86FKO43(~+KOP`lfQ zDd>y}89#iZb!>dCDUdN74t^#C>Hwa-h=Fj2GtH11a)&4AMgMh}0`oVINz@vJRDLyh z&)gf18GYaD@%;T_-G<=?w|$L0?+t5F*&PSVbF9({Bzz$-b zGEM>~PCbujdbUD#_xH(AIn3>072oK8VX|mtqQ0NTozgmMP_g(E>UmW78mL#z9Q3mJ%P_vC-rR83m9o zR|1=+Q58d|=i;|{!6?odu1C+_sN3GpmVNqCsYvCw*plw2_{4R8r^*ET$)nax!-~WQ zq1Xoa--2$~QpGJwbn3Y4oj30`E8JA3HDOVZ%BYh|31?n~FKM3c&8<+k%IxX(=*87J ztyiOTh0^&5HsXNd(tTs;#2Aw8hJ#l&i}jkOR}&~6h@CA4szqzB6Ztu$sq2x)GoJcz zf!=U#>Ci=u0~O?o1?$YY(9fJ2ZhJ2Wh(aAUkTA|)lI#i0jMs5qi2{85NZO%!V5Jzq zC4?bT21*BasQ5cQbqfWy4aGChsHwP&(3&szM69SyFskP2T`HP64eSm-u{<@2e|<9U z`Rjxk{W-wW7+dP9Hw;lgx8xeaWFowdKK;!D^Y0<2dot^T=_4ij;#d2=w-uf}(_<@6 z1DQ${>KjKx;&imt(=+d8!zVnhLDoXuOrbaih8wU_Luu!&@87nbZi(7C*GxGjAXAiR z3X-xw^2-xhI<#-7=hzEjdvgs%4#vAscLkm()Oz!gd+VWb#|S_q;Q}g0u#CrK=jl-$ zEXnTEpSK-4Eo?h z>>vjUdag8QRl!Kf?_ngYg@)JwU$={_q8J+*)h+5f=ep6!6n{_0Y2Y_b6h8*ggaC`N zFTtmx&Ka2}Z-y@b77(1dlLrucwV0i&IFEIcof+y=XCROubgd%B0R9lXVCHw#&oiXK zRAm(14W;v)#Sz)1aF;3pXi0xQ-FBODq~wwuo%fsTorR3(kin=l*tyuc6JEcrLJe$n zD`k7S+yu8fiiXONO?BNv=uIoYtu4Tv^eIg-n#&FPg*i^O7W*w#qZ(IGg5;CMqz1N~ z?CC;Ho&vFA(wYu62xScvs!@v%vJqnQ*L8QSP!hlXzV+Egyc=PNuTxDiAgF_^v}Z!5 zxL%4OIx!iSas+obHMjtrMB5mB=1A6Mfc^s$czY}t9}rfI2DK*!+Cfg~Z<0_b*^iT%4$a~eX<`GMIY6qO_z|>2retbLhLN_j*}s^HZ2cnm z3?jBl3&&Oy5$+)n^5f?jSCBk$Opni>TA>*(&Pk z`x;Hb=AY0oQnSKT6PoIjex|cV#tcdZ&RRd)npG677HnpxGXrmudnDnDMV|+w%`i2~ z>XaP0u6TM0?#J2wnxXtIan2qXjTiFtH=ayrgYO!rUzP5PCKwqNs%*zdIAU|cz1Gv+ zI8Azqe@eK70n!soy&qU71j|wd?5e*Ue9{AXYLE+Z$s5^ehlqlNL;%(v`Lq{G^oo4r zz-$d9CDi>`nicU{r^Ys&M3C!+>DM~<1EYe|dl0z~V$I7(pdrd0lGlk;WCzrd?ggx5okfZerdWlWO=_+C1b|bcqat#siPES#t8*?OWX( zI5{N$f)BYIOy+@7js^^g(8h^k2+>KK+V;^FBrI{)^sSR6t{${|uM5_J=Fib(inOW< zEf8>AUXv1gS}1jWP2{9Qf2IQd zSp$;6-U@n9%(NTT+n>f`@-f+!JAc!`dzQ5r_X&@$f+A0Ld%gMEyORe#jFd=p`^Ng?w2edkMv>GAM)6VdsI=lvCVxgbumS zNTlRFn4CC<;niUX1KDY&i;*G6vx!8*6q=N&ZDWIPG4Gcweq_|9g-WtWi$kcjAay-3 zYRUjGyHF)kO&dYtWxLh<`pxh=GK_Dtj4+zIPLr0&@L2JoXs>=wwAF()n-LEFV4H8W zWk3RrE_dUVwnki4`j*?3!0>eI*z77w6=!`Lyf<1`0-HWf$<{fp)?3|rL~wP!fp8a^ zq)zq0Q*5@jo+CBTa_Lqmiu#;Cq~j>0EAf~u6=0o70^509O*dJl!z^IYZ9JJ)qKG>2 ztB>tI%_E^5`tZ7TLnd-%o{iN+Y*D=Q@Ljd9$_!TKgd#gG8KII~N~C7K7KShee%W^( zUV^ZvHNOOD_k1LgqNxsC#_z3fNUwxWE`o}odV1MKkF%|?Ym<>Ws6#A49^`wBCWdF7 zHeAF;eo%*(6rP9ELNB87@!kWvm)e5&Y5KTI+_o{+fJB@jS;y7}j}qa_wf={RT8#~vMR<1;4>+I4N&d*ItQZG~Eq4#Ry;$^ug zEbD*Kk(G$;*M|{%wuTv#QqyMGwb@7=uWr1Ag>a+=qBwe=8xdo~H@m9FLLV0?>l}kmvP{V&DM^2kbx1y#U%A}C;Ch~f^+Ggen)%O{_mfte=&w1b0 zYqqRmgpaN6ZYo-=hTqEg&mj9#(bWUQbu8@)DE2@ihkg*$MebKn_K(>IdQYGvZsgJ& zkOl}Mk(8dP0<)n%fCKqfbwtleJG4oDi5UNU3jax5V8*QJ!&+T!GWPe3 zo5g>AIil#_(b+TXwf?q*Fh=4P7IUQnj_U6O<3Cd*5~4p}F_B{U-&UvHmB&G@p&fGt zDAd!kA+6j$8uJg`u7<>ZX1Ln(WXm@EOW6NQdo0LzqGMi{YnA+MQ~vIN;gOgrr0;(b z1pg}}#Jv7VkDsY+fB4&52=IYUIFJ~-_a`U$XE9#vGeFaS_06*B?{8UV$QtISHP?Fb z$BzEljKnKorc;4Mvq=5#ZxKZUUNfpf_^lQv1zdZb7941#mBb|9zIIK? zt=X4gy+#z<4nlGy`?{>*?cvKt8l=$V!R6I;%umm3*nQy7R&mb`o9ouR_4Ng>UUjf` zpu(Tov9D25a3@>oaieSwxLia`c<-}K`D0cjoAe*5xl@s@g)FRHmxfoFTr>T*kN;az zc^9bWv|0AFw7ClhA&Vs4X~8QC(8Bo2u&&hMfFPzO8%pXE5@b)4>5(}irxW+R8|8b8 z-oNusm->eBd)FPSDmBHlm^++t-kdy*>*mCm|$g9S?AXbN9!DcOtlMC!-|W0oM?M9m`#itJ7ML+l>*NMHwV^9^TIC zYv{htYA!WD>lYoJ%)r)vver*2HA|91`&$gfmS405{KPGFgAm)jSmKl4#Fh}GKd3zP z=1I?zHI0Lr8%k(Q*B&lk+dzv_4?+@6}xGa z=s=Kle}m6Jm2ep_q`}pjRV%ct1V%nPLs=6#0ZKG7J;e%G^UZh+A~5Kl$>yVYj1Meb$?*XwQ{;?5^(FuLJW_0w%;5*im)#*pfP@nkRk} z%7MY&OK7n3UgI;Px-&2v;_|Last8B{@@U8n0!7$XH0mYv?odxO8!i9E$mav(m1acZ zS(T_7H^<_lZoD-`P=%fp_9mfZbv-98ro&!S#jOt`X>e9=Mt74Qw4`wLi-@&YWO=jV zvE=Q_O{qXlx+5AD7AG#4o*`_awrubT=u=?8A{KujNs`sJk*)Tr-9^We?_65JPD&kr zBGnq=q`)5T*r8K=jcH#vk9(UGmzzwKmwa9bpTL2nqv%>$>sO3Cz;bPJd=sctg#pjg z!_Q+8$0_O8lR0*A*F<0jK(KGsYXuyX`0+FVSBZpnNg@dy0FIE@2c} z{Z8!5E`U*D1nl(CQY55h04Kvhw(^=b7`uO*hHbHa&-|OS6L(p9wxppK|BxR)TiR-s zTgE*&yC$|+S6^~gHK$t{0w32p2!^e`p)!y)$0TxSjOSaS$xLd zJQItsGr7lO@?XoilX2L2j+=7v%obcX3e;oIu}It4Va$9GOj9sla&KqAbiHrBpcr&j zN72>*3y#X^BM?ZEEC!qP!x%1arCM*YvCfQ`z53zU%?ctNHL|+&E|fyUs;0DB56?R$_v%#*bt~h}X1ad%l=0E0V!dSU zj$BKd?RJ)nCwAvZiJ@=Wg;kX>G*42mnHkKjZ@95cdv+yU*;I9VQZLcrE zD(^Q6`fw`Ex(+qJ#=1Ua59W=`e}s%ZYlecex>tdr@MCV|;C&CUXW~bk$?PJ}X-1X; zwVz8L=(}(pJT>pjP(#qA5wqrmJ#S4%D=g*j5hhe?jljlAIijJykt{1QbhpzQ!)>;w z*#4n*^|VE4vlni(|Kh_NGB|g3ej3&hs z8_vADdbpD<8uhS~VZ=Y^SSuJUmaTG}j{4NxVEkS%ZcuPl8?@j3OPrY8@W)4tv*8M4 zFDe#XmAAJ8Uz5uRb)<$bOt5r> zaoe;N{HWe^%V32WVxjZM+72&kVsZCAtG-xXRimsd1^^-Q9N(s-zI5&00x`?rNmDQy#u}Js41p{Axs2D-GxmT zbSPiE{9B*qEY+Hz)F*`rof5xL-cD~J_eupvzCO`vzs&Z+u{3sk&M?-*Z5C`7hd1%? z$E-M(mWAiS;3ayS+-V3#?Fh|1klnhHG<`8qPMAPVnzzoh8xMilys4 z*@|lFf7;KVtT(AbP-{)O=*v1ylqB?GXcp)S2K%-l`RhYWxXpJwJ)b-x@FXlWQpD!7 z_HWSI{|s1p6j_p%5GP@TlQdt&kQ=o$VTMX@487NS92HT{S*T#rz1^3B>Qm&YA)a|U z_+DhBqlUSr1bdIcAf!QFwK>G)>6jG~%33PibpkC&=ZwjjIg&X<%vGm8Kzsj0b}=?t z{^$bhjF{QTb8bt?AHth&$?zM<#UfeE3wsT89^?@L@ms%O9{U{a$4;Yp<|x`BRn2`IFNd80r{zE@97_;_NGbWa&^-l>oI~am=ngV8W z=4BV#AFbu?j=YWpTPX;p)?ZRh)PB*+8T6Jo#80;4W`p&_hwXGCeHvrsg3 z`wnU_MA1}FF7&0h^`0b?OjW-(Kt-2IG?83p+jOj(0i_k6cK9_{+fyNX3%jL$QI-*X z)=C%xhe%l3683F`2St(NzA1*Eps*9HheEUg9FaTzc~L{zE;H?bU7E7Sr?? z!%@#qd#8krp4Bpdjb)>6|695>6iX=5govF716v)C4%cfJ!~@z)oxFvjrHj5>Q_=TTL5 z4`AOX;N6!Kv_-EIU6aD23%bQsqMv)4C$CzUKp`OH<4fy&ue_G;{n{VOrtc~%X{)n% zzCd~U&;Vto)#dr(LJ5f!yDZ^k%6!%QIqtpdugUTP?xKxOt9)}dIeQP2U#pIL?$aTc zSl7ku?T*NwPT9fPU$qOrPcLY4(rL1Y8koS+055>@2sSK9!GBovCc*tv48V9}BZZQH zggSH5w|J{&CRlvXsl*;8G?HXj!QKP!VEL4@dwh>@@26G zR2Pnr*RZ=E$Na`j=<|L~7*>@|a3J3&aNJ_P!W6@Wx{!gb70lPtnK(wH^^sb>(Dc*5 z!1U;k{5y%^-sM#;{pZANMp1PQupKNcE~qsb8r|hgg#UIe1Oxmhupf(Ed-gTs&CFpf z$>q@2yY^t*95_#$!}tn9?7ge|KJ)j_hO3g3@$v;P_QnNmFFJhf@dXDnTQ1R*8B0$d zz3vY(J6crv61I8rHTR8UO*E6;Q0^08k2_@F$@T4)!@5T-qIyXBJjQ3I> zE}d*!Us@8|v@y7!g(Aasf{_&Qh!i2fvLv$&qrbRcLO^guoG z)r2daomOC+K(Wz&N|9h9v8uQzZRCz?SxGptbYA&~mlbU)8}qluFXo&v*fGMNhE3NF z3115=&rR%d!gEz8Z|$^*i?oQwSxM#IeK}EHy09&rLvUOT6?NA)ZO!e8MXuE|4wgth ztXJwFfmO(O@w)Sbh&rzG6$}Ka5au#1f!8lWnoUV1%U-SaLpm*5c?cB4-Mx3lDzUTwgy9RyoaFfwKW@-mzKiw9`sstzB%YZ5@_)3}Aoffy|^|_WmxVks$5dIiApf7*Z_wK5THG5E{ z3BDI}KIt&wEp8%&DC{ohxv4c*Y^^@gI;?|QJg-q)ip~^keQvXz{p{UUPck2FIruf! zXO{6!q9XlP$im}p{X~?N%HDYX3bzSr`P*;A?&};s93y6C#JxkZyhR3nIMy- z(=*w*CqrEP@F-S*jQet~JNSM>sVPF8eDeHh<&C|~PJ6M2-B6QRBlo`53$R5q_rSqICz3(j7@#VS<{(`%4P(L}uEQ~~! z&Z+r%G_yLH@mlOQ*Z$Ur;H0`8+5V$0W0JvnS{t@H=VtY=&~VkuH;Q~Q{p1ijhDjtpX-8z0z)P0ig2yL5B`B+ zp0dZVe5;A+q=FwDNWvpe&di6Mzo$>q3dOlYY#T0GQIm$Nh{UF?eY(?FnDX5`k-^h^ z5|OVwV#KW9es3+fHMpJN)2KJ+8{T>J!+s{cPKkx|Zh*GFH`1)@2oFP*z-Y^D(|8B} zRx3Z!Wy^NJTFK*1&264|fmdd|0U&>M`}1Q->lKqt;=<-SOxBABHamA0NDn+ea)?15 zk+_oXL`~p#x;=hcGkY?(@KJqTfNR}dV;`sFwS1xwF1OH?17esqO|%v>HF1EmTcoV9 z213b{5LL73kh<4o=aA#3B3L{hQLE*2HFt3c{zS)v3t-9niVe_H+P#ZAq$iKpUWXf; zWzI#P;N~u;mgE}FOkle=clm%Wz3&PCXuxmIb)Fsznmv9rjAj>Q9UG(C={Pk_UhgPM z89KDvI#3}}wvmc|uoo>->b6`!ezRd2@imU!E9&yR+u!@LP`^%eGK*%*>>YK#m>idgzXSh~i_ct!YkGj<3SA|Ix^vy&1di@<&8%rT>_Ye-^O~ieO zW)Tja3TUcLq`;TIG=H6@hvmh(hMB|F{y^n_N>Z=GV zW+S|qu?APe^L~%o*~a@HMFw_~7rq!5d5FAf)X}7#X<{OTOx*;V^bH|d7`3V1nDle+ z(&-Hm_+C}mAUEH@QD00~kS!o+f^hl4p6b^`?#WgePEQD(vv8543>=9^uAQRCFAnE&LqFR5aiW3Angrm5{0aK z^FKxA`S)G`l+vDxQWZmF1{=^_Wj76*Gnx4>d;gLZW0mQ;X`Al zo{oAmV4o9NjSG|-PWF+1Yn`~ds$cklo^+)rAo>!aXwdig+_X2a{6u)E>b?F_)pW)I zvQSyjN<~H%Seu~Ip-c!@^V8=6sy1E@kYqj%U%%kT5m9t}U;lM|GlNvp)yzwr0(||} zVBe^vALq{n-F7&xxU8t>x27?@g=-y>%;%}at)gm1I8^1n$b(KV_9CkSUzXeys2QXd z%kwl|&%N3aav@w-q;7j3XXdc?U0;K1^Zqe^_TJ+9?4%$egUW{@%cy~DzlAxd$#C~L z)^yzn_0W6#jVFZ?9}9aiHyuC7dK395=)!qC+wZzDVO$QCjm^fFe(3Szl4 z*c6AEgWsUc7Y}eC-E;*kz&v~G!FW0?q|@Q7RuhE|oMVN1toBqUR5em!Ds4>_rv7yn z@vFsp zJIjUHw>#Hu>|0Dx3oc;~s$xPPX-j#v`BInj<*&QouxLKBz6k%zKn z(pi|*%h7t(@`6KXE|Ix8G1jqnMU6sO^vGT^TyKj+iS zqs}a8fi3Ogn9de;8#{Db-#^>&^qOk{Z>h3|-+kDZ(^2EaTRAIQhdkB|>crip{Ak+6 z&8!!p=Q3QrPJdOq*%*$$V7TqGOtd3lH>Ol{arasz)r9qf?7LSa$`vok8qZe`H=wVM zj)F^8a9kB>LK3IH%Z!&lRBm*ZsjxO{6f-4^s$arFt}#>K-5=e@t8EPbAoY`GQ}le? z-|#WIq2BpXre06S=!4*8S%u?Xzax9W{DDuLMRe*8D%96cO=ve^#HA3uxTy8Ei4)_p ze|?>;YM~>xN`*7a`;KVZqsHeU=dt(2^Q+w{I$HRdtPivH1+S)CkTPRG=wu|Z8BDmX zbup|y$ehPlgU;wTzw2Fd(r%r%gkJB&w|sE<-=!^=(w zFfC|x44HKDxZRu1-?)+Z4pP2TpN7d*IhyK-HYf1$mdItwTzeAl!v>k;ma;r{ugp$h zXDzu@A44cYOWxGwe;vywo6oGL%Dx|swz5p=@FfcXi6M*6w!|Rh?yu`iHv}?ei-Z zpVLZ1DkbJ9S6}AGdo-1t66;YSaH}(-*P|9&35yT=sK|D8qL+P95>XV_kzHW|%CSehRM9JgeIYdaeDkYHdo*Wm&EJn*sKA?Im3G4sE)?Y@|6)oGMaBzYK_k{&_cMI;p-CY+B3wKDc5Zv9}-QC?54#C|W zKF-;@-S542-~ZX#m~&Ls95t%<>Xo`wVl7yQ$#xO;^iYKH9F-a-IvKG64kCVGA2K28 z3|YvB8`>FhxacjmdT$(P<^PG}I-vul0zt@!9R|&P2-&Fc24CfZ@HXE4@D?*~7XS#N zGF&k_7)@29YVJH>IXM_;Hrk*PnqA?aBD>Hn3{&EM$#?*vQChJ19XMUa$~I#@)tOGJ zAF3|3qqTRyc8!PkbxJP#pZ~Y&yhHV8M|Aa*DwZdOI!90$`J`&!`Q~$w@#IKI%mht! z&=I{aZ_r;fr*87$cl4*pLmJb2+FN*o7uBGB9U!0eM7XNg9*ZQ%LcqiYjOh`g?>lEh z`A4mUKLEJy8%e;p)IM2!G}K_8m7HM=2(#GPOH|DHcx+h)&A_3ipeBm5rU^Um(nor> zP-vs-+dmTz6mnOaJg51s?t2ZHDkK2QN7mtoSY=rFrQEB62aNm*LBLoj88B<6 zL?6b*NW2!jIoKJgzD~I_y#8eQxHIC@=lDh&sQy0s(1?cUwQ^7RrHY-U$UliG3|3A* zBqFz3i_v}$JDPzgW(mCbqlK&`R=`UilgeThRuQZP_=BV-Dj$L(>9Z$Qxz7tOc08+|^?{@S1NiF^tZ{gY>C z^zXJUK*cL@J1l@`8Z@qO`f{bke*R2a2y6>PdP2xEDH6JLE7qif3o9t9Ms}5gq0$Ir{ z8rjXcL;IFH+)x@b@0_iN9zV{SO0B`BD^pC_jzu}i^;eL}2aJKapxNE~mbXWfXDJup z9qWGZ$MbsRiI3nH)I?UQP7pUcvq!e7XgzRK@K(9VVO*#QnKx2eAZ<4Vwa9RyGvac@ zEHD)kb?Z5E<+0g9#Rb5J=oKv{ELYE$G-=S?f)zAfIrmL&-2wL_CDYwE0F|T;%fW%| z%C<_ZY`a5Oi6jsbal51uYa*%i;PPd>!NJiq72!P!kIk)TTLtE96;n)DcwWHHJ=zOJ zVDkx~ZV4b}7_D5aUB@e9j@YWB>LxK2A2B6@UZk|0m%zRb1H%q1kePJ`$pBbKa&lzaHrT)z7aXs^ca*%y5K-to^>pb}cJE69%R1Px+ zhK%`iOCd`z5tv$e(cR1#HEpy7O~34o(4&QzYszw?{l4j2p8AUB*4Y{-T6DG zoG+B9HGSWKeBZ_jFB9?hJ&WxI;q!ftX%JN`S8u(?T1zcV-^T+TN`YM@Y22n*m^J9n zARTT`j}i60oyEyP*3grm%}$G3L+sQf00`*G7bIdf9k7!7@Wy_gKlgoj?CqgrHrG^O z$9*OcJXXd|slfaWo#dYEUwr^yzR82_BUBk+CR(=n25~>F>g`sEp#Nk>=_&LVBWE_? z(c-DiJs?m@uPv6x+)fdP z4#lh3FqUi|d507ls2`yAex@XpcoF;LysIV(&Ymk~Xx`5NwET`2E(n8i0H`O#-NW3m+j zd!`WYF27X>QNXOIhQu%Q}=koQFfD--f8*$fN>dwEGbwj@d_nN%aj(fp18 z3@p6L;kB7FO-tB9M8DtBb-w_c~xYxJ7v zq;T)Xp~U)x`+XLFcp6o>EX_J8oP3ZZAKKv!lxjDmqVQvqh0P}Mp+DP7eLL3x3!h1R z!D>Qpu;PR9Ue$g?CpHn<6Vu=TjB|BB*4uBPki`NrHIEw)Bn1rslQ$RM+wnhSL_*;1 zV{gvkj0J3TtG9s6u+0H$tS8hP&z5`Sn#p=az}c>Qi34qlJiE9}u`#Gy&uSoJGV4o&M6^ z57_|!yNg?HI5YScb-HaWz#@R{L|C?zS-tPsY&-z}p0tnJOJ{J=AGL;jxsgOZ-7*f9 zGj-x0r^%g9^*p)kkNOfV+7MEeW9pIW3o{1W6{(aam!0w;jr8=Vc@JP!*{*eQ^8{sUF|TT;O=SINn<1_Nil1+CVO*PIAedC4jan_wcCi;dyKR`gWG2`8vB~Y2LW4SIHKd1a%*|7H;-ZMczlw zWcbLpuv_5nvuA8;NS#!PPMZ)8!ny*XU|Dg%_vvH|1a}=6Cmp5yth{kR0utUdDqj=! zh=^R$uEW~NdjFbv@#~9Zcw?#8&Zj!ANJtjEfc(?K0p=L??;fel^W%M7I11h%x*@R` zsGpgukOZO13BT#nLXY` zZFn>fS9!DqgV5v+eS+L=hZs9iu!|!{wMj1i25KO^ zKGs6*KJWH5b2^9NHnRf%!6b!u5Q6>Iq}LWGH^HZ$R|uK*;22M=PYw>__CpV`p&Dj} z0QurLv216uzt4V$QtLAm^Zo!|0K~!iBk5}w|46Sj-`nts~0k+ z;NW&Qb8FTwec)i2M%_9^PX22N1NQA`m`w@c*i78}RH9|4(0S@*FcR=*K$D{J%Y8&U znn_FT7UHW@fBsKY*Z$?Imuxpp!!Z~i)_OH8c_e}79yZ67CBLNfH(zpno#Hd9G zF5e#fQXyDpv+w;K4{hKYbsKn4O8JFgFPfybs%&%1_D4Fn)vdo3DjY`fBH31)r9Qwc zvVJDPhmA?Og*-pPo+iOab|=`Kgn$}?DT_4KpsI%#i3Vl6y#1vk~j zbN_Gn7}5g@mi%=Yz7Kf|*u=BF{PCh^d^}b)e69jD2Y~!e$(t?a;l@Zngac?SI%MQrW`4QSC0; ztE59%&FNPF;^PE~H+3wQkN9kbN=Ou@bn4}t7k|fT{-z47uX&RDETO|>4YDn!W%p?| zUn*F8+4gzfz^=t#pUvb1M|7QcE=<=$e6&h3HdR}X;9rJ0?tM<}2H-^OSLh?3qGHy1 zY0xXsJ0dofe?G*pe@PwF6TQ_wmN%1|=h=FRHwT zD%d<^R-I5fo44PmL7(M@N3dI`)u;54quN}%C(Ca!=vO}7&Lx=A0&~zCSk!jX376IN zkoL57_pR0EoxxLm+?y(1PVZZVAW?wAel-&KgQ!!d&ptSIbViR`)fXCj!UGXG!W8Mn zA#?P2C4GN{(K4=Y+|L}l@ZIsDR;N(DX;5@>trjs=>#J72E8nKTJBEZDpB=r-&PU-} za1vm`=OBNuQ|o8Fx6*q>>2=d5?SFg?wB^VSniqG9FQhF^+9jU!tFc+iFxqPKd^O)-uR7#1Z5-}E1SR$?^! zgn*q5Qiga2+48xPq=tG^?}WO6y{aX zq=4s26QbTqgW=X^DdU%8a{>wsVyN#qJh3Mwifq_as|`Q+^0C+e)fK>Ta6+v^G?Dr7 z%^7w5$G+2)@!Df1b$`+p?r2E@-MHpyq3U69k!+jil~mZX-l|rX`>O_h|1tIE(qJ`d z(TIgYR?WFUJfAxu;YVNV!$%m47i4VbF~Q@dm4@GH3wVvWjAM`g)4}$U|4Z%`u7z)Y zrc0$KQ1~15m>@26<2(~Kp`Vc=_>FvVwWb2(zI}}R34n8ZW^jze{0PZCezP2WqDOxw zJ?j6pyS*R?V!iD%=4H$N5Z#WEX#Z56%n3);e3;xi{Ah9~zLbyuAnq2j;>~ek*5<^d zhGd0-fLI|J-XPOaRTbMV3WpMZi|{AQ-GVk9M*q`cnip7W8h)BMQ!8V2R7m&acQIRU z6<41lPnC5bKD;;RJk@cLy5@7ya?oPS&Bk*tEgOe|8`+}@x_E=Cq`RRECSxDN@7uUk zE)|l|U`Insgru2OX|k}gqMLub4vwHeq(J0I5Q`gPNLb}wzZJlHAn$WHSVY!EMUlA7 zNRCg<_AH?=B&4jZX{!CHE6N6uZiHMdoW6Xhg^sK2+#Gq2K}AM$~*H;jB$`T$swzu$|ZJK^!y z%N&CfRtj4`W2Py?N{odYhCzTD@c5w$er+`K7L&ji1+G3##!PCB^M_Sf&p_ zDTL`RW?vhZc0*|%iaxie>angx?Du9M{Dmw*hZamy-SDVwtsk=J7QG;PEZ#%Z%6LlT z@Wfm4h_yTwk9wT;3N~1IdcE~8h=F8I4q>!fjC&q8Y!M@~#1ESy->!?%X-omYpid{? zn;g&KF-Lj#=wiQsv(B*YrP3KQe?b=)q6};IB3QfRUPQO13|Y1}s>S$6XB26K)0M=X zpr>aP84qs0HdECLC_w(k|8wl{Pyoh_ZyYO*NoCeWqt=;@|ZXDbE zbH|E3LPOD(ljW4h?8dc7E#hs`+KOFq|$$8?eA(kYu)rN(+e zX>s%v|0!CdihHMOM>{+r#TJl3vLq7v+^WA(;{H~r$qPHw<&DDhMo%@F@M3hocJOoJ z`04`Lq;Y#2&t}e|24A7@3kICVz8kugD-tJ~%>`KATJYDjkeq8&wB;_Kl4Q_Y$f}6C+ zBLGs@owlm=?AMsm1xMCNlh@N21a(C~8%{m z3m@eoK}bXBPEoWx!DV0)e}$=l_|9pe_@mVwklSGg-F}FFn4*MEw?fx}*3Psf-YFV~ zpeWsiCI>U_dqCK2(mmxI!j575$k&z{Zzm+)_@88_jTx8tI6;y`NRNgzuqc!pu}y$&&Uf@7LbDEaQh4)vL{OR_mJLRH=iM8<>&eN(D-6Hr~EGCQ0enPN~gpxefxRLMi)Nj?n}K3 z9qie1ptX}7pA_Y5>ZPh^(B!Xn5F0!JSLPqk+H_9Vw$lDQOeB>3fSk1#fu#9e zX558B)BIL>Lj$I43&_l_)o!h?iCOFsTpxKuJ-gQ4C=pJPr)aY{1&LPZn-m5VUx{5<9Tj=+4f2iWE4^M_p6 zxDNE!xS-woZ<}1=B<;La?K-C|=zf&0ODB}`Z~|xQ{GD~G1U_;`FyOs|b}K1sQmXC9 z;%eu^dQ4)yw^hwg=CZSOK36rhbCgy(EOcneuqXF!`R##5_iI$$8rKi?6;syrj|RJC zduOjvb=KO?*h^@SI6d6)DD}gMUvBw?oL2l-p(ILugkGCG8(b6$#p@t^7N}fn!LR*k zvuOM61IzUn@RQIX7ww`q~+^yct(!_w230og+-O&g2k#WZA-(xLZPAJ$+ zT>_&T9uy}}W&+~&iAD2ImzTp1$VQGvUzdFa(8>2Rg}tAOt_G&&rUmD0ST#I6sF7PJ zMm^)PMu_k!5q|nZVrB~i;7y72MuL7UyJJ;aKJT+5Z3sY*1to50FnJoDm>O{N>1al{ zkHp9QWnNQLz%Cbqxmat-V=Q-N%6x`*uQ8T6Fv@U{5+Ixnl3F+Q3ESRe~8+)a^^Q&Nz^N`MpKr{NdWGP{4fL4M#!&dXAl zQpdrt^kC8`lTiC71l+_k!uXKX5$5xvSW-r_SWg4s(92=>V=ne{rGKORLa+!J?0=rv zasXj)(is?2K_eHdd2?X1}*>it$>R(6o)2yZdP^2a++%1Pwhuh&N>IlNg@i6B2(2;=@$- z9PiF9mJ?ubkK9ftQreXA-Px6|4a6Gr$Qp& z$C4zgr&hb5LBiXFe#esS>zmNB3w*y$b!Rb2auSLA7}1GFE1(HrzJnZ-0p(t7MSJ3@ z5jy=!=u<@+^h#o3nfaTP5W(xpFvESnCl#6MMfgDHHk34Go})8RUO9x0mf_T?(e7am zI&ffX=KkL!=W`~YFd7ng6dT(nw5doisDoU6YjmfHrR`;k+TzHxyNtF}X6^XGYw6oJ zk|cVp1ioTCmG6u&)Z5fYPUW6a^Zq&mGNWf(b?{%|g}(!)G?`R0KA!JRj=i2gM)PE_ zjJo23Rc7OOS~+Bdo&todX4+R(s9TKjdQq6Vn@Z>%>5%M(eRE92D3QQEh8p+?`+$sp>gXS`*2|5=+dr|8jfpP8mI};j z_TjtB#u}K)4c$8gy&bm9Gn_#)_0g`xPZTVV82T6-Cynkn5+Nj&3{W)1^6x7xy-{R=#CsY{qib7QYUur^YdhFkNG3VB` zch%BGT*v%(n1&ER?iML~;X_IzKdDlxGPtpjwD)Q}q6+$<4-SB9YjEJ9% zn_bkm=>9VQ=Ekc4Tn{F{;1XRqTXoc@Ogdh~v2#*I;)^FiGjBwif$K4rE zKY^zUo$2|f3t0zI9sg~^kBAOcE&&BjsHfhif+f!m?B3ZZW7Z%#mOWPFz=~d+108E8 z_1R|_*V6mV={)^)ll>+wiRbaGDTmrEYd}rT`}@)#8>cd9fc;gS%f6cm?@C?0`O)Jn zvlk?Kf)Es94eZ{`%c-D!*7}=SNwK)`8u{CF)w!;>uP4+ZVLJ3{jRg2^K6jy8@Ypfq zh?A1In@felu*|u~1X$5~&BDP}&)@}fU}2Fex*<<*>L&_fZ)x zJV{6*<+@bsVqOvQBS(y|xS1%BU2led(`A?7qp$dWXU^M`qQYQyPffV7p@plP7 zFZ5q(FUIGyM~AwMW&Ra^W7sPS1b>meU-x5U{5Pzspjltn4i>DP{R9SdI-(SxW$9#E z$22eRA$1#7=hOo$6zMuTWS3pXt|zX$LR`#X65mVa^~!@$&fZikF1=nI8}iWJa-x>e z|MK$M2@{9wwJlJag1KFbal!6(d70sGRc~Lrq;Zw(Z zpJx62*H0%k(&!|4JBnMKFf-y*L!b1N@?8MsZ22qCCcCUV*W2&6W0*Y*OZ_QZryPPD zh6}15o*QE-7%42lG358usq}&59alhtJ>B;KDGM$dj%sx6D-a#V);|IzP84_pGb)ljTCCdmX?FNi(MZwY%p5+$_raXgDwiveC_w# zjRe^i?rJDSINl*0G9gGhb0a*-`Ovl;4VTY_UDa2g{M_e5QrzVx9M9Xs06+#n{wwop zYR=x%wXu-4zB70^-@k5lGZ{oJ${k^DcNZz4-!sUbFj%zqwFY{T$)SBb%-FLU|mOC3~W=-7N6F zMvp0_Vg@bfy`Hqh2*%Qj_sT`@)^2}npNI+7u-n|2=G>`S(8RLz ztt0hesr^{Z63pU%R&9dOrtUduep_yyn@#zRV&Qhd;S!x%BSn!naJh>Z<`gQEApHOs1}ZjfCCzblD4V$oCJFxN-90%T1NR>AjhUOpB19}G7D_x)8y?dc(=aJoz&YVHbsK<)8|u~UB^Z@ zMW9h8a0_8=<7|)yALxYYSPaWN*7_OlCX;czedH0-oay#IuQ&gbcMZ#B55w9es57i~ zKKLC{G+h5>VjP?eO2n^H?QhG$AxRuXKKPZ(c_pjseeD&jW_G`2jn(TegbfxkbuP^E%uq|kF(Ow)Wea32;q+tc3?uj9?c&34F zUWdf*Eph;-?sB?bB5Q+!B8j>@s}8=WWGFf$(vEQ9Hi2tKqU6%YA$YCAlzqmbmPz`Y%wb;&#(4Hp8(Bfh_(^4eNW09yIaZb{E z?{P|1w&WC7%~>b_jL^Ysb52b+v6mn=Wx*>A)6Yz}_9)=?LC37-nFlm^vC9+aEB!EVA1nxu)l zD3xTf_Lh9AkRJ4N&KxR3MA>$0wRnhgyx6(WWU=9h*GotRfMA*G6Nk;O@x1S5bu_&w zd;htsX_*T(60>a>O}qpBj-Ricx?4CTP)bNe&Z%wRJjm2_f8y_Q7J5KmJVOH+eu6z~ z{tyz!DfHK~lH!*6twm0|7&MJEcOIE|zcfV|_+!^5QG4CrCk?d!9+cY5gqoHy=AG$c z=o@Tvnp`p?;Z6I{O$L@H-6~}d1_tIAwjBv3YV8J9n~feUqgiw&vlg~zWxXPd*>-*W zzH4%>6=FC53UX5UiDq8j+^E;_w;EwVIv?%-0i_@g<9>7=7S(6@+7Kn4MXPxh_X($Y z7Sjc>3XZyl0|G3j%q(ZWV;^X=hXGLwUZ50Lw`hGYRj@lcpvoRL>(Hm=($*P8JKwGb zr%SIpT(J--6?&p=DBTZkW4Y^2<>gkW-D&DMn2#3#M?epYx^~xNuAg)RVsFm$dI!0o zXDwktbD_q!F-1950_Zmy-hqu~n3x1}Q6}7lx`|c<*+yu^y2iWe&Yb@nt<+y2(Rt{5 zNAd&&ADiLcJwO<}<>^C~w1Poe&X6pgYmldDi^LOt#i8H@nLe6(O2%~5AMxogp6s4@ zn-hoRKH_QLt;h_=%O4yqhr_rX4rOnFEtv1FuUi$rdhZZ%90W>uCAxUN=vY*8`kBrY z2yQ&u!`ioB0ys1NBJMJdZL5{=(t7Za(ePsSEZLJwES`L56Yy_#mXF9(pjy-3_Qeng zu(+P4X!PPq}nP^NMu$N5W+Y%0?4W`NC5jXrCL6I~_I+P>)F5zW65aYW})Huwn? zyVJi$sQ~us6D7BCFP5{lWTrWNrs=ku5*)nV87%+BE{v<-E-I!(vZ=M@sGRHLAIKJ-=Z+%TUMP$?;Nd{Z@- z{;|B$q1p6IiSNTq7=wr7mF@0+O9)2HBuF%=;@{BqE>cxv*dP#H=q`=I6W~R_;Pr{n z_*6ii4>0-Zc6ETOyE$DSloRQ7`O@)x_!jK+%9pcC5O>)RmVUJP;5+0P{CZP_ESjfm z6?)aAD0TVB^}RkT_`Q*TM$Za!-?tT|LVqyR zPEf>JnVjeCs*FCzZdy0m?gfUOjV44su9DH`t6n1wTr)uWA@7?b7p76o;02Ech}n=( zFiQ|t9*G4q0@UiBD5=uXxV@y-B}|^CTLv_kui>`fl-z%8V@o@km^98jyP8S=+I+ub z`%2!^{qEHj4BWfEoZpaKjv|1Ma_#935x5j9I5oAejnrY2^KK$&j9Cqoz1i$*-#EFd z?Lya$fBD%V)Yqh8&|Bt=YBE$bWxQld{HS)9kZSDM?9K+i)VFH}l!deSAn>oZIjF_u zcIKRn#toyeSTZt>k$>!RO4z3Bsa>8XXh!oTP8ckgOd1qC=B<5Otzyhr`mj<0t|cXV z*ixGlZiI}i>+FQJx+*P*hF#Jrzpzq6xQ3z%=TVe7u9aJM;$C(cJ%X0WbXQmbdifLk z3KOMy@h0qn3UAQ@VZBOiIyQ!57sJ!pFs960hU7kyhNA_ia6(5&a|udMW;XC%Fl6`zIGvm>19zM}M3WDWv;NDhsu!H~YWnYuHH z`G*IwAK~Pg@Ahb!W!7Q6Scmkqx$YnP$)IDV24nFFU#RT+fE2S7+1#Pw%*XvpSZI3O zkWP_~=}rZj!`{l>wN1Wire*{QRGWYhA!7C^>C|!jjXN8{bx(}0_Gv&Ef#C0Ju+&;P z4+@{qv87;_-XNxET~k+I7+2Zoeht zt+{=1?~ZqkcE0vs3ks_BYF;Myp%af+9ZH95#R$52K@RWZAYJ5zz9M@*eztcN@A)bj z$^y=;f0{Yug|DqR1f8CUeXZ=G6*3eQngn6ht6UCrx?q&M;&5<`d%r)<=AgxmZ?`il ze!{e1V2x1KK$1yYPV|`BsU|nOhMqbK?^dqS#$x(e%SmQKKg&?~Cq z()8B;lgbVjVoWLn^JN9han@u|Z-~xJB&Ld$l$HCV-C%DQc%FxMk(|v7Dq&#}TZL1~8u;KRxJ2coPUGZ_qigyYU%V- z`H{2aeNZtZTtzx0y-ZZ1l9;PKvCA4Ao%By7ZNz_Vc44*J%q~lZCRYrKBNh!-AgE4r zlAh8s>bFx@$u@h^A&l4y7S9wDJ$GC(cCL7TY4i1vhHRv9=P$RbR-r>WRuQRysal$s z+}z+OpGfJr;(0$G->|N0i}%{qsBt=x@xC@jWxtCv96cL@Z$|(9{X%lu?UMVpc5g5o zneM^!S+9MjHhHaxC#WSZiG=#j<3_A*DamNHbc&_YfR0~ThUsi5t7j#G>zhhBZR(we zzV$)$00!QYQYms_`FdbToa9c4M8Y=HrsP66+A`R_f|_7&3>QWh+7J`UkuI&d}i zBZ`{s=0cUtjs49}Y1RL3e2Xo@lXNCY#%excBCUNLO$!Inp?4ahQ?>IT2zk2!SMj+7FV0;$krQE}N@mk?wz^zcA1AY#_6yolP8k2*%r=c|mtczzaevQA z#%y~RBYMjeY}7PV|D2RGdjLx5SkPlLcq4YCJ@zmhLq-$5p>o|8Y^#V(Le%}eJDMS` zNFeA(L1rd70URsW-JJ77o%p?f3DQZF{I|{VXcV1(VJGzKQBrbuXoBwYKH2SvZ&gkQ zechaXX#4=2*BFDcqzLG_l100`rb*zHtVC*_@BeebWqgKHHFg)k9^raI7@gJZ|MTG3 zqju9{e5D@G;O?%@LC(vfs=f2<`=1JLjQ1cSzJk;?tKShSP>rL-|DX#@{*CKD$Y;L) zObj2`$befQ@rt@XtKe_Q8y^z;&(Es5%fG?-^|ZVsq;~pqdH~Af%L}=*wKa=UH;KcS z3wFY2HKm2C=X)X#h6<~#ABeY~v*EHor%lcB+gZo=*y`j8`C@%N!5LjKdX`36uJFc zFmCWlee;g{RY9-*<@xvcb`Z-dlksAl6^DTe&KT|HBi%C3g$})L8ighRwhnyTg}?E}-p`JAjKld3;!yron0Hi6 z{>09{?^9-oiN?E`ecV1QxbAtoInFNPzy9uRX*AJ*>-}I&^iRS^2Z3YZAJx|PNZwuN zOzDWNLC_XV@l^|i>k@MPI^=-9SPk0jslQa!Tjy0CgUhxs_d5wr>owf7#1{abfCpt@ zvL*o#bNuYhQdbe&_U=naCfOi)y`o|+qH}OQ)%})tQQ#&Qs?A~*QFgX&zfubmBaqnP zxkjnAcVu`tOKK^&2jpgd`39GSs7Fd-T$uOwyf)Y#WXz=S_u$OA30p1)#=Pf7 zQW&fgt;3C2vndw~j={5+l5(|=$#Uy0$(aX^=YyaN;%YyqQQ*{OpCNxT4PoaLt!LZ@ zH#Mh)>Ii6`>TH_T5lm?>U)qYfj&b^*qq|dsh_jUn*>KK&A&p|4y`{}n>|VvH^gwoc z_ZoOq-Tf?YSAob|I_+tTqF1H%$d;ep-C0_n*(-CtJbog2f2^%b7)3{ow<=^~vrMBw zrBePZMo?cu-lKq11=aMnxH4h#g^kc1%2#m}6z~5G){V;&arxn+qkPzlvVGkjb3%e~ z5*N0PqI!4!R&yiBiMl+Bkdb)`S>zdGfnPn5;It=FI6{?QHySq!8|sc4c{u5B2l(TR z<%SjB-^juD4?_Q`r9=nS&AOwvlETy+Gy4n7wOIGlSGm{x7=9=>B3Z%A7-5qe^%cFR z34_a-cIVj*eK*GQO>4D~BwP2_rk1}81j)11$*fpO zJ+I-v!wmn*p0_v674Afk>gIgX_9u)Zhd|`$+dlo$l(acjuNCag;D@4~>EcB!m|hRx zGYezrVL!L;cedrk&R}9B)chY__B&xpv1BrIDPFK1 zsEmK+EF=KlQM!SUsImSgcVGvCI~3!t4|pjl;`D`0WXapdPU@?5Y)d*dy1yK_#JPHU z9$adWjjcL8;i=4DTGP13!8K~0EzVx{=;?qGIIHT$OZy_LktxRRLmDp!1LElJx&t(H zxMr@GF9w3Z1C(L8r4ge~Kwa4Vfm>bSLqcC0^QI)2)~rKmjRwysX^NDYUc|{wQIj9a2ruLO;8sAw4tZtC7X#AK#@= z+6@8K3Ahy|9h43PEF#epWVg;a(!z%WyW9kMK{iK{)An1Ia^7{srPota(Qr6*wMG7t zVM{D`Zf2)^-slI6215yTBH>Fsxy>&9%h?$&{oD?i5-yF4ECm9xz3uO(=b-^$L=Z8!$(@o@ByC)j>`f)b0O>}q7UOhlDgw97>1h-frE;AK8! zwqFvhtV83(%$EDz31U-(9sn~7UEe8xISvgfh}!w~pMv=RV6LC9^|K!ax1M2#FF7sA z3o;eXLv^i2mm)s-oh^6pE|~E&Q_Ek@{h)Hb`Runba4NuNigcR04KqV>#u3SLB^>d});Bf7khc?gRt^HRNe{#;!wF4J1CQ``6*rD%GrP$?>5ovg06}9K;To@3KHMIn3%Je;3apL{#y3LW>z< zejtY-B9|nOx?jMY3B&SYt-xCf&j0J1{%5Uj2?$s_yWkyL%<3?I=ekB}7H2F%nS^@W zX0^rGPpOu3fmO)QoLM;Q8&iW51Ami!OfPdxn4~aIXug|WZ$L&kE*RnJBxzV40x^w= z3xgeC?-W@XDm$itw5(0CL;e3Z>whgQtPjs@nT9i}3kM?you1Yt`iqAkr{d>~wVwNW zg-$r35WG@cR#J2>QuxLL})4Ij2;%|!j`+^nxRMtH{Z=ds) zVvzh``mg_Mxj(Xy?W|K2n&z?r<-e(h)RNJ}^u<=6YVI4DMLe?}Jk01RGUiOY#;1rmwb<2SnyBTNxDiRdgCM2phF z<=zo;hx}iQ3PbQAa)Wt<%q0WDB!o@Ewh{}Q`S=BsBVH!Jr2BPWXCbu07r=j>rjD@m6!_Q75A5eiM||Yn8lb4X_nR2OCIib8NIi4>BsF_Oe`TLypM69+%y&zihWoGB8=D>f-zp3AYBkzfnKSK!#`W!vS77r!u5FWlMa96r_y0%0m@*nZq&9xe z6-Zi+MM0UR%)Ooz3&^F+CR}Zatv93Vb>3%P+iU=^)NO{GKbw)vc&bUibx`+9>ohqc zTJ*L!3pL;4qa09HWIH->LT_unaB{h+ydPMVtI_(?*WD1iD~H}U;vyDdtO5m6Hx~_sH@RUj$R<|W%z-WYx!=E^L$-J zHl_dkQ!pXg;Oy4d*U`|?A&H5Jxp~0?UgsPL|JwYo%!Bp6X72rPI$I`SWZ)&cx3J>e zK1i7sACj^gm0L_G51Tbgxt>+8giO*W-=1w@`t-IRdF&b4&?$J`6CnZ#VOpgD+C;ar z&_AvxNcv?Bg?!(Bd^hNf2VuYulF`ajwzYJ-4nt!SumDg1`hzrXeq3*DTR{JHPzosw z^`Bq<*DvMXa98~782Moy=rJ*29tSvoYeySA{-1h>o&9dQ`ZnoTBGlTyflm2DMy1_|6)27_W>-wLx zWrMbAmHzr*)V}Ti<;(%SOrKfP_GZ{xAQ@RUv^_Z)**9$LL<^mN_`Yyv9~+^wLvF%e zLJ;^F^X&~C*A?26FM^%n#S54ZrAv~k6n=;4df7?)7`OPGd4DYUW}C@MeC=E-5@=0Ec6;tC)&l3o80V!Yz->{yJLVDg;dDo7Cq3G`h13@mvWdY( zMO09Yh17)qCH(!Lun!3P;V-fpX3XVGPV=Y5U+@}$?xz!!Z*U+&6(IOsdW(tY#*ALU z)zQDvQOAklGEdOh^PC1mrK(`J$@xK7uess@NVr9*3DDz$f#D_7UKIl%PIP~ zVTSxl{@&><483z_N@hPcnlRgP{Uy2FSEmCehsg`F-EF<>VfC56L}-Pt-A{G_W#8Bo zbzrmRs1_O7xw*<@Mp3ruEK3NsMZbfwf2j7@K^IJ1tndRyEk!hOLi?SDf5%K;tc#zRrp2_7+eUk9roThIzEV14)Z*6TvqlmC1w z9=lhb6xtigw8L^uYxcIgLMd0KtY&CGWx8->2s5APsuiY=Q)lg*H7WIp>ieVJr+vIk zf+j^7hjYG=vRlRcYC~bnE0)7N{85v`IX5ly);t)VED$y~%}Ot|PE|u%ntAV)8CTm+ zzRu$)DbIISpZ043!;5vX0nJ-)X1QC$RvOg=n1wG4%(`NgwQ%kApjq}Wm~vP9WflBc zxccOr#&&sV7Xm5NSwn$&rD<1sgdUd&6Ju=&%cTDQtxue*pKg`j6&(%?aG^D4dKK2G z3TK*MKe%1UWT`eo>M5t-L(xn-q zly$AyU#Urx7y5@aU22Xv_$u&#)~Q6Gk(g*YCcwKTv2_Y z{a(wzbG$F|;+d0DXWsEUrm!|>c350j_u5FqIKy5AWj%Zq#I%!D(mQFcl)EZ$EU9gBk7*ir zLF3e@Enc~aPh+jhi$6?^I>{TgiZLp;`B}k=kh2DR8SQ0^;K_SND=<}aHgJKC#qI+O)0AIcS!=lEQ_%|L!%wvgJ)#-PWxJsxQAo+|L_VYv{UV1 zjA~hw!{g;U-PW+AT%G=BdQ^89)0TJh3O?jBtgW|wxn`}IiK$$xb0~14nQ6NZQqq7k z6|{lYZWek}!ew)Y$!b*j*Q*FDZsAl$?5fOZCM%kK-|ppXz?ETG$)2 zl-b~`s`tvqn5V_3HvFEliH5SHXQk%c)TQ2?oEKVw**a`P z$&1q9rrq0@7VC3Yl|Kmbj@?epxJM5HMzjHyG!t&AG`-xg*L>Pp!Tu!Xc*U7$h3$IGI16w3n zvVpco^vW8C?Dpmc_AwHU+sqV&Hw+LZ7R0lSHNpjDWntIXURkr%?9JP^cZ1TbGS)k7 zs${A5G?K>|ZYMZrm^CNl-nb`y_L<-teExLOO;`(b)8n^$H|EG41eZTJf?4AV)3sTS z8_edNRTg=5_w1oyj97pMCTr}0C}WOm$8J|wzqz+8*DK`ay{9R4I7~(NFg&Vo#muOJ g(U5ci4o3Zx58C7Z)a?E)8wMcoboFyt=akR{06F7fw*UYD literal 0 HcmV?d00001 diff --git a/ROS_Core/src/Labs/Lab4/cfg/controller.cfg b/ROS_Core/src/Labs/Lab4/cfg/controller.cfg new file mode 100644 index 0000000..7b97586 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/cfg/controller.cfg @@ -0,0 +1,11 @@ +#!/usr/bin/env python +PACKAGE = "racecar_learning" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +gen.add("latency", double_t, 0, "Latency compensation for control", 0.2, -1, 1) +gen.add("ref_speed", double_t, 0, "Reference speed for control", 1, 0, 1.5) + +exit(gen.generate("racecar_learning", "racecar_learning", "controller")) \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/data/data_example.pkl b/ROS_Core/src/Labs/Lab4/data/data_example.pkl new file mode 100644 index 0000000000000000000000000000000000000000..d7a90fbc7acb14e6432c156270669b4f31049fe3 GIT binary patch literal 166563 zcmaf+cRZHg|M*c>%C1C(P(qT55?)qmm=%hQ?23|+mO{ziWXs-rD;#7+SqTw|>~-H} zO8VV>dguH5tJCBCc>hz+$Ll)hx~_9x=XK8Yyd5_NlarB?{r;mH#83LqYwJxrORIar zMz^d@ge~nXY_DClw!V5V$ZNB{wTaQKn>M!Ac1E^Afk9rB|NDnQUeq^@|NN7{pmSs{ zLGt8=L9RjPgZR&ppWEmXWKQWtX>5DX%H%gfVR|gc-R;lcZtx#^l^Swm8 zx-S(In>DX>UP!qcYRR+()1IWEWUoK5W3nf8LhaHqw0`*o*Q)X!7)ZCSH*-o|rx_cw z?)bRmU}zI7fs>J+`oQq*E}M3)RCMidYK;_wxfIc+t6gZk07Fw#rS1A$H~ci}KqHFPF~VEyK{~+aw(4 zh6f=TJ-DZmmVhSG{?J^362~Qi$}#kd>?l2*17Cr>jeOwromj;GA5B=WdhcC_i|x%; z<#)<|7!J*!;SA}HL=JCj#;o{dq;jNWn)ZJ#!Nl&#XL-gJIRf1VFVjmDLeahd=on9? zuUt29eQs1EY_SwL3iQ#!?b^PCsmIAnxwbypnAq_-*A|Y6kAd3>XEQ3^ z0HpKz4=wZAzq+X;2}2Vlc4UiuAA^a2Af_)%{wTUn_>?BKVR@y&27xX2VlecX2v?qC z2IIhT=6HCLv_Hz~{g1BbE4Y^yjG==Q8iEz5CSaoo?0l)=hmf@E%f|axrO4FoZT+>y z6+^E=zklG&IM`DkF5Yk@1Raw5LpvVH&&d4cjiCo3Hiwj1Ou&NQz8gQeLlB>|LeUcI zlk!UWz}DMo(HJ_T#bf*%%OptZjbsnFK1a(Ef9PL~cSTS7CSqun9_xye?vrrl&FObH zo&=$Zomp-nRf$ptD>B)lUAU3y*sZVm=?^9$u3IaP);$oJ?D~&pl~g_S5;wM7oC!bo zsC^Rh!k#M$+zddavT;8X+#AXV^ljBvK4f98{O$eL{tN0;@MHh-oF}V4>f^2M6^xpc z%IUQ=>pho?q5Y4@n-tVdL5fuI!^f7ssF~+Kx|7>7Co>O2TeE~(*xZP)cfoYZNMxQqR(82iS5M4a3HpH z8YJB54KLllh1551XJv>uDD8N5T=$e`5r*z?-rd1xI}Kve2V<6|HK3W%moC;(r6R|T zPd?{SF@|oc3W-nfoQ4PQ$OrCdJb+@BKQzI;u*4z{H!@{CZQSy7+YIdbrLc)v*$sZm zKHvJp=bE(I+mAFR*Kp%`gwOt*U$rw}f9Pf(Uq=8i%lx7JBon{qMdI4M@z>y;`Gd2- z-Ja2K)j1UEWT)%|S{y3;ZmXpYXyjwsZ6zU2t0^`MP6ksvAAUtbg8UzvY}#bfgatPX zwkk?7Ocu<7|4LSS+?f~Nm7y)twYvMXz z$HAJQsmu1)E7FeQVO2|eapRhIpFoSN90BzGL!KT#9uLWlRx4~Ink>e1&n7cL_;=1^ z<8CYT_zVHgZC{ms!4ePsYkboUZYPlAXTGctNgfzFsy=A{J6!@u=Pmg7bH~9Erj2?p zNwmyqx|A)KUts8fLAj$wfdtT-esAE*{TyVIk5SszT0m@cuJEEv28OBNX~>Sz`b2Xv1Kk)na{5*@jm*XZUDWuw2Sc|9ECkb; zPr*lv1s(N<0yHTW5Ex}cBV)Yh?A;0Fb_{*vY@w)G&Lq&dm|mkBDn%Ka_IMw3{094Z z7cJvG-(hHJZ|bV~+zEKMAbTz1dIjQMVfv*qzJ}O1hWHYWwqj_Se#2XF*%Lss;Z(7L zZ6#tm_&wmb`cL$A?`(Ikb03D@G$LCb?uv?6Kgd(Sjnp^M3_UBiMlV%>Rw`E`#D8anAnfQ=b-?!|6w(%nyuuB zU!an4+$5(WbvOw_JBk+HFX|nGBEsXd`yW)Hy=8utjR)RArRWRxFL!a{+67k@k$X*} z;I5`lUKECq_$g`m+>m!b{xnzW*y#ZD@6o~Y$fg@Fv`KlY0b|@ZheE~u8Onlb_g4`$LGg=Tv0Kqtc`!_BXB2AB2N=`5RC-yMPBVS`y|M@{;zW+o=e-zOG&^!S)NB-(*wY^+Ziz>%5<`dE#|DuxvBx0N z>LZ3e?*3e-qjMC}_$LacuDK$iPgad>gM;X4>pV;gc4Fw8zR#6RZ;in-^Uc0=d{1Fs z*Rg_5svTV}QH`$W80=AtO}t+o2+7nR8?VLp!2Z!d zW_syC^8B47+Od;eK%G51Po`k3|#n> z1hR>3Zc5+|?y9{zY-CvRKjGHjgxd^z zv|mmF%T+exAodK1vEjaMvdb7TCGGe3x{Avc8B7Jb9H^&&(9lY?e@_~OGoQM7i$wEU z_pX%fz^#G#TwlZUQ&Z5#$JayUn+9$}ZnkxS(!l%tg>)}7ZamL6eK1@aHwEu&x~GDr zlOb(D;1Q>pAyO=8AKT&(iRm?a^Nl}(>89ay&hXt)$z<4;cHXCO)dR?Ayts{=OyS?} zw=4T;^CE+3C{T_Fkh4gH2H|5bGDtKzZ;cHy#*L|BdHoEAE;HZ~dEZHxG8|q$FOn!} z3j#73o;uH2dCZls$Vn@2sF{Ipb`D-f-C@vF=2cZiqB(9S?b`j(3PW#tnA#BeY8Fzt z6&+mNpTj=pF}GA3KlID))d|UG4jB5j)}yuu6th6VyEv|17zB!(m$jGYUC^(^rUUUQ z9vHgXwl3o+8v$6B_vmka6a)q(SC%7c>OfJ8MzNWc_5Hig6{JPr(K7;k{TZ)%Ksp41 zgwzg2lIVo<{gux;6EO4$LHyHg61|%bp+edai05tTn8>?}c(dyAI|gwxaLMg}ngkO9 zaE@=iC&3mD_U7#scU(dc&s*~M8y3!3e5DU9Z58=$0og$ zs7wsa!^fD~dw>XEg1<{jzk31aX*2tdgrq~jOyr!_Y21p6ef3&U^Bp4mRBG9;<`WI| zY2LjzwAv8whXt#>`5BnlS6TO23TG2xf=9&Qgl;_OD!Qb{B_u=TzNMwQ&$u_V+R{`a z@6H_Pn;r@Ky^WakV6m2M++$YWaDFxgvBrnp>>OiG@gnY=AWK6p^+)vJYtuP0l?@?SC zQ%?ovN6AqdL#{|hJxaWm30IwKNz8xVnKuUp6c>xSW7ELGUYYARU3rnC_Q16`Ol%G@ z-pCs-=HS+*sN)B{(_od{mb&k8HpuY4uj=cL#n87IruNo_&4Gqj4{P<|bWr7%cT`!b zL5}Uk2g|GiG4#=C$&imv=YU()TCYnk1G-1#>7_puqTktG#ngEWebZ*w9rKJiFjBW3 zsE$g3Hp_0>U$hBu%1W`G9O1G(3of4)fv9O$d z(c$(<+A``-bFlI5gAo_+IGEAUsIvc|4?J-r1~z+e`FYEE+O6iJb08*Vtap$)8WO#7 z*!3rGL%f?P+k9OrCU$|UxF&P+931Fy;mLU!3Pn%YVogajkLLxDEX}~sC+7}X(ihKx z>{-jgCiVc3tXaFI5EX@ZQ@w6)kj%u;8(whJ>Xy#I(eqywqUD}J#PGhir_*YIXDeN5 zolP=^&SEGT;~AR+=FaP;vUIt`=jFHmlWpVg33YH$vfA< zd8^Na*zPFcX&=5};}(OVS0%gd=bW4elWyuA^(pcwQP}g&J`$~1x9?Tf^(YLz1FZ@^ z;hTrD&-Jel_=urMGtb=3Ka7#$z#NN~9qw5RbeXQplbr`Uf38!g`8<4l-Tw8BOa+j2 z7ZLUOgV4X9wX%H|4nKP|4_^J@_Fsdofj+xx%$+S5@kkDQmR7@!4*D-9zFxPQhvDE6 zj!C~epxr4I`Y_K7csk{jc74WGg2{e~3Z$Kzhew(|l))@UpzoB*Wc`~?Pf zr*2&v3&}t?+a{D8xA&pp8d@nn+xHmyREzt@LwN)c+L-f0;Z*@r_#|`hhtEct&vcLd z-_v(v=%||n_9-d?C`lcq@j3PqHOZg+T4K0ahES>~uw$VPLyPwxR$3(GYh=~avlq3? zP-06s4LvmhWR4}BOp?IW?mgEo8p!RRf#a9Hs_B0h7ogUe?LAj`GOFjWTktnrGE z?4cBy0iFx>qkD#`5pQ4ph79(3Aj{ch+$DmWzwKkjJ_zle0gIP{yzWJ>(fz!@3me1h zf$aPDY(ujs^zXMM>Ep+EITAf5Bfu(

U2!Z@H+scMZso1xnxSeTwO|siM=Kjn`-3 z5{v%yeuD;-`K$HxC+$@rn`F9NYf*}cZL=r({PWQnFt9W1ZxC-ly^FeD1i4}0KNV(U zrH5OO#qQnSpsh9o9f#jCFg~nDiXOhDc6*0GEsaU>O9*Z~R>(PG5bHAo&7Z}3--g$r zQ$f=SC3iN+_*p9_?HIe;7>O1s6t+6qgR4@-*BYc0T_OO* zh6{l`b_r-xjeT9W#bs3a`4QTu6^*&_^Z5>fdNl-iCpntZ>XV2XXd>$phVLTBKI#Q# z1%LSW`%NLg&*gL^0nD!m87!rwB0{dBN)(A6sFqxMCXtPyvqr>=X+IJ`Om2tT^7#y; zCQzZPFOdmWcj)?~3~_VGrs?|?XpsOP{WLm@c{0!$TI2oSGwz~pp=&)p$15?h$L>u< zxf~-x++2&Iaa|_bV$;P;k$D$codaFHgenYuOCYmrNPq~6)AwdQ_U51_dY)Sf6c-Si zZeQ)^30&->x@Sx8Q4ryiq+9)Ei2}qxMtMh`MEiL-+R3n&V`4WQdXckBnFvCwXXnbt ziV^!~OKSL{3^^ini#wTH<+&F5j-Eq>hVsgLy>q?UIdiq&XBN3sSB z?=FZSM|ED+`xgr^^i0d0dWYk4;CX-0%=p_|lwx2y8c==`WOnUcrO3qXo(nVHxE$y) z2T}8NZeQo#q3VeN%0LqBXTH5gR~onfT_C;O!Bjm5mY2uk={%d!oSw10HBko{cwF!y zP~!H#Q~dnvC)?)W_Cjj(-1fIdrhZ@m8s=?i!XpYOzF9{!S6K*08g3?1uHW)({Kq_$#BY9eFRvc4 z874Pd%W9$SN%wEc43(JJSKK&Fvgj5ds(nd5|6?s$$bM^6(k=>q38Ovj?l}6)GkQ;I z<^`x}_?+`?_%-TleIxLj4*i+6W%NK5CbrOnlRX#w7C_7A(y`L!D%5o_YPYAb4)_Ls zi0L=N(O)O8XXw3KfLe9B3bMBd?a&jEX8cTA8@-a24)nm$%qteY^^}WnU1&zDleD`= zt!5llw3ZFuPIl%!UBI>brL23D;J!s*ymN6+P)!LsvKA(JFEIc)mL;Zs)GWiad$PIj z*elgV=shlwOk6HP{ENab<@p>CQ<03U{s8X%o|20oJ88QJdt?g^e%)4x>iJUl4@;#0 z*TdcFUkSK%s2$IQqD|f+)X%ynYk$s1$cP_(A<>n#kK{{>BQaN=e5vD`Z2BSyyrE^h zemoy>uWr1t(dPw_2jw&*#a+PA%((?J`GJejIJmltg)$%MQXbp!bRhyclD~?tGQ!mz z-V=>4cfMGJ`ySa=`xOe%xCcS|4pS1yZKAe^;xCoXB#>ZjWMNfE5cPnx1mB$QGu+88Ht;iqBLZQfuMgb7-^|yVLPm($jL{6(s3bqD9~fFcVt_1IeOI zvoGQ?beO(#>;oJ$87_cZhVymW@7|mP=Qn%qN#@DZK~)Oa@~yS>YI3Cax#{ ziPj(kHRJX zB(8iW-2RyAk9vVluSHNAD<0{Ks6d?$cFnQdbpYY+P;`PUt_p42-?Xjr^&<51?YVf_ zy$bQVe{nx&GzDCHuNsCK;c7iMoz-OyUR;9Vs<#tGckYQ`(^#vfz*fOeH;I4eU zh&He;a|xumchi@M*Px(n+twK@EEShNNJbWvq+d}JwyKp zn|jdmHL9>|Q%bAOM>PBj?UoF zY97g%pMw%4mOxKpsOalbQL1ljUH zUtRWM)GA!IAWE8%cb}L(DCCE`-#_ej(h2Tfgm9CBjP9U(L}wRfEMh$d9)?u(r_*tj zgW9ZE+v(l~pndZsmzbY}1o)z7$UapfZvUXJeTJ==E1#`8mOc4?0qzD=l@EMPM)`q# zZjybKs9)i+Ay)&Aw%X2oEFpdYELAdgZ>)$zHS(F(G4Gt<(!kEFFVSt7*oR#ORXh|I zKvQDt6%CW;=(=}yX4uV}uM-qYX44kf_kAADL`8&2q{KtDL!V6k8v*n=kwVoz443T*orpCM zZJ&o(8qPN(0Vz=IWWa0|xfyoI>zJI?z>RAlRNQ>hZypM6oN;}tlL@TE7mF&?ixsp1 z9ljSnzm-ALInhbjOKcYz6nTu(+om8MazxO;icZX8% zQq6*g?!3*v>4$0`3YyDsv*0F`<-L2==YjW1^YYZCOvtvSu;-}ZKm$XugPAY#F|nE4 z4zv_$%mc-9J8E}co`gnHrQOGcV$$w-Fo2MRH=<~Zj4`vk(R4d=pp=ltNe8gQ5 z$&KVbIX#VAhyG08dVw#5bidCnp6`2`0V}@}m-3WOp^5He`hnB9^_XYJ$Ni0s^I&~u zIaMbt9h9TrWpWt@!`HOidi1Qg{M=Ze>QLmzd9YYpB`z{$f#yUX`=n7YOqp5kCNflD zdM&LoT81in9*(9rG%E3DgYA#IHBCpJ6Zotv3MQ_Z$InTjmm948KmnvZR*`nSHGf|)s)hi5$ z#@(@_%STQ~sgR!Y{qA(zR4YNnI70Y0y~LZ#N2tQhL{Yzbey82o3ZHLEeSK-kryT(LQj->f!QOjQVJj?rh6 zr-$G<>q=|zJzOo9oTb+7N(%uV+Iw0jq~yXPRi6Eb4kT4t&vvw8VqdAfc;rFb4D5{E=q@K2i1dHxj>w<-h}Qc1?w9_;?c@e9 zh%MJB&p@!4u-EWpJn~9CGG|LO4GK&(&${|LFtKCH$LG6WO@r^-_RBGTiAdmrL(I*U zDbS=epZ`(Uj-j1;bAJxyPJ`%Xebapg>F7h(+l<_T1z`7j)Kc__fxl$CFYT&B`AW2N*l zZm-6KLohU@ata(D&E9RB%twL+mk(QVGFHxcM1%{K;+~e|4#}-rK~u1h%uQ*~SB$hp zzcF~RGgMBey1uSz>cq6W;Z%3>0oy5HcxA`AN?(pT&e9K!-(ZsA;Sp~?MTUFU9z1`; zzr;5MaY7Gm;vQC@)ncE{H%w#bSkWWK8#{4pB4l>SO6>V0jQRV#el3EKTr;&Mjq(`M z4qK79&x?D%EvYxGE!0myxkF(UOLqm*zwX?Ak#!XmM)Rk<*>EG1you6z%Uu(od1!b3 z(56aMBVq7L@4!zWoA{)qcwHaUYnrpchcz9?!H#`c^jv%e(#srfNCQ{5W4Hq)7YZ}3KHjW6{l_v11T z$yX~^ESyJRuLkJoy3YznN-O6tH_T(&1r=g4f#I0D8KyIdI#y+Txa#tv!6 zr{M0TUyZX>xD5N0m0sxgNzy3+ap%P&4kf6ItliFefd~daVpJDuahZo>p-J0&($@+r z`&}}el8aDlT?)+nBm!4qPtp$~9Nqu!he1;QFqA(NX=4Z~Kopl*MiA+{Nx$); zIx?NZmgeHnVfe;U^Jvfc9JEn!=&0C}X^5FN-llp6SNY$QWhW{-{1rGZ#rr0tXCTJ2 z6-D=+lIRZ!C&J}%s~Y7If4|%AUm@*HGH1G3Dxx^TQpF`W2_mnVm7orTtc-*VHq4F7H!IL}zi8opu`b`s_zg6#^ z$I*&qv^&&z$ALGns%CgR5vig>hxvB*Nt5Y13h#P~o5xZp!&)}UPeAvnxIX&gMD*fx z@Uh>t+T1PPR4W{vSk0yX@W%v57}zEncf_L$rQNyR^@SB&*^4Xlx;Q#CuIHL_$t0*O zTDiT)o= zCU;qZWOAjD|(hqmenODd(n^|?%|gf<%w z0aoWsmg??0Y)txy?nQe3`rBHeV&-fkjVyWr@;w*{AEqGrJ>C1yrRM}6J)L-zCQ zJv$Cu&cq``@sxjL8mhU?DwvuK;IFTz^=N7G+dVkiFL;M!%(*EzP^z>iv+XYYb>^rk z=bb1C#a%fU@5vGW_z93Z?rhT7*uYnlVgQ~c1_HN`;A3nGHD+u#N@3*`Y3V*FPWS?tHZ!HKzb4~ra z>80HTC($8~3gxhMnr!X^bFQf$hIR<&6;Y=4HK&u2+% z-JWO#T4`ox`$ysM*Vp4HM$MQ1;R%Mm?`vVPM%e@_X4Z-uAmaaM8^ib4&$(gfLq0X% zjOJfM31`BUw^|YKMCLzNP~)Td{H?wix<5zsXFpvz5WIGy{)y0aTE=ZDUwI_}L$ikD z7EDf50H^I38e|PeKSo|x=8|%zm9Wm+LuS<&dRuMV@ z%W{o3Q|}h5Z-@M&EGi*~qu28_M^oX=(r<9UKO{8c9#*gfZlckMZ&-P>%wwg?JBW8-Pquv0cZyYtz4ws)ztGk)a^?)`3& zUL4mWnWZLg?bvQ+qJ@m=$o`k@jU|8gFgl5&FC4z#EBSF64jy9I#v}R!-fyD#AKjqn zdYr-(cjYecPw3ZYO~VmuhTBiJ1Vgs-pKLEz!d*k7A7P%B=QJ8(tZLKn=uK3*lS>3p zTK>uQ99!?+ar%U-m{3zSvG)&8!`2ZF!(-cGf!X#CZJ@@}WpxnutofclmH)VE8f35V z-Q(Dh0F?h_djpc4QXji;Z%M-NforOk)3Ev=t6xDl8UC6fxk`^N+a%-WZ@LA(FHdZy zp(A8((K*Yc^=!{EvEN&T#TCsjY`h!OkaS46Pgr~GR)hK?y&HBuHORo_qR2q_Q5tY>=$JJgFc?GrGx z;I^g(p5{pqVA~S?dPC59w&%#SGwbaST8O~SiPW(sYq{_EMEW8~(aE$@9W zvFqNL52kQV!o>JKb1`!F^=yw^d$!3m+z9=<*PdQrn(HL3LvJAZNqRcx^?Z%2{J5HC z7;gS{nlWkl^l$=dXV_JiUO!yVnPQfGd}l~A)4yZK^YT1f2%UgkYpjtyO3v#!6PdHz znp^{JE)lcwWQkOnfUR@paUQ9z>zPN@HQJ;D2Xip7HS*d^F0)U-)DMfH`7_?|*HUPu zB(MCT1$SCv^NZIz`0B=?ChXI=pm-2GlKf*SWK2-s8pMiQNuJEz$spV`4t>gWIZtcD z;qrf$LZ*(sE*@swY;b&g!j<-*arh$PIdfei2L4(KWeV9;t*~Q@F-@oQd!=#USw1Ne zl@w&Xt1Am^3oODYR+Kw^z5CkF*vkW+$)(U3;tRP2}`5C->?<3rc6${ zixOjyWMmeK&gX!F>mN%YL0ayL>tWpe=A8N(zjI|2e3}NY7#zz5i~lTzty=Uq?ziKf zHFizq(pvpdK%B>(vee|lU&o=r&k%(dow#pXxa#(4291vZGl)~NQ01*V4qs5jOPq24!x1Y5VRNjJa~fbCSf}$49_*{AjUuN!Gd{(Mjv5_`n5k41JV`m|&7L0zWp_ z8vim#UpFK=s>)J!k2_=N$*5x|UbT&YQi{_SiBHMvhD35df|e$?E{0w@{rsBVj!_Uj zYAA1B6c1*Hwsih>9Fj@1N5!$3z`w`To#A>trDsRMJoZeO>e(0Te#OV8jB6JUJ7H+c zL0Tpv=}D!e9%*-E3R(9nI_{Z0H#zHpp%02J_Sw6Q!kU1f!nRHicr~7I{(o0KEdPqz zF91Vtq2$Qi^=uSWx_BFgBCXf`ij{0M@d>P<82YTpl1on4D9BLlMc!#v=xRDM4?D@u zD1-K%HkpsY&>1V{@pe1LKs3-m=j(zGx~yHASmkyC4fq*4rF&eq0IlWgT*%>P@XK~69lQFTqT!J4x zd^iR_BR+mtiH<|u(Vkw(fQ$@YSaA zlg7D!Kj&#Zi%iqy<6u^Oma2DSCc46x{Cu#QbRO9=Hi9dv1VhVnRcz?IG662u^(P!@ za#28Wi{-()B%0EV+Afnu1 zq!o0vwyxzN8~AGqbXr#A=%9|99z8*xyv^e4$#O4>~&cLHGXyVqf0A!R>+Y1PmGRehM?nfxn(X+GJnG z>LT1J5ofbGs#@y_*sHSf`~po51pV}#pO$DxmG^FIK0kpwHBg=Vrev;i0{Ue3|I#qX zUH1$+((%qE8sk>6!D>P)?J83sJQJ4nZ8i(!v+ihYPv`*yn)2%w&u|&nLU>GSWSiwReIb<&Ig%^RL?G;By(_w6aFm}pkh<7(J7A4(+# zLkUo0m#sAI8oTb>A+?6@j!#7(mGsXvjr!oLxB z$C_JP?zh|}Kyltt>qBJm>$bjt$0sy1j^Ne?$BoaPyRnT34i|sT)|e&28wWj~gMs;o z`N8PfT_(6^O>h3p9l|dHsO0)B*}O@Dyv_1Ohe))4n*d`v$t(KrQ8DV-&rq5^0u*j% zGHk5KT(|WFSXRY6sKB*5s6@gbVU+-z*=z#UOtQg$s^MgkjUSS^l61~dEfW*_MEKZa z#&Obja&D`PUy^dyZGB|$ZPPQ&NDK|(Dc_3ph~TH$z4GG(X~zA}w@23WblP~?1^(Uc z@v_OE%W*_-yfe9bGAbLk?%YhI&%cWv&n-u0zly}r#215KSN9U3p3n9ep)Ci#7kxbD zKr-gZMhvZexSE2Ye`+&OPu(Pf>6Nzo4CEOQzEefai)74`?XmEG8ABRt{&{{av4hPj z<~b3bIXLMQzD$9Qne5b!&(pzRdhKAyodOK~L+_g2N7AXU2sPOU;Xh-c|2|vsJIyx4 z%yKp^^IHXmPOwl2yXi`V483OcSEO^fa@6l%l9P;i%$S6G7trr5#N7+z=0YRNZgqUDbT&+1GNo>iegK?dQZ)iBM;7D%;801+jeR zw&iyuxuJB@nyJEZyNdTI1RqU@5+PpagUErRC+M#+FUIP^lg+PjZ`K$j!hx1sXIpmPLw}8VTt>aSIeKxi7n#4!cg7Q; z)qc%rdb1w7_bl)BPm(e3S1A>-!V5PWXzgbvt63$2IDbb%YT4y=-=55YP=fDO+)nOM zMu$KVr8!u>S>Ro4f2PV?}*Pq@Ax?;nbn(6$ndXOeuH&F{fgj`_ z*;uto`u4h#6Dg#);hq-vi-!*k(aeE6)qXFXxR7<<9+~K^eQnXWlUV(C_vO#=%z?Vd zFJC$PC}<0R|3Zai>*Kn*nk*87qX&64X3RT@aJo(7$Z}K!gdJpfdx+%Qi}`U&_ns*( zZ=rcdV>dlVgk)Egsh}7QPL`V`Xi2_3nd0yBhyzzCN@J9e6KNvCV?+0Qn~b8s!S>TO z;k8i2zW>c->n)ElBh!?STP?*WBAk!hvDZ-P`MRx7k+=U8_h2}NCco4Zw10#MNj%iy z$5R5=ZGEzYtp}|i;pP&xb7p6nhKO*kPG$3H-Dm5zKACMd?;p3vtt6$2Zm=vLo&yu- z&w`h=4zJt#V#M9-j=11flEIZa!3DN+V53Joy2Se!RX@#p7r);g7zgJL9XeKtY4_nJ zouY3BbHEtkpBP>kwC?)LSsO~@Ypuu7$Cv!dLK{fF9x;=_hf%TXuD_J7SLqigTQPLE z#^vmcZv#o12(!1YU+V)}S zj>UI7M@c#Ip6HU7x17pRm`BY4j<3#o0nt#$ObGfFWuMMl?#bH+2^_2#Uu zZG7{(>(4Q#FSYnn8HU!|DkgtlX$B%qCYdU0T9M69GO742^Dt0Esj#!sWMoq7^7dd-uUJBwL^H9=F$xNv#-Kz@8zkmh^1{ zeVs#jb8IOp@pGu)C;9fwAFfbnw=`ntrJ~GA2lHtNS9;j>juk=KQD|B*G!_DVj0+j^VVH| zF(YrSruX1#*cZfqre6Lw1?R6x9@sCNzV7<_CCIU(fxZC#{f1r`bvAiFKLuZ7bevsH z)6j!x&cKT#Q($ZTp}Q^?xKWXHTUK$o%@lA)oaPLdOGTa^mc`ddrohum6uWQ9;^xr3 zy1i4is#Bmu(Kg&G{ePxFzv$Znir;YbGg*lv^et16Ma7qFlU9H-IMwHWyZ#0|*dunH zLzs5=ie2iu#4-iaoKD>-Ka18)fokm+3RDwuxkJrbB$L*mDPVo7PrjT{hJLt+j!1t| z2DNlH|3g=B_4Ahk&CPbCudZ4>LfsiXE76I<5|RIz0*S5g&Ih;aP)BE*vyW7b9V!0! zQlYqd-7`pjyld**!)KUw#~RJ*YS2#s`BH?z=}k5N=NSxCJKnhWDdtK26ld?g$#n|K zlKqdbl+>3Va^Y^w=phpbOj<5B^8*9{Yt_<1sW#i@NKP>(d}ybWH6qc_SLmH&gy?DI{aQ zl&f8V%do$3=5&51osJQ5nHB?TUo*pRxzy^pkVK~ zNM6)}_HlaW|E3M--qY!X7GQdYLwCC&`e==n~c&Oopq7Cg0OzE-xg2&8{+j zqsA8Gw4Lso0LgJ^#U?Hl@C+AQB}!0LzMla5`o4Xjx!sJSf_V0IksOC=u7lbQ0v zoxZ(;F@XRsU+0?CKD|Y%haUg@PNMw{ldO9TarAVD?!uHb5#-C11POLb?Nk$4V*@4xXaS;v)GKZzOA}{x&4GnxFQ4Lxo%W-+plQ=z$_4@Y@#F z2Zq)lHS2`{cakBIi)vGP3_mV+aQL2MP2WfaRo8C!yDwg^`xUvyo(vB3Bw(KNv%dMS z<=+wE#C&wyNOJYMUs1;6cKGTS+^)k$uZ&Gu9CPqg{Sz8KT8+5+wt6R%{EFlUeD^|w zBPO{dc$1wBgpFKMQ5@C{u`FLUd!+VQfGO zw(L~bNObGkyUL+^6_{S5XCMAZnNI|xVCtUlo^RIOjt#a->OTysF!bdw>MCNfq>72D z2HgveCS-BY@SsprC-Qq8)6l&cx9_hiea^3p97!>aMR2hcLk(JHL+V2ez!E)CBQD0Xxn%A0t zGM7b!D!TJJ`}lBGXhuR__g&I+UO{-;)X?w_y(@P#^&+_)X==OqU-{!s4RHJ1YzPpZ zgFJzn^os#+QLw>Ur6P&83e&q#1h{>F$;%FVwyThSBgiN+KZ{gvan9%-yXi=PGY`6i zBi`b6utUiLoVs?+!JSl!_rIdwpgpfwY26;rz^AgXeGk;y(7#6qp^e`ugGja9yp%?9 za@YEGGvrdJ%ZFu)b_~5Ym}oCb+I7%%4sck!T8o0+Ju5xzI-s@Mt}0=zPk(V6(wRFQNSUUbb>#zmx$`7WrlzUqf;fLz5ij7Al`Ve+PX;F6p5~V~l z4>sb~-;~_>8z)Z@;mqh;cm4*F9U_FUNkE6>mDG9iEy?2prrkQttP^RwiJu>;q|!irXSDKP3|}YHhT7$VB=rl`!!Sr=@Vc<|noP9Sh?ew14kro8nJH*OaQ` zi^}tn+6;xT(k!mmcxB=QLzU+sT+U*jwo)qkL{_-dr9L0k1l0?-3gD_1UMsu<7a2%C z?CR(7!&E8jR>}kS$;;YmaK^ko-TgfNq}jlpCi2ZD?pUN=zI8z{qZ=p=Ua#o5h*w%wr{xi~ zIMZ|6a9NLi#nlb0nMBy#e3DJ5G6;PP`_AMYJ}#tDF^BR&NB2YcYs9QR$uhA!_cbPVovgV# zF@Ol$%fb}ftCQic5wmvJAfx?aEru2h*Cd?RC!JV06xH~EHV6J1F+*LN8aQTgt2yp- zTWxQXe&3*`zR{#hz6kyrF;{&DkDFdd#KbmUcqBJV%5rBP zSF^Rp?Zt8j-cT7QojLHlw7SY4T@E)hsHhq5jKSPuJ{NHncS7Y<&sFvVmr3LIj{2wG z{Z;VSr+LY(RkQLIF5{{iXw(=Z{f5XBgC%zEi?#6Arzv~y$^-gy#qjU(yrN0jw)OA~ zd`opG3eOJsVSMzw|T*X22W zfG?nFA1-$BTc+=HTPC2oU{`FTRW7*oAE}BWnLrZ_ztuO4;c^H0`-)~YrDL$8RwF~5 zDs$ZgIx~~R$omwx?#udmswfleA_rE zMSR(5#o>vxdQP$Yrs>mcJc%A=82XV~jo-=g2`IXye9ST;09ATl`Jcly^hl^g`DR=l zd6_}>>F)4J@Z6EKAWRjGwCQ&Ik3M1aKF8+E9_M++eVyy+q_~GV{ckILHOd#A0k<2ie3P9b z;5I+C=5?lIlrbvSQ^NIYUi|h9(Arm2+%6IhO{EH#1~Go>o}+R#p?yfVS zdW`Uc_hcw+GJWAhh4E7xIHjbAd{MEUjVT7#vgR4^SdMp)C_Wf&(^ordeZ9d?RD^7j zTXb&l^emY5@>`n3UNYXMuL@Iz?_euHvXfeT?6ef3~S zf>bYeA>tRSYAGZLam@lAoy%Mld+ebL;fzQGrZ(-lM40YE`C~06)LK6jXTgJ9`s#BM z@8N~PCXqk%)zj2xK4h(+#yr`(RrB8SSwI(P&ivt#JQOwVkN!hn9aVU1nH7qfYwc_C z>6u^_29Jj@2 zPk-N;J^=4-{xEFJj}rfW8)A>MTV+!QZq<;Zs^8M-Vl_Uv&jP>cNDj9X&fxY%&H7f1 z-Fo-nF2C2c0f@GvGCrS4i^3wJMV}IK-q?U6^c?{mn0j}AiI!u*2ZUPIknEP(z%2Oq z;M~iv_l#+tg=i{=5;P2o4w)NxJxUN~i^`4f`dsqRy=)3*OA0xjm@1RYx)<&H~ zGvzc(ch_e@QeF}H&L{eCoBS$dUh;$INC={BvXhC7bpmss&BHh5>IECPO@7s0%o{tr z5RXv5ji8KphpBgDX6akWe}vEc^||)X4FFe3`A?ML5eW62BgBibT64hl#8>~Va1Y4S zU8gV|UjWZE9Alx<`hrkj^j`j&>N^K=Tq+5(OulfN{HjQnk{rx|>baOl;HI$i99Hwb z8boXR6>gJX3A!ov3|Xkm9`(`nESZuyPy22&fmA9~x(3 zapcgd6aCD4QgL=`(*om79etFYdTuvccNoO{G5@w5;ux`fo82m~FGjH770O<#eX!e} zeg^?4Y;XIcJ)b>qu9%*e!FUj4Y5}O8tk-hF^19> zCh9hxJs^zoB>hCflVn@wK=$;?v!J;YoW2TUDqqW$p?rf&u^mnOv*v)cU4ze!=5*L^ z6(?Oux>wM-@nSkGPZ6vM271d$m~PD0$4 zh}nwU4AY>EBtlOIDw{em^X5esR{fS)FV1+`FBoT-CY@H360k>EnwwLCl7Tu{2K$KY z@27$xIEBvWJBWAKO7YA%IJzv#-)tETlZ;`%qXdQE-0=d57%tTAFcFyf zjK^;j4335+b$LhQ98u=eB2>@s)*;$f?r5&MdT|ug+IiHss)fT4@-P<9>;_<&U{dH2 zfU15wcw8?1b>9eBvtd~*nexXeq-Vr59HrS%>OJ4rz2##@0OQB(Ip632oFn>XnCgj4 zDr$|L9AqCA3LXJsChS9Tysq$y-y`0;9#t^<_0i#yVALuRN-HeB(l7$rWcE}RW?JJM zQ3b9GZ*n@z5To|ts^UB4W20cN)puu2yC*nDG-dbPqcKKQOmmHad;MMi2pEYytz)2I z0=7A#V#bviZ=o2`cBqNEbo1B<;8^oZH{o;y+Z<7qd9@+(KGcppReryOMs5^D*eQP5 zpJ@ZOsaCxWD%1O4pmt;pn=WOEQjAn^m3GKN-3M%QM1v(yc>SbAS=dgD;xa1pqhP-$ z=$>K;1ULyaIZ`}53RUOvj_pQD{@56Z-?2#Q?i~QONubQ^37i#oQ66-%?4w+J>2bh$ zR`xLIydS{XP`zd(=buL)#(esxWaiC@ap2NVvx{HY2W+!EiRSm|x3vT!)P>94*EoKU z1D>1h@h2|0fo(Pv@r$4(IV}`<<{9ChYWuSZ5S}P_>vx+yaQQHB=^qkk+@YkqdMFE9 zqhg=GsN@9rIJ24@&8rUzuAfi+!}7fGj-u;ooG1AENpwkrCie-+1n~5G2FeW#a5j`+ zXUdhNBPcsnB!7P?)x!z!jB2=aM${hW9scnT%aiCA-IDc~1ETG~=v%$q{1ZTW!9^!j z^#lAWx^wss36v!G9gd&HQ}jcLWDy_f_SWrCb;cDq6fhme0*o`pBd0?w)WAk?q4 zik{SWO@iOlmoKlK_Q2^*D*bhA_aaf2hiCSelf_tdtFVH)Wc{QUP68#$HINEvi$Sza za_YgMDDNq7K)b0ZBHR-vfm*h;e{GRKd6EU^bq+NyPl1@qX>%@N51a(bJaNqNyB8`_ zw3Xk`-Ap$F!so3GDcap}5-4*hIYVp?YK1Z?JJu~)&w$ZgVK#j=t~d!)@cQ$s%5y07 z-u^M}CBh6a<`Cl8vay2ObSF#c>P%`m)OUZsTQWswI}1#*Umvutd=0l*o<#9-@mwWQ zh%tZny607F;w(s^s8f-=D~Gc@3uRB%J35CT)CL`U>Aag}L91MC@LokdoaIUEXu+kq z+Z&-i7IyNp0p`WF{1R)dq*n%KVjuN|xas6uT2S7ptVLC*SWFrPUz?u=CwN+ENeoSK zJ`>T+y*8zOCgAVuyU}Ie0bk}hFmk`9ndZuSoX=Eb2Hdhr+!5-jKt1Qz!gJuwh3e7! z;_CnLnN}wDD(~|_s40Rkl+N&DH{Zfv<`zp!<9sIQ`N(=#uNy*r^5(BPdD}Sv?kMO7 zaK3~%8FKgT!dMdV7LHK!IPN=j@)C9%X}?$Yi)0J9 zO*s~zj4&{&CHfFnb&5i&%IHfrq`J!=F5D|6%zVWZ z0JOiw7~6#ta8?kvOz1{eA1ZcFv9tXA-n&?B4cS@NT?bM?FT1M$A6`%LWOb?C0aOJ1 zy>4}B#Z>|r-YMn(UNsG;{S=<{SnRrv@`1^=47MVk6M)o`nNks722T5#HJ+T-T|vd} zMLliq)HV~q{ihb@yX#WGHm~Q2Sui}xiSlCS92|W2j1d5D(Ozb8szk6&+z~Wp{X1V!;U!$i)c=PagvIbc=vFa+;lcw@&p08xp+S6EUiL(ckTxT@kx>? z@KNq;@r{@ec&?CDiDQ-kE!8f}MBI$c+tz!lIeNLtzVKg1uxp zZ3(jFI!2p-<;kpzm&{QsG$pMO-u0LOfocz>+|7;Q-XKT&^JAEr6(;l#pw7^f&!-+a zPGW>5XmsrRkUvfuB5v{&VxBQa{9?t=xYVCyj)BP9v=*|rVSwS>2^N#zgFtZpQ^lD+ zROH|PC#kUQlaN8($8Ag-1;;4s$6u zr--|^oI&_7DwfMP^2|&9))3g#w>j_4o%$cANd4z4b*4(hOuZ-|W+%ij1cvr(($_V>f8H<_CB1k`t5<7qIP;~EA> zuJ)@o)@9(FBEi+BIQB}^`CTbB)f%!f49a;IFFCPg;+!I)h}XTMz9?VNhht506^l}x z+8p^@mXrZp6-|DxMf?Po*N9rI2`HOMmSpi;D)}g&`shr5jU^3C^L7;33Z+8#T+!zg zhfp?C{Y(wu!&Pn}`a^(13FQ^rj54}ZB6+1yc4wxAa3L9pm;*=xN9*Yvn z_|J&nd)cbK_LblSsOG#hC;L4aoRx{(PX-*p34-@5IUj0$tDY}kRXRQio|PqG?^!1S z+HaTjw2!F46SRisCeFtr+7{dkVjHkKn%|z7`;}Zs1e6lL)+;=(gCF~SmE zf=R&_E>vXjlX81}WA`-pXxN;ZypRGo6b~Eb|8@e>g4SOTi=!+qLG|xsU$LrzHEtjJ zYprRZl8Y}W9#eZLonE_QkBWfvL_}{MiNxM7vHx%+XC@sGZ4|t?{)e!%5~(6rhT56Z zzmIzWv8%av}M0 zT^x0eDeM_x*gZQ7#y+SuEX95Ur|Cu=VlY0FMOB&k2_lqFWceU}ruZCo$K#j~@1FcD zoX=!=K}d}BQ~+YGk%)}TU+%;1GW`_ZjZH6{&$Olf3rhcZ3;u5P3~LF^2wo?E^Ih@b zYm8YqpUKkB@%CsM%J3p(Fvj z>k0_q1GUgf zmC1YmZemm(SdxG1xFyLvc>1F+afp9GiQ8C2CFn?#tgPH4ivmjs)y}Zw4!$H~a3z=uRHv$)>a_X$W=d zdzSIL0P{=crKO@x-Jy8`<+c4wrSQZ#`x(!5l+84hBwDe6efJ!%n7 zS{0?f`1Fofp2j>N?LT49jJ*mG*jM<*sWk(h*lXx^{#g{F=aY|91`M!UI44RDZc&Iv z!tV3(vo#X-kZ9)@mv~NRgj%M=^Q_vnd2q0PYeKFm3T_jYh>|%3v`v-Z-^ct_&!uis z(s}U4lE;UYE*jd;?@~3v_)J7E2Dr_eJ|fgA!ya2l$mYQmzfWh&d=$*IIS`^Tp${xf zy^3zdqI`p_mv5DlAIxL7uDHwXJEP!#gr)v^HU(6!=4k$SV}dRA-usWRF42t$7%+6Y zRxB1HEae8;9%V;aJ-=QR-ltcd2Yh$C$ult`;^!HPBr=SV)EmGfU=@tAxT>@d)TTY3 z2Z>#WBikbbp!Gi2@yi$^Nl;U_x}yUXIS8j{UpUS`4<7S6hO*eje;GIXfh76M++!ZvPI{0lBFAW3hS`EKzj?kbXQpFKH_h zCoD;KaS05ZLD>#H46Zz$SY5}FtKgo5awOO$EO}6^j0|5zS-C<@zXtPJuxQOpe3s{6 zC|Edfnm6S~60lTk*66tvf>__OTpIJ<*jZ9WF>zUrFA!WglbG<}Y&WD!dpN9>`3<4& zWzsy?+)e;qqrX#6@302KU4n1cT}cIlyN+I*b}L4x-}i>c#k?VaO^(1LVZYzOgLNh8 zNA{2k7GCC7@kHKDrTHG4TCkr0R z;Cm!D?MaN@7E$j{K|?+Zq?nQzi}#_b2Hr-N3T89S0i*u47eg%G;G~x3x#c^vAb5oA zTKNlA+QEda2C=S3zkwh}#)_6BYK2w+ ztfnXqqt?+0`FrSl!p=n{m)V;`z^}nQpXD3s23SI$7WFf%3asBgt>n9)Jrs5Nlx=)! z2&C|eb=>_}jyMg%Ig^y!ZV`ae;*TkxELCV^%OmwGVTT}hl9%2LZ!JPS=qlZR28+i2 zs2o|Hmhk{MBWX^!!QwgU)?Grw12b3b{Bii;H z4=!jCnFr4a5{nnc697&*a^g>#{D9h1WqCMHb|qpva@dNe#%wYmYTC!Cno8*IYl9#?5d}@!w@S}L$u!F%kDWKI+%E~)9))-oY#~* zh*6H*-X6@%b%6-=i&vV|m3jm)&&l#uEle9s5H|JCVU#03hTJ>*Nox`6m-IpEp6+vi zHcmje^l1>zDROCTygDq=j8KcghP86cABzv-3*LX&15%Z~F7LoNMRFIUY1@K35bBA+ zEoEuWSzukI-m)to3a1>Ax+_x(u6H8TwZS*FkJw{A@YVQdFDj#P_23$8jCSinsGsz; zFSl|}fqWHbcW*2=lOD6h8Zu-G<4M$>UhMmUP@g*|Fis{m32fCrv8pBH;Ebfg;#^@v zs#b)WgKD>f58njHqx5KVO)7+BORMpJC`TQuchd(4>Je(8+|#X6ug3wq1w&f3Y!S{# zif-hPd-$^qp-!tK^KlCu1JPR4FJrHiz}u8+Y-<=J$?A@bz5Q%HLM_6mcvF4vICv%_ zBH=Jl0;vt#=|~bxVUg_@^1-GIg!(rPwH}?wIH+;g58v5R25V?eyb{J3Nx|buJ@Kd8sORgJ56shml0| zzWS0B_JZ8sE$rR)1$Nvq*sZ$+dKP`AYRL3UmmFZ~-jAN45h7s-HStrYFTL1pBoF0X z-+p;lX;8V?gvHXztG6dXySePtX@?q|k<>e1%*0=SQi}~%Bum&$f!_JB z;IfGtoRJiqnN>J}-IV$JcNZM?`5aR*1vKODe{dbHfij2QnEgXJs@a$ybU>+#CNAld z&rg9ZYY&mi-L*I)Dfp6_OUw?GIx1a@RI6YHlzD7?WKXVz+KCgl|1gq*eFaiowL%d+ z&!xRO)~_hfwkk8&hY z6O{DR9HD;R8ZLXdeHIu*dl7HC)ZvsPqS`#__u22k-^X0x`9&Gkr8(f7`R=LB_d1+% zL^Pl2&EDmKP-{)p=1{R?_rK4;KtYE8C`T5Cf{TYTED`FgpD7s@_X(hn%SvjwtpQ5% zMy_!Os{rVHUaeQb5Aof}7ujoyt`I=rvtyEnG#X*x+vDeXFf}u4puDLpDxS)bvc*0% zN&q9&JZD$48X>H67ahhpMZw)nv^jJrZ?5;WhPd&Wc~HepYnD6Eh;xd#U4?g?`-1Wf zMp_z8uYR2e6$LUvD{YN9rzp6#O?Em3Wjnkiov|3mp9imncI8YsH{zV4*qzN)IB7_e^w5NLC93E2u`$7=NejU5j{I{i z)e5*LYG1;xUv`j!In?L%4%Da-Upg%R%YOm%ALdbdsZs{XrPRDKF;);!to*ct)#M16i6|O~aHO)PwVYUco1qHVznWxC3_SEO02Z}vY7eW4gt}A!N zilEQNqoUs*g8)%*c>7ZLMZ_-#E#PaX=tV%Rv8Rrhq zSnkjpd(2i0m3HzSw8dCK%-&B^#|lxA!ARc}LFU>;5c#Nqg1fjFr~SBDB@eM_q3o7V zFFw!eRWE|+>vS*Q*_Gn7AKJjI*H4H`5WC`=qBjRLGq5q|>JMizE{EDP;y!mO+aMq7 zOrS7l6+%5X7!&8#xd?VTPl+lHRl>yspM{SF%mcrQxJktiDEpk_`dOXc)d7fJ{ucX;k+KVVbFTfA5~N2 zM5mtk1N+4uq<<>ieWw!V^(geOTW23Z?GDj9iuG$2N;AW=!Hlw%3lYVVSIr<{iqcbEl?-%bg&BGk!Esj|H$ zOMu-?!TVe)HpcsjX_MJ!!43+liJ>}_dUU+~{Jw8XfT-hT*JsjfoSDNHb?^CbAgbp! zj>p*tmzKbK`{TVM-B~y@$DwjPm6i#m-V)DNl4)K7BL#WV3T)XhhE&ONfUy&>=B!>e znnj(Vi6bu#j4mz#8dCcZs+A0!dSlj8Iv@W4m5a5@8sb^sSOPcKSY2I>vSGn8XNn+w zGbA=0W~Y054l(8hk5wj?iI;(`!xINAEQ)h$gsFYhc-L~k->p5ynYA=pj%ARo@H2YZ zGY3Lii>`{h8=&D9hep{3DrYhK+`8x)HfrHs6tMxP(%?3E#-%q-OK{l>(RR0!M%DP4 zC2;&?kfEDE0z4!h>t?aG01`sI`7IBWBGeD0?S~oM7lFZTckXJjP^jBu8MAY40lYe? zc5;py<%gObOlK$mwE&D6^fRlIgWxXX&uZKTqkyz{XW}p)YES(j@$SwW(gpA&K4LY< z?t#LZIJ+bO>t z-M6IU;5Pk5?#9T-eXQo<@4t5%Wd>KJIaW!%l13HYmj}1$FT{ePo5>e@5bED*B+1@i zXTjt||EGwmQs{BO+u9rBw^Xth(stzaBGh_Tt}*FtGr)mVkWsR(25z%s4i<;Hc$xMi z)Xx;%b8croeR==MDFW#P9RN-rZPXqVwlEdgP zmkY?h_-YO!)S{mIB#vV5U|W*N4km+kxXq3kCTZIf_5h`(=HogUn2Ehy9_2gox!@<% z;x!ZghdiV6h&O8k_1y;^5FYQ~odlDP>#0I#d*C*ChTYWno!%^R%zxbK{U9_6-cX8* z_dV%_Umv`pEyl<*2IA5+r=N5qzMCQXqR*x86JSNFJj5`p4=2y4zUUabjZwY+KGzD4 z*T^e~OaP#>L$xuvA1BYu|6q^s;A=ss6C?c93=d8K1LfOMQ9J`UdB#KdRNw{j287zY z?%LG8fC*6bpwWuQZ2%|FTpSA6OV$Q_7Qod2!szK|1u_h{lm{Tua?X_@j2&}P`7pIy-=mbYGZwr(u#Td zaPo}yx8-Q}=iLbPxpBHBg&$ay>Wx~&C#7DPPa-)^rsfUSk5jV0+S7wjA2zdykilxH zd@BXii@vGHSEI?P8x@M z5$e@N?N<_5cI{+uT0U)5JI<}q4%!IgdxKIJcs|V{T%QFRL60?$7q;Tu8tZ23^)^wI zIyQ!{zV!VpX!bj__xXG?&aIi)UrRkRjv6)fK@NR^qFGQttz-P;N)sIVu&DfpThq;v z_Y6TQ2MK`UaJ61q4)M)Ely2i2;{xqWsWP%HWaB&dk!`_odR)s+|*nt811 zC}|4Ltx0a+q<$fRsxW=(J{95biQPteUp=SQmI!^6UsasZH8spI=5_6ni?G?pF{Vod<99#a8+ui{|rzT5jK7Yg8o z*KOkxU-lnF#hLuw zSS@zGBLKn=s@{hNSva@GC@U*09%9Vn zH$TosloG&gg*z_CUB2Pmn%}hLA)OfJr?5zn|UEWCyC z{X-^#LPoyLfjbL|>raaEaPmy>iLkRqdp;vZ?R0CV%_uzq)b*RprM@eKX3cu)x>y!M zisx>7rv@sH{K_Jd-+&2wG0xlcCh5*%oEn5C+iYC5j`h>3&Y=3=fJ^M){V;6BG^vUWNeKw=&kmbcfBI`Ak^&}v71b{F+LMj zkIIm5A!JZCSid|!2e#s-t?iKO`|-Z!Uxe=%1MO2&1T#}1Bo!UFblGMK5D7R&UjBi~ zaPc$TKhB1|7#Aq^QDC6B2&cagGgDCQd47b@ga+d+oR-y zM6t}79@Q?0?~ZLe?qrcV19Fv#DHxawaehmdIOWP<7b>n;;%DZnioM!)Op$rH{3*l< zEMieB>`cO_v!olih-q_8fh_vlagys0a*u}H2nnfzg0I%s@A{%Dv3$kIt}%R>1cwM0 zdRnnJx3>u_f(wibrlKK;?_LeEIhgis0?^QZKP2(65GSw@?cP6i_lqL<`;J_#$RaLJ zIspc*sm#oc72yOHt0(czRHB~{>WfrYvQ7QR!MpCfiO}6;aGStFM6~Cai32S{eS*GO zzPDl=92~gSYHwNrw+SpnVnk2(v!L?+*EQ-av@|CG53^~J%g0K%O<=KPjWKL>N1cM< zhYfNm$0op(+Bv>cSPc7dOI?Y!lQ^^_<1Bexf{MO7A1GIJy)X&h8*f>2c~!vF8M9;! zOidK#9vtzNW;yZZ?j-#!t$H~KUd!CLtbyMSmf_@=gWRPT)7HA~0pn2)DWd&{XqH;9iWF9K^#C!slC5BT_( zV3oJE#4$b`@u`4^9IqJe5U!pvVuQ4)N<${fOn>+b3e~P|pS9G!VfQ8}%Pw z+!5-vw)udbvy0%KsHwa4zA)I$`Y+F8%VLpe#914mR=IGVg|-BHBPRN+=>}`~e>4zp z&d?yccku7ueJP&5z89-MFL`>yt*0y;r-2k|FrJTn;f7GJmX01bo1O!Zd4<$VE&@vb zkLO`YHD(%e7FAOu@->iRe>rBaQHR_U*o=U6dp_+7v6LtfBpS#St_Vc5&A&Oxt+zP? z)IH{Nk`*H1H~N3oh4>C&m;KZ`v}plP=uOT zu8EQO%p@?rNHTO^IudTvKvaOE(&`6P&7kn%?@Uh0fvVpK@hC_y}_sE3$70FdZeoFj8ca=EG#@aGXV4p(-z}f{h{W0 z>b5^DksHjaz6trL==&*}r0Bt5PEs6peCE!N|ah%uL-F%VvH=m8w3=1k4+d%@hXaG5{q;L4&?gDa?> z+kCnjAoRWq2xQ3=(*%0L&9fSIj3ukrgKv^bsoX>DslJlGl=#$tf~yYA@;Sc$N3B1^ z6t*uK(etn6*YE2Hc7PWqZUc<0UNEX!Z}kAywxz)!J)<>BttV*nw9BOp^rW6+^^o$0 zPvhuLFkxzy$3;sKoT!@;pPOqs-hpSK}ATf=u6{XHRy7f3h zsRe|vucq>tMZ;}=OYiuQqd5O5X*Sp{Nr8#QUn$^NOj9V*#aY)03dveKeovY2|P?-)0R-;*= z^FgU+qtEM|ktqg8uX^^3F{j{aqCE5X1xJ)Rnu@|>e_%CmG&t-H)eGRepI`ss?MeCC z*s3?9ENpXX)kU+%?ZB{?X`h)0#MR9F^or_|s5q0A>M`9K+g?B+eA6HzvjDeKRnG7y zJH10$J&#(CsEfJ}f*SB>?ygQAZl@A8z9Cb2iHe8@jXsq)%YwaMk`>u{RUi+i^*u>d zP~+`F-T%IH_e~=KBST*6dDzlgoP%4rDq@V0Sw~Uc-16!Rfp<}pAn;C%!O!4axKsCE zE7#J*`L4@#RBi0>l2Kx{%_&g0?^$1!P#$h07t$AA2K^{|ZAd@XOviH??rm1tww$Ko?>zWCFKnGvO=sI^f(7+{q<6|t2kajS(h$HKowFdr zn}z)7!AxlMKMT7d{U`ROByx>C+|;yOm<4a0dyQ2?(;;KezZN!8l+A;TB$Q{7%V(2) z^Z>?vFEX{bUy_R3=Ld>cU(4`d(VM^C;HLP&kl22C4ix+5$W?13z=5nO>*1^<<)c+|9Z7koB-ZE zURM0J`V6=3iDvCw#HTI5-&e_!I#1P4UIOsY4!*;1(i~nE{MSYneB`Si>xE)!cYMtR z>u<1pNyiW0gZ|T>aSK~&G>TZnJq4jIeD#a-C3c(G=)1Y%@!KJ|jU0Sd(MD(T-y2}+ zXRw<)_6V!v7Gv>Y#AI;4Ce3^EV< zLCY)YMAwya5Ng_Dr8sAd&*&_`D^o9<3Abr~S^Yd8T@q3GwYv{A6L&~rZyS?driz=* zhTF8ic3D|VM$KwO+s1=$H&>1mz`m~CL7#acWIl9n)+KZpCMz9`5zcEts8jt5_)Pa< zZ#v7eq!neB;IzMJ>hn)|C7KZG29?Ti4s52kH#_t1ds6{#`B}7yC9Hr?1@9TW!~dOa z|NnDs|6|GntA+$ncxAq_X`=>S;<=+2es>cp6yIQD@~=a*Eg_NmIY0wjCv<^320zw8 zKh?6$gI)xTZ&U>E8%dC_&7O`l^P#EQRu;!sfo*PbQXTH28b3ZAGR|1O4#sIE~= zs_u4~2kEOU{XuONkXPioP>Sz&5TqN{Fz~4o{(Wz1i|L<&Nb1V2o}(0sEGQ;$)&m@t;XZEl@Pi<2ZD4a#Z?vY}S}={yhWZ%dPlVlPl}QV4mR zvRedxmmZV1y#9gc`3pgclvS+a;g~5QNw_ZyW)2x#oLXH3E%(ymx4xs)GnVtiwvpK0 zGDH3)S|t`T@DE&U8tsQ=1IURb<%le!x*(z=jSP{J14!M*T$#$DgGwd%gUEx zriF^$zuxmzClbr2jt6nv<~?r=FHqRM{(cQp-?h&W&_a#cuZ#l*Ta{Se;W@>|YbO_+ z-`0E0$ACK&rEYo7?7mcuy@q8guBhhkfb-j)JAI+)TtLlKyOO4_T+`TlR=17}Hb!`W znOdcjBf_bW(sx)iFA??KWZ{z@wuk0GjaO7Ow}&s_|MI1d4I{8oR$4VgV|QKuK2yI9 zYVu^#&w-DL#>7(Dp&;0hMOz&su!(swND0)SR>|VIg6{K5b0F!&RcZsxDBw>g^70j? zrd&&M(_j0JX!}T-wU5mP#?-phDIDLO3>*d=jLI2*hlz(tj+zplU=+~;CW7fm$9)in4+tqxWz(&!#I`WVdb#snsFm?38zB$0A zD*Tfqr3fdm&Aw|mxBDDwZ^<3e%aHg?0NndJ2d5H>0YQ6^HWXv1(fM+b%)dv?b86=H zXdf{G@KX80o_nDbcq@p^9$2u0mM)GACAUy^?mK3N(vNbY0RX;12;S4pR$(j`%_UGX5^PD;K-3f(}1t2~Dj*Stk zBJw{haoNQ;4hVKfK9V$xM5t}{*F=9=A%N=Y@7()J%YY1JLN^bl4o;Rl&;BtJp?>Hp zYsJkt57N$uTe0w0;0!e>W&2_(?ox!Bs_|CX5rKJNRDKme=?o%#!RKoQ<{tpH1;nO&M(eDU#jk{&<8!Wdc(84^VGL{DJ zlzu+t@<-iPOM7(>>ijOwYdj`}sSgO~gpFbZwrvU;rDwIo`Exahw$E9VJ5>Ch2mOa+ zkLlhH04JEfl>eciJwM^k?`B($P@kZ`q%yjWu}H)RX~O%g0sR__(HV?_R#n04zMG;D zp*}e8+jl`^0ld2!l1|XJ#wlofxjv|LK21faeY_XrExH!K2-C3}yu1J7m=Oj4>h8O$ zi%>Hb>pxn^SpXg6LA>g+;jmG+gK~>992ACXjEIe)qS(3y`SdH{3jnf~PgdXfkAh}d ze)Nb_D=O0DXvLA-q_zMu>P&+G0~sD|La;!%}IV2AX)&EqHnnK6~f{Ar8NROhC_o@3w+OLQQISv zTB`{e=>n)fP-Y&{6#gF$ZR5o7BV|+=!2Ow@K+3BH(7@nHs?;9}BLWL^c49!Y!nPe= zl>De^lX-$e=YYflxM{9^YLqbyCQ9)?mD==!L{*O>hn7%bfPRS=>F-mpG`!B7Q{d$o)87>bLyZFI%9D+xHzr^tAV z_afSUD?)hT^KKDn+~oH?{^>h>**Gq4$=D5drQI<0*c?Epe|uy;v1?xh6an5d_Q#uX zpxFXv(kTrGRNDJfzr|WOQ6zc zQQmZ>4HDBtZG85u07Q?L%y%74La4u%TseFdaX%}oSP zG{9{eE3$oKw;9Uxi;p`oLpo)@Zdz!me#UZ?v#5HaRc zhFv+=_bvnWI}Y(G4=Z6MMPPY22AQf~%8e;yLLDj-BRjJ-NS493$-(PQ2g`9xl$6n7 zqMcZQ_uqf-YkrDHuTw08f;6Tz(`RKkCQ600phTT1D8oTd zma7?xJ!Su|BkBL1M5T$^icbzKgXB-U*3}M{!T4j+^Fn_>Pv?fMY_m{i0Q=3&Qr5G} z;K->fPGUY~aNX|0@E=r@ikoD(m?|pSr5vUbaR1pdkU2beD#o<@KiJaZ7Yd1lIK-&w zH=QcdF2Js1lV^sQb5}r`$NGL(uWw$r;AVMir4orylg#9eHNIK_Nsgzx+T9tp;&04`rFAo16<%^KUPB9Yz-_^vaj zLWKdY7(9&S{sA6&wYzq{bwa3<2@(&ev{ryEuY<{>{AwI{WMS{R(?in^q2{M4^LU!N z0zQ_B9uIY?h0!V+BOdv;fEBfp{a}g%Lf!IUiL5Jf1)Tg9WOT8i4q9&oY8cKvh8C~j zqXUu72=$HKi%x5?E5Pn)HvHi5AF_x@xITql4fWm8KSb5t-md_A!_$vL>>Atl5EBMB5Do za%bniVEcK#smI}@W_aLPRGk5a4JvdMc>nn(YJE?Zzs{+7y8?`uj;1gvH^YUbTEncS z3t-P`<7U7LYG2DZJ12V5WCiRk8z=TFXu`2UZV!15<*=f5WI4Typ_jt3v*c8`(9@Mh z7^dDW#DIZ+W)+{+_cfIwzWXL`tE^wa3Rop2;qfkPfXvKwaZN*h`^xdQaRP1|?#*W%zG-;CqE zKH8`<*K2me@_hu*MfMYYXq{!4}I+A4UpgYzW`T?G#Qp*WT3 z>%)xt?#B@xG~vpt;L58*p|z={aC7iH{|5}+Q%EBYzmlQGyn}ipPSgCU1g|yFY4k({U zO7}+x&FU&RUQ23`Oq~zs<>ze(iF2TXz>y|fhZ^%Rc^awu%WGgpqaa=3;5Ya^-%`V+ z$OD>oNqp$fM9miR2jZs8!fRmdFn8zipk$a}qhPetWflD?bHF}qN0gP4Fg+vpYW zQuB9&zho3Ry}Po3>Fg}vemnF!aS+w^i;b!NMXZ|DNM^gd%T7tBA) z&sKcXg;J}KDc&L#Tn8oQ*V;=SXab(@<41#DZeR~;+lHsKqk_5&>>|Z&y6a$&hfax> zAPM*RWVSK34#Nl|djIa!B1F&Iwb}(`;2L;oDK=fc+aGM>bM75~WNLP<1fiZvOXy$J zUj^=Sehzkx#b6tsb22u@W|Iwt*MJ_8zKSI)Aa`E`i>E>Xco|PdzQ<$~BnZe|9brMK zM*|$*d|6utPhE9yU(ZhgcX!w{6?7HCZ-V+IKMPPXkDo2`OD|NGfh^T)P0-{Gco?3{ zC49F6wa2(<=#Lj7zFXIapgp#*1XxK0XFG_Ez&1WdPWY53R{<&%e(cd1(W#~-aO_|h zo8NN}9AR@IdWnmJC;`znxoOB#nt~;exN_N3Y==J%q0u-xuW9%;0->g_eY{gCdI^{u zy|8Ig7Y(`DB$taY5RACEiTi_?uL$+Eg3w0^>q~&_er7Mpu4EkLqMdZKN?+C!p{AsH zDRi%X3A8aB*(l*k!%;3i@4Kf9C`=LRj=|rP_FhY%CV)n5uT~~xm6`iS6l>^A376dX^XPY`P{mCj#@2)_TEX?d6GQ%V7!}YLe(2EWP1@k za6&~6lw#JkOyZV-b=22}YPMV)N@BFaDlYLZ7x9bbZoPH7nzsy^-{tI;znKlEgQ}Mk z=hb0(@Y=vP6_mC2+^SHuVQCrEuwVKlUy_M~L5iJS3Oblj$;k_StuD4aD?saFPxTqi zG#u@5YdKz>J_8jg+O2l_ah~f6c-Zl&dR{OIF3H@F@Ebb>$HcdU$G1@S8o5b_K#lhb zNN`qo)oc}sJqpSAG_K4Wvw^H@{+l43iH6 zzoL$ytezZ^Ys_!uSAo@8y_!zi2S=X^$q2)3`)7umu$pHjg# zq+-c!c&&vt9Q=LMG#1YEuybQpu6nY=b-EP5e%~zk!RsRAFihX#y4W@4s0ZX+{Z|s ztiKILsPkRDk1MfaPxV;|UH{gZ0vhbJZ!w0_7M`gnv#U+WLZ~@JJkQzxSOj(_jfRdh zg@I7ZCFj}PJ%ZeHRJ_u+ej(J2_aC@^zrO^YSTa-@3A@3Vg3tFa*Ni}NJAsEgV(Ss= z>4uwoRSqu!7Z0zD^O7;}{pDDiP5R$pCUVOtsJ{cD-XVNn(y43_d=8U3sed>FYVa@h zD^;z7!^_jMwu0>lb@c2J0p7=pK;Y21_i5@mP&r|!CQfVvFqFRti1S8enUq=Q2OXI) z%%iSGA#+F`9AR>y(Zrt7QBrK~(P61XwEaeqTgYe}OKpy%TpuEXIO5`Wp~i*o@hXHm zsF>su*YE;hm0B9nR49UE%4%k@S0;hp)joRvcvKRe)sanG@aF;uzxE-nYq1zMlt+VU ztl&qmAcL{u3Tn1+FZe$E(urkLpUwki*0TQ~72zpu^)$|io`*lxU>!WN2nc1YW}?jH zIHZF4TPI_=ay-+BcvYV)&)2yg8Asy8OoC_2=&$b2Q}>+7J;OG zdR6tQ931tKC2Ra}_E-}_?QHvuEBwPE2J}MKN5l zV(W*Wx!9$s;gZ4>IX$eXEU>p{7s~&({#{{Cr(D0%xj~y>>eN#HM1d1OGCNd8=Lf&e<^M7y) z4fh|VpJGHsL@Q?UEWbJ|fq?^RtL2?fabUtR{oK-`Ow?5qk(0ix=aQB{b!b!Upu7yY zpWX2f@*v3A(sjQjDo>u86e+gU>vZ+yheH-K*{_zj;V9#8x{7SVIGaDEJa`};w0ZC$zvP%S6=7g|u+P~oWI zj!+Yw3!Px=S^~x|&V7ub=C)BRnALr!O?+3isB)Y-kaG&B!NYpZ5P3EpRdX zFf2Fu8ltASn`6=^<4+o)Q>8bh@-`C|68;GR~TCAKVX6Ud(?REY>d#OH`r4r3~n>z zrz4L4g`$YM+P_OSI6%~mI;sURg6M6FB;9p|^6dXXQMqRMxyEh~^+$7Y-8bkB*ISby z0S>=xBy!~c%MR>K_naO7|ogx6DwZXY5+Z+sQav^a^e9P$#QENDfOGzEw z0Og`e@5j_~5RNPVEjz${g;Z%8_N7vq4(dy3ZvZ;2Ky8MuZ1ip}(<8Vt;WB>tQwyFI zb}x8>kBA}cNBO57}irtBS*H8{viSEZghUV6c>G)iJvjK35s?U(BEDSBe zZ_2#bqk_TvzD;cRE&4aWK*~<8%|<4M7U9m=^j}>Gg^b#hH!OAzGaF#vcT?86hgn$R z0ED)K^xa4VM7?))DZf{76Bw{j?1Xb=Vdy{3KkJ-`YYapk6L-i_^C`O^18AI-`*TitV`!cb-Iqt-LeGhZ)TwQ$H6e_BjmvduB3o998$s zSOlf~UaGR|+AtDrT$y+#E^gVHHZ zeK_Yr04_fL*8Lw{Afu*Clb;_=y$YB~L^bxsI$*TDMe@Ok4*0B&G!Hb4oG5CVISnzmFv> z?$EK47G9ya45Td5S=f_`F~DZD_RBUPz+!v!A_t`7C6~bmPiF&Fp?nOm!CkuhW}ikF zTnw-=b3Mwgt_9nlJA7(pmmOFHC1Y-0UG>QrV6$J`Jaftz zrgp!0<8bnoML?#PzA3u;6a#E{RJqf#@45?L;)MTYimLCE7(1-!Lavdq4ZhMrZap^ z>7XCDnrUugG_$@7@or_%UhHWZM(i^Y~=o- z-(ZB@P-iYO1jBRuGOHhngu`;k-XE+95Igf5D0rT*-&u>o@Emf|p5!oc*k7`vQSD)& z^c$R>(d{1@c&{(Rod7{zmVykvgOyTaagptcI_A)8rn_u-8l z|67^hfaA7~>LCC0 zYyK5;z*g7ulaNd?2KVsn+aoTrgN>R*iNx-R^E{x`*A#WHFU8;E!duu`@Nx5p zwXWCmpvt~2=E0E)4DONC&+wUj1iJ?&(&lD}5Sa%~1-;6ZJ{6$3?0scrX8`DOIXm`y z7?!seL0YEIM~qtT$-71#H9-Iu?W9KviU#45JkH#!h=Y7Gr+qnyJKf$ro%<5mOVB?oLK*{68*H9&y5El$$dJeui!vz(FCKSQ*ti8FIId^* zF2ZRLb%e}j-unj&fO)?GW&W>H3@l=u&oZa*$b+a)M*T?cFIoV_(%H}Dh)cl!3`Vl1 zAQVe#Sh>8S0*jDY3=FvXqTrww}&<+furL>={bL*DejA~1g2=L3Xl$%I<=(s zB_mh_!a5?XH#QP5uqY*l(Wy`brq=Lz^oxOP5$w0rZR3xL03O$qRu9eJ11V(RhCLN4 zAw5^3y=x;evjE6687CTa{Q#{~Qp6vy$hTR@OiR2RqAomBq+NJn5tuM)twu!H0Mi#L ztbf#9q~3vD1271EP}M)l@XR96kLU8ag=-?wtkj zFy`8(3DWZ^{-D|cr$rF16VAyw7mk>3h*Q1nDL`DVKPRHx4S=XC zC&>&H(4r)yN=DO~sxgS|+g$S<6idSCTzBy)f>1NFr#gUealr!jK!cP7jSX& z-6hxwn)+mhDaGmnkTbMZdG+hB&pxIPBFsHg8Nr>h%G4=f!JG_z>uU^ z3~IvH8b9=4NJ9QSGdaerp65l|*7=m0-Xn{0HUEX0_D)ZDez!`4sGEGt?ir9Tg5CFn zOc_zpNa1US7(*0^!s#foI1|BUWbWrU_v1eo0Ncbz4Xc_6B-TpeqeVmnGJ5#PA(Bp5 zY>)EMx8??cMQ}{+?3OH9D3T|#zj8aJ_RoscZ@>cEaUHLA3JO5qw?K-)PGY<-5;{+w zMT)Xa_^y-vZj3OP%V8?Jno0$QR25IQ$M?A+ou9r$ss16MnDeP|*UBKHmYL&l?Zl-; zAkpyY)y=!QNa(r4ErKT_08!HBYjQLq{_i)ITbwIut-J_kB$f6RpEdx0Nhp`QHmOnQ z4amRM$HL8(uJA7crSGGxLpiU&UlJ;MWB9=>*W1e83x@)`<<*4@9s84c|z;X_lNeMrM(Kp7c zX}lOV?GCt)(`nnH92Glx(-Q}#OvrO@ALk?1>X9V8z!bxY=EWEOc5?6H_mPO1;I; z4)U;hjdS#Q{N01|!0(!|ui%p!#Bv9BIqo1D3wVIoTb_lfJ<^~<~hr`iWx-U6sU|55qpMgt<}>0NBiIROBn-+D{38PfCD zF*j562Nys)_0Z{r<$6RmU^c$UW}hVAX6$BHXfH&4&L97>fMXF@Oh_9D9;`)ne^}+c z3Z4NDSx6ks2JAlcrt-r3%GYQ?Gw}Sp?3U14C$S zErdTeNt-0Q3S@`AUJ(m|#hJ?Z55BHDwFrDTx&s`A%Q0?lK{$20Ar5x_KH{?=&Rw+t zvOkY~vg<2BNSv>zSTBVlI^Nzz-6dI&QM>Y_ducU$9@Ow$Wp|1y#;ChjF~#mR(f$y% z8STu_!RR@lJtg;}Kk+lNx@@F&9Bms{a$C?Q(ioza36E6zYCjA1Rn=u^6c-^gOS|Uh zQ0fl1@^Hd*#u)tjJFl#@CAxlT7FY|ZcqqIq#+W_a5u1FKU{^@n1@Z?k2 zye6s;2)qi-w(G@RphE|wbjEawfw|yRrQ;%JFw^4yGetSv= zP<8g~FJ=9CSkE2byx50xTL3#2Pfw!gIYt}$1mLOOx5FYPa@1N~owpZ2zLk!{0eL)P zKF${Whc?6omPZ!O!rs{Ck|nPpdj96P9~OmJWTG`@K;1{J*RstNqRSrbXC4wtZ0j#X8FpFgkOYu`TV?;+2v>BLQN4O;@gkvHxW0@WDlh%01oyH)uVqCWie zbIjz=B@h`P^+2h&8d-Xv|H1<0B#G2Q?=Q+ZfPc@a5>LX$Pg5;}YU!COpB zVi|n5KA_~ySBknZjc$ zVC>(Rst9Qo-o)OtL%NlmQJz)Vi}$49L3rYGIjlcLX_|vrQHem z9J1*|Ot0j8@_`aSK40mU~r$3KMU?*1!jhN+OAQ?=)LQE;JlA{zqo(k2~< z5clscNe)M}3d)Bc30dI~b=l0oLgRxK;MQ?U^hQhvMtI_^g2pedYC_cO2N9W~*Xy9Qa^6%Nqf*5%lvdR!D!xFX(qK*33=bphg)6? zAa1!*WiPoESp^(^M(5YTB;B1aXK%uYKm0b?loag>INoxk6RY!50R#wcA{`6_U8fvycQ=7N{@vo7+j0MUaV>AZ;I4_rZ1RErWO_5k|aY zB}SLN<$D{)E!+iB2U`|edoeD9hpzX2+#o@aUVG*xM(b{Hqr|agP`DGKF1)faXSRwK zzdgdvlSNsIOo^yc2v~IkGyjGC#vfZDYPAy?9B0u2vKG5WN3-^SM*gy?GcC`jNTI75#@|R8R;8S?nsRZl!^9EKGGcIFPm!hpf@Y+ zA#Bvt>qHDp&Mt#5myTJUIG2q8Iq_C)of<@dd$E1m7WTEYEPQzr=ClkNNbUI*%CeCN zS~@L+3C;V!rwzr6!A{VFW(A_hKQ9BnPT9Py=NU-F(@y2osyt-7|EIT0E$lA#u}aVr z`MG6)Bl=a+m6wV9C0pg)>6n(x^B`}`I%z_|VR0D*7TMpc$LAm#nEHv2C^>h&nL;2g9wxC9wAF^-)&u4~Rjgbkd0X4ydQ%7JAPE z8*}pH!%Y#fOCUgI-y0l-8fshn|4gpWc{_r9ChP_~&ViGM1}&6ae2$#LbKnEuDCm%sZ^eG zdtJ2%H*!_kq?jX!LkOP^>muvRapYUi}Ytu?_7}QKjLv|1dr^r zj0jG4z+F;^^7S0WRaIrKSB!il(85Yqf(W}a*WuLzaTSM7>?pppr^O>s79nlFM zhzG_WvNA%SJp=M(vH>~-Sj^*m$YzW-f|h_kt#wqyED7j_AEmr`L>Gy2`!=Oa1-l<3 z9sVtL11%^1>RDEX`C0;aEaoV4162kM(W^zN zC8c2W5%RS>D+r)qM%!*xCE{tlnF4OTbG(+<$cvnk>!zVQ@eJ~hxtX87HmkJ+UJTa0 z(n?ANf!b#;{ZXIzSa!OVI~bxqnwYV&$Fl?;gjzg3$Da;v4a(9Pg;N1@zR5yc+60I? z)H}`U>((OhI924(n4AvqAGH6&1LF;wr29oOA!=z>qBx7J=NM|NqY|S zaa3JndV`~OG7+LaG<2IVzqSZunT-59xn3f#-P`0oqcpL}Waa9un0Sc#tE|??S130X z+}KQ5FV9S`|3|;7mhF=EOJ|Ygy}TNZZ5?AFjTC zx&(AyhDFNRBw-}8W4fAdAS*1cX!vGldC3i(*PbRBTX`m8By;3?=COzg*d4U&tFLSM zooJkC*M6S)WE`TZAI2YLBn0xFT8tJ5!B&GEkB>cr!%HAhzFqTXN(6F(@@e`X4%&w7 zWEmkEmOFQB;ouW_)C@HCv4UKlcOcR~oMifkgU&hn%wK61wqH9*S^RG72fBWXB((5n zxFa>@#C^NEjL3AAn*X|1Eo96kn7y}!qkt% zkhZ&MUasV!CWagV7qmjfkI~ecCx}z0_)(>Yu%63q5#hQXp}X7%eMiW&J^+pTHV6Gt zb&0#O-Wz4u`aRv@hm@ji>mE>BbMx^B53YrUHK7#sz@uX;EGn>5Eal>rV(I70K=B&) zb%(ow7)7noDrKo`k_#ENoaw+Wn$Tr1#gd}*QY;YYeKO}iy7&X!D`_rp3xut}MLIJf zA&tv`_E|$kv}`C^L#6HZTzUn<1acMDEMRKe&tXT^0?_Cjx25IfH=lsF4lf_g!!S@d z)bFmS2a8(RAmO10QFZ9?*RM)yl^o^M*7hg#Z0z9G?epeL-5H9^seJ?)3B4pp4SC>_rmw^ha z6XTD1FCe8owegX17EH&`+n*$Y#r6({h7~H7F9T&}tGkhGmf%I9ME}j)6>#hJYj%c* z1(2RM4j+5}8!c^Z@v->=#hqJ#bJ1L0DFlt)kdN(q^b58ccsa%|FQYmCEIpk!-?O;_ zKYc@bjvqvl+@U1a^e139nwK5I%F@uNq^}|6F*3ea;7tA<;ioLr_&1djH=k6(M$L&; zo8$Y7Wx&5MUC-0+jdUv>`Y~lfBiVa;9)II0EN|}s*P!>K+shz*(w*DeA`~OIb*RJH z&d$SP*nIOh4uqg;lVp|mkF?V;g4-;Rh;pJI*0%oL(0-5W%Ye^g{roSjLZs%RPU(ZQ zJK&|cP0=@1*sdo#@r%x3^!)u&?u4K2BeV+2sB`P-!)P6{p@y_43L%j1-0bo`hT9cO zKxA)(k4CKoBe*3eb8)}ZU^xf<3Y$znd6z(?P)C7UYB5G|<3aoP_??1NJfkWY|qrzyJ+?&b3S*75VZOGE%-~WkA|M} zT&0D@JZ5@~Ok8nj&j0R~xW4{{D^lSM@fAEV@0&-et{y)sUl<8*T>^>ie+V6Dk(ct3?fZ>>+JdJTO@|U@HF;iG2 zlZLGZ8QI&q)P#8;x_ZaT&^r|~f5i(^pcB_DNX}jP&}p5HWVyP%?YKf;G5Tn1Sb!-Oq9#yD`W}+|4Z5i8Sh|KX zF=8JVFBBPsTB84Z%oTV~(niwG0ChI$idmH`#Lw*i?ORy_{3aQLU>S!DHC!jQs-^&6 zVmjHJX(q<|N4K4I(KLds1}^5LB|YYo0Gv-{^bF5He*D+Il_+>$tfDULmZ|#bR=K(I zFZ5n$1Fs^ThE)r|x4f)jJDLu8?#w;9Md!0Wf!dxgRpD$JX5TuR7(-q$4Z9b--Z)rp zaAE??RtLxk?n}jL4Y1l!+5LD7%U`46Ie+R$23pN&+AdG;QZi=#Y9=0Odi-8Cr027~ zY@@oyW5AH-%_L7rB37w@weLRP#s*C7w@<`I_0)I3W_0_Cz6n|lB=zq17$4Je>Z}}P zO-I-YT<|#E_F2(4u%A_Kc(WrOvyL^pd)%KMtxWRoZ%ry`5U=)j1Wf+Sbwb_0uqp{S zXL8%fJ(xPwx=v;O`yiD5Y|N^ zPnkfz)Eqie%91Q}R?Ho;RrULfSz@wA1buj}0h?PGoHW&&(F{|^tvQ)__d-M}Nu0zA zwLr)FMd0ymWstTXi#OM;nau&K38cxFx&SlOR96et5j+Bmx3p8}|%QJvUCjT8iGaob5l$_Xb{uu!NxqN>f?T=A)ONBdV#kU-=kKb zGrC9I`5u-n(Q`q!Y$0S7X!m4(ADSydZavl!?Vs!duY}faF6qGjvBcw2BhqQBfa1|& zZbDT7!X?vt=$p<2*c*Rxa~1Cc8FQOY-{| z2>H%?la~z{KB4vX)I1_<(3+)1kCcsTJ6C~O>+3L_A#BXW?E@{`8CHPd{j77LR-qWN z|Bf*g`4mzGY1`IZ@39p*8m$p}pXsk|5B^$WO3pj_zYT%Cu^SHt7#Pkjft;DK`-#H# z7_pB_Fz1j8fSnEYzJ)We^eh6~f$tZqRo-IEy|dHTq1aQwke+`R^;yYeUILbuYDeb2 z>iv(oFY8l1r3xGKfCB?(*`$`hwXZ|d;)ks;=KkH3-L2Ve*xYjAP0mLABlJFW!BZCB z;)PjaD%=WEytP{o>3LuPlXb$IB_Md&kT2tBN+om&oUeL+ zTIymlM$I=SE;x+k!@ic*f@*_F+%nKlV~+E_mV;6AjW13qxd2$E#?w^e)bxoZAk;mD zyX*KFqvj77S8p5n!oIc7+X|bkcTgWDjT1^{<|W{0s^-UnZBL-FYBckV1op<{>x*zI zXf74s%yHStt#XW9mt|O!7vc#3|DIFZ;(j}6sH2&89-A`eM@leTO5AvNZVu)&&6CB*T9TdguLT!4j@kZ?DiXF z&tDyJ&JIOu5B$65#mN!v;*P68Cg`EAFCiTq`{wRehqC87ABi$W~p z*8Do~;9r+=i*iQ(T0^?T=$MDxft`WhzS1Y6c}M_{*7PH^TC6Yz+vQ}2fX)CcL&fjs z^vR4z1dvQezok=j9rXXadguzuVB^VdkL~w>somPmSZ{_AfQLWvr>{aU!CwYjvblvW zMJf~W+?NH}UlVr{z+JLKpK`ce!CzxZojb`Q77nniAdVh0-;yo@@XJef%NF?n3TOt7 z+5WMHES}wx7lF+VHrIbAeiPpSu@8M?a@B*tUy2$RCa!UQA1uSv;@OBn&neW;!sKjZ z|NU_A*BWw9@}BgCYp}byEqUaX?m7Wn+S$;i437qXIp`Qmg43QAOnr=_cTOGcIjbdQ zSL#9(StCLSweR83`5UlQh+3|xj03?L&Q;c$BP_eB2X&5b4v^Pbf_+Hxv7qYzvm5 zVpn-AlV%$AMtWSy<$g2*qlu%d=fzC5VKdXo(azl!vJGGoPJeDL+a28Py&U53$CdF( zylv|XJmmkrUVnMlF#xSI$h<_==x2r$D@9JaqOOe8L0`L%RWv}<<7MLpnF|Eq__U4l zm!l6x6SKxFE|ZaTLe%P7rCIyC2_Tj0OZcvF3g*f<8RKz#S-uCNCT96+2H?;#_7 z_DAcGWqB>TRH=iKcpj>>J0f)uwGOLZ)_~nQFk2)4D!^Wka6C3Tx30JVT&$J2L>ypu zHDe}yD~}AsL=P6ODD$5Ej? zY7NN^V08Atc>P=hMz*?a$uR{!h0ThGK8a`>t8IYsvJlFF+x1Alr4*A@OsibQ&GA0@Ud2X*)r^Fd9YyclpXYS?3I*bo}b&cz( z<`Y=vUGKL8e7koyz@5F}443sfBv&(QrO)&Zf-AaPe3|qUr0p|&y}y#GHo%0}^`IQo zF>E16PBj80JV%vfpGh;rBEgo2$h9cYx{`h@0TT zMLn)|XJ%@|C`+FqiqBu6eCVyi6ajo~8{qu1>IcJsM&vM##O9AHBR;XjJUaJ2I`ax;&;N3g>K%GNiFskGf&S`z0ngY5Nasr*XOe0{PVM?~@70MSIu$SU zylPS9#ONDu<)dGKU6 zIrriwpmZGMe!$XHz{eJh z*<)>C-JJOa%gc?D59dFru?-l5dbEj!S`jhBllMIN?}5?2p?gab*^stvmoNNGd$0{G zCcD2xcef$O9|&BbMyWeNqvDuEe%MJe^YyN*}gi z+?-F}&`?P^>`M(*t2iVbv;{0v?ymE{%f7sW>Q~=GzLtzbFTa!t zZGl{yD4XEL2IOo+waXROb%2-2xO1ciwhGz>|2lQ|;1-Y+^s6VvHDK(T`nbDjC=qPT z$!*IhKAiBoK7xQ@D6OupWTkrkwDiHW-SR*AE_#gK3l0}kh^>pmL>9}HtuYT{w9d5aNntw z#$(=w$LDVGyhXkK{yjUqW#xXbeR~s_tt4vHzAi;hzx)19>CtaMZJMW8lncueS?jp| zplA+tgd~>cWU?qlsDnA0dGD=&VSCcvjBHr^Jf|ij%T#R(+)n6~seV<0Ts8iDn4njK z`0NZ#d0WBaiU(pwVyscO6V*Z2UWn-QDO;RUud@hMN@_8 zm{2J)j4NPrtItDLK0F>j>;-#c$Hm%t!~C{^Rr2GtAhaUKUxrKDqceI>9<~B!clzod zyRZX1_7#L}tsoeM)vq2qd~6AJ_r7y%h^W4I2PhnRF!sI_k8xD=OC%RpGGIF{nXRPL z5!Sn)(#A_=7j+B&%Q9tD%-1V7z`mB=pF911vb&%Pm*b4vDMmW@%T|O)R>Ap~edkuJ zV1Ehy>b2}Myu09Ihwd|zoNVN;L!kH9zC#jeurcT0=JQeJ*#&eYu_MB>KFD95=()^S z9yTG^>fgX!h&(ad0ox}mqH`AuF^@kX_ux@kEm= zJ__mFuvO4ZIBNV-+7>ulduUK~e-XGj_ATWP5yaj~r$(m)Q@cMLC(*Ik1S&BR7dqLp zfmrqHuYWxL@N`ss0lA5go-@nt<4P{u0Q+z3i(^Si#)u%Xixl6O)?s^xiIpfk&%+G> z6x!YveU8A0phC7Q4`~@ZA#;oLfvIAg)&@|DcyAja{2n8M_LZGZkY|JKxR$nOPmR_R zK+0+5Gh3xE!ClJZ{~>}_`=Y3tiC|}gwLKA%&1%#=eCV^z2Sq}~U#9138poX{{jhzi zoQAMMKsH+M{FT`OH#r^f*W>SFu7zSn1njP+q3HeSLDYwfi(5nHiT4ML%DGh*C^E4P z`^R*Lyh0D4(Hdr{ho?LgL%_yf!dfoM)ucKsb4?V&Rs+|^?mDh31n|0DT}Sd>9Qe!C z#PS=F-5`g}in&|XDWtswkj9j5SD}yw{&F?8AG`NnF~H9LV(GKeW#gN`X|hl>`a~Y+ zdTHWGfs!$4dIx?gc*1U(5dOHIj4=dI^+8ZPU;H!p>+!dCFDH|i6V~&G;geg;o*Tfk zuqFTA>r!xl%_<@u5k3f=yr~ z?N=amy#eD(9O@5PGA`Rg<`%Bq+|gb9Ca46ngvi)>j4x>_eA;bx`yFIfobNpNO&r}T zS{8QCt8LX|E`6_pk=Qx?42ZfP>0P8eu?40UBM;mzsKW@6XK%YnZZP8^YE#wek6{a& zAokkDRQZv5j1bAb{^3=~mu86ier+(2N29TA8pA#4ZXUc(5m~Y#p9Q38!gf*`-4OMD zx_vjhdA7kIGq-CmS{L{)<3ago#(g#O3q*aqP^HkWd=pf&nVY^HEdcx{sA=vp6HDqV zX4mPmwnNmNM}(h#WZeYRjHS3Vx@?T`SZ?%iJ1AQVQ6D0Fd!Qk;1zH$luaWjyVm^B@ z8=Rf*B)&t`MK4I*e#>rw;?MbBtUr@6N+WjHpfY;61EP+Zs87y}*aAi~@dDR1i;#!L zu3b0iw?U`i>7O!}U}Fw`=v-n;+5#74J?Y}K@t9LySy4}u^Jy645i((Faw>ldaC)EQ z-$j{g>T;&&BlRB;a$C)d5wkgvo?j(m_jsF&o+NSh{I(CPk)|(kx892X26xER;s$P1 zLexb5zmGIWZvnc;+ezGIHJI0(^PFSW(y@Gq+VkS~b>WOHz)fR(U_zk*p;oLYw0$!R zaEAlscXoXtYBHJ!LmdHIV1DxI%N+J5j5lZqp*UI1+ll=9RMUJ>xboWlEl|!};#(Bk zfDr@X+Z!E!AKc??RH{hQ$Q zP||B+^C~Ro-y>L2Lg^@MMqXMF-1E>x=e3J;dZ9*mM9U?3F!iPxFrz2tsA`7A6&J)D zG{prr!Pm*DGp1xHgumN^IxLz)Jgh$j6L1B)Q zBUgwtqMOnaVJE6aHK+GgL#Vq^Hl4tTFdoaC|NN5ZRB$ou?B7TCsN*|&FF2%mr`o}! z9Ls$#;`@buYq0fO_%ME1AH78;OM9<;p}iC#_lWtA-yA_@G5FbO*w@1OG%+cSYXkJS zDu@@z6(KJk6aB|;j=Z$Q$uS$Y^I*1DDDk_#0eU_2S8CbvvF!Eik3n;hJdKdQB>M2- zt>pF%uow6B#`hno2(8us=bxV=dYSWc0=7>TRqdGAVA=%IG}_AD0nu0nc?`?kb$Sxm z8xu-5w7%-J2{>zJyu}9nuq@JxYfdEw}4kz9`^SwC)LpY zXvlNZU(t>Y$lL_qB|Oc=jbCH=$T%4R+BauxATtwP*x8%&EL$ML#Qf{8>mFEU?Wk>w z#dKyYM1Ac-cdtIWZz1)ef6zxBf@BW;zhj(>U9fbLG%UyDp~RUj^&?y0lCj9pxLg7v zDD7U-WT$&sM>f&q!dF;Cv`<87@wf@P>lsQ_6edf-Jl~ur`Sd4rKS6r#Zf+IM=)DC< zi};cb-_JxO|LghY?EPUU?}-;g%}qi#)m6R)e9d}j6BhsH`L?H|Yt8KV7@`)U&J&h7 zu?=JgMHB6=W&h9fEx4h@oZ1%o_iEr6(Rz~%jrAOPG(Ko_Cai`v$ zLje$VXJza~7qAUXn{OSSqRRQ7=UavK05S>t*1muz1@8B@K|(UCt4d%Na$fScHE+9P zg$vOg-TR;7A#De8t)>!$w?Wum71Po{8WMl?|J68}>SD?}Nf348hI`wwv~3`KF=>I+ zISDZmJlOlkwaw+|c^7A8Se%KcDnAjGB1HR`iXbX|RIpCK;IT+JeiQ zutyACkhX8h9@2I--2(S`zvzlee8zm&qE5YJ>VG#3QOjMq`ul>_CaCgvVRdIlYu5hP zca3jKW|{Z_Y@fRF;dAW1cjy_Ix8u>;CLR$LQ8bHJ+C`YcCCukVhahbejHE5Y*EYbF zrhTD8pIR{YG91<0^|zGn5cQ6uvHZZrO>k6PX(xZI1IuQPKGQiu768k42ot|`hJkSd z)D&jFl0s|Voh85O$LY2T7M>6tDKmksp+21}H|9{sbQAkT-ppvUGUS(UTs4zphzFay z`jby>$iKgqZ0#=kAv84=jd#edmF88RI(8knoBzcdbK& z$lYGFq7Gs{Ymcv4zJ#rzpxjF6Inz2I^@`E9@~lOY$Of98#0`Q2yr+NNR)zIk=x}Rw zGHxBPhqC+n9j`{jBoEa|%H$#>3LQ!LQLtTZ->Ie|+J!aLaV90YhZ?Q)8xhgQgZgld z%cd=G`gK7@ZHJY6U(Pg|rzvGfpzJ6@qAl5s4Vd+j8)_U0VTxZM>fj(cks-l#Aa$RA zQ9UvT`Rl_)azvi$%1@YDpQ-Ztaj*`+saY24plBp@l-G&HNDoQyd6%im3sZmLFC*(f zZtOL64Y|8y=30Ow4`U$@HRVmnRPdGsC!1~-eXmlW^(hAJPGKw4X zj_Blu!M?Sl);{Or$JRl>XOYCHd)ZhG}7BfX|A41hDUbp^Eux9+pu| ztIZO9pBt7fv0q+sU$-U!C>ygJrW-E6+^qZ#YTY0b&W5y|8bc{8T7pI;3v;EO5ElW> z0~sSC!D#@O$HwsFpf~vU|NZGlZOStp0{GqQmE0vzh&f8>{8DlY^Uj8-1v&>WIpNm< z(7|)h-Sl}H<_X19OwvI6y9&}aA7#3OYdZmuFyR^*A4CFn#)!H< zu1*K;ov^z^hli-yE#q_pSx}eV%PVTvo!!7Tkrmm9a~7ce+Sz6){TZTmDxQ@m_-uet zONoe0GFyaHg{Nq9wFaRn)Cn1JhTZ#fUb){2Y5aIv%GR5z-;JbKWd*sqLdiV0s$RMk1ylO&cD&~!ZV|A$i ztpeM5L}-s3#=Y7CohN2ECH*syzgfLFb+eH!WjjdE)q-8uFO6*h_OKn3+k{LcY=Wyr zJ{5I064`rV>FtXA`#a}8B7bhJAI+AS@_n9vECbmR-CW}R<8DM6(w*=NwpXmWwiKBWDzWW%Y8*==xGSZv$q^x_!H7C5mt(uN@1jbd~oIJw=GaB)aTI{m4N)s>Xp(;aN_s?yMuOPo@KpVy9JUj;_FxOamZhf zAetHeA+G~4_5BZZ7pc+A90m23yBr;{$lt79zb2{i@(Zwh2h-gImX_`AF`u63l?UY&?9~vppSy!XFq+4e z!LxUT)F~f%);X>0a%=?QNQ(O1U=NGsdNZAowr<$~p~L-76{}^K(@xQEo>%WXdmwGE z%3l^6LEWS^BU{eQPX5m;XOD-Q#r}I34+O0*40>Et`3rFrI-Ml zk(bx;JnC)hV6SD2UEZ$-u@C)GV1woX=;&B@ES-ymJohBYUR{LWI>>7Z(X)9`^S``Y zV1{?|c?%hH_g^+D6g=x-p3_H==T|k7K(%`^zp@MI=@FdIOB4U(FBlufsfJaJ}btoD@tUJ#Reo^ddla_ljzl zUij43VtKjvyz^fJ^r9i^)7l!rx?=<&B{=aRM&N&WxiMdVL>QC8-uFdL&D=Lt1aNuJ z)bTZ;7V~Wp)EbEQJr0YX552o}iS`Qtj84DPZMCk!oL6uUUMb&qDunbr(nHOfqnH5n z;z+-U>(wFZycPE!Ud#XsJ85yY_OLUNT$>u}`$PgLTFzSx_iRKI4(Ri2qTVU$+$xRN zDquSg3H-6lpMo2pJodqU?>j9>^C9-S*YE*HBPApQmOFTrKXUcEw*2vJML?{_T0 zZGbIeY1{pB-N;jZ8O1+&xzwXfeT3kAh+1~eyDSyWcc2(}YSXvejl{`3x&6mOBwMn= zob?%O6gv;FRtzYT@m1AC=OUJ|9>05>O#-&`E; z!8}BCh`m4mW`dn!O%=)+!96r`@bJRBj;$UfbL!pV9~Tf0?ir-l6n6gpw0-y}KywZ( z4>26;_}PP~i6w3dpe`VIA)gHAE!e4M=1qVF>sta)TJbbidDeqv^|DeH2mQ8bf{eM- z!F@5eeh`2bp<*icOE;F)o77bOX_C7IqRtf3`Yc#S01cP*B?9}uU|GEluX;9honh*y z3eIhxod^JT_xuR6XBU>$>%vC3ZF>fGdLP%3NdJPKYC;|}Jgpe&Kp6Cr+APql-hPV0 zbBFlbAw4g1Te?=hO91g@4-PZ$wIVB7EtY?rIDBcE+*%4?>La_A63U;^)0`;Z^K-L} zm=njmUZvv$rDjOmFD`$sZ%5AtU2Mb8@KJS`69;wSkBVW`Q{>-&=r5z%Yi&FmK%)P2 zLVi;cP6+k6U$+p8tHm zF7jA#6BJ$wUEnEbK%}o9e3CgIiKq*FZ(C_?fvD#~iPp)*H-XzvmB-ANTCkkp@W?2M zX#v|(Bq4HQx>NYU44g<*@O~^rg zN8fSUArR9bt~Y82o6n0l8DH36L^DjcUu^qcLfc+HnX@D11^XX7yeFfHM?~l!E@q&0{wLG4Exz1YeFzcQs~MRMLa-uxtLtHu(L-L#t9J5qNwRsf<8f0?ZUStTuVvAY&etR`yk~Zwu^6 zC@3q4Wnx*qB*mOG1y>^=v%`x3U&i8=P4I$!#gr~RAIs{!CKmnDnJ5*aj%I9*Q(M^p zpRLUv;JI_KtX_unD|x1yX%MyQ#~98n`3-PQx@7n)5Uk7yeZ0zr)qXWlId3k-wq-T|^25;B#N^G}%-% zf?F@SFoD+Ef6XIhTc`_*GcB34oTld_fEp^@`^xdrh+EpDkWw@!m@+Scs74PqBOl5i zq~N9{0OvbY42keU$Y>;|0K)*ql0Nf0^q)i4~v1<8~T>9@4 zN?cFMx_+C7g6C8d1X`_f7ETh=v zRrh8Sdj9sYNu_Ueti*DH6CRS0QQPD|{!p2~b8^EX8-S>jG>AN~63Yo@<{4i2`Z^1u zCS>lWQW$T5)nV_18@rWYmE_cwn^_eI6&?BbDLPn8lVj+lIqennzNDkz)h)Y9&=RL` zvFkw?IBlq*x+;|pnN#JDR+& z@9l@e&emfY#RcS&31zQgJx}~pb91Z$UB5YZ*oa3PvC8cNbx~7GQz?+Pjo&0y>EJej z>Eptn1(ilDqgdy7pufKztWrTUMS{s3dYWVM-z%T0Zoq1O}o@2N5 zP&I`?L-NYydaQbS|9GI^)f`w1d%!0AwH3=Iz_~kp5mBna>YsO9bK81&1-4hzA<{F_ z9M}N!&uf81I)Y?bBV+GW$t4N2Q*3wYdmugkvPWH)mx9(BC@Kx({hEtaFuxu1e0$>g z5Jc_q;Qt7F?|7`=_y1o-iXyVgN=7I|BJ-(8qJ?Z_OUWp^l9gTd%-&@0-DPBxoxRB( zAv=E8>-+n>yl>ah?e@C-dA~iL$2p$oc^t=iKF{lvc`WSRHbV8vy*=}FIBGxn&57rq z8&KJjC^kZgA6T9qA5JWPjNZ%j4U%sWO8SJ_J(m{c9hrp`N$VR(1YnC}nZ_g8QbOoG z5695U6z$rFw}=~@vuCn$#ug0@D0o|ziMA2VQ^oS;KlKhz6kj;vYxs*ATi#O1K3r2W zx`ogm=rh*eG&?*|j3d#uLUt+=OS?~McnW+Q+(K3wI+aKAJ|3PZ#+jjHc9oRJ^0c&4 zQYlOB7Lq7R+<7Y?=zk}QA3PsB9`1qs_efoEqkZrHcneXG&-s*fKl$)P@qufPWO1$x zmZ!}KUPigjY$8w2eY!EUn~f@?>HB}TX;*Yb@ccN9?K@GJA@U*#X( zru~S!;Oq|+wkVkSoMlVy*Cuk!WqapqW+6(a7U%z+D2|fp-6EgDwkA4N(1n|{xQXQ1 zk0%H?6`<}1{{Q!3&oCI)zd@hN{_kEhtj1}tuHHo4kDr{je3O58AGYt?i61yQRalK<(kF(MDaaEJn3Eey&b9gT_&a4!xiUPLXcc$x(RF}{@gR^UL@`BYa zhc`Qua9-;>tBvg&^j<5|_F3a?#O3zZwyCTGV*YzWl z@a^@1AEGuQ))45ZFEVmhewP0?HjkX6BY$w>=Qe_0%}{?}8;tyW9vLUfFY`nFTP(en z_dAZm41Wii=a>4d%NC3zdd^kWCP z+B|+tr9mBK%2YLQIbvP}b(E=p%r6Sd({iO0RX@~rkt#*SKD|Ec|D8vEs`W1O3$_zU z{bw(g?gpQ&u`VuVBlO&*1p!Enh*OF_DqCYUFVI-+AQKk=f6}F<8o0oq5kzE4+tjkeE^} zsp%h{N5)B7d?t@R3;*BkHZM!*4r<*)45xOM<#9C-tyEIR^VQp;qZ2jRA?e9jo~9j7 zNQ*%4Go|UNn6sjPA+XE&<0CctR%y-CY1TTT*yflEZN37>+dqhSS)0k=c`f9mh6GYT z6N19IO?@#Y#vJ+Yno}88AMcDn-xkpHA@>cd-Qm5^D}Qd#P*UV$d3v!nxtiw39>VuX z=<~>LACzBVs}Yy=PZY<5%sYihZ2RZyu}((uN_&VMgU5^2N1su2t;1qb7q*ZKontJ= zZeu$;r$4AuUo(xqr|8Mp0eeRd$_RgTl`n@<|vN?B29SgR0nh2eB=^KPyC3 zisGtZdU9oD6%`$f^F!=eA(nPe)vfy_*X|&=BpefW&;0LZ=StyMyb(83u)Ob0{}WUR znmY)eUcw^_nqm}5l)EeUYzJb09hWYG99xDRU?*X&O1Ohud73MHhpGfMboLUDxICel zoj{Js+emDF&CKjY3(o8oQvCG&ma}`_;oZ#9PrLC+e`3pWa}TZ#2pgj#@U8x@-ncIh z&q6n>b)f9g|JnM#$6CWvmzM^$8^{=A+|KSN|HHG;B#1Kaa!?MIr;T~K-l0BhAfyTL zpI27m4$ng4B>!+S70t!+wCQ8QZ9|6*q$D&XFA@FUh5tPZ?Ou+Pb1ey5?m)@mHI{C= zftdE$H=II$7yI`tw7aMIc3lm&EZ6*u*$FR`4W!=ke5v@|kB4WWXNkmo-eLVeJq#fu z?Oi$>$o1&6xn%w?P{f6NrZ3QEp{3I$+?YAB?bf^%End(<_gXK*>ZnYv>;G<7UQih_ zaiC8$^6y#bS(Q2;Gg@rBbMYN?Rg|t9$cWyn+IqG8CCzMq5CbKZzbL!YFcJ=;k2?J2f5rZ{zrF*a`l z(fy(st$i&I$vGunz>PjhP0}-eR9zHX&cs*q#006@K#bnxA1UuEK$^-vR#vtLAihx) zy32j}SZYq6{VU@{+6E#MzW6jpxey6dmRzA)cSapyJEOvO7294eLHwgfVXrrl`?qdA zeA-lmXcnn&hM{j)mOTFXy+(Q{ma+$<6UO-4(P!WLLP=js79QS@jI&a9H3vr%`R_hI zD?gOofxm^wo+x_VKb(JfKQd02@s+k#Y&+om>Iv*ZH@6Vf_Z4}@hTOxm&L%CXgeYG&pU%j>@$)0MEdTwnm8=&&eJ`rr0c(f__*K? zX!pE0Jk5OMiCNJ6eJ3oVX_JjFx8>nk=!(kV9TyX9 z`>9?L^=cOAU+lM1|JHpYVsv;GdNfv@$XN?pG_bL=6DUOg%Chfgt5x7Nox`)xn%#`& z1n9BtJ8WfZR?i9UB0;D7r&3O-AD)G_k4*Tmb_3hflWazhQdxJAkC*WbS&rGDLb-^W zxzT5##l(G!iLz6%yfI4-v!uPz9mMtY0s8WHUzDx+AO+`s2+G&GQE3G0i9=--pKig% z9fWL@jp~$B6pC!TS}PEJ!*R6IO%dVMax7!*-o*FjEUsOIu$(sea^aW5)6Di4AH1%S zs>Skj`1a8T!|@%Ywa8$cL@D?1j^eB?K@QsC7A#LIY9|ti;O!!GOOA;T$4Uc`Xmc?iqX&P)?&@6opf zp!W=t6lvQ~|K2hj9d@VQ9#a9Lxg~GE_v|1OZ;9x#!oQ<}{0Qw5R{kItPCG?=b#-7V`>u>CXC(>xj)k0i73Ikd zs84&e4=Zj=A=bB_L`yu!wx{{~Oo{SqzFkCqr-HRc>D%FXWcxd=8FH^Du#_D_tHN4j zwu|JmQa)QXDM9bnoYN;`9Yu|rKjL{2IELlvlw~^+5%ih=ul@1MRGH~0oDOmho$M+^ zf_Z^h;bI?_r_Wik^mR_`A=%ATI|(O)QCX^VTz6MPQ5R$T|Uuj;%Pc99oN zy#AtR)sgwt{a0L9bdgs*WT)lcVau83Ty0#oHg*shfszb<;xOdjdxAB!3^;Avv7KMD zpWZZ#LVHDv7%p154L{`HdxGtwt(tzQV>>mV?0t;UofdsV;`(%AMCCi=-xI}DSHJaJ z3)LY1JyIVVdLCarx{Krm1z&tM9)p}V>mfawZjI79TUU2|65Cg%sf+K;@8Iqtn~AY* z_di)9|K1Zksgd2}v5#$jo9tyE3vD~dddcqVpoHkddxBpIsQB6n4q~Y}PVWN^WuhI# ztYXO5uQwY-L0@>~pYzBxL~NtirADzlt#;Nj0q0-~*>Ki>9<=iH@Rs5DFL=B6&tiL; zNbjEW>t*!$^A~H@6XA6zBDGf`|J*Xns1_b>a1EPpN$ts7vMfjEYb2T@rf$tBIcgi* zWC;Nz*?_)%EwT?w&7)U*mVMBtTR$=vQRR)dAD(8$;XcXRFy4jb>1!@>S2#azA)+sD zNEu)3Mv?hhDExDp+3h^R`)Tf0EKkQ13o&_1Zy~ww&rdab^&H+&oOMB?;Bx3UEKmDH zxU4mv-9m`9ozu(H(EtDX|L!P`5sKo~Gr_j!(Jejkyp?SWq56EOKlY&i@Qz{}e1@M# zrLfHsnXA0Tr|QvEBX|-khaa%#31UYAbtoB z`Yg2AB(Wdvd?1!~hX|<~QZjBK!8`u=11E=3sPDdaemc4#IMSk*R7*5b|2;#6h7whR zQ??Kmg($uk`@<*)O2RGnH>D^sR{Tf>USBLve{;G!WfZ!FO!HaTyA_V0?h{jV&IW%% zMveO;>rZ0aUkeQjUI)?aAg4s)s9r&XZFOS*d8QIghkq={5S~0gs5w+ejBX%(hGU`xuvCoJlS6dFYrx}ih^;4+sAdO1TRLVZ|pbGO_LPXGKq1m*I6U+^< z)jaO{%=N1UJIJG>wr1oD-G?_EyU{nq*0W*jwR?+#uXN{kkf+=7;&DjV;SI;zWw(4; zo?&}q$`;bY@0E5DE3@{&z~~MXeUHC`B}oc$qdnc`B!X?fg=mN0-`ijpSxgDIBY3g> z@P^|HL!=Fi4%mL{kVg{0MNqkmR1AG$y))8^da-;jNV@(9>VkCIiR}OsmiJxUPD+>? zxQld(3!6@ewH}^k4sE~6hlBN=qHk4C+lAZFw|SWe%gy99AD(8OR`cXC8^!jwbWgk_ilGe>P+3wb9w14_~IDPYuwfUmN-K zzZ;G<7nlrtTCnYLO(joiP3WO-NKETNXwmDEe{VScpp^1e{Wi88(KC{*NvS#Ldo8XH zraX}N-wnrmU&deOp?^>I-yT`1@!^Ga;$4LAU6A=;N$KGY$KQxM?grsv+smynUwQa7 z7JV1@om-mJxW%Xl(zA*vnl70L_9DwEN-l>k4W>tGgik+B1UTEIoS?D6o zeuE_P1mwSajf7xTA{c!GOUJjnOxlFmsJ_r05{H}(gt~iHZb|DamZ!h4-KUGR-a}Za zn)MQ&r=n2Ac7t^?e-N$OXXZnG4p^RU5q=d_i~bcgMX8GSQg<{;)L~D|z40fCO_DEw z^jjI0c4zRm)`V5hd1$m0g5PKR~0-)C$GU9Jz!uSb?IsP?#;*fNdYS zk(E}an_?F!qG!G3QR|5Odk&lEy+7f8BDRrgt=dUXesUL)mOlIRH$w#CM-}K8h(1Zp z(mm9;HG?gFS3Zyv_rphf#iJtWomUeOt#ArL1@!&Mmut`eamU5h?kiJzW#a2Q2)?#p zT6$>0;YsRKU+L{;9%Ea7m-M%^t)pvBD}Fy$tuy8DB=zEv_0(b?Y~Ep(XD zDk-j8Pem%0tx2ARpF(KtO|+xYXN>-PoR8eB9HvA^!6Cns(y91ahi9R`eZS*17g37k zY5EI)5|YuYcQcl`;5&=y$iHWysa&q}my}}r#r_AI5GljX9i(_)jmC623;Fjf^ayT` zSeio)ma@NStF*tlyo3C-Wz3yqs#Ro4`XZHH`-)wjL@{d-`EgvU+|pR$pE z&q8l|TxCwg`ajoQBUXnaVm1*oy7O6_aao9y>-Rf_=(Et*y4xN#g#==$dF8yf?Y=8)`1_@qVV45AxrmB`>LcCie0u!Yb3jal|U& z@OI^(PiL)Obp>O2+E>Xt>q&SQqR;Ib={ORHB)hH>UPa%{{6KksJ}MpCxqA+$j6nvg z8f5J~jxo1U?BOYHmU%m=BZJ}puWY?10jvf`KOQ&J(R!)%I>0}`fJFSnqBl*>_={jv zfJ=Z}zzcg$9GrjXvEpxT=8=AY#yZ|@|L%(ZY=ogLOBEv`!0iOowNO8)n;X4Fg`v&m zx_tc1QS|l?26g3}EE zxx?u0BfdlwrUmNLNAm5N(TNd;-J?S{!g^xR4iSTvU6JIo{O4aSVbBtnpl>U0vjJ`Y zbiS$%efSYmOC_)z_T31bP+(YicMQi5|9%#rh=|+4^FCS(8hvE(P2CPUjlj@KDF$}_Dz5~TAbzED z%@ERZ@ddk(tLS6d7#8gO$4>uDf_8hzJE&H@;CrjE(I=piEdv&0UrqRW5kR}Ie-G)$ zRzeFck?cCYxOKpS0%$|06m#{TsCF} z(v-J>s=9fQW()zeFz^NGN@M`7E<*t?k01Yp~a25>*N;DvVkYM=ah^OptQ zJq8Be@exp3`_8d>)hDnHZ=IP{O(Aw0~JS9+#0rcvouz=`G^an}|yGHh2Q~gaalIe6Ryk)F_ z{`Z#g6`S1e(96wvaGh`vhJNxls!w2E5qhp)H|=gb{DnSs#(5EgIT za)PDt#vahWB8mapb46{o2}`kn#-{J=hKk)sFiVrT73oJY=moT84SY&mOwR#Lx^XH# zG$9CB_(-~apScXu`ZtZYpIfB^ZTMY>d*bAfBJS^oPxj{ktr7kmF@cBKfZ7>W3gf>o z0<@UxBbj1tA)vEgv*NZwpxsS|_OJG~SwI^xaIWU1ZYrRmx9qB7);v&{eHQs}GMlj^ z3{dIthkt(1!JcIPdGrka_W+>nnfZ8dmiH5&g5e5*_m$%TrF*z~aLf@#^n%pc@zu3& zKwCnBI`4D@y%CEsqK=0s+Od85f?(1gvPXmaf3*P0N_*?NjngEcV_a0LJM_?}j@{AV zm!5#$-n4n-HlHD+JABO453-7xs-`@4M5F7M?pZy0wV zovS_e+1nb@6OIRKa@>$Q^79LY)WVt-;}woPTZb)v+mgHB>wvSuY1ppMT9`VF8P4KW|SIQkmi<) zI&<-_`c5{Jh76a0n!P#}ebFEly@i5NUzveRv%r@b!+Y2j}E&oz;2X-x06FwDre*`qFLoAmeIvv4mg~0eV-9>zui8UyXIyuzC zoa@a@M62BXcVNMiEa4 z_Dm>YL%~;|WqjVlc-|h;p%W$2tl2Q{yKsKpy6*tafY;U*@hZ=LfcoaI94$U638`d* z?AZOkJU9*;qg0GBj82+otv?$L!`^Yb@N2-HpaPU8)=C>qBwvK4Q{xy6THl!>KDW7UHby6y%R~(f!Yh|IAD>GKTut5mvb1Es+70NtN z2j1DC^D)vWK-X_vd93xq7ql&4=UJwB9o$Vy&gT->n}EKAES;%5`&%=xfWwzgL~y$a z&~(4$&4Co?cT&UBZR;;X3)fivdML8miI0>46kmK9<+Na>P)x#dQV>HCz%p)35`r3Eu~X2(g+v_BdV&9>KxT4NJBplp^lSH z0d4GLTV?Y$)PB%HQYb6nT4YX`@0@BSv>=*bh(A08wa1D)GoOb41f|*T-bM9gzk;vMI= zMzFMzlIcxf9N6o>Z|;_Tkb|S7#bHa5y{;Ox;+SIQV0xAxpt5-_0ecMnh_jy1vK0D?h^5FPe31BzWC+2 zo&liL;m%TQLy>^?#Cp7yzGRAEw&F9p>(^juBS6Uv4W>BWMFR^)R-bc3n8JWI?A^Hu zV;)98y|tp^zlo~>+8MnRcE;8o*!>eS%`D*g2vA+Bnb?7guqR26-{v{m3j1MhGyPY} zH)~MZsWr9tWmloL>fv0K0_tr||vbiveYKkP&PB zQv#@38TTnF6&TSMod8P3K3rDY;nDoulQ ztk-a)-n0@};1%%Q2x%$<^o1$Shuwd!+s4S+V!zKn@GOr7)Zt`Jt=M!v3RBxRBAqV0 z`3=wykCZ50`!@sn{>s8o=GpInez0H7SYU?!x9HIxbE#bqf?3+BUeh*sZPR3Cg+V$-(m!{2*yv7-RcLZZlLCLD2q z`X#K?3;NB$hRy20%Ao>ogFE-B0jJlR|Dn(JXt zl5@2B;2S~uIGa;3zXDolB6FC~ql6wjT%)|6@C3{%QWShm{A%E+KK@1^G10Od^n(U% ztKjNr(^<`GiJX*I$(Z~OEKr4S1G5|-WT2ii}e*0I>~3ws`<2eBWmUDnG%X;Retg{87k zd-C^6t1oUL(B9y%$7L3To_15yYc0Gi4`?4N4_zdA4Sls7?nf&xb2!$oZ15H=vcs{H zU^heDBA)gC+YPkx!1;fFhoA3G(M+;I;K%pZXQVcp?a-peqlJdn2Vw2Gh469PP5+ z=`e-VA+O!JIz9(_@-iv;>Z=yGah)7ov2ulQ325(XOAGKXL+#7?OzQf^MW8i`KDO-l z6jJpt{QJ#0FkwX!n{A(`z^xYppA&5Ce;t~zQ|wZIlwJ)=LuE`;e_@A9SD|O~`=YD$ zKwHnJmfPdk0_Yq24Ek%naEmWw?_o$MHPoiO6F8Ic1HLy)sU8j1_dO^~N6~W1S$0>u z6Hx12LDRbe4S>2FFv&;97XsROb;q$2&k@iwrCvNjIQ{B@XxQaFaqfJMXfKmS76eiH+A~82Opd*mxAhZs7qUch4bX-#f@vDa%6(CPT;@$Yz$UO1k)f%6#Jbt2md=zj}ojcv{S77n=Oz&HD{vDY4Y zME{0otXG9#oSSE_w`SjsgY-(zt4>7`*uSPcDborXa7n?( zh2uDNdII#ry-auKS{_Kd?FKrs3CDrf)x0FhyB)@?OOy;l^5KyBI^kw8XhM24(R*Aw z2HKU~cTSmGg5%+W@_io4acF_9j-;$M6l$Yo$e;Q>gIeYCBV}oFeV`TR{Bb%sZK0q1 z^z5f(7U};bK8N|v<711@nsQJm%sEuGahqe|DvS(e>B+cjrrkh$xBk*~&b}@{JEAF9 zBGJE{!L&PpT8K4#*$SwoYVoJ9Lq&krbX~s8ceVo1{4a6t%ds%^@7{=D+dKnlap-cX zhes)};HWx@=coXEs(3uN82@?rNz?Q4JLBHqY+xaErkX@bFdxu$li%w{ccEW@{o0ZC zJbez((%=6sDe^D@Q1_g!z{dv3fTmqqQZhRI3DAW8dR~i>SU|hkN(|*bz5{fIkIM6X z(t8B+UEmj7^NuzM0QAZg4>enBxb^a2kl*gHW&+TDCD|v;Q-*QVkZGm+VD9_{dUJ2CVOuW|MYmR%oGP7|%$d4ARjvRGCwTkfsud zq&zH!lw;E0`-nJvLo*pmgW;uc>t(I2Uh%VZKd7(2hVcF;|0+LA9;DXcUsClSz|yv4S5l%DVccv(#odbLgBFB?M4z8mhy9?9OJ>X3 z3j0Baxug7yCyZ}%15`AvY%q4Gm_1*Lte*sZrk-GTPILoWcwWqPVl)P7>s}}Sw73cB zpSq=c)>LpjFt0>taIV9wEo3g`7Qj z^kx(1pPQ*LyiuFZ&*$VTa9b&U-%8<>0IcsL!_0zVDoD#TbDznQR|31_E%Uf`pT7dC zB=eiT{TYm=qt<4E)%0aR8)|^-fL8*ep3ez#a*?ZWeX&jJUE)Ln-%vHt^5CuyjCvo8 z>SeNpVBDl`ZQ7!Kk_qZyV@{!PFbN|hzms^{&>WEXwE=qNKB~e{uTfl*Kk0w8D9{B6$4((Ph=cK4% zbb5b#3;%vN%;hE<9>?X(!FO@>o^A&jE7WqFyv$bK438!pIeL2IS{Kw-QSunq2EcW9 zUR-=TO_q*mH(lG=u}o4ER8CuyH%VU()K{|h01r(!VgD=AHqIxb?ZnR zm+?Wr0o36JD?!^2Cg@?tn2t^qYe5UDX6@@E!O+52#;ZB8@1TX)<@3&$JK=VA(L7y> zXeNv}`|{Ln>+vlpOpiF`I4{)p&wo6`h)%av=XBPpV00R;eI;xAy%K1-8O@E`(_y^e zY*yhCqRax?1gVTD+cvmk`27n(e2T6k&{mmqJ=b1B?V2Pa(dPJ!(hW&kQ6oT1` z^%-_u1$(HyH79TpPXTIoHxR{AL8$Fy$x#{1EC+U9MlPOyaV7!Kg3V<~vr8$U6=&wH z+VTI2dbjRdqW?8GjF1~|M#-HLAyqI}YMDueH2Fr?Iqy|SZ?wHiruu7daOjq#+R}3v zA+I~LxROM|h#vcNJAEhz##pi|b_I3wUqIWk>1HYh8Q?p9@W80#G!=~KMGI1Kv2T-r zg`@H8&o?*a6eUKsa%=K(+??PMJ!)?vi? z%w3UXObR1TPmk#&3+qo{;fdkKi~3=>#(CgF9KX^AY0L^)$pwW)U|~xro5Ray9#9#T zCyzv4F9Vu`a=#Ke3N46ey_1&z4lVS5k^G4F*O!$gitoA)?O?=l=$xQi?u2&bT*g`7 zT0*;C*Oe34MWD9uX(RuIUZ_pEytEmvy8v2|5W;=#JU!eKd!6K(=h0LFwC8>>=)Hdh z$HT##j6(fy7#Xx5iVeB5!=1(Dg+ghtv6<^=v_JsKHjVMI@f9?E>f z4txE915;_mQ(F2=k)-+a|~Z7Fjofldf?ztkh(97 z(#Hho1G=8nfL@TUP_-;xaJL>{UY{52S!Mix)W>9*qp!{$|v15em4p;G4Xl6 zKOQ4+c5hV}N{MUs0t>Q+{=ED$FftsEW|pn`2_wU~97G}27-rkm8f;N(9TUKALy7*t zKG_VQN)x(NFC?M&ls>rj`?bRo(AG$lY|dN57$7%Y_ku|cT5#YTjPjI*l%5LjtmiA} zl{2qhd=&l_Mkks4ic2?c&Vf33K6|{SmEbx{kQY>sUffqEKV1`6PAvG(uUeO zlO@**0o4>BJRzkqgu?Wbo<__w#Eo-+#t#kHk4G;6x^+9{kvlh}dm|*zPfSe$t!4n8 zZj^IBpp6NW_EG#JfS#qhu5zyve#7R(ael(SG6=LU_j!rOs^OeZ=_uysHuDEstH&}p zwHZEulG|Q*V)(}y!R&`e%a?{Y)hvP5xtW9PQj9CmisVVD#}`Kf>ejaW$-wv`s)A9P>#m3cRdxxm(EF9$T_XeL_NSKc$0xkuS1ud<*i(CZ z#lXUq^K*BMM$!ST8_Ffo=Yi|Z-&ZFa&b_EXFyEVFZ>J!0UIn14$Ii*?aKX44F)M7s z#SinS6Vo^fEG^x@f>iU{@68*K+Nm20>Qlr09aX=e5<&t<%k^miCkv?S(`jMNq}WI8`kP@4P!oPQ(8v#I;b6F%qaoa#xwo_2ZxQnY^p5jv_ZFTW z)Y5Z?PiX#iNlSLPQ`F~JsJ-mXIURoo`qb{%=86+-uryi}qj*vgy*-O2 zwF#LZJn1kMPLyvzTMt^1!&q?TL{c3Jb8h+%9UOU(-VNyf$4nZb^R0juj^S!6_*4OE zillf8t`-7Hp{}v>I~lHzwK_j7vbw{(@3wE4FH;8me*A!yTY{6m3D{NI^`(=ZYymXL zH0WZ28q^|%>?p0}TA=k)mEX4@gF6^ywl%l!p#Q@HX7A*1T`%O*hM8{Dki_msZf^ur z>&qqOQZ@=BBxn20nG?@p7Btx?*YxJEuQ0v(<`wN}dO_QT-2h_!uDdR1Ka~r^p6cCigDcEb9b7KeJza&~`T& z(6a)K_!GoX8_HypL+khnXpNQpeov0M1A4S9harGU2*G^w_on7s`HKyK)(IyhKG(n* zQ2%*<9d(U3K-IquO;hQ60=sWgr)|#`MF8#H^lZlWl5c=EF>$x7hA16q1E=}!rXjI_ z^1PC8);0+Q)GXbjiBtz_l{CDS%q?Jjbu3O%ovd~Pbzr?H+IKcC2GC24wNx_u@qk8Y z^aq`;u>f^ASg4Rab=w?hYs%eEEUcFRnxV+0J--N}2zlsd^}G0RomD(WOj_3nXJKRN zTgx}&aP8#B*>30L-vUabm3!b%kQNB2z{6*v7AGrEnByTP!ArG7^-k94Q4iSgj>Af zfBgdK*LxG)hDEri5KPZZX7tyUlix!4i)mA!|LvRMFz{oo1oeHDY9(9n*O%hj(VzOS znxTczSUWlr#sAw2(qlb5HSLqZ9fcF)0xV05mprt+kch(U;hT?>Z@QSmx8YDH{zzD& z7+45q?oley>jN}!Y5H+u#RQ-)dgJ*%=S~C4yn#o{A}|B!Kc zAo1@sn4xjmn47e}>jYZ4wJUyfxiE`~z82|R7y&c1Y}TiJ?%HrX7`&dOnYasQhK;gE z`N<=2eUQ}pfILeK`cKM@_v*R+Ft6yeq4-Uu1npWBaU8YPhJJbI<}~e(GmW5khR=N* z5wnD)DY4voSI-02YDJQ_@67eVC~$XLG=}XaTs@`TKRrcUIu1%p>sBMO>4WQ}I;z|B z7rFj#9v;p@qORMvDtyVn0xt1)7Rs?Y@P>rGSiMk4hVM;c=}o|1P(RRW-CmKS8G_Vr zhH`24X)ngqE5%_G~P)P@pGcn#m7+B4O6! zxzwxBLaI;J*nKZJ-*$Ls1qcEsK^^AbY3YTi!r5(mw6>j77;29VIa>+Q!1Y%gLo#({ z8KeXRyCf&Qpobx9=uM_&ft0dji^aSRQq+W3N2NWinUt49K6f6}KD#K;)^i(DJG`Hy z@dmJFd2ACeehkVy>s5ZB-&}K9ndq>IN#HFVJuVb^!#J6^$loAt1V93 z?!mmx1~07SLUSI_&UGJaW+cr9^fcv77VY{hK=*EI>MOP613K5wqqfx!wcJJ}yw=ZP zw$Wx2V&dKn=|IQ{B0|9;U^j^7W_)D^tl7$GHonKSDL`A@`uaW1XJ0@`ZHEQ>Vq8#| z^8&A7;^o#mCqRGgscYV~>#0E=?UOJI9@vQ=A zyNZ%qIr7s1bxZlB4qE3CY*)98ZHgXs1u@ZY?Xr-8T92{%i6#VaCLIR-~;gq_Zs>r zvxz>5CS6F67K*-&QG^t?&~?-GI-Id`&9W@~kuX2|ol7#`q5|n=G$EIqB&0V_c88y~ zfz;n;h2+&G=u3n`i3UBrp_UDKd;ZG zF?T`g|M1eywZDG3_|k57iixuZyv?fR;>)!k;A|nd?sC1cwgZJZc67KhXusvO0qXS( z8U1Jm^D~u?q_SP+aA)H?vu89_UIDORJKT?Y@(r%*OzSUF>|ZVdS`)(Grs>;|k{AYl zDZU7I&{*Cu7MyU0rSX+0*;t>1d0*0>0+pkk&;m6XbG>2{v~c3F@FU$BSclsxu7ws6 z(88I*FD&zm&=W+^hTi6Ihcx)xum_D)HE8keM}KI>nW5Ht=)9w)HQY(eUavB<;D$Y! z*mjOGGzqSdr5hhsAF#xL(%$t_B^^g#4EWA={OY0$%qni-aPI}KLOM9bSFx~CieQc% z&f>IR3Yu{AZTf_jveiNlb4C#Vz06-1#a-KKUr8VD0Crn)mr)^cKLJg=Nf#ft4c8)( zmv22*6N0N5hp~_&>UL0Dg;Fy}IKK$&etg|i+4gl7&~+jgpZZm3w|`NUX><+F`E^b6 zV@lf4KiFh+_Rcgxf94UyBUd!m21*m$tUS6YS`Fx@QnB5zlivVs-miN}AOItSfsj`g zsb($EJ`<_;y*39|5}CxdFQ}AYuYZ3}`cA_a*6fTb8&kGBqzQinZ1MBqJI=grE-GUU zBhDu`!7qY+kiPp({bt0f0o1qrqLqY38*JN;9}<6%+c3T@-aPe8;x}xuw$iOurd&wh z4`vhve}@*#Z94InhM<=V6!!Ye+Q8d(f;3Ry%%g1mWsiMPnDgRk7s2`w12_vU zw7BdTRUy@6uaLtlg>{CqaN7uV&rgq=K2)^S1o` zaV>A4osJo5HGKIAP$}BUx8EipJ?BwyMB^je>ovaYy=2_&1}vDBA|G#xg#vnm!9>s_ zAR17Uq9yydP1xf6@jKB!j9h_MtnX}{dbBN|9_%tKA2uBTRWP_VT0Zd>P=YHK!z_F6 z5X|>B#`016S2Y|Dl@u;9ysmJzl#dwu)!uyG(Yc~^ z3C8&+iDEYG)zd(`Z2HI{Y+xSH^xwywlRF>{r);{qI0?O6zBcp1W7#EO!7x~m=+^NC zKs}kt-a5%c3;dx=6Vy7;r)DmZ7+kmjDb3Tm8P!{mj(f<+g_n(i(%9$kGC!$@yUJ@io*P>&034F1(vM zML4Zt6p?K+<{p`cKGpa@si@*Jv~X`j)#3d~NV5wiDx%b&1-_O`Qv@F6pcOx4uGcQ6 zrUPo)^;?W+E)j*!$R*0_v*Lub%3fy5!xGsD!&U)*8Ml-PRoWi*$ z%^F&8a_#$bI|f=HxX~S_#L@sPjQu=f5*P^SboardhR$lBl^oMgAFH7Pm($B| ztXp0-r!Vq@WBtjIb3ascA$8zk*Ld_Ej&;vGl8D-SP@59gHA`**OS@rwH|ok79P7&Y z(cupXY(Ohaci)0G*tpU`cZH%@1I`qE*&J?Pdvv9?F zz4v&|5pn2YZoF`QG^+u{!=`#Xq_I2~I%X=GGno#(h zmfwRZpzTQKaniP&0n~i(QC><0^uK-qT^0fn(69R&vAbPpfj)KnI^+CtDX6u?>*4a@ zhuUk(LcjF$V5Yl#+amKA9;Cl{k5$MI!8r8AZ0gwU&ye~NJ(Idp2WhF;Mv5f?q!N6^ zqiw=JK|i!I`u^&ug*2%;`^UUfKhS1AJa_w~1kBIO|KPD-SIP!jo11>*0WUA)pmR>(vdV#el|)%;?@$hVeN5sKE!(1Zd%U%vw~ZGOQU>>C)XW1ZwB!@o$=AJypoL%I%caCiS+KqfE7S=_P;0FgQ}t>TmWI3ui}03$rD?kb zm<#>&JLHP>smyOA^$<{N5iGD{TUf^VKn z;p^ucdytA&|FCo*%>@>A#l156C?Ku3VGHs)5BC%lFN9P}IKmlV=~nWDVFgCAZS9!z zg=Ua45NUAT{RS;KL=yJucEI@N(b`?|xDm$V6_@m2mIl~1+c)bfqWl@4&%Pqfk`iL= zfa<7eq{QJ50Lmepnf+Y}`sz;g`yCUO(66tA^`GXMf>dqZ?CTjaNX5J+zM?)syP~c{ zd&1U`O1M!AMaV!4R({?%rstuSX~#w3+!%}^QK;<35k2VFfAV>mo+5?5nupx3u!soK zBRoetQ!l}Y6MoS%^kNM3%EfAQmbEva|9#z^uK&viMlw@{k%td;2SKlI9uLkie%T0U zyl-!^$8|VcUTdCM&eDf*{?gL@dsletfQ2S;DGh`5T0r$_JY(*vm&G>quy8rYF2x0-=9$mYQOrw zGqNOr)aX$Z=>s9y;x-)bf$#TW?-bcusJtwJ^k)7i#{eHlwO(p=d|!d36}Z{pOOhsm z`l?^k;xamxg2MDhZ@Km)hVz2}4Pbiln}8Rt=da@$o85Sr477e8d=jE_v4F;u#jSs; zO8`{v*2z1zL@He^d!t%e->oSC zP?{aubE7ygc87aNDY`1bnI%zp_shN+9I13P$9y#vAtgzFk-EwNsod(Xx(~M@#kK0? zyx8*{!5j~vUv~8_{PpXdkJ3ITqFkYcwz4ukWkPsP!L(Y!gjB2>*wwebIaHqlvv?Zw zI=s)iy+9iyaKk#Y*sx(?n`a2_>C3E$h<>&Jc^o9zKDHj`a!p0R_yzAkK_W$pz_JKrEl#`GLo z&^P?O(VYX|kQ(W>7h?ycOSTkVs2h+HKZuoE)rYiL_6DwQGVpu2D&YkShPSnmw9p0kpmry`qA0jtJ&> zm_0?m&1MYO0iw+}vOF(^0BuXx#}~#X3&3ucewTv&j~PHu#T!W+nEPA2T@7kHUQO?^o}UiJlw-G;^J8Tf=ey zP}`KvSQ_?D zjHYgg0NHb3p~u@yN1zv;G&^SKq(M$>?L;JcHW>+H_T9^BE;EXkT`Z0&Ip#WGQpS{@>dJ>M3=z1sT z_8K@+)z|BEO@CJu5qmQJfw}ErUPxQf8+9J`V>I-OE`8UcVI-fJl8N`RSd`as|!}U z`SBG9W-By#PtTFQg5Md&r(Ya=$}a`lV|0|BRkBbUaD2k;M148X3O_XD9i@R@Zi=Uy zh=UFVw1&h^+J?N4hU{i^n8arRtw+Xl2li`qD9l#ipO2>I$>;_2rdf-C+^HTwRr`qE z4Ls`t6z531*Mc?lh$c0TdF^U&oOviL?{Lq+Tsd09_LKirxT0csVAUUe1kO!jyt9$` z9B|Gj?IlXM{wTw~Zl~ zJxOypyJLj|T2O9M7kYC8(v^idNli-Vjhal27_RoinmKn-o07#t%G<#B*!~!#rwUas zo)m+2QQx>f#L~kkZA|s#SH)du!QnaG(YJGucJgRyzEp#~{xTCc@x398-L)aP4p!%k zK<^Nb@igJKmV>b)|Lj^a>tDZ>ABt_b`SffH&}Jy^e|H{g2K4PLU({#HMnEa|D7h?T zAQh;TxwF<)548J%(W7{UwSa0}ef=kE4r)cy_*Dy1p+}TCVb(rh0)5oEPC5ggO&ehM z1fP5Mt`E%Z<6atdQw^mdm?P?<%-Xol*J3~`X{_-I8KH-HSU_;BZxTk{g~(=eDJ7`2 zJwiOyV^9z5D&b0hJ3Rtd;~@^QY>g-wyA4hlBQ?ibb%~4&Mm@6h)-!^3&_V#M-~pZ=9KTOw2Hx{tg4$~n=Jb?* z%|e2&M%S9pK?^wH`H2Kv)r8~`omah>sTZVa zgw10#FQ8rOHm5d!O-SAQnPOrTpasXV@Z);@U7%)MBvf(?g)pyv6MRl6_;>}-_FCZP zJ)+A2w1~c<*w(WMg*j4-tJ_LFmKy-25B~qkI`4QY`#z3aMMx=IGVc@$Nu>Kk!-^hv zk?bg;&=5k_jqH_?sDm;>Wt4-AWM$8kamdP^8JXpIUeA9%=im41`}$nJ^&UM{( zm$E_6V%a|YWXFiR-11AO$qU|!TW8E3Vbl484x{~^+MWL{NMJv7eqN>A zuN`;DEGDwXAP2Mbw~$q#(j)k+C zIje7C-~C(F>D&F`0#JCq*Z6olGxmCcN!0C&%}8Yys2WcVmxDr=Ub{0je=bmU$#bff z&UpH+F;^C3>*Fao+DYT^XQrWa>v_0zRg0hPR};`TY4W*TS@_EgdxA}=LN4k`Fftss zG{Sf$UDW$I=PO<541MLa_v(#~V;DA|t@k^hctqk$Jz zE4+H;3gRlLV52oDYkmf4!LcF3;xqURWiVi@(*8Eye;`EEw!OL12zwD`pPTuus{^QI z)`m;PS)`+0RW{u3Ft;r62Q{$BBE8N`mNKAf2i=u)()5lrq@v650c&Mg+Yc$kzcLL( zKi;LL`Fhv|=_TWI!BbpF$$>#Dmv7<7Ol$qpH(%ozUL}@Z{;7`i4}$7Y{%3gO6y|ltmiX@-d5hO!Bfj7QV?q4+Nxdli|t)y6pYP#(K6A=%87_t^%1aK(9<_-1rfVwCb(LHk%UnY?6olbxGpJK(W zt3&8l*HIPB2P#?ARKht>36vo##8+VyqsBS?(=<7%Enq8sS@kbnDXgweY~Hc%qvqoD+ObV4PIv+0Q`yRR^{uvtES6;tHTLwbSqP zHL>R%v8JBu$-upsW`AG%U9%Pxnrih%*b6b16gLK3V~fD-zmORv_;nLKRzJeWF@@qA za(os3t;PhLvBRLQQIODz_zXZW3@Rg#+`s)BWo#l&*EIZpdEQ9^TA1*h_DlOK zpwT``Wk2~auFq_e-4-8aDQ?}(C6y;n&oSYur<=!4jmBVvk?WQ%HtYKV3J>C@*oIXx zYJ@3w2TLzvC&B9NdZzm=R{R>z_2QcvCPDY^5VMFE#XrZod_Q^L_C;M^Z%r{7ZluAE zVe4)gII_?h@mL1|j4%o$``%Db%tOiJ!9uJ&ZLq%5x^f3!>SA4;E9d#}**cyQA%hz4 zh#aIFU+Eo9ZE)vPEOnI90zSez9N8-~<;IDp+Vfq9$+K~c4}w`@YzA#Ow_{6(1RU)# zx9o@&H+dR~JI`g#E_dGruSV@#9;B6t6-Z_JQm|D!-tlG^8Hu^-kDX5)SEsob#rxis z*FLh`okd-lIQ`F!5!tW~(Vub*8YsTPF-UEyV>gdcjxcPy;!TV3jJHy{yhE-Ec9Yyr zmZ~v%4>Yvcfo{zaJ$8j@>XhUXM!EPn`jvuXsK9tp+K6*D17Y7ugJ{*WBLlOkI}J@GF%)gimGgLUFH?hh@jSBv;ayJLn(N_Ht z-#8%=t8EgMr2hRitV?djj_-6h-w(6+C*XFbTRu{5#nn&$e#NRnqHikb^ih14-|ybh zKW>fvd@s)!%>`zp5)2);3|&xnbi|UrX&fV$#z__FIwIQk+nWferl9SgHzU`TIPhwl zN=~w?EvOK$Y}zKefjvWQiYgC*4%fljbZ5CN37@yjq<$UKKbit(@?1YrvG~~+pnlnr zhl5HxfNnn=C{`Zc2UNqx;EZ3~08mNs^Dm-bBh`#?(w(d62itJH6Z&ci=vhT&)4PM} zG3)VeFjjjCV`cuXf+beCT8YCHI&ACowO z?>AN9=~K^7q_-{_0)nZl ztFkja4=9`0zBaA0e4z3toFYCv&IKCOZ}wLr8Fgn5CU1!AAic-zld8^$xjX*kx?S5E zUd@tUbpF!*PjEGjcrNy-<0U|)Lhlxq9Kki)G#gU=C60ZIC0RK7Ef3E4RO^2XgZE;c zY9ZmQ;Pn#eK^Fto<*FPQ!>7EF{F!*%3tQHy@I@V*v2bY;k$N_y^#2}v + + + + + + + + + + + + + + + + + + + + diff --git a/ROS_Core/src/Labs/Lab4/models/model_example.pt b/ROS_Core/src/Labs/Lab4/models/model_example.pt new file mode 100644 index 0000000000000000000000000000000000000000..7f236220d674de12c199ea313f058c448df1c432 GIT binary patch literal 81493 zcmbrF30O_<*Y}&}l2po&CJn}<(y-Tkk~txjBoqyVqLUDcG|xyXgrr%>SUP*Hoe)A2 z88gph&OE*O{hsIf|Nqzff8O_c-{)M{eVudf>)fC7z1LZL?fYJPZTE??a#B)CN>cyZ zOIJ!wDr`wmaHxN9)ZDP}(BPp#b0g;t311XC)4|KA|9NU^zx_-~8b{HHL>e?i%Z2mCW?;3O%fNb#UQEa!=aN#em> z`nrS-`I|R1Qf%cR9`@G&o4#G)>JUBaCI=8cRLyLgC4{WZYuZ(*bVg*HMw z=AUU}C&osK$NdFM6p#NSY{K6l*GTb153$={!tDQ3*rb0!*^4LtGiu6T!rcG1SZtDb zYL~t)VIF_;JR`+k9^z?#4Y2=PnD@WX9K_TAndbAyVl)23V!nTb&HNiQD^fh$L+t0H z+~wTE{_E`V|1XxzU&qCB{uws+4=mshO!|+>0{=Ey(BHt|Nbx)m@%+EetS;bR?jQ26 zxMAW2|BPEWQ94q*=r3HNIP{OUu)k4@BgIQR#No?g#Nxm7`G*BZ&ixY{#1Vg;XiF`8 zy3|RDBV)wN{`$S;!4XTl!h?AEMCqmfaoVnk5l4mmSAUpzWsG>$Kl;|<)iL7efAoio zV`9W>{?WG)uZ3w__8)2Lz{7CDh(AM6fP5zUG;|dSKb!aarNPZ1hc4&x( zozNGe=Zq6(4Kxw7hAN7(hvWz%i%V>~>Nt_Qy^2sLI20wKKiJ zz|Lt%@b=s1IDU+`P-#;GwJvjn7caC#Cy&O6pvO$1T;m{f);8e^-|Bf zuYIid`+UA-xuwWxf{RFI%|o&rv02c4sU@2Fx{5^~c*%xe))D!o^k-owzd~4*iQso% z5MeJnVP#1rJuypV3mao8-A}q6#wD?bIXhrv)pr*Bt(4^$_7(lH?EF#tS4jPd=3VXo zWLfs_EIVwhi{rnw>_1!izyG|-rIii;Ug9)OX|`z8%a@duT+Du}D~QH#FcF3HQDWj_ z_M|z%h~{kwfT-LKe$x5@Y|^O(l;?E}6`vKcKl&r5&-ZlhlK-du_xg3D;NR-+at(+7 z{|SUN4y+&9eK!=ynX+!qhD_2o0Ot2G5`HcV!!+R?eCOiO_RKJr(sL-Y*(5ET@{(gg zm!_~)O2Gooe*`Cn)}hhGcv|P_Zt6gPSQgNNyRBA|i zk0~3NnZ~~CE5tRE?!x$`9XRmWb2|7u0G8$*2DQ^!1P8l0C*JxYoN7;TE_E*Dj?H^3 zr2V#KW$ABVf>I4lm!BdmR&576H%HL#=7XbquM(z}l~J$i*Ps#Z0f}-aIF*7k5I^RG zkbUYUMs-NBhl?^(tJ7N1K>%Z)udee>nzx&UBXa6n-`XAUo zznc>N@c~cm$3wdUgVdk)-}`{Jl;gki0qe0YcK@F)pq&~)Qc3}mGu&MEsV#~oBD-vKB3;#gTJ$5a*@T2D{k}2tLb$WaKa^v~=g4?K&lwdqvPhp6v##FXIsL!_X)cvs{=(R?$+=DuFzfgho{Pdn&N;fl$7rlgqWm)Xy z)fq7R%T%&hSLmpG!;YkBKGD^+dZNU7QNII?>)r`HZ_M95&edCQ5VJ`bpm zj&fk9)d#@O`xl%pX(qAbkqM%odvru+jnnbtAs%bHT_VjTA)o|3~qO+aZe`jdo7QnTy?}EUYMqEM0qM{hknJi!$+gpnnH5^qK+X)x(V&p!x$YZIc zqfqb8LGEz7CaX`rhSO)I;Moih7TerUqLTUufBzoIV&ARiLvCEdjEXrlsD}kLch{i> zmW$bJu`DgnHeg(e6TP@@#>SlN!GDhI4pXKj!H*r2Sm6d+yteBM&bixx>n7^5>PI*D z`#n-AnWd0@#8UKmaLi>UC8e#S{A35ptKL}uqq4iOyl^Jxs^Z7II?lkXXIrq@ z?;hP;*U5a}7qXr`3x%KD9i~v8$%J_v4T)=@Vb-x!*(P7Va>Z6QHS8hn(fGx}<;JrG ztz)V7!2;$nC5DM6T_gtwWAS$&;mBSu`nE8Y{qjCW=fnFml}rbk z&{R!^%1zia`wUD>siGt4#^;mDzlusma; zP@yRiWXj9P^5+_+xr5O|&%3;esghuRdMFl{Zv<=~RhRku6I(y$81!`YWzjX^A{&E+ z^y69BFQ&RX@COvPBSkWI2KY2g|~avTH(d$5iI4Vk=D9(HDmlc+!HA9Jvlj zhxNg~*h|k+NO9~%4=qYq_PXAfH>0me2%O2-OCvV3?i#kN31oq33*f5S1loV;2u4S{ zu$J!H^mge1wBfzT!qXI1otjF%o}m=Ic02a^v4CmfTc{pb3{~IyQj6Csh}9j#pLDnl zqo0o_i@Rn}_b8qD&(NZ;722%HtdkwFbYedu4VkljE8d^KiTzrijQd6fk&c=Iounev zF*t~J-NxYFck9SOem%^-c8O`9I>1Z23>7UZQy2Z1x0zLv-)7zIeC{;q0>s{Tk;(u2bt26 zv!>K}vW?9T?#;UAFJNgbkm>9nK>a(2eHr}@Elymc_>v-~ue+J9SI>Zl{kD-wl_CX= zPbQW605*D45Ztg&;ha_5*r|dE^x|7T(o%6?5jPD*l8=wDY3)q*{cSaEHY{gvO)qlJ zT7lHD@gyo;a3QNhH~GU#I<#u$FseU4oUA@v0H39kv0Cs%pI>fpKGTAI39W|gY$9b!MA6cyFZXuQ%P0}N(*ih>;?66`PQ|@^|SiH3lE9n z%wI#2kAq2RnK{X7Cvva*nc}uShN74wH=N!toy5%6jb+(ZbBL=iC)dfIEO0^wOr6|| zcDEk|x!*geWP>ji>m32lyf57CJ+}DCMTIFmR%96lJ=nyEW4OAx93Mx_V)8z_n7nEV zaOJu9WBS`;LGrqktXufk`ftq!)hn@G)Bn@{pXYD$KbwC}gbrK$Yd*LK%*Iy5a~Su# z4{QJIN^?$C0q>{8p7eF5@zckm#-&ugqp2O+PUZ5+UeoY}_H$IR-HZ#)eZW&EzVPo_ z*ReV4he7yBMU2vIhR`R+(YGL!J29?;JfmIl)Y%Z`l=XrQEPaA==lWq$c(LTZ)fP}I zYv(UTn=>UcVACtBa7XiemOXA2zw&u1lgTs3F*-w-?bcX$UYSlYt*S7-aT@Cwmd8yg zP+jPKMr5R2uVN6eX`u=epes&&)#|~tZm2CnRoZiEv zE}3J@)IP9o=QH@VK}OJ>vl<4aK1WBta8y`m0SYTF@(a%v;oRaU(2`aRR!2-R{Dy^- z@23HzwCe>dey2|tKM&{C69+LW?L#^S*<7WAF12d(rNH;{EWa!rx#?@M^r{Ryu||uW z%;TZcLJRCx4Ppg-sxWiGb2t^g7abl{;?IFC{DzsYV4BHW2pBSmecT~&lo=+*uRl|; zRY`}*k97fqr9;qfXDEmi||+iM`-Gx#g&eVfWo4H_mq zp65l)SJe1dG3JyxG>BQ=9xaU7rzaFg-9g#6#dxdGl-_MU#dY(~*r4#VwMN1T)< z3}EIHB)BoY61C=-lpI_%0!)n%J;Q6&&YxQI&weX-*FJlSg#NDS>+Nr;SxSbbfl?z zvv|+IcAPuC15bI3L!Zj;@N{A`+)VDohSs0xKcP*+x5_bNpLSF~{|xG`UxgcLvQ!$R zO8p-WApKTr+Mbz!y}y~Up~nrFor4L>xa2{fR(9fV#cYy8w`S&~tGfkD4+p|b=P1{U2R4zb; zvjrunTRY8odjQQldQi2|HNJ<+Bx>KCj?&i(xo7*=Fm`*0(6ak3-zYm2EF+Alf*x$j*4{iTc&*qSk78mhogL=%$}w!#>UA zPZh0#tRNk7HhBfkw)^35qb(}g_|V1>4{&`RNA|m?Ly6NG7O`g;PRYxIFl$3Lcyo$F zqH-3RpK0T>Dso{YE6u7_%tHOdZ1}$IGWW(thjc>=;Kas3)H_&*!S1i< zIw*j<6w-m*v6Yy?6>=#bw_>x+8a}FQ4sW))ShBNDPY-qC%^rBHjG}-lZAYVBEKOQx$zIW zF(J*V&hT-)WQO#7+PQj+)26SV;OxFLxOeXWCjP8P@oBrU;f*Dm^r!=lOq#-NPQDH? z8wS9-eUE9K*Hv_Btiwp1TU`7JS2p=v2^-$42ea?kOwn(S!ms*TFrBf9`A;59@zdPd z*+Y6%vM8A=OFYbctzYq0tG-FT1|34FC+nE`I#t$2MYN~UhH0zjQFHwOHbp;;yOut! z=H_!fCg&PQhurVNh{qea@&VT9c*?F`dcb;qRK|DontBNKP41K^Iy4J)mCeFgFCW^f ztW8Uu_wkicdG!~s1%mpyyKMTU;k10$Z*Z-f56)}%^-k*D{~vXFG{5WEE2EH&3qLhFipkTtb$!gg(1HMw_PD%t>iE z9$);N*WO?zBuza|59iJSw|Fzr!=u~acxDDaqL(xc*FFupR$3Hj)sHotvw_-ZE5dEf z=&s&dP+R*Rzw95*HdhDY98s*OBq5Kioer?inu-*q6o&gO3#muC1M4w=AKZT7Bzg67 zC|9dBU08X8@qX!9uxFn<+j1m{>yy#I-cI<4*F-A9^R4G_%H+|kw73<+beECCb}5Q2 zozLz?ZA4Y8cCOETb9^uDiZ_B{L|3*np-RwZYJYtQw_RS&?VhL3Cd~N;&lQ^_gXfK+ zfju?~<7aMwW$Sb4chUpi)o(I}{wxp`9GFhc;-5@UPnZ4hlw(KKrO8RqrOYK4al5`1 zE0#TrUk_$GmFQ+*-~)NKNfd}S)~WbY=_o4f>cKuZYqNP@t^Q|P8K%LZe^=&T@TEg|#*I zVa1UN?6C0;xL~1$%jWq|UC>F&n6Jx+)$@!^G7tpYIx2Qor-siZxN(juz1cbfTklId zpPZdZudl{4AHx&4E?m9-)v{RP-1pEJ*Ph(icWOB7m>pFbsiVeYCtB-VS2y@$5r>*Z zuyWOSl7Jkjjq1rJDs-d0qSH?6u7u)|o*Td|`5trxZiDk%FTu!$8~D4FCAwv^#}Ez$y`SAA&0_)Gkj)Q#Y#Jej||^Blx^y~a5|{G2+~i^1UW zVpOyCU~HT(lRfgA|E~NLskR+vOk9Qm^YySdpNJp!`0-PZ_NRrq5Aj8YELMEptdH7*AM17`m~3h-^il%s?#A+p@f#*6@i_`85Z&5IP0eH zj4sbe?p+vi{7Sbje^4)lJ~c8dr`3wBGF}LYFDJwKf%%lM zc@|46GGeo5KV+Kg!vy2(0x~+2hbg1=Vc|Gm$lbV=+aZ=^5fMuzvdMcfLevc(MmOWh z#pBTStOlHU_ztFKj9}L{9KdcTl<4`eIGWL~7Lr19?BqPhLu=!WKIdJ&ca z2X6FdFy{o=_R$mtzHXtC*lQApH$5D;o|AFVu&$sVE3V_*?a`2|coshoAHqz0HE5M` z1)MOGr*&C2Oy41^&U|qVWF30M`8scAp;hgC#;KEV(jtdTc()HC25)3~n{vp0XCdgF zP{-m2Mxx;9O>C3SUO26M63kMwx%4DQCc2kK4_1_cO;io#H0WUK2rZ^1q(XdW8VIXD z0S&o^-dl%*OIH%*PTXa!I%EKoH8MK-YIG&a1Mf!u#L2 z?^1`jq&9UjF0!Gm?yImuqYaiv^db`{d;VqIb^d0)2_3!lmIIC7#|GcMh-)hv(Z>Ha z1j?9`OPB_oE`1A}%1Ru${{-(VSIq4_SWaJ$?Z=fh8f=|M38q%8WadeEe4jvXe7nDs zOI=e5>n@H(+lB!wc3dj{=rm!eGY)`)0pq8=D`XAiMU|6gg8iLkto2ws=*vdnpw@6Q z5TRt2@-wU%5l@l6HIgsSchS6%-QbXF$V{GnESbx}qSKr9PU)$P<)5+Ci*DhmJ`chJO@*G-jAFNrEW=)n`Ec*{Zb%3+ro)x#Tx#Iuu5&Gl$$Cc7$Fs@UxmTXG z|J+Jb^xCkSW)^Phrbl02-iDwNMb!J=1nPVPI3VCDEG+It%H8DY=cw(dJ8U!`wR{N_ zbgv@+joMT^If|`L<7xcn;Y@dO0u%=N)5f1a*`QHjC=+f;@oJVVyo%>$cOHiBk9d;w zZ-VOQquGPOiIm-NmK$_^1uI)3a2IM9vR;J;@Vd@67@v^LzKq*IyG}(=(4B5LXJMYx zoL+aJ_KO@1X&lBZqIFojjyK5oAz ztv{Z|yl!rBQmq?KDLXkBn%0-Tu6V@n*Pg@leFxH_!fv?BsGTcQH=y>Mcj#_ifZq%x zZ2m4ea(XlseooD0zfKkllP?tEl{fk{M54x-*Y;yId^W2L^`@g&EiwB?v4WSx=ufDA8z#ZlbN-_Omxf9GTB2F&sXwO3}YcX)F{u zO*I=0Nj?U&W$Y<@F}b?VdVwwXIZXu`Kgo!0-;{RN>{U+N3rk77&JqWjFXao~>|k$X zHQDQcQPiUM6<%GDWwASV&?8TdJuDl~dOjY*HlNvmC&Iq)U$YdM!kZ)v9jwg8xs0X7 z-P&NH(Kw7dnU5FDH7GeUnq7G~1}!g}llqJnXg!rhxr0wTg&3d4!P^ws&8xMPcP$mJ zUQI#sgG;dFnH3wpasWFU+Du2c9$=AW%UF+P1K4>dfzGa!XZQU(NqI>Q|LE3Q-mcx5 z1-#ltra8^*RP+ao{hh#VP$5`icn1USAH>6JrI;zIu&SFG%-3rmyh~N3VKdUm*Mp~jU;2^q6ho&MvTrsQ zAtRQ@n(sWG?%hORF7IZOmU^)2_vq_Dkfxesc`p!-NUe!lM@xNvt6S&kY) zkJ>&#q0M=|BHj-(;`M3ft|3%)Duqi58ca{awV*lT26nDG0dnhlFzIOx_~f$^Go5e^ zMrAajmVz2>$nOn<^__9+d;9d;6%-L(n zfthHY4(ku&ovADSAiV(@g0`e1A6OXa{-v9U-@LO?G8QKQNftg6#|T zi8lN06gC#DC9Mp-2a6ndaam{Vg%dHw)vBh#q`Uqz$9>XiYG{BZFdmcSefK z_3gym&7(T!aj(9N;yYG@^6V1Y*VuLy@cxsF* z-lxE={J}JFqYY}gbf>-CU_OhDg*~M$oJ{Ok7;NCo`u(t_9iRHKm78Rtn_MoaJa=af zy0f@aA3GfPdK+cQ^rI}vJ5KH3XnqDKa6iv3fRi4ZanPOFY=Ze38ufOLD6s7;oH?${ z>Z5jWo^Ji<*YXTnc3=#icGYHHZlmc=o*8>FZ70y{=aLQjA<(ld7uOmxilfsoKjW@s zvs)`SH@T*(j^YQ4+;<-yw**n?YE9;C?t}sBrm-1CoA{3^HSlo21AK0y#adcj*!@E; zwCZ+G@|<2J3|#KWZ@pc?**~AeAKkSc-fXmIx_OgXYFjxKCHKIpUp=`c->b;l)RMWK zHmB`JMzTpz4ZpQ|5vpoXwj_ng#NTJ0ea~U9^sRtqzAU-UnCX0c2btm!SUe^X%UvE~ z;Z1wY445uFvr?n0b_<+lbWK8PexZVfz43g8k8B zP`2KOqK$OfJ;Oe9O*@(!_k9yeIpwmwd+zbGmy8i@t1;!b8cVZZHIpd#Mg?gv9gb}- zFJZ%oG}aswPvtuI@O`Tqi@H0Tsp*`;S8fL++p5!GOv({F?P9@(oYjMGu?B3l!C6vU zG+1%wjM_26v>)kvY^vYnXuh#Gl@&+_NuZ$Zv%LuCz zr?B7s<)KH?RlabRwrGO;I^l(r99rx%#HBkm*&W%ou6+6e=HGIccBvv;wXp(B)*7*; z^;^I~iJD z9&7;D;wku4EKkwj%~|f+anwsK3>S&_fw%S^>Th^J^y$VN*1GvPyWN#LSNF)_Gv0S2 zMh>aJPxgIKSR&z$2f56Ghz=j z1o^md(z!nzjXO11<%N56Ua1*UF5ZKa!IwCd3BxI9t~__p_BwB>b_N}f>d?r<-n2Ca zAwE@~l=3`zxi(G88#9oaUzoy%eHnP|iY9GUS4OSy4BT~GpAAy$gH+kb-I&>pQNee- z^mQ@bc~k)hBlIXFel)z@{sBr}TVj=tHgA4dhDsBTan&kAp@#<#CqC|lzEf&R?%i~< zIQ|hDCFyMUt#RzxC<*m#;#kpy6zJ}~oA_C_tWl{9uH~P@lU@ci@AF``cyI&yFLtA? zqTOU-pa?Zzjq(1PPw;72Bo1FL2B)^iv@O1XM%3Phn8By{?C#dI@<4a0+>%FquJ&ZT zetgC=aY4}ST^c-1t%9k#nZm+_8Y0Wixq{AYZS3f#Op1kSY{t}uoYDLOs94`9*)Z)l zybd&?3nr?fIf^Fa<9CZqbt`9%BR8_)UAebhtzZ_tu?0a&CU?vI!v@S zWilwP9mO`!^5E`C72r{E6Muj942YQDSNK)(9@JYW2m=xtVd&&+QSHU|Y;RYroH1!I zOGxWZvL@px0AtbQv8IrzqD!VFDpZ`jD|GKBP<4jk-(x<9w$xswHKj#QnXl%LF+ z?BpHR-fzIcQ>vNk3sq`~dksg_ywG#-GN?`11ydKvv+u5(Io0p|=u~%q80+^7Pe!Iv z`FllrQgRR%KhcGQ{p!FgViCP>KF;=hI!ZGSs<3AtOj*%}9F(5im*u`P6L5JZ?|btO z7q@B)#6^uE80SRx3w&VhTU%!5eUMj7G^VEB6EMB08%x;9Sa#2N&f#khj5d0MPCr5< zA?_ofvN)HLg{7SP;Zk-YRZGbK7(^3na!5;Q8~h%b#7?-rpbh&A*|wJhs4_v9-LC!# zarJjtpMfek$$c%&iC@iKn`}*Yqso|t2x7?};_<9?#+lVT{bEr$>5Jn^@B2e1jg_~x4cTioKoYxWj+FzyR? z?4db5pDj<=doT^ve+T7Z{n&-9Be*j5Gk3%IBj@$K4u(A|WX%^UU|)88{p};OsNcsz z28Qb)=#-{N`TlPl_iQt}P&kCO>`uinpO^4vw+%Rz%@q<#zC!eXNa14lXjWfQ$@1Hj z>wW!P=x4%fI9+Ot8%OjLLI%Er>w%Z*1sy5WmR$>HE_E>Tjkoc#nys*I)o$+15`<%$ z3@Ff!!)tFo(w1AQbp6{Ex)bfgSjjfgLNz^Tn_$Woh_*va$QV|4Sc!xypTSONQ~edW zhj7fSN4>`3&wQ%Zcv1NIJ@qo&OLRE6weFNxD5c~)rY)>Ar|lNLc;82_Jx@__>)Wn<`8o1%n95EH8_{iY*Zo-kee8D1QO>LV0Q~IQcWEf< zG8eCJkY}<9PG9T#uQqq>xt~6!ao%&_L(x1s-};tq_7u>oYk%VKOpg-ZAI7iqpTc6b zMQp~_C9EKDJQf}bkwhMT$fEkmWBcGI!pZV4TpFvzXs(*r$6NRv_t1`{p|s*Lfo1qB zFkG~VgtDnPT{!{ruFYUo?e^@B#Xu&%T$UM0FNEQp_IP=P0i83=WZ?@9nPp81c`R8& zo1g7R>0JSMvDgtl>3w4!i3eG^@C4o~o#VE*ir5UrG_;DDDEz6vSS%FYlrropKIm%y z&-Dkk|Fimoo|En2K%orp{M(*R2YSQU#|EVG(~B?vB8@MH4gfB5RxazA3(>uSH*PYMN zXUIm+kLS6_(A9L!MhgcADKq0}3o<<7N$amKrFdA!UwP67f9&t*>^}1UUjM5t^>6E6 z?EYu=UpCKu1fdOegWn!|3qq7N?Z)76NUiab_+9 z*lweRY=2*Oa5&%7$t&tQM4ZjRHHD>olHWeKe%%t1yYBP1>^j9A;>Xi_!#e!5XPLx% zNh`X(dx8c-^U(R&OVI863S*xI;+Qe(=y%gV5{>!*t!q=*@I~jdXIL<%=pWG4P#VR#eb>&Z_pE&_)Z>6E5K^vMc`-X#_uR!Oi zGteT4_|FHmAu{SM9itfR_=Vrpb;CI}hw=>r6j_Ju zIV^A62xIJTa55uw*#c8dX8g*Pso%&TrH0Am`mPBc?_{W#WWffk8N&PwTkzzVX1o{a z%jJH1j%r8G!~UEqN#UUjkTyDk<$H7!D$n(S#i{3o$g7Rq6@D}SD!~>MY!&LgcAdvx z-4A1i#xIcG9gS9{3&Hc`I8od_2X<-fL@XU;3R1yOMTSAV_w|B*1H2}L-s+= zxu70={Dz`;=np)2d@E|1weyPS{2;pL5!}0^7KaqxgQk#n{Ccen&F%VA?Ho7QJIVsq zgiXY79pWpYH`(M>!sWZuos5Re0^^OBK(5#f<~{v_&-|)kvEp|)D18p9`!_@K$8TJ^ zye+pj`+{VH|44KR+3PgNtRKwMSpebP`@rFlB=quD#M?6GFk^prvK#vbBLhmo?yCV_ z$*si01&8sT)@3|1b{m#{I)=`o)x49}SzNFtnilmu2S1*VV{c93p{4yZEb7W#WyfZ) zPvLK=aHSi!(9MR$to9Nfc`n47O)A1^_X@a`{)n~QXyOgZbw$dZznGN$!Mex=>$&Um zcZ)vWFlKL_^g$o3THM(`on7_U6*l(Xfv+!ZlK8%9rN{u)`rNl?C}G|ta2;SteyiTG zYmH@0ZgnE2(`qaXs&eXg-~(RUa+8M_su-ug4dYHvWv{B*MWY-57A;Sv&y)MG+%t?z z?*D?ZX@HI{r0yJ}1BHiFUnVm@}FpVNlR zHPH024c07w#GiRv#pl>g0T1K5cx#(}HJQ;1yjOw53&2{Bkh(doy1V~FjlSKm6a0>2z2xLC&Ft@^WEY|l)vTCepP$;!?#)>a;Ym+b=P99HIG2uTY>B?y)aE@0~l6K=WiE`pzR$pf`;}| ze$N7LifyTc7Mlaid%gs&f6C?!wuhs8=WH?#^2T?`qp9gkK2?1;7bc9;q1W}j*teq7 z{F*0|ghR1TXxF)uo~ou}`VkGzcv>~Recu4fE={AipX0$aup4YY>PhFW_%Thxw-{Ye z3^F>hOj+NViv8b6+Hwa|~qK}IgVy6ec88}&RL&t@E29h+3WUJ+~|K!h{_*EKE0aZ^Xd64@l_LU zkRTX-N_I*Ls6(ZJwUDv26bEd2gtlHMU}o+U%%8W5TlA_Kmp{n^sr|~lwr3$KEluXD z_H@~1a2TZY9Eh(bXF7hFoX9;GW((gdnk744Kf;wCRk`t{JVY;1q$>(voSZ|f`CgU^ zl(8=q=7+dCh@>XM600o|AD?FcPtqNSZWzmr-<<(HcNSoF*FJoKToR;=l;C+8d2l}2 zo3B^jg%$4)VS8aFNYPUVo9Yz)(WSZk?_)=>#zPK|SJ0x&9I`g3=3CS>1z)KOTB}e=wb%1`{q!Be9v4|ia!ugA zpECsS(d%LGGc!0pT3KYMsQ_mCd*iXexzxung6>>c0$(ne(v`qm+~~3fCdD4-^bdPc z(rrU#uiTFcuZD5P&r{Lo%Uyi!UC4S_`fA{e;Mp-^kbc)Oqo*Qez=nM z1LG5xf$dy5rdqh0^|F}CLOK%!jeRD(>y`DWbisPM(s$y!)d5FeW zCehUt0b}1-v8+p%;ez=mcrjB!)cym?TiLet!kKm$*vUgqZ0B@i;Nl8F%U2uT zc&$aFEE@{GJ%h_1mdAST8;JF{7vZ$A-lX~MH};rMJhO|$JAT(V!?sWSa3y8v-d9za z9cxCvT_dQ~C6jwh{h9TQcxKvk5_ab6uzq4ONoyYG70zyD4f8v3$R-&I%zO;nWKTIY zNMEd5dubarWTuj?X9qjgp2_;=yP|P<2?UJV4d#xO&@lK8M2(5#s;flk{)C(gsWFUNI9)2}{jOLPD>>MQpS}vDiW=SqrAYKSg#(ka64?K>O`YixK zbrVRf{l*)7Y5=QgrJQu*WehymfH_0EYM$@h#4GE1qQM9wG|5&2otwACA1ki;oBJeP@O9nj_kHFRgFr zV|ooI4PRBap`<6*GGRN0bzL7N39mWym!m1I5@_*yj7qw?^l+yZ`ME8@aogjem{p=E zD;+I#qOtr*6D#Wb5Q-feU~u{xe64#JBK6y0&8q#V+qFKN6p~5nliuU3Y-iCC=FPTz z*dzpHIiqrjKMIEP#3eSnI+Cvei%IGUGy45L%J*1T@}F|@i7e4IM5*zGRZ&Ra^k{z(vR zbAmp1)fh{?OW^Al4u|h=cqsAg4@*Xzf~&oTLhq%Ap#D)3tEj$(9#`j+^KUzDg|(Pk zpZ>-py`rGUaS<*#ti;}Wu3}P-rBHq~9$xhf;?*vfaEp&#Lzlya{NZ~W;8BJmXn&Q* z8SeXW|Aq}X`e84uJa`{Ij(iKD{fog%%M~_^@2XL~_?-(CAI2vABosxR$EK$BxUZg)qz#hXJGu$Esl6dS`!c-Fyos9@*umy8&#`E86AqL%!&`&moC@35@S_(-!ms58 z(6w--2laW_pmY9M?T{b%XzT_w+*=Je%L;+>K?#5H|cPGK^O69V7_DD9V(RXAVBW;xA;Y`5Hh13kmU}; zT%+SS{CYN9xT+qMkIV#{M~m2(hCb;2ZVi6l97_e~44HEC0ak8xlPj7e$9|}r36sNY zIGq@E(f)-t&=#;qkWy+o)~Rxq%^mawbDy1s1&5EKS>$(`GOTMqx@aK#vcn2(YD1xT z;YQrHaFl3??p~<7^bSsztOLj0{umT)0Yh@8(ft88F#l8lUpO-cLedy>CKGt@yqZk3 zvVcm8@IlveOP8c`NqdF6sPWNoChDUFJM1U1>$yKbRVRa~>{_@^ z(=TxP+bswZ`O_~a9Sk5l2(NDj`_ESF)S?oy4Bm>tM;K$pCz=62<1f@O~P9v zdzv(|p7(pK0CCO@hMS#r@ayX% z6lmLAQ7W^1zJaM*!zA%9OJAKT+7n7ca*gQb*l`MCSs-5x`PoFls^{&5ah zKjb&3@ih^%I~K6?{nuGkYB5)Tl&8B{)}j^s7TtbQD$Jz9ZVKHlbXh?Dr=YW55DuXlsC>TKGx zH4~nD$HDF3F~Y;5GQ`77l8-M%iSLR~T5>lW9fiwjdA12;vL~4Opd?&XxCGSp?j$|e z#X)T9AS&N`0E#Zt;iR7t{hcL2IMo^||3<*YJ!6F~yJPXJqzFCS@)-t24MKAqv3I*Kh1C7%AQLbt^D+~k(uV>0BXwB zc=3HH3n|=h!v2$F7N_@KUQsAiTAYoOJMS^i=T%~nSr;T}OAv3xjTFm|&>n3`Mn1(1 zMvvJ;rh^3ef z0$9{9K&_X3`0G3YQRSQPmD}rV&2GS}gHtWEe^;QIY$N*3oXN9)n1W~HwqWy?f9wl4 zH+&p=g7;YA7E-74Ffb5>51%c-h))&F-6jQk@j)||yq^S{Z+XG0-T#=QjeMwj&h?MB z7}97QfG3|C*zFD6XQFuoA5^)*hPFH=`156~8I8po@)7X&$Oz`&JO^8^MKGHFxmerl!(>MN@kQ2*9%Sq88>mn>a8w7{LjnHlFHf*3xFy-D5qxGx>+wUDlkz*og zDcuaMyKjMKYb+DIZyYUo-Un5-Z<$Ba$3UdKAG=f{ABLKb;qjmSxL>~%J2j@UJB>Dy zZ%=-Z17vtl63EWzXy4R%sYHh!(EL9?z=w0lp9;40_8u0BhotqX9D zdowZclLfCBHX}WlybewJZy7rf)3zq3*Oi>4xVxlGM(=Izr$|Ne-3-HRE7( zC|xFAB=~n}J9EgSnT_=iWW97n@mjhf8D4UmHPN!cjzlXQd{+t5|Ng?xXL+pT$#Wbp zf_s;vGU*CMclaQBgLdBuhXvvbNt)LWwEFc2`me`8pz2YR_8vNa zu^J@L-vtc=LpaP>lcV!*fy1mDI5GGyF&yfJw1?~XABHH*FVnzxv#jWyuQjY;T>;jc zyre3^jkrrTfcyx}07EWEQtB!}MqCFf&lVdKv2~LC$huLyY;~T!zq)`K&(*<mXUHH_cG{8mXN>l3;6Zd(MD^eMq-pKQGGRF0fJCrQUYW` zDAv01s&egN^^yTPMcN#So`yi-=|=DvwWKBIB~Y^bI+1U3p);)A=q_%is2pf!r(IE@ zo%O+--eX3Jng&oj@(-p2+fehv9q6}YGg0*cc6gZ^ZVDWQ4xtpWd&%|C6MsNNwl!U3 zyAy?HD~a0J5TdBp3^R8gLHhw;^7KTF;MRgM!t3L$N%-s#>X@ZMW=Va<{As6Pwsj3{ zd+SeMdoCvX2ezS^vMqU6$C9ka7eQXXkYyyA@UUwujA>qjvRsEvUuQP@=zB0~4i?PV z+qIk?6CJKNZ+qf6x){AoU zp)(kdHHPx?Hg+#&!HpADtnl4#JR@QR>E(Sqx9{GlJyRLXZ$0Jm7h6zPNtM=K48h=* z`!F}}30@oi&RC^hV(V>&!Paw#HB8Mw?feIVq3UK(Y8VTBo@>!$%w)*fGQ^mwjKy_X zau~L%8yk;b$JIX1(5;MNhffD%h;$oVE;s-VdrDx(v=3C20db0%?yhraa&! z6SIcPpL+#>n$vr1DyzrN>-+G9xHUYO7Rb!bAHeXh*U@3q1IX_UX17ebCeY<2!1ATp zc(kfWP&ah1}K8)4AH~9XW3&@(LU?NQf={px-|A{Fm zI+NRf!+u%bHcn=&0;OmREx|9#D&WD61o&&S1G)m!@Y0YNxE&U^d>1%?`M*A}>fbkF zkIg|m`jvs3J2F}A8Y#v|qzc|YEQHaI8rXU1D=Wh9fSj8*;oiwwj;R%gFH@$#>jn{~ zbzXu+m75{`9%IP(d}h!lnhp3a&E;Ubm@jR~ysD}jJeyyV)Ufgxx_H+^(&Zrf2hOoB zP0hmYk(>DQzzJxWZBJG?UxOpMzu}HU1j$!(N00s2K$*J2fA^b-^072_y-y-~ zo9Hoq$zzFG?M{+!(FcKRbHJdC)4uw%c$&sa1%V+bx zh}AR4<5c)BSM)I&J`1VJo)4^)zBv(fDBx-OzhgALCsR*1Q+jGs6pXlskn~q#^uOb0 z+4A%l6jp{qPGma!Agdfpp9#UGX(a?22ho$3c|w)?$E4@@5O%EHL^hqR#K_~jn2%nb zWQoK~lAhE;svm!Zs*ba;(Nb1;DnJfCMg61O)UM$A`h2qYd^LKUcrDCG^&{3Ai*Qbj z4L#SMLZUt8h>PPTF2jnf)!f(cv3|YKUiC1YTjGwY?ceFY_nQ1$6IpUbQ-UO~=mpDE zN#Um5a%3oHFX|-EgRuq|aQPsM>Q3|FZMQ5D*=xzV+_*-~%~Tns7gg}^&T9UQBeE=c zc$MgH@E5M?tf$X&GhybHh2-eP`!J~o`R9Jf3s-l};4gU=Ocx&UB~@cTGOs_cAi?pz z)MfG|F77g(?>d}>)6I?0Xv|%h>|Ov`GmfM6-x4?+YKKy4?Mz}Kr{8c{tx98kXzHn8 zv_B5RL+f(FD>I!s`-yC!U@$ihgOS&Z0%2RNr80J@JCvZqxhGV1IXX0=Tq zF4gR1I*mk;{5^xN@6W?Q&j$SQU?nPsTtdrrMWAwrvUj5`K+EblF6+L4HKMh+sbLKs zy>1Wrp>?Reu$}eVV!>7&@)C$GtQTyUB!qQYDHuO544xg{&7M?J!3ME1*0ewxGA9S1 z7aI?S_R-i%wm|Hy!>By#2@XFy3f-;@*M)fmGtDwsV!BteY)neZJKg7Qu zO2KV(4&&7M0`*;3xD@>nXP#+AwI~+=burXFJQ)`*mZTG_=b&X>DxBhX4n8z6q+4?CgMMiP zn!oXbOQ-dY6)c-a_a< zdWFIY3*7N|0d*6a;fyVJ*u29YFeX$VU(9DHdnpR!Qg^|uFe4I@lLwn#O{EuGJ`19B zSQvC0q&r?l&=Ff_FwNbDe|@&ofS?3+_oiG(mvW}1fg&XPuLe0^v4>v%K1V3h@Q>T) zf~fw@7FhW^0KBsv!_BIv1NlX_z->#!G3t!6cR)8j&{xe{ElO8cs zE=e-~&g!$91>c~2`7(;b$5E^3fY7Wtfy{aT2H8hTFsROkY*Z+Ok}_v9U-bj*O%^A{ z+@4^%x?TAA#9#VfZW;NjAWsiGJB`&MSFnlG*{+ndVY!(fTXi;)jozgT({6D5F>W?k zKU*EYp34C3y)SuJ))&I9YYt!=d={*}grU`Uf8K_$+vre`37VQ$P&1$f{9L7Q6sB`b zwMI;-pNkoLk}>GVBOHve!y8Rg7@c8BWE{7`v)o5`(exJ1JkW$ketUpR<2$h5If^mu z1rS;4$}xt9@vB)c?&}C*j}~+N#g|$bbIu0nth1bFFdgjruET^O1N_GAjz{0FfQWO| zpv!i%eRW5`yfhNmPxypBA>WwY;t@>zwXt}1<~;1Qn8c26dW-vgXJS>xMil!iO7@tz zvaKzR_+EY?5&KyS2bX0-@mVAI?~5E+Dk_b-%hl0H&;oY*f08wBA+SaEIen~aNB^J? zf46QRcDdVA7Y8Nmi1Wq9Js#v&(Iw%W3mRPRP?T!5-i6j{8f4OGSrTPwN4KkGgW>o2 zRSE99$iq$kSgU!ND9!r-y!p=aDRm-#q>#fz$^AzW(D>wv0`)G&VXabZq_{W zBDwWZL>QMimQLQ}NyNDKa@;ZnJaFhX&A5A-bZl5lmWy!T70q0nJLW3=yVydQeP}WH zxo8?1XQhF7&uY^=S^5!5I>UhBMMyjBug@^XGIp`;o zh&w<5U6M1|oXV?s`o=f3@_CECzqdkPs4tG2SBR^&E7EiWWybt;2Mjb+Kz*wisLQ@! zcrzZ8ts~K>>i-Fz#@~UX8*h^#T4o=a@9tL}<7%3y&uRgA2z9)wVqdAI2V} z$GXKyc+pH@_orlL=$smVG~znUO1i+FeWXOh^pSQsHww0STtvUgQEboJDbOC4N;R$r zl3iC!@L}yl;d-0dbdB{&9O!z@91eO$cj>4?=f|<+tbRZI8TbosonM*S&0f^Q?lMTk z&VsZ*ui(VA_wfGs0Npajoh*I4i#k7aA*G)kv26B!s=MavZR0abnS@;qbhk)srHq__ z1iPGtpLe**xv~s@i$9_!*Zu=%uTXgX{3PEarvMtPjLG;T31D*f4eF1- z3s*`7chxN%tBL={2m*6) zlIC0i<%!a;{n>g_s3gQb^fBoWe%~J67mz@ z=Vsu2hXE+;l)?n}au6AouE^vGAYfMqJaT1uOaBzWeVZH%P*A11Ub!%EHw(2&df`T0 z22Q&^f<1qo@l>7^mK7I(&)yNn_p~&X%+Q39ntfPDuET-R7Dk=l3la|H=y^d4?~X5E zI;=Es_^3D>J^GDpQhA2=;{#yzD?9uZ^ciZ;H zvRW7kv&C8ZWqX8v^ylJ;9M!@udlXPRny9J z&e(=W_Qzr1n@!Y=V^y{84*^S;V*GN!06SLtQ1@*^0Iv#=uGK=hNgPA+CN`htAq0UdH7Zs4-84Szd?9`l3Ee|B?igkNm}=w0bD%eGXdUb8-2G zCBmb+3N&`!LU_orM%2wez|Gki%zn=I4Og9jyn)}C|L!I+4sH{!+@p$F$}%Vx@DEO9 zoTE$no0wHr6Udq0QS|er8Dz`M8RVC-3+~WxAhwCIoX17jAMcOTtFvB%%))OFb|(og zixy$sq`lA8!*f3a+L5DzV-^$%6FVcupUnmGyZk6z_Lr&KtK3QXlqec=(`$skb9q;o&TGGBd11nP6$S)VF3a>-T< zuUt4lxik-RD&!AsYBCr0R{v%Ey|^5k`ZS`oAQ*c@s_FR}Nt$WBpB!JKO}Z_TSp`nV z97tBf6Q@03wTKN=X}x8~MaJPyqh@?J)&;6|T!V^N5>)45AnA6^u3Y$&CEiP#(MF+~ zZg`sruCZeL6(jlVfGjc@Kg(f5c?b3VCxq(%l4181Z#?eHl&<{VlnQ+2*BdlhY-~~k318d%|*GV zL)pt7D4UePWf{jp(bBaLuW+4u&kA8*q@73I=8NQGNhlO~OOhOGLzr|_mkoj`kTdLz z;bNE2;q(XaEvsc0I!c3?d;}f+I|ate?PfNe&k%-pH9*Ds06OQK6HIt_hp4s%le%bz z7%V>z?94=Pam@xhSpmIta)dgc|4dEf7GcJJQP6QZ5anglXw7EMz1H>uzpz3gu|^cu zcbvnduVJv(t{>Hkv(a+lEtJVRj{PQMz-=7M+qT;uYMf)417^XaG~aS!Y)<7?`g}x&BF}>yF}=|A5zrg!((`UZUF0S z#)8PriI(}!v2a0=`+j>j3;HX)ng6yIvtIH27&h-3gw=XOjIK6~jGD{RoDbOd^(6bN zI1^^S>c=wvCmbkE#J$J<@G8CUBNO|U%`3l$QiI%Qpx21@2ZeZInKI;fs)Mp!5o)g8 z2y0?w=>qF$*0!0;u=?*|dUqWF&!e1HxmuJhTy%jpIW5PKeMap1HanbI5Rbv8W>Cdx z))g@wG$H#cll@zZTp9F2ttXG+jrVP+h?JxWpF;UPDeLiT@FY0f#_{WYrKgc^f zPLE&rU=z*vJqDf!m%?u=O?0!9gMd5!#Qrjm@aHXLp*j(EBpiX^X(hNuI{+m7)7ZxC z+>Z7|$OL4laLn6T%(8VS>0Olw-n}Am8d-fC493sFW9k>lp97^ruT$4)QRfOG-Wf_n z&L}~0G2qg18=$zkg{CMLL4&FqE*_Ql#`p$zk@EWQ_h^ivFSBG4f|3 zYwOekWcMRb8TS>RJ&HzK*`-*%JO*Q5-hnHZ)&M)#hhy4#(%7^1P`@P>^Ed0^4r#G+ zgK4SQ&iMi_i#Ibq&1*r|z?^lQc9neocpenxDp=L(a`JcLN@DKo2d^JzQu)IDkiSrs zp6ZQfF18ta?^GgHxYVLe?u&r)c1 z)(T`?Mq#o9H%rR8Q&a0Gn3fy|R^KJr^t@ zt!tQ_0r_A*wE}f^JrisloX9_%sm*#AO(Pd)WYK+PY8;y@nV7BZhhGamvj*1P&?27< z=ERQF6x<-1SBmkb1?NK_?M3N?BCg*S46G!_|8(4JRA5+`-*jy08I7xm%kv4bB zCRrP1sAUaCPC1B|Kv3~X-vhg~uVaJaC^Yr;Fa_z>*kSnz)SWDVx{t?bmr%5q&qE!* zRrrO|e2LZ#+>)^c(%WMgH;rD_EMOVx3;M7m=^ct#RW8t+)dEx1IzYE!Kc3#MjgBQ} z@Vfbb(A4`7JiEBO>CiT;AAZCZn-w$3cmLsJznhpQ^B#>FFF?L;3Mz{?z^5dCTy3=q zls}h4xriTIkf4Rek~f$$AF`M$T89La^E;t*{48d7BVcuXDjT|>9TraDvSweLs7PQL z8ZBLcqfa?45+1-fj&E}7q!&Cew`SrN-hz?w4JdI|K$jjo44ZgDv{YdFcji=6-)KrakIJS5Ir+R-?UCmdoz=bBwc1%7A*;MTqKt1M;CQi~sbzJdrki z0zGSW@J4wwZMoZoNg6>U^^qtIz}>X*&ux+^HUplgI)PurearKUjv?>(E_z1kA=(sF zLNphZ$WsufMK>1Vm7-?2lbA*hb!4%3|L&=JlFBy#K- zGdR9Fh7LS$#09>~N$2JXcxTlKN~T7@h^Y*z^~obr2Xtr(=ar`9bg(+*#iVU{J-HRO z7^Yj_XHp)i2tD6sGSk#JZFE%^9|y&(Hiwjw^2jIXys<^_FsGGlezr#Fr*jq8P7NX5 zDm*l*L0wpCFm%?-9@bdduSdTd62rp^aTH z&chS?GwA1{jee)^39Pgf;jT?RrWCZZI7tChjKg7~LL<*@!)mPe3xwkpXHk6hA4VRA zF|FJJPyNz{=BWGV^VZ)oB;yrstdPX=!#22<C|6i#z|rJ^g3k)}RR09=DbR!sp$tl^ zkPoxJlPwY{P&VD3^o;F-yX`K-^Wu11*=fvb8TK)|?!7?up#d0PW&*>G-@&ab3xeLw zBOaf3Gdgn-B5xmLbY&!9+_-Y|kao>BIJe{qDO_KJdZ+J_y>j=^dhT4fKfelQrREA=EQIqXDMCWtSLNE zxeYBUe^hPDGawT}jQMfq39!c+gqn_vp!-J(v-P&#?fh5%^o!04@=MHIn4bNXcTnh0 z4n^x#{q?D4Lbf%-2OSZs3i)B2tE50aXH9_loc{4~=?P_a@bAxH&3U zlbj6B$I7nR7x9?8Ib$ki9{Ol+E()rH(Jyi}bXGAmOE;nKOvj-TG zk%tD$o#@PsHSq6U6-p~Cr1Zx+OpUt_(l)t_xurhj|4e{LPZcUHVnsYS|6{eWDa{Sm zu+)yw$99t&+(!Hr9n~kZ+5uB=&uUBJw?>n#Dc=AUPh(Ny>P)gpV;b&{ccDK9I8NfT zVpg#00NuZ57dtlmC0V`Q7R}Uy*CRO=^r zaoNalVG?Z)ln}182*b0a4CM*nOf1Cfn4*;N)zKy=pGZG|ZxY zQG=FEMrkl0x4B9>=bqrmm_5)c6!O?>v&p7RDfGGYl5JC|;&ap+=IIYBy!9%K4CM>y zk*$ijBVjj$t4xk)16%bGNLZ#m?V145oD$9>W z)tQrog?H*$y-h*FZjK31vFR9zF6qYV&nw`{P%1Gud_+&iwbHPGL|nPTg2r-L-bh1p zq1(YYQa=6*TRx?g75yO2agyz+p=}C#U`aWA^e_}Y*mDdACnX50H>L_Lw)&7CP4dE+ ztK*0iD@JU;m4iy{MpEs`z1M5cVvQQ-BRr{uA`gaq5F5nAV;0O}w_A9wzXtU`eJ6@< z4M~2&N1x1;m5k{9N6*Ju;n*Yk(A#W8=2qY2GXFBDo0Y=`oU3F`PW;C-vPz(_ zvjF?%>Eqn9Ze-Cse^lpkE&JDgV&!N0g3enJVygQS>f5s*`uT0nr?aN+(u3$RynyC( ztwCY%e7bX%3YMJbGFWFB8u~gBKV3OSuFCLXqni|YG-U>xlRO?{WOt+G)az6$@ILXI zQ%75z=A-EQyPQ5C!Mb-xGID|gf`4zt$>0)Sa?O4_;QLMFl9vUBUb%=>CM>=(dw^Hk zT=4D5G+6S&lC>?q$xbj-1QYawLs{Id3#BJSa=!xEw5U*ET|X7;c5z)s@85zulVr)S zzPrr+sJGB_+n$i^H<%6bl?a2fV0tGOHYD#R4);WGT;dU6v#T%+U9sFZ3`QT_VHWPW z4>lA1D&?DG(D5I~k1J_~Hp?NL((@B?P8ULr*aw{TMT`l`FQ-Z!cUhw`bLn2c$AY@) z1@Py;S$ObrAGkhTg4a~!*cumEOq}dT#V@K@Z$w3!Vvxs#*oRS?Z+bV^p)$_CVGg7=8T8UJZG{X;s4w{OZwll+ax{u zJMT{GPiEoRyNvhi+kENXe)QRXjy=Ao7l$9EpvOQCIz&5C>$zz(&o>4)6( zkpTC1*|1^UJnAa@h^b6pfGRGMR2uH_9XP!q=D&$V#ypVjsVJnvs0%do;3eXB>46~j zm@)Pbd?05M9|=2B`?0)i7j4zPhD)E?@RKxk=* zx6z%{@81pPrN0hMca;+EeDB1Y5S>eoE-{2Nr}|*ddv|Isw~ZM5wIRts(O%t*Q@ z77rHV%Zw^g$=xqWycUJ)9&Mn$RGLg4cbVumU&nuHdxWK;w&3TMP$^+C4l2#J62rj& zk`=2?@6XS|d+)trL&17F=UWD?>b=Zl&zy?Qb`jLBC;;4TH^1%_j)Svw!wUY@$sy#cUjSX!_8uLM zCeYJSN5MSvFXMM9pLh9uJMqeV0C9WWtG;sCMEWiWs{ho2^I~th$=Z{cW=SxP-laJE z=o7YNjTm3yZ4G2J2SB;53Y27OfZp=&keVn@dabH4Yu`JR6>`k+`**2c`WQAjOO9XY z`V8;+ck%!JJCDb@c2E*{hNyOYzz<4u$mG67u)Vne;v7E!eSCvs%N5Xz6V!xOD=yI= z5AsntCLdpK%cCVr+6R81r#SXebj0OiCXfa9)D@w%muE+gk;0 zS%bLYV<+)iqg)xW`XhVOu$8=dR!@z%PX3wcjZ`CBioa{tI5N2Y60NTL3`4W@gp>Nm zG8THv_;c%Zh^>}8id>%r7aYtv#$hZiGxorj$8#Y4doazFEE2|Te1)I)*3wArZ&>A7 z!fcIw%_@F&1jj2BhejV^)s`6`dD@3?(GJ`bD92L|2?EQ;wyLA8(dfut;*T5M!>@hM zvpm!@n>@V~!T%^0K$o;nCRSUA@oeG+jDKxTPG;;RXNq@`HDZUkzQh!v#O);dep49D zP!ATaPD+Q{??%8%<+Wgg*J9z_^%UP|Ceck@h47|s4~nn)5BUe$;K)OU=sF&xo{n<# z)v*L<2{^!y-O4d#dF{f}ngL|;o7<3N69dM)GCDzSsWAL-KPbI8NbCBz?B)44*zLe& z6e>i4fABa-DAu^06t#zzR<3}A?dRc-n>@|gy$U1~KEYfE?ky^k1p$kI=^E@(L}>_ZS~KEijxG*tX6A)GHzfGZ~#U}1PE4%A+xK1LmtM~+Ma?aA9g z(dz~1#?K(jV)bd`Q_9=b;{c5#aj-Eglc?)Y2W7pjMB=G9Yi2r;47)DFCSP@8{wWbc zb|;YA=a=Ec{hCbqNDH%J`5W-MIGZ`xzaB%f-qGQ3J~fThh8HL6q1Wa-zUm!AlK*H@ zMU~fxIfXcwUroOAztgs|H1O+IB*s6uZ1|n=!c?U&l=!(9b+u;G+Dp}N^|Bx1DBZ?3 z<$Z(Eu9J{Ca30=Rn9;0v_c76QA%xw0h-XGBKwVb}toi-$@a{EwRO&qSpK+02+;bbx z>{$dp>lZTlH#f7#$|b33&dMzW(li~UAc|<|f8Aj}fn0hl7b}4$0!_KcM zv8=(t7A^Ai#A=#;?>N*=J}1;j5FzWFdO_4miv|@hVEd}1>BGVTK}M(=3GfynUq)n@ zC-XMr(zLVGK_rzu)aXPs=G74K(oN**;h$i1Iv0HuwaDtfF8K7zP3+yrvHWgcho57W zNY!u*qxbj%3gTmE)2$}K&*Ss>Q$ENL{Q(!@kC*~TdaW+}TNICT{#Jm;(iglY@5OMp zSrJoy*pj%d4VV@vPqrGmk}!+kpwiO@t?v#HLt|qy$Lb!+T@_&0qzl~4!SQ;^LItA- zXTpNp98=v`37@r`#o{^(c3O=uzLhD2jaz+Kov|Xq<}M*S)%hbF_YDD4870#0bd_B^ zU5S+cTZSg3%ecfy4ezX7DfRo-N?pyVDk>mfmr&Tt13;bBQt4*~>uoOnvfO z#|3|DpNIMx{;c(W&g=PDBsgol0xw>;hj~?5xJp5U>W*}>u1}9Z-&#@V8(^4k9ZC3f zRuryZna4I2{>G+vPnp3*qSR+h1g!q*iAr0>(fOfjw8Ju)^Ho2w{l~V!nr#)(K01RI zTWAB*Dv#=paO}KjyBVIwK>P$X>nv6s1Wg1b=~JCjPBxD9Tb zE`Y7_4Qx^nBOe3Q*SWU=BBI9yaoRsIan4MAgQTZljEUFd-4f^_toKP)^wu1orZxD6%?Oh??UjlKR!D;FBh^^72Wv`9tUdi#q=wJd_ck(KQxl_n+!x>yLWI=jr zZa@L&KkxVwf;*W+kUg<}!RXBK=)UnQ2=nD=<%YeuKKDH62Hc_3oJ0AQ)^Bk}>;=A_ zcPDmlYqJ3y0wAv}M7d&ifmhnIMGVp{=iOoUhtseZIh)^<# zznIpqNT$1Erm-7-${R`NUpe#T9Y%$Ce7m*FhhW|c8wK2!4&#Eqx^=Lp9bcCaqQi zc6+jB)sic=*zCaFJ50At`^67M8qoX27(aw{CJL2nbaN9KUege=nQn92h z*9Jt=&RA9jsZyDnsc<$(oOG3c2kmM_ep#zIo2@d7#B^pr*S>3@c-a`l!vfH1=`6vc zf6ml1{s{(JTt?YqTSmuj21J)X1fNy(8Xrs24f6@Fp-^e7Lu{Bi{7ap5DBFC#KvD2dTra@WQnj^ogi78GIs3 zUM-qHe<1Z{is}rQ_Udpj0XK4uhf$^#iTu3ZyMD-%$=D~@$A$b}z% zRoGFLf!j_oIERR18oH_)POptZ_4vj3 zdPIkYO7^0@LJf|Q+RJ|NmBm{<9fG?Z*|_(u7dBOzv8holxFxU+RhSBp&w7KYZ&tHv zv-D6VJ`Q|j{c(AvG1$IO2Z!9#YzU_(+?U-Ac4FUnMyAoM<3)9%bff~!Dm00oizymA z+Tnw+40^dQ9J=o9r!li1>%7Ooq#8j`b3j<8Bf~$!b#0f&DbPzxCNU=;)uGVr06ov? z)Gg%)=@A=_F|#!o>~u`<;5Sc@8nGd^!5<-Vd^T8Q?-K^(s?x7D;pCb6H9S@}o<^SI zG?##jc;fvSy5!SXIz^+FFKPP@l3&*dXY%(k+FH*U@pT*V$h1~&kM$?7%I=}%et+&a zq=~zi)GPUeCzpRX#ZEQ%A+!uFd!z4QC^kBO84my?ZX!Y zuRimrn_eh%p4KB9&i#Yq84+kK5(hSmW9f;tL9}DMC>04kj1t{X$(>?3zMjSe=v1l@ zuIG0%Qb~v5=naNHK4Sq<*SiP(rj?NJZaj1_JGr|f@7TSZhkG`8F}Z&~lja0h5RHK* zOjxc3qC4#z&^K;=U;JBqBXzb`HnFc z;ou)9zQfgt)H}@|Gk@2?V9FFBKOvQf80rw+hh2=NeJW|+GM0W$3nXVe7Luiwx7gHQ zL3CzFALH~Th1r{Y2FEMa&`+kCaB}Ku)M#6Q>ho?g3uYD5gcC-vHCl%MwXXy9t>npz zXn9h0kYS}QCeX^&(ICPzr+Sf7glRcdP;Gq*-Wf?D-@E{iPdG;oORVJE?RO&8l{cu# zAe24NE_(|QC{Cl2`M+a{4S4-MMc7GFzEobrdP#IdfOr*Ekxf_Zr zp5rO07wmmi247Z7(A-ERqBZ;y`bDJCpTHnYaC@rqw&9E$uD6@KKGL4yqB@(?e!D zJf)(oTuQh$y& zE5Za^_v?w?P@MIVDv)wvVnwY6yXe_wI?x>H2Tieu$W$pDjc zHnclMgjDu*0{coA9bPTMA}Jd>yYMkum;F5bQ_N7-B3@rRTm%yypIrlp&GVdQ#azK?j9?fOqMN2WrN{qfaxeOj0vSvFA!+5TL zbZNq-=`i->H=MO53J*S1p`SiI02A#rJS?4psp5Yz_LdKhPgbTSO1juGE{*#wxrZO( zIxu8^E4#(%zQ8B70Bax3hamM~#$s_34xL4a)!QJ*y4S+?ahcmNcM}LOSB0Nj7oz#n zA&w~*!G5*ZV5OyY;5CO~=2gfMI9S?>@se`%sb4)bywIfHa$z9lF^@yl$yC`!p5*Z*psjR~Vf{+c@xMe`z;&ym+h*|(>ujUO;F;h3({}I=$h;b-ty>){Drk5MD~^i#}8Wr zrOU>UGo^p=m*F#58|6-VzB$mG$xoS`nmXWPyOI@MB1aQy`|(uGJ;-1DKhn-LoT@kM z+omKbLNX;nhA2sry{>zsk_xGWG?F4s{wist%o38R%rYwp752LBt)e8+AWbS!DXCOQ zQ9bMV`hI)g*Ks%;zU&X%+RMGJ>-RfPO)y=)1q7p_!m0aHal^aKtV?tc6pzVaENaC0 z%kS3F_vT7ON4N^}9JAp_!+$jMza4Zl$L)2mG9`sKr_wc6*|>LUC>_+@Lw^JvXT9$a z!J{N!{Pp(+-ZPjAm*S0a*k%_#tmbACgO#-_mf8{zMwjuaKgk4Fv7mK2mvn2?Fc&U` z(t9IU;F?_^sk)d7vnJ^Ye|O9vJ-xZ8{P!a^R!@P?Rna6OF_`@;)?Y1 z&gJ#n3R~<;Yuoh-(NB=bPF}J^IM&{tRIlESqBxcc#ujt`KitXI#2aj1uN!EDhm-hh zG5E3~MYtpTA7uV|3vxETFh6xrDA(sKw48ed%AM57NH)i0jA5Dn5Akf5SSotG83gAs zXW&Xa$NWi9q@mXiL-yal%pyS?Bx|y$xTyektmNF*6Gdr%LM();ZRK_gH!%Lv1QaO{ z3Zzzyhq)Z<$gjl<7min?*|jeP*KSfgsw)Db(^s*b|I!%gMI%@@NfPaZ08*c)GJ*Fv z?t}9JoM%#phej`>`u;fBoGi+^G1}PWRf48Td1#i?hhH0XaNzcCrbqH2Hg1~$zbC|j zn$cD`*6aqg%N|1Mscf`*;LM9ras$R?5u+Ip%Ih?k%uE=$iOjnUZ2yxDcFo@y$E|np z-iHVfu?n=f&otBYjx1qm@I8DM^awU52%vMX7KQ}G3#v3@iKL1#2A=I|e!%?Udk$_?GY!EPq1r?Dw^vpo;ceqo|Ha6A8B2!v3vH zAud%DsEfH8k=V(QpSOZ&W2vsNIs7x+xU30E=bd<2b@$=prg-N04URdHG6U4FHE|uU z2wL)632U=Y62IV+Xi443(=(O)YX`U(471{I!OQ5ga3(S&|usS&hzFCW6_2F7Z%6>l9d=7`PVwG6kc>(t;h|}*O6X>l| zKiR;MYWzDrn(aM5mOfi8M>Wk)!sSsv4Dfw{YYkFs8~>dJ<(AXjOvwp<-S7sflMyK5 zxB=n^Ccr|c44%!2Zg%2~muPi$C#%`|hxJUmgxRIffiG5znH@dYZ)1mTYLlskI_D#w z@<3qGx)RSV9|Gwsw|R9TYXs&Yrl66Xi!z_}A--1~I@<1{PTU*3w`M8^z8a5ze)O>w zCfqo8@>yn+gCdIP_gYSz?1{vUncWhpIv|Bv)%Kd+xZ>B z9aEI?+W^jKB9NDPg?C_WF&clBquI^Mlrb9;lujK%ow`uq4*KlC;x2rY{FS%pT^in+ zGLbb4Gsj0S%~8(F1me4QuyQM`u))&+%?(OHao|6YJL}IJxUJ5Ls0G5dL`Midd#ZNg zhCU4OeaKYva@lrmb%3$e8o=<{3~hRyrfw|D9o z6TAk2i&$1FF=wjLj=%zl9AAoe@Z`9+!q2 zMpyAy3^GJF3XP>xiD33l_|9b&>ppK_#nphEI9G!zZsPE%b1ogQkRlTco}uWA1JuBy zmUt9=fZ{4;VY2BU_I{qoPuHAG^@VO&^W+4tgyTSt6XE>6>0a#ICz5z9|0jGqlTU4b zN0Qfzs%g&OaEv|t1XdN_!D)HApmX#DBiCpKV;62jWwNQ@ z@C5SqYM-#gGz2q(CbAk^FO&Hvo-kfKNqX*d=ou5YWPh@d^D>6Yec_x?i=f_6ip#%O(BbsiaCxYL zmna(w3i`TapNcgNIyA3VQhtEm@|;LUzPr*p4dJw{|0ko65egpHLg{`CV5Z6@ky$z8 zg?nZ&!v4S>c(sZjL9?i)m}dfzhd*cwW|$%FI1Tn(Bs_zSODwLx*K)L{hu3=>0l;!`n}SYE!uk zWdZKWYXyhLjzYzcH=y^mEa^Nb$>zHDvaaqXw8FoHu)iN;SzR{WaQFfVDiXoslLqkC zv503}v66E}8-g64W7n+tiIFO$7^6{-`}bKwTj(3eGuwyVlO~ht%`q6Q9}f;S?tFUg zH+cMxBcDWWkzcEtQFpf}KKs`I+Pk;m>%ZfKkG<-tkzF@GEc!QF|2z!}?}^ei_w49H z-SI*=AWM20QpvvQ+I+8nK0;sTeoRPj2CvZNFg&jfirUUncbl^q_jeq5>zx6c$#m3s zcAoFYPXH;GqqO_tdNNPBhNkb}nBk?_#LsP&Q1a__W=uvXqjxJ0YOa)%RreN99nm>( zJih==|F#9|wS_{@58-5a;by*KmV>ZS>oTaNgh0j?A&EJ(kw#wFPc`rU#0tJ4U(@sq z`|$lkV&~-z`X{IHW3I0Q+kuZLZZNLS=Hv#lMn#lWmt*|EEa5C=abe+hJ^rtIie#bm2c~h<6oQi^L3gtlfBvTLptJA?3791>Z1-7A zTj#klExbJN)4K`I=9l5#coiz)dIAK0Ein7RaqPG+N@%UIP&3w(eO0-MPPD&;!@3H5 zsxyif(-X+^n+N$<^B$mQfH(8!fgK&Xe~dcZjU>J&USLJ6I9;9QK-zwsBlA!11tkp) zXgao&uBO&R?NksYkHqTiCoCh%Ius=w0zosn0iDvn!?%MMYKu+xz$4{mYP7ozV&*Ce ze&`r7+gG^I{6)n=J*AE0X5b)c^+T8u?<15Bh(V#97?oXk58`E`NS{X){kA5x?gx$M zZXACxV68b$*gL1LZsKaD@OTW>o}9ps*(FAb#a@y0wjP)hG>z14M>f{%IIG>RPMy>z zVB`8_Soh9|iE|2}p-19rl4leQ{%t3J=2+1F3mSa;^v`%8Lz&NW*$?YlHON<-MUryl zq563U3~i7kc4pP+y8I1p>9-(e>^Y*%xh+bcK7g58M&$JATu|&@O*@hmNaq=E=I11~ z+HCznbbnNaPb(eJdt*My*($?svEB%t4b`~VQ=iONnjoYS0`zzME+}jq3r(?0AVeh^ zN*bfc8uL(AT1rtkvf&w+NzW(t2K6-SLm2V9IGe28CrY!LT-hyO{z1@ zN#@xES~EPJ79_33z-zhacR-(MX?_N|Hhr+ccM?f3H)BP(Gm!k?U3eKYMB2jNfZca@ zIxRE<9$fR`)UsXZl&>yq(|5pNh2+}t`>IhyXA>MeP{cexAP#+2kyHW73IurZ%wK4aehr-R#9(WSi z%Nw2>3pcxqEhiklN7$<9b4sDX~0-E9{;U z?~1W}pV|pzcOPXx+@47iEtOEXaw|BD6QSn@BvA6WcHKud6g=gol32Hw7?yJyM8X1C z3$+bM{z%Y+NnI%J{ttpP?b&^T0^FkWn-n_#W-pf(!Z@W&)HMweGDY9u+hU`-D$~6* zWo8qzjbpb83)f?=MLzy~xfcWXrNP5_^LR;ZmvG7w9{=eLDbo0JAsL9-LVLM=kkjEj zFkxaCnU;BY@ToXe*RKLaU3++Mb`{>#d1B1NbGSn_oAj@+0~^ni*m6lgmhFgwNqLIG z2c19I(I1VRUmKFwr|vd2AYd-+T#YNbSdgwY{jJbOEBI zqQPR>Ew}g*nSuSP@;0=^_cRCgKm*rI&`@TwCmTHieoO$g$;7+rZd% z9F;GBiNDRv*_N<}xOlHP9UbyV>%7Ulcu!>}a@{tb#9fO2Y*RS~5{qIUO~4wMf=zcf ztE={s-6y{iUM8tf7YxO|mP&Yk^$h;$Qo?;n^5}%pC=oG_$+MeCKZqJJwH^`Bf9F5; zs9FIqWE5vkm;hoKpK-C^0O)^E2a*30EvHH=(0a2@+;%n@H$Rev$G3+t>p?7j7N7muaMne05jg{F!5>HtONJD3JNSpMm3}7^A%V>J{9*n|3b<2&S-x?mY&+5Oh|MP zj_BFbx`U6|py|2rG(!k$9VZb^%0-=er!#O9;n$!y2}s|7_aib%!>w>)Z}OJE&)5KR zeIiIv`+h2xy&Ty`+1&i>I&GaVfgg{^g2kdy82ONi7nS#p&XX-L{7|NO#C!alcwQHXH$A$VG<*K+#0HP46v@N%!%$SA>@o# zC;9Ssfww4^)oFf-5~jDIw{Ugce{RdML$Ma-=Bjczv}WAlzLt)4?V~?mUdGnOWX7xF z9ZXUEjB=j_*xR-T*;&Kg=LJdLd=X+uq> z3}rt|q_O8~m{q-PaR1_0oL*ZmFzDU}GT|v$uCtYKaUTaJe+pT};xmw>naDJ|jxah# zO{~$yXtaGg2Nnyhxjm>Rjy`yUX+uNMIo=)8R!*X!m3Oh*R-P7hXRsTcd1!dJ6$0cd znVsc2sJ=h~I%LaGqI(K8nc;+4SI%RrOD`H%$T3f5-(UhqxlF_(9n|^F_3JOM#J^^} z>|+0;DB^IQcfRl(gf0Dmm-UqC`H9!SF6JHvE~G#bMd-5ND0cf)Th=QgmFrr)=W=Hy za7-~5y84e3`7OUt(f$Q1`ZE_VZhFc7SHv+S^`m)D3v8%m!$tDeW{`>0d`1q=l*CaL zQ>)>rFPVcwWBI>=S5YfpGvqfshNI!nz}#dLJ;BXwf{i}H{dfs-xOO3$*(H%rnuQoC zbBWgbYQm)nZ(#pt0Wzb~Fl~V(z4O7Fv3YO_o26zGC&w&M%j#!Mx7=nQt*ZtrVU1uO z{{(0Tx(Y8GDuMEKIrLzC0l0BzweOo|k-4$6$f^xGw0}TIt!v}4)`b~aq8AA;L^5JFl%pL#ivg7J@QJU4g> z=g!sR6O`q;L@?6eA0-)D{=$y1JpzW{UpRx`rYjTj$t2`^5{uHAekm$$s<1TZh3 zp$$qh4WG+E^iDYBg_(iowc{8x-x2u%Z<*qG7LXBs1H6Wu@W@+TX4W?crb^wH9nk%X zKeHu?d3_$){yqnIzS(3m?-kErYYVc)GQ_CvDl>J-I7t0f54IaT$m=IZ;i6qKu61=L zpPqISW^|g+-pU`+T(Jx}Ie+Yl5chbnsH&Iz$gdNz=b=<6tNp{L?VwQ9q zvs5TfPW;X>`4~(&%%Yce2${342Uw3EJlyTe-4~XIpzFl}Fxfws@imkcRvZf^ z?jQf7Wz)1MDSyX%J)xXg(lZ6GzbS^7{tft>^I+Mvh(UM3JnCe~!l^zXF0%Lty+3cF zqs&~g+rkeI_ul7Kt-k@Q*12MSM=lyE=rFPwmc%@jFMRbtAguj$4IeI$Vl01&kbsDH zSb8&pE?V4x7FIc+6j_Wur+ZPHwWZYyxcr?T=Z>`G;f6meXqU`N^0;LguJpUlIiRKK zjJ5{YQPIis(|5w%W@8~bC4*Gss0judll#Scj2@{iGTKjAuA35q|}+3fQg%)1Eztp54m ztm&a{PQ94#Eq8+=dKABm#-oK)KHR^&f|oc$1nRFh<7&2;xwfkivXzlHXU}5X zb?UsO=2{ur5*LEnqd71xdOIuQ4zM(DI(6da`8JIb`21%R<5XwD{QV1C9IudDxl=GQ^g2_w zF$&`MDEZtfLEFlFVXD_L z+&_B;tsR;Tk1|uybssnT=(@*_$S)y%l?>XbZ71>p7xC!_E;k|CkN><7A~s$?zX~CI znq5TejLOLHEgO!bG=rR8W=)Uh`S3fGbKvll<@{~0R)Oh>EztdV4zYHfBmD0`2Wsp! zCVySx;8~#y{(GuLOh0}G=~oPCn&CqZ`b*&E8U-?M^aG<)@&YnzQ(*N!cVaZz1P2Bt z3M4jehqV9BLct=A%kcFZFSu~Dc4MR%gqM7weTf%X%YSFk`sRMR>BSr7{**xCEH<8a zKWoQgm6?QhqZ71tjDc5IH&HXcG5r2Yf7)NZkc6xZ!#||~%#O!V^y{5%R9?@RT@iPd zB-ts`U%n}jV=qPCzlp?E8`@DOWe#kwyp2O($lOutdx}L;N`wSjO#({->K3G4O0ZqM9 zmQgFWd`o17VM$}@)$yT%DYyi@@2Zez=R5GJ>vvq>`~=dREL+IS_kG|mdk=<+W zQ<9+y-fkRA_s@Lr&=03!hhpinZGS=MWC9tpvYC)?7s!jXg($jaHPK9$gD3KySmr{} zBeM%OW^te4S&=B`&4W&-B0m2^5L12c1sF(=vUsqPA1v#}{NVfwS)PaKJsWLue^)#W z%b6tnl75NGbG=i?{6c*9){Q^6wBi~LeP!27WD0evXhfLH9_V%Y92NdI01 zsi!QH{iU3p>wJP-a5X`f@d;$gox^M^*W(qjw1D}6xmafTjm|fhrmklW&_t_YfY0id zPp`<3Lz+#Dq5l;a-Y`|@#;XV4uda0MQgMD)#|!?vvnKSUkq4bQ^AWGGvXy2j9U*y@ zF`U=xi9jayeeF4;M&kJD2lS_;LAEMDU4(}qQA(DIJ_;c3v)4k~wJ=yU5K6zVh~yug z-zISQ?%im|5&rqqALw()8$Fw%$(Wm7LgODYAh&)K42-TtwROjF z$=*>|x7L*T+Ax+@-PuhR+bGeClZsi_J8MX-t{$VTn8>8{Nv??0;#_sO^ zL`{=4$?|-Tm+T|XhIVWr-ES-5rLQqqje0ZYdMD5|E)&mQTtJsQd}C^D?%=nto$QbC zdzi6%IzZCCpA8!3JaMh3;i=0U^uD15Rc1Ru>DNqRd^QMfn+rg`>KQ)S`wAv&Y^E;S z-psk*>cY6qyP(RY08G`!(#Maa$;=je97vL+e#`_Y%{&Od{`nEw(tALH1`0KqhAGxq>nBY@>kR4fO%l{% z*D7LoC=O@us9@r*?IOn|GEi6IA67icApToKsa4u@{uN;qEJWgH{3y=S}}NScbe>ebcLuH zO`=~aLYWOIx!77YL?v5I=$ghZ;Ww2o=AG0P{5y6KUK~A7{YzT~29up3<_IAfEjv)Z zTAa#OcHp+A3|8dU^P2qKJxuDfUF_)eJ50&pSge!Tk5hFoKn@wkI}X<|;N3&$yEm3& zTyXie{i&?a%uxPv?K-%ZGMOAzdI`sOO(NaaR=i-teXvtIn`6=Fqipz5P?~ZPgt{U$ zBK!k8r)Lr=x;BoO%zJ{vQ|y?W5hrra`zRayqY;JygBs4zgavjm7^Vmoj3cp0pNYnaTxTx)7O&}=7b~Z#gV`GmVb1$G z)UL-4(yi;z-LD0Dmc9cot8CggZW;8geogddOd@95@^uwQY9QYBJn6e#Lm{gKQr+!I z$Kq(3ylOF9>Aet)w2C;d$$2n5y^eIRjU{vIbl8~2Na7Lx73(*Ku(Ee!K|Z*QHB}KM z%kD2A!!@fphN(PFEqw@$;!3nba1<_2JcLC{F0r=JD@Zd3Y@2qjk8|2O)g7%K2lpkN z$*US`IPNYGUfUUfjgBHf#Sh!HeTXkRPKKWB{sN`-wP02BjDO(rL?VCm z1&mdU=KpkZhWNEo`egnnziS>^La{6&P~7401CT@X&DFWpL1zD*@VSu9nbAdW}X#$dCx z2-y)QMGcOJ!pwy>oUbK@xUP^P0p+8xu{auLEKTPaP=~PO+zVXUr&e38LfPevG`-Aa z%A=CF?8%r6xKwRJyqMc$3~>jO^{<&mwu(-_QO0vIJHnK_55sT6O1!}-1tc=&6Z1A* zo(60gh3ZB9!Yy6h@Wa#v#n(*1I>iT+jj^N~tY;IG1(QkD*>W8HcLJLglVBk0JZO5T z!1|}9U^RUiGS-IhK=77(@3-KG%xp+swHhKHe`72M<>3(5CGQi@0hc=;P>w8RoW?0L zesb+>LQ)W{-a*i4PaupxAx;es_d%<>5vu!Dvmd^sf$FFW``}?7&SJPO#LJQO#VX@_NoU1SwKL~!4mD+|x$59(ppL(OoF)b(< z4zE4-NyyD8*3tO*Z_H=IDpHvP{IO|AVcP*|q4TxR%qiJSlJ7s8kYBgR<+``nA0;I; z;Mft7#`ow8(;U+4dynd!3nj+_zoYSyXUy7MlzqeTA1MN46mEsD8|Um_pkmlc`p)Z-QG`$G@0ZBiRn393-JR2=WYJZ6DxtmRQ#HR?ZO4Nqa} z5N7`w2j@gQak9S!dvwZVsM-D=JEKfNpf?%ie^Bh?c2R!5$MJ2@0DhP#2UC$nH}6xZ z?0ATY?Fxo{D}BIn!hSf~dkES+uHyB*&DeO(0)oGZvwBf=*m!*_R1HPr`gPv0%jz$d zPe0F!T(jj}u)hUw#C^HEdY<55sVB8D5-0QGZ@^8_E>Km^fZhK*f&b$YJy8%su8!-$ z}pqscLeTjR)H^+CszZQ;@uo<9VuNSgNdQVz+%i2yPYo=&w7c z$at4YSf0Zzl-_!v>c3n}ZIUFH&Aze&SErN0)p|s$v5eVP7mThi)XBj-4WiI?4y3|| z!8JRA?z|y|^P9!F4uceFGf*X($^n?NJ`eUjet=5L_c1ovTyN^ld03~O0;L53a4O|0 z^td--sOUEOLr;PU?^9sx?7B6|+8Xn;_WjJnVN^N(V*X(@VzbWaQy%c+eyP z1#vr3r)ViUw$?$NGO(8;BJj8TB&wno#jKSQvZ2q+@LS6^dZf^e@62#4fyzkySEfsD zHz^8-*Bk`dB`1Wpq>Gs`H$P)>)ocU>S6Rb;&Cc@}@SU9d8mCV90!cmbpp@4$88bBTz)ZcThsF6{Cd#`-y$biR!lF;qQ^;bN1hy5V?!@}%+P za*_?v5Xoow_Ca9xMia~yj^~eD3Zg%j>cbaqrnXc>Q_d*^s% z=ZM;REs|s;0NcHgZI!>w;O(sd`731D!edn z5-Oei09{6pA-KYowOsQ8{L12xtF&-)oL&r;Z$!D?U94uOI}`J527J-0!U1lUTNG}O zPDXs@smdT@apoJE>~&-U&G{IAwwkqC>%bfMv=p4qjKSdUK8PRf2kEM(@D$!N<-DcL ziF2tqH}4~cCy5e~^A~HM295C2t1h6$?R=&=_yd|LZDWJBOrT%3y@T`%$UcdfOcZ4t zVb+yaQa>EUD&`iF=gYF-&Q&R)i*_33)+gd3q6Wn`g5b5`W7epm5#&Oo&_@u93Ufr6 z$LreRZ>Iq_?+S&(ubjw=$QC%aVlS>deUw~0+KWlODUf@s9WOL~WUHQ)!`QPr@cF0@ z=O!?s)!a|N6k~jEtV%8WXM(NaYP7D)$JYEhBC??unE56oaos}b3OSLaOWNd!?1g%Hc=|WKkHP+dXCJBaI_AdvsZD9~xUtim$a|h~-x_Kgd zwRv?SD%7k%3E(T|MXyzYH9slLoOGC#>(;{L8PmXb5tq|mehwln1*q8_EjT8fh@*;? zAmC4;Fi3mN$TP>kD~qQ8B34at6-rIL}Tg<-B*xTrhiWxIj`o6$QmpXpHDe z)LxejB2q^{-}Do!Z1E6n*)QN*u-P`MItF>b`ErmW@>?(L2OW zI=zrRd*T#0Egvgo=)nYw1dE9L@3+%(aS0I-DJkx^|Km$hgoy0gW`slM6jSVG6!|umJ14&AHtk7(!^nc6+LAZ3gSFz=$_AA zhyEI*u2Yt~2g!hE?ju&>Pd)p4ZK2@l23yQ9n#oQdP@wzARI{t1^vO0)XLh9S6MN&X z7#v(b1Dlo))@VJpz{J|+INfJH9x0s(`+WbP+?I0qt69bdkUSi^HVeA1J7f0nI-X?a z8MIAq!XsDoh}6afG;jAA7#cf?*!~?uO%}-#0moa4N&CoJr?U9aQjCPOmBN-LO?Hpe zV$kBXf_$?K_Zh2(#qoel*bFp$C`FrXI#AaCDO@@A5pzDM5{ZsNWFKF|`LS_S--x1S zdjP1eDT07&T$Ib-fg$g13EafS5~Y9c*mHN7QAsNV?PZh6R&HkhHOGJ)kr1cCC#&${ zArmrXvo#Ekea6@~@5hG6-pnn&82#VtFFWw|DiJa6a^t@LudhFg|G(?+$v1H-GxIfT zXLgr;woDFVJ}+cGR2=8czjT_;Vud{Y*D-9s2MNAdoD*O2y)n_ewvCNkF^oFh8aOrO z2r(Y1f$x#ugsTU~(%GfQp~6BNuLe)Rc@yNx;qkZ8tMN8AIQ!BVy}vw(rb?LSyA%0J zQo>}*)i~+XW#m;Rz>`P0NEKyxHB;+_`<}#rokcM&Jeo`U6OZD;$dA0sp7S`jsI|r5tw?#ZZF z$uN>97>_gZ5e8>yRM+IzFdF8=$G^FR05^gOLMb?AY2B*b~TSlD)YMRggHY zo@6HI8K}p_KbyEre460rV<8^2yh&|_W3c+;DO~382xrIEqvPCY6bxPgA45GjZ!asD z=Czi>f*7;b4TVH}T~0Lzk8FpB3~<1^#HjC}>MoZrtT<|G`e zSjomHKF0EbBJhv=f$LI~xgGC!*34cMcc(|d%J;Kii)IOI9hb&lXfy^JxgYfK@EUmA zlfoYUSjZc5Kmx)Hh8R8H>ySU^0O0_VxYfs&zT7$%*|-Q^y-p9cGH_z;i#Vs+7)`2f z;tIzZSw@_7ATRBT(Kj-SacxRrrIb#Se=WMC)Hn__be{91#-E4r{UYSwECqNHP=qgQ z2icO)PDZk+50)*N0e9!`WO!?R;6n2RGI2E#tZA%ahSK_24=Ys=P5r`FDTTw|Z3ii{ zPLdAY;DP*S4PgAZ%;4*Mb|c4tnJ=3MB6u0B#wifz&Q@%AQ3Ni(yP3Rlt_yqdKBV<3 zKt^FAdpS~?$?`3MN6Dk0QY1|xzEv_WxHFZ-#3AOLac%8YsYdpSA=me~Ak7MAya9RPxy=X()58p(9e04#}0FR)UOi4KScqMqrDCVPq-fRM@4Mkz;PJ63t{>t zO*mh3gSq9{!I-+c!C-wT(>!vI{yF@V@%nNc7T8Q@`;Q4=+jlQ~ogNAo1Y__>^(R(B z+msx+t3ZC|g}}*T83-6Rk^JU-h;JrrCP{m)Ggr=vu`~9n;<1wVptUlXJdo5OvMN6W zqp*W1IkK90a)z73?pwvSv#*(W+blNu;dSQk>?nM;!0z>=cNmGhGs;FDGj&8jJUt*I+Y$EITqV1Wv&YOrXL^(BmnRON&#2#aq?;XP|CJ2Gq1!K^b$bh;E^(5uDRd>=S+$F~ox=H~isE=* z%@QEw!kn5e=I%~k&`;&|5hKM!A#@Pl?+fJ4yKRDx+d|nDnYpmpGJ&jF z?+fj9uXsl)3*fMm59rjWGrZ0dY_b{4c9A5EF;l@x+jn^LuRJb(Vuh-c>ez+1lYrJn zfI=YmylMJ_`bH^oec)2?`uLeq9<>wnRSXF}joZndm;M9O9QMK451i_gPJ7yCqBULoTNpj|5PWcwQ)7%>b|_hH49 zas)rcjmdMhmr&e01+8v+u(xDZv7TYCz*Hdx{S_L(A~%AK65T;&9a_ij+xxiQP9u8t zDU#$5b+rqI6F>phQklA5teYxNHd&dWe7h!yrbx37>W#7Cz-+RqryUe_tMb0NYSsEr zR74MDJ@nk$2UDaPVTSY-T-SIRv}0a?)U(y-7CsG~bOxdIAn3D_%nNG&Xg@M?W zFkGK1L-zjX2h%r4faq#Zh%!yYDNAzz-tMLKrDc{Io3!C^6t~@(Yb`vL5fAD&m*A>c z4X)R^6rU>`#No%M;E32{X7{y1up0hmX?$S|bm%7H(YDi6gB^5=k+xWLmjilSNAo3`k_dc8~SsOUD#ae$xf|Vjna6+h(B6 zjc8~zSW1p%t3Z>`nCn!>!`&mN@NbYWX4fi$Mnxf$*Cq;kPen27UDPntsEu_LD}eGz zm)PKof0&6SD?sjLIMcJVlj?WLkn7hZ>GjnU$(5<)D6;69Amn!dYEDXmIp(P-sXCtO zIgEqEY)O!sw@)bZv{tZlGy_JX=3($M4LJX#hq36FBwzU*sD0T4@62h1l6$V?;iHyo zs?!7E>#J>asLBZ*CF};V*@TgqCr7s~xdbonOn`K?rJ$2k0^f8>*|tnM#z8BY?!20T zk30Q@f4lEOMP?3pasPx+jC+>OeWgN|zw{yX*AB1-@7q~z#cjmIDV;5+da(Hn=Z^f> z2C7=|%zcM!rh55*uuw9c`W)Rxs@-x?ed9`E=lvSzO&ei%CI@2g?KGHnWEoLgcn19= zhS^>s&F`W);ZZ0D(fzPR~z7AD2&LpaHWJz~a9<0A(F7V9z z%8p*0hI?M?@$CEUNWD`E%=;`tHWoY}14j;^dz3h}%zXuvY=^fe&eXajET(&YI+2X) zVN8_HZg|kXlonSmrww{*;739ijb2s>X=5G9x3fjCtTmfh)ZB*#u2VTIYEA4~W8wSs z5!4v0f>N1!-U79`SgKdYX2<$7fgB6P)y#o;F+342E7#;rgBhwWn3G$AgP^t5n;QTK|+mW!NV9dQn z{I4&ET~i+c%jX}4Ka;oM&7EpY^DcF^`P(Q{(NT-D{IYOU$q6*}Jc^mxQXplRjP4TN z7^daHdLQ7k#@~6oTQ0dc?CHUpt8v*!3mY7^_IiT;kTyjICU>Lmv;eo3~oZ2 z|Hslraygnt)ZnX@I9yp(&G1A!=*(~*3ff)62-37Xo;OZZvG6puGV zZJrmd=9$3gvtkIeQh>A3(TwrEdff3o8D0c;u^X0ValXAPyoc_$1R+7e;9~kjFmCHi zHeqfpliRW$f2suF%h_>Q*--|P99PGU4P+N}7DLQy0q@xF6`1dF2KLtPM|MWfRDYbnoLIXPe%5{x+zwpAD`=XD^HXY3>bf%Av@l?L#Kz)@EH^mhXpc?5hZcNw zo{R_CgIL~bj6sX@!LQ;WJFFDNTpc}!9))?FbH0Yjm=Xam7;gF1kO;pTBUpdS@p$>h zW?oH-IR@3wh3ttJc^QG+=fKth3q{@tlE0K;!muZA`-N=q2ucQLx05)ui$JNq9Xn}l zI1Gw!MbG%A+W2;^_j=wAHZ{d!wO0%@YlmZ~`yS@LOBFudx(WP$U4#!;4uO(hDidlj z7JS{8Fb$VIa1s9;>g5%o^`B@oUmwBpOjhD=H+OUhm<3n5IA2=8D}nDDH+=L?is^g* zhFKXj1w~e*ps|=gsL5F3T-zJ$udoPMG5H!>b9oJ_$oWHn!ZyL;QhC(R&}Tz(t_x(% ze4#gIA+O7aTgpt0M*TGvI8B!_yN3O-N`>PlAHTwy?>GvUDq2vTNicWeW=tbfId^D1 zt0m%v#>V&9$P`^Rf%CFk{VZhJjnRz7hm+9o-wi=id?bi^1mKFvt6_)G6L)o-gcH*O zLAt{L1lt@L{=-*HWuF(j<4iE#KfMEP%Uj_1ide=ap^e>g^#G{n>+>|SQgB6^J@O@z zv1sk?8p&5Da79rWUfXe--E$+56&lXKW3-dqXM2u$=BEYDda|IyEQPp|n}WxePT?={ zDlEP3hkq+<(9T>3-hFXK-&7CG(J#Tt1-9VvCLK>-UB)wr&ji^@FO*ui7HUl%GOims z*{rRFOme0O^Q`g~L#pxx!{?)!De>;ii0)EUjZ8y*R+iZ`?>*x_!y3L1=)zgwFs6Qz zH#A8aFd8FDIH^+trA{Wn0>^70t)34zo|+RFbcK}UZrD;NkCk)PN&EgD=G?_JbZz{N zKl3cm|N9(rNoz8;JD0KT5v>9Ru7^0ma3#rmsZXB0cH&v*Z3L(1u`oDNj2D;8BMBSU zvwaH>vtuG&F`}8-tVhuSH2pP+Y~uEkiJSV_n>Q2CC(00vwylSZ|2*JjnI#;W9)$+n zV0v*jf^%#>tNfz{c1!Q2`;w+W(gRmWP&UFp6CY8{*gfbX8VZ{iO~*Ty1(wS54Y>cu z@$5&7g;4(D1l~0{4kI0P;M}$z)sBbImwKu&Ub>b!oiUM>u6n~9aL{D0hi-*$12frY zA2oT6|6ahagtajLbe%xFNP}ZR=#g_%lSz8`c(U&7V&b$|3mCIF3=*5oMAg`n;0?cE z+aC(Ki-v18Cf0z#Dn^-5IF)wc80x*5Pj;G{s3vyLXGHaeb=aGIDvO(d0 zC_3+WD&IGb8%5d42+7I_l{7i`bssB{iXw@WO0+kXmQ`l5g^FaBl~g$Q^&FIj_R^Pz zluERvq4j%y|M~MgUeCC%&-MAdKc%p_&ygxk&Et}a{{yM^2jt>CbDDJd09YsNgTtri zq35bWNH}tuP4sR>t?ma6Z(twfj{U-2nk^88o)p2K9Zf{uvj%F>5`LVGq^qo**xrv< zLG9{gxa>8aT9{6vglCCWyJ?|(S^=!x{13Ky|ALB}JFsbsfK8v0hI7>-;B$Bw=r-_~ zDbEO4KaEnI_k33V&n8kZ#GJb~tQp>K$bbiHp0T0Inw-OPM@))43ff<@$(|iYA)$FI zoS&&cj^{elcdpN2mC0LTm3e{Wjf}#VH*?YZun9~by@e%S93(GVC!$$cE6IFwgjjby zfbDY2>1tOSycB!}->uZ=8S-*qWh;qKR35>rQ?bw-9!WY}q-d&65b9bNLx1d7)Uh}Q zwDT)`oj8>}m^qwh9i)Qi;ZY!?I~faWqTrJD3pU^uhh8#KFwgo1tL$0_jtWC*ztwN{ z^JF{c_B{*ETo?rxRDE%>p%F2O(ne)-O?qm_0Er7(i`nx%sY25js@(sc>{#dwX^FGw z!mTlM!-QK9*l~hP>*c=(P5aR`KZ8Zx2%$19s?HST;<3St zoV%Hc>{B`xkB(qAOVrp(sTi{S!Cld{i@Xn|JObm4CFts;E8K)Gb-F@p56f;{1`R`x zVGz%nJ9b?e#^_uEm%jzzc;XU@-B7fDr7S%^NkV+nYZGcj*TEC*be;`3g>ApP1e_~O zX`rtr{Oh-Z$$ESi-vX%9!SS@_7T=q|XBQS2r=jwM_i&!RfGaMFT>BAeI{Uv|p5YTu zQf|+~Zz1jA6rYa~Q}^Rq({NBaF}?BluDKA?DT_CLHi+}ioFt|68ti*MQaEG$VfOF& zXxR5!k*=N}jOv!Xu=I&Mdyt_`dy7T*sAVtt?tQvpke@qFni-->u_SjX`kqZ&+jH9@ z$q9IFbrBvrHNZZbAEVpXCXqdzFZsTMuV6NNsW5dx3~QVpi0Cp4%Y*#5NiKZ;peqfo z=yu{iR{`sho=M+?>D!)YXksnl`-G=F3}O44Jv8d=PFyrsfZzEY#ldA-bm&(%>U63S zpIlzX{qSlBz2ko&Yvw2#BxeP|`_1WwUqyENTV1%z^>MknI;poEpOsVqRTu~V{^?+5h#iD4S&4n+Su|pPFkIhg z!ea031)q*@Fk*u>ci}&2y2L+$D_GBn0k20k3Qxix=c%0GO?&JeTTdnxY0!#8=~VmG zTie@;@pQ+uFt#b)7y|v0aNp_-=omSK99vn+)LUG+Chg;>VHiS|k2n zKTD338)0kpD)^9=$SwU{1ml7Z3C4bWPV8p6a4}mOP}^J#AUC9rt*5Sr0+7~A9YDXr`z-Xm?{u--7PYsN)zc-l=OqA8ZG z+{`(dmEkj~(KO=4bwQiyBe?d)5nn2LK%&1Uot3OZ<2>9T{`6WrIcE&qd#{1Rrkl`~ zUv{LnE)?n`o{8Fwv~Y2MIrN`#hm*$_P?P(6nFMD6%e@roN4fDZ*#z-V?hyVQV+IdR zS_%A2gU(oM2-e&WTZHOd2(L39x+MqS>qe2D_i|!S)pcZhodqs+o{E8k#iDh)R>N-T zWK=3Khpu2#m?ilfhF&d%uEkr}xut>Jr8(^oa`ps!FQ*I6;ofK#t%t*7dSO9o38bt( zFKA9|hKX?%f{@Z3%wg(KHoCVOwi}Qn61`5+M7d1w1rbvd<4e?Y8V zreIM=5KEr7X2$rH57BbnM1kV;H|$D(IH^j#!mO^Zgf-57q+mimi?y?Y#H}?j*-S^| zL>_?bf(C9<=zCIoyan71Zh_W5J{K}}3-5Dv;Pk3+$6kMxP&b!%K)XYowQM|2u`crAr2B+^v%NEG<|df^hEE&03So5<-UW| z@ZB+EH*6Md_Z`XEzA~oErTN^Ti3!Lnt%Jf|b82zTn;m$)hU)8HA!8nYhmBsU+$)0w z;P$z~fhnh1>VJkDdX->nR~N`-8Nj>NQ)mXqJ1Tn=>5)%Bh?x-aNR4Izn4&nm*WHm?kO0I zZD62v7G$4~rVDxhvgGwD5}+A_eU7i-!QUzLOt!92)#xom*ZRPM#zn9o{v?WJt*JVT zq{17sslda6(*9!5c=lE>NwgdBrwEEN?-Pw}_UNXo%fQbO%O%Fbrtf;F{xMzPc1ng8 z`d@?Ny8`GS&*8}k4W)ZWXEE37!|7Z12ski(4K~=-h+<3>sixXqnEcWfmv{tWZF~|e z%>TjB+f_vTB!e!jo`;StZ-}PhM{qT>ppjn~WS?9F9ovgwVMH)}{Fcy)4H0au^f|OE z(TBRvYILk~7!-OPfY75S3CWZNlOv9_Q^yScv`LZ@e+!U(xgGmr1ejXQ;b|&F=STyw z%3~n}yyL%bll1APXcxM98^3e9{Du{kNW`#=`CmM}N-2*~XCN@~hfX#bw$(7RcJE0MSX z_Rh0m($N7oC3#B-Dg{lY1skm{bPF3I((?Tb-t=b#pHtZRB<(>Ox&n2E-;A;2Qh&aO(FMF8QAZ z?Ou14bza{@*YZ~A^pOtSw5RJq&eaDuq7ql-=L5>~DGV<;jc#LiLgu1G(zH8Xq&vzL z6kA@ia91OU*;R$rTYZ?*Xu#g`4z@?*3p;ZE5U$yvg64Zxf)w(s!^j@NQMFRMvM&Ww za+b2DK7P76od=&q+t}sr%kf`DIT`kD7VMaFnYnMU1-)%SFm1d7Vs;hwuZqWydA6)j z?hC2X8Wh>TkA(fJk7MR5C%%go1wFE^czJOFoKL*LUaaxK*2x-RJrIwaT8IozVlQqR<6lt}zA%)6ZC?tR?b#moh)XABD?K1RZzD;u zJA>0xd?6($3RX4#6Kxv0NF;r8JA7s?Ol`dc?tZ*VB%zyx{=!g~CW1jTx5ukH+3d<#h|D{UVYzny?~TfU|n{kQ2ILsEYacZ*?BK zt#c5@hF!z2?l&8>>`m~fVmDcP>lrD}zs%&O}%_@tdEgGQ+p-V6rkIKH(hb;n$5uAPCLY>m z6fwtz9cYXMfr67a~69b~RcK3)vp zjO!D|;yjl));Mx1I>>H-9<_Lq7HSCB#wmkrdo47cTTcv&YgtWB5STeGg|LzZ&@5q$ zvd<3Uty$m5!l>75>6j#PXl_1sXJ`Obbc4Fi7&7p!o6Nqo2&yk^!HIbnF?&`pdp0)) z2A7P$M5hdx$#+oq$oZhW)jiA{9S(aISwZFIS&*Bahm}1A=>AU&r4FXz0~HBqQ9Fop zTJv#70YQ5keMsidZ_-i~f|H96qs6!bc(Z*tM9xVi`@8dy>t2uJsw3do_HRUGjtuT; zw!&4quAuCY0@q8th;FzQ{FPW$|M&2E(cg;|82X_RJNaGAww5Z~f4dlahTS7GJ2Y_X z#l;|TMTOXp+(p{26$;Lq=fM8wqp^SpVasb7V#e=nvks;5%pYmkLKE4}w_4cfdW60H z63pkJ4uSg-GdONFi(P#bhMr4mAg}4DXl$4PTsad8B42rOMz;=sXJoRg+5+fpICx>! zZBv}6a}bN0+^}a`FFT*P3eK(>4lBGTuooK1qNzKzz-yUL{Sc!NNZ8!Per`Dm11n2$ z>>UmKrli?$7_#B1cs_F-6UOpT1}$6b(YvXDNS%I6PK}BLe6Q4S$5R`x&+rzlsGP=g zE`DR!7YUJ*OaKhKdm3NON+Hj?8nAO}ITSYiV-ZFNQ1RYR0k?h!>{d>I7fVj!37&(~ z`ALQBt1-uv^ywt-iab_rQ^Jj*yf4noilwhOjYD_Vk(xny_VUgUEN$M0DytTtrrv*K zSwig4yg37AEjP2i_SD}U{fmva4^IONBo-voo8{#?rsz}dxIc)T>aG=ybvAv871b&IZ~bP2}if*;!0osz7uDF z3IALa=a@q0=+~mLBYFMIS%yuoGQ|v^bR2cL9-ZyO$d8s;pr`Re(75j{hE04a8q=kU z?K(QlCQ1q3tvZ7)1>xY4mx>#HzF-S;ix4(_63?-2(-DG18T~rA^M9Dj@GWg+p8M|kM=7PZPlUJ;#!6h zl2&+Y?ngn_>tlG)&KRnCmXTpC=5X&dueHo9N85rPR^B`f_OeIplxzU%90|vncdMA) zP74e;6-eeUn}@R`EN~i;<9oC(@>z<<0{3fsu)zTA7o=B6#W0$`oH@^WK|em~g6=3!GUbvTySdZBMp>`N5B{Oi~>W{@%oG z>77G!a&JMwz;B|t*cDFo$a90QO2mzhC*gA6LEL*&jq}=F1P>(jh;BueaFS*)j=$vu zd)miyJ2Q=m)}0WLjO&KHd9gUg;R+_KIL4+-RT280k3l_~HptGarJHM>z-_D5qA#E9 zVSD!<@R1pZ6@2H=*|rP9-wv%%7<-g_U-<~$y*!S~U^LClHMXkQ z33PUMb7_J3cz#YPW>`QYb?GoB(zAp9nwR8))^$=IJ07Ce7l^AA)Yz3s zbM8s2JERQj1<41hP<*r&h~pjjo*dWE|3i+xR~RI_Z$;qs-vOeGqlrA{VKS$GFBiTB z@GSo=jdby?J`6A$N@ZCgxqh{Q-SPCrpPTAnf%+qSKIRY8*?f>*`uvhjUmJ*Ul)2;^+T4tL-{4o?WOTLpP2{v1Sg80LY;WPcOcrT^s;eMPG{e4~ z$o>4snW$?D&d2!DcYcMmXx?+ubL|?|`@7PbqztBNWksJ|Ur8e-ZJ>#=dMN)ijk))> ziOg3Y=eEdCrjJ||xKqN17}%r%dq&*Hg1#txE2Yb6&JUv3A`@`;oZz@M5FEo7x77%tedzWJC$DHKL0VozEW!{RyCqlX;V?6Xt{7?@dB(I&v$fI z{(~jH&7g6A2sX%ivVqZ~sN1_ttoJSAMEvC5v2HZo)I5RC9OXyfSLMNj@?$)ID3>0x z@f05Vr2#5ln)s8}!q4mDQG?He$<4Ha?K9WV!Qq5%3wCPsSqii}V!l}E(<$_*iNYa4 zV!^~6)8K%=4t=NBiR;eQk$BNTxRN#lcMs}Q#l)$2`_Vi&|JO{sLPVg-Kme;WmO;(Q zP29eX1Duu73JQ11;m15H+QgpY)K8hTq`--OAGsC1cZ8Gc-*;ok@b7F}$7?pAlTVX& zs)+=LTcB)eD6Qf+Hq@yQCJ)^RhhKO@`P)r6*J>tb9AX1n2j9a2+bIw+GY;kdO+c5r zBygSifIFI>kL?-5=*6G1NW!9Mipd7noKD+m2Y=!}|;(@{!g zIo!94!D0T{nAzM(T;p%BsdbBCVzm_H{`ZufE$${;i=^2O|E;KgYX;OPAHpE35HK`C zQC~m_{%wxH>@1PU^>h=)giH|KFUlePS;<&b1z?%mPM#(n!s66@Q2FyLjtexx9Xtqh z{MSqtwNDy8HDzN?h%GbIA0V?=T_tMCaS+PS;Roe;i@_%|7}P$D9bP@6;eKUos{Bd3 z6Pp3LB|gxWlZDPhD@b<1Lozf`fWOTRu>06Ns1NBQW_w6ustsiZ3As&wCw#ti(n( z|K539OFrxMx~BjdUWPLmy$koX>O=59WoB+V72+NqVS#gOS%5}545;O>wLvimdO|j2 zb{^*5jwEs;`20)ba!40A*5r3h^d>u9MTMhZq z4s5!zIqpsR!CCKHhADS)x#_puxe2z?%*JUyde#mhf#EX*g?u-bUhPEEJv|LP@AChL zM8$^ci7QEN@j<(Fjf;ts$t$?`vkX68$%f;1#UOLYg&OPlP|>=XIBmr-7*M)LRduRS zqw5$h=Q)SUs#-LCza?qc4Iz0RS!8Y1GL&9^0m3C2_ie@}QBH&mgoZDG5wUXk^Tp1_ zn-~6r1<8ppF;cy;(C|LB__!G6o~mmcR4BqHd&k49#RqWdC}nQqnHq7()KT#1;Ve$l zCjy@R_nkeGI4q)b#o|+PF%X!hE><_?wL6Z_bzZ(Lsy`G7{}u1?oeLcYi1QJ*js$hIYlStT$8b-j9LG;0u=##4&M{nv z#k(%CqOc`Mt((yE*A*sZo*1Jyg#4#mMWs zD70Kop5KbYJQow}nwg2i9!|hck8mcd)6G<-xss_*<6yM)31;DX7{2RV$FJX|@JFDT z?fosvZ16-LQ&Bwc^LXecXV4>$T_IunIY#L0) zNjFzvmHQ!7-FshjV?nG)`pQC4(4$=3+I^QPFY0L6NESe@iUJyYcoVC=O?WaU1oc;y zk*C2EY%Y!$6Yni8IBBjbN#ePku>p4&8MMG=zbIG}os6*^%W&N9jpW+K8Z=Zm0<$9? zGM!pSK~>vch}pA}?;bSl5^>^F=3%6PU_-3oNU);@!v?#C?3maU{TZ3n@6e z&j^ysd1koQJEl+)jbj}{VakRY3{+GRSo#gJ&g5ox=iFIbS00PoFD7GtZ3PqPSix7a zpI8sPBOk~q@~yrUx#Phit)A0@`ImTBcH1&I|H*}g+e={Yj1_Qhy*!W!dC=po1&bVw zz%(Pk@aDxo z!M!&&WWmdHXo?Pp67~`o=*(11`qte*qo<;|w=3?HuEvjh7#hCtfmxrYg58x! z$bVi!Vu$>w(=IpS^6ZmPW65E$(~e2x;J4{uIZ{bnd)5!0#M#iN^6VGTDm zT)<}^C)3RJhrwdnBVgLY`R?IyVwf0D|08pR5=E&{G$%`B|M&^H*lx=<^z*yEA%QUU z6r~%cyMbl4YvZ-svXlkcis{fKsMMWE?#4cb9TE2h#*rCdZLtrxI*+tHD0l*WO>N+; zl?q4Z3NNZdwe7fz=MZSK-?O)_U|2E0MSH}{n_E5mNj$2PR zv~+_|b2;3>_YHoY zv@WtE^N(PHbsS9eOA%b%l!({AEW*hVx5>E$6g0P8;8q+8f{LZ4G)6NO-PUJO&n^T_9D(mIjsoL@#c1%&R4{VUT&n1ij!!Ps(S?2E zs9SQIpl?An_I=dGqqp|qJriF0i2s4>cTE%9ZA%A*fly4*5Zv!D(LSD@Nb05#m{W3ZU$o z%3V;8fs;-pAepVf_p?pG%1cUAV}k+=C~l{9pDp7|QW zMfwjB4tv#xyOi%ksFxGB)*+jW_8q|-S5Jih>g~CC(RMg$S3Esd_O9XWqY^CCEuuGN z;!$>$1^0Y*Gl)(qa~k{^LGIaMF!2wE&bjqy^EwA6^Y_$_mI3zW{xNise@=bVk7L)b z8`yP61!BqxGYnAVLY^)l+Mo90w#m~m7}V*u_DuZGEttyMhqDp(|3Nay;n3fSg3EWB ziH=u1NWS=i+e1>As*4T%aBMC4b0ZIO4||~J51~l$XdjFVbfof8g>XY+F^s*hM^@c@ zO+Fr#p%wcQ$zXv9%@=%uKF?Z#R$wBLV@h-q*Zx1DdBj9x`Uy!tSBH zFyX0@K)uIRFnzTWmF)Lo&U`N6ecc(1dC&p{RZ4+{FS>taSL2Et7f*Fw9!Cq z80bFA!t-Tk;dA?Srdk+>^Mq^Q4$pYm8M_RVb?iBxgHp6+AP)ZS*MS!kGRe&C_NY=S zK`&dsB_&0N1;r<<>8^=l7*&%8*Dv*gbXg}D=?BvF_Jy#ulfmseB~+Y~hE}|H_=n6= z`the8&3^ks6xYS)0jv~o3V6dqI1aCj%gDzi!K^cD3%vO|+;;60HBn-0o**cy1~s&L zA)}eXimwh-zUvaFcRn3%Zg*fa3N@+EMV`0WGzWVMj+4!G97Nx^Mt&LCa_vqkI9MCU zWbKQ%f}vh8#{=j^?K$LxP6Kgjp?Lk94i)#O!A7%v;2zxyqj7nNd; zl@1&!ZY9Zf%2nLKT_y*0C0PA` zs>mHXj3YPmTp5Wa(8lXLbv=3wS&8!m_trR4qr(RcdyiiuZuo_yjvDr-&#gyPMm}u z`))&#`zET;W=$^+83h3bMDTE?ADpV4i+3t`-KD+|fE&Ou{7$3WBM=GSoD<`!MLHUX zvd-*OGB4x?%f7dOrq=V{r(Od(Yhwnpn=zUy=2>9yxHxiP?v(T9GTPMo%~|rwa0nMz z@~T0@RtKb4mvSP>5_tNp2R43Nj=lnU`tZ&bvaU{_E`O`T>{PXB_NEWeI&~fmExZFT zI3J`^W^j|dqe(@inB*zEA&VwHU<+<52p}pKO?wjZRbM*H?Kv;lUNU7)b^2U=-kPm2_S|KaI7^XNy=*C%bgp0e#Bj zSQB~# z-}&d5Y_BJiI$ehshHBXk?rp*Ik2c}CfVD7R_XetXhG1pQAv83#f#~diB=q+p=9`)W z&i&VMk!CfV-gX*YzgEDfjy$p?Rsd@%OX1A-EIc80gKPZ&*TYTVMD00L7o5bm=TM&C)l14^H^R*Gr}6tsM>^rE z1Kd(dhw;<;(fr{r_`H4u)OuZoL%#8xRgMMvv{AZr_6*p(GYj&I&#-vmO86M2K`&p{ zr$zo6bfjiJJ1sdL+&dN$|CsNfJfQ&|=St(Bwe9fZi7T2;ut5#KH=wsx2&+31P}*`H zT;@hX-{|*j_KAadY^5AEl9j^rpmDHw<8sity&cT2Nzs%IPMlTiLy(1A@K|#${JnpX zbL3%xJI-7ss)1LraNUsx)eJZMr5J&72@$X$cL_6H(h76KWT>;nWb`OL!mXEY5q!Mn z3-&=JaL-~i$c0_P=OOZNcBUN*8Kny+o{XTeuP@kcP`?7Zo4jVcy<|q?yk^ka;lH3k z{w@3}zXaWN#%TY9?=RaVpfeASq-}vWp^Crepd~Mf=@*9X32Nm1SJu#Hd=~?+S75PA zDt_a=e9Fcp&{1BCY0idJba)8gZFLIng|%`A&NY%GlVZ$>Sp>&lxw4rRMR30Bm#w9e z8qda^Mb^|walYl};KZ~Rko4~57JvC-vzCsaeUgvxOr#6X1*;-8=s>T;Kj3>XwvvxH zg!=Hk2PkVxU)D~AQ>)IBjaw{Hy>~PG;`OGyh6fnb(+HvU8}Y8zI2cs(!4iuc(SsCO zj2}#eOXY`gmXa%$t~d>=GcK|9eMb1*r4;vGj>0$A)iAO95o`V&%R>2{pmD0UI5pEm zAbz_P_FM`?Vd`{N<8lz!#~L%d&?bnIKLZw~h2WStRCKiV1(A{}gHC%{@<}rSy`uGT zt^Q`Fx#J-*Tjv1|-v(?u$K~N(#j7OcyCLLRErb=yd)OxB4`fE~E;c`_7}H%M;mPa8 z#ClUKq^3o}1$PfT(%8-3zEXjXC}n(hFdgn6j)jk97nt6WJWLgNU{>d3d~4J}9A3O< zfeFLmvEvu=^y^Z5ZFqpd)@6{E@`=gyIHCTgX}Hup8{XRF;LKl5B+Y}v9kiQ_shEsi zzR{wsvONtkRVQ#5&B24eeAv5xW3V?i7#HmuWYHZ7@J`JWk5nh%tg(`0rAi9U?#&i> z`!%x9R@o4)S}W*2IiF`)jlwnWCkw>)UX!D1OW=4yCaD!Zz~kFWar6*g2c7LFI=lS^ zaR>^BkR9^wM!oumPNki-)`N9qcc!ai_B86 z>H5GK^7sC>8*m3>V>{oHnH z?Ysq5`i-g5r=j$Rr7G2Zp8(F!t#JC>bx=JziJLNM6vdD0xvMJRN@^FZ8>U8Q5_Q@(wG&b>8n?by#K6Eg^oCS120TpX6n&KF zZ4Dn99;ZTuQZuRKj0fcEf9KG8;WVnce35X$@NAH5v`0IwyYQr)_jmq~pw_VgXi>A2 z#@~{s4F*das|zMl^QYG0;a}4r*Xs@`pJ5M5yT>$qO}_viGUf^B0e5)mvjY8slgMT( zX?kn*aaN;j3$uPJia%_KhcYE|+}f)`3JTP?FQz=ZNcs@Hf94LzM%F@H67Q> zUfbGfC&`^1Q3SP*cN1mjTzo3Qdv2$%VEX?ZW3IcJxo2%LP*Z8nv*>DZVvi$jF67|F zU=})gI}T1L=SuC&_EWe=isS3ktE=WG7fx=C-b)l;N-Oew!dj8NVRx^zuXCY z&Mm;1SKY|`997>3hCa>Z3J;ATW7^3T}xKOv&v zHTiHwf3fK2iKU{_wb|@)`xYoSDgvR29gKB~6>K#wLt}0@yh;oN$9XqUV|NIwOFhD8 z?e@XVk5(k)QVxv%mPaD%q(x7I)A0LxJ1o>O1gBF@SicESFvlJ5cF)1CQ^#;gdKG!6 z_7qzdF2L}tkGAa2S;+dc2~w1k zoLW7S4bjMk&4E_0#8#GT)Hgy5x~9eDfmD8aBuJ}XfW3sFmR zZM)yDgS#%?tnq*irj?Zu`%F`KBw7f8mtxt}<%KxjDghUrt7Q^F6TrRt2?ppm;i-LR zMbGY?#x-(bP`bv9c(|qFwlbbcy6Y%@=XVepNd=glx*U&;PlnxXW3ca85}5tCDN_0Q z4inG1!-|?p;=hm20Qz3$yLg+>^2Rn?Iw69rzg2~-&Qv2gwJ3U&iTy-|zwOo-q0bObKyd{0q3^J2BsvW+uoKdr@4FwsRK=dy-6)#uQydl7)8rhS0cL z-gnfXN#8{B-0e-JQ0JmSnUcToRm~76yT!k+8XvG09a{*R`;xxuT@UltG7GC>;;_3+t?dAs>{S zM;l%r&ucd2Y2whYC7}AUp4+x3TAb)^$MaG8A<1^BIDFe^T3qx8{rT&$crO&5c=cRl zd~Q7rT>XOU{#c0RrB!&`t3`Nd(|q>(`3Lg2RTB$aZwY(DLxmex?Z)<&WU6)bsMsb$ z2r1iCg@^5H5PANs-j!nEi}yNo=8DYr1g)6SU%L5{&7`;p0mq^{WH_? z*YPl7=#U9{PftU}jNxqNVkq3^2P&C^ z;(2bf!MN9$E{XLc$3ow8B_FSHE~O%J_GdXKba*W`-tdz2_-NvGk4Or|E_8mU7Zw%! z(-)&pbD6uNxGDGbNpkyaTH0sA998tW&B9UC%uikTCSZ6YCnLnt!5G>e-bi%gH$u~= zOx&9*%|#SHBUwE|7`<-9`MO@=ydFyNnqm)8;a*W)K@QbUVxqXMF1WJoGr9O)jEg%z zaDP{{LH;&%aq7tkvO#f;Kr5n6R66TD_n%%b!0bBg)MeN#TLam&3XQUTMK?_>X~l_G z+@0jdqIG*safhuNeR!jy!BXiUQMd?=tG`x?e%}9$QWEtj8Z#DGd|FJ`EXaUm$>$*; z$Oqp3z5(j`7SzG7o7G9r!I9UcY0z7JYI^Y=OI_azd-Y|}X6G_yIYgH9>?{&m_sT-M z-zQG}d>n*yr{fjN@r{Y2M{=>h?z0QgmmBk$DX+(O!6?HqjWdF7GmYx|WJ7KjPDnSS zE@=maK2DP$+h{b~u~NF>yT0z6Z(7RZ0 zL5*6eH<1;$K0slyFV1o|fRojg#AdrCSX7vBbAMKGDe@m6&V89sb4puYtUZo8!Dg_)Oo2(gk>@lsjkvYv&O*@@P0+jk zlhcfzj#kMn%znsajG@D5mM9uW3MJXa>-;-KuYg7eQZUc6#%o&(QOjbOxZH4raCSPM z57cqQyZOWDFwJnzWM(Zb{dWK~eEDwss8U$ysU;pMn1=GalkFd!3Tv{I>3^Xj-d8J+ zhYS>i58a-!*`qH&)X+C#$BXjV`}j85yFQQQ6tBefUH;;UWv2x_%Oo0?bsiTOlsZFd zfD9)XbpoOG9IM;=ow@2t3O9Z@3%Al$gpGmyByu0$W0`SEP(OD(*S^aVr{=uGG5a!6 z$yJADtA1w7Vm{IOjVa=@YF60o=*tqFnC*r4|40kJzdn?;hHD-!q;+#Q(UFS{IMcP^ zG<>{ZNyDfyN9t&2xPAo3e(-Av1QRw6q^qU%7^$vPTwdte?=}BRQ9un&!Vw=uob7s-NS80b0PK63OKF5 ztl`SLB{0;gkNg_Afn{}J_%z*(?O!V*#tW{a`r4NQt91q-^QcUatF@Y4jo-vxm>q>b zjoL8E;sAJluNIBHGaOgW$;3;gspz<7EmRK)f<@0|(e1W8K1g`L3=Im%H<_nofy(rT z`4T(9zil|EW}m=Py%4-@%xAY}OhOkwJH|7j**88bdhNFdoKw0_LLddM)qW8jP`HWg zc@++8dnpJweA9N;%y7K*YZ>J4xh+tdqld?DS>VOhor2(J_wmc%cAWov4rEDr^#n9L@}JMm{;%P*@~i_lR#3dh55PPM*mllaKvjP4%S(akfnV@E$R$= zarGl}y)Os$tv2|?EEGMxXJdD6ATx-rVhTmk=sJWW@~Sgo)!j^J{5xE{_<#;btuz33 zA`u=L6;lscJI?9t0fE+bW$`|qvpD|IW<2mWo~%nr5t=M1CO@~%fu`RraHq1B%X7ZW zbK8~yEc-$BK38wNH*u#?p#AN=H_f@ER|j@{B~?V+*WpFHvsA2=BFH}8HvA$oX7|q%B`s# zjzP`;xROsr@GodoD&sI`MFx0cUlDwn>hw|o%C z<$QV|(wB+EE!|(3kVaEo2^Vq7iJ$buT`hd@(M;_1uS_t#M4848RTsa7Y4EoD7w0-A z9M^>%gpOlU5cT91E|DR$e7-B)v`S37qHV;<5qj`*c>?EB?nWb&zLVXXQ=$Gy3T(}t zF8n$6CM)6Jc@LYaaN(;w@n!E}cE^tLynXG1^l<+*PQKiMJDjV@O>$Nd>x^nazl0z( zo?L{ZSH^Iq?ZNc7y^LUvgA(-d{Sk-oKPq+^;FhhEq+>&xK&zk#6u*80HX|AYXMV!T z^MxS&<1n2*MFMo5PUbuI#&b4F!)eZD-W&6C8EiYZoSSy<9L}_sg>wBOXy<(!?Z!5+ z=XMm#kC+B$@?B_y>{pnQbOtl7EWmp$QaE%#lZ31ogreJCw*HIv1NCfU62HPQ`KLV1 zw7d_!HU{w7<_JtEG^Jbr&$i}!eplyw7i?Ed=(7^V<48XRdaPUplS9O;!SOwQOjpDOw=a-?5kU}l zitpEzO2mt^zB8L^($xQv4*eB0hTgJkAe9eO@c;hKLg#g4=QTyDYcLT_j=cw6xd)v}5H!I+ws?#Unejv#*GvmX+wp%`;^%U-86yp` z%lO^$;{RB3=XcH_Fq2?bBiMer4Q9jI1j~LO!Ggw{@L$J4kUN|N|D9E#Tc#vK+SN;- zZJj}&ZVLUP9Zl6$)aY7yGny~SGi^pBFr&ZLFiYBzwi#UknFaR*Q`3GCi(oml+&)V1 zEyfg;FV+dR*hC_He~zENWU=YdCV11}FkUpih}CKV@Ot(Q^3F|-?zOAs)cpgXIx+`V zcbdR{uLIanSB0;?0-SEx{lCu6Jf5oW?fZsIC1hxjB$Xum zWDF@HWlSlOsgUBVYag0Klr)J_iRRLr>RUa#`*;7I=l=HlKL6bN^;&1(?91NkthKGZ z*5`VEXi{VsJJng7d>Dx>D^936_e+)S;@}{Ng53o6`yh?MwvkSIcp=X30c9eFkp$wgH@SPvLIs zKuDUf6q21sbGLLGBOCaqj-2YPSvVcV>HsBm+mv+9(>WzYh7YF}b0lb5n-oTN zXVwI&JOQ~k2Vj%4q)77IZgyjTyRge-HtUX@#I5$5&*`R*qe{=6!T4zlJ$~*Dey`v) zDC+t&@54N%8zu>lrj`lK@9GQppNzwIZ4vZM)Bto_p8$3h$#mDT4q>Q!BazXSfvSBu zFoLyJE8n__`lm;IIRn+#o(ddHq^Z@) z=g=!^d4s3!asbihj|==jBPk!t_z1s67ohc!zlK8ys6;<=YEX`?$&ZJZa#oQLvdE65DL-* zs`1sZ8Pq-f7Km9#!J~&CQ5gLh{Hw#b@{2u?{VE)LUYb~i-PYjDH5^2)8QbWQ=_*{J zWGpnh8gh<@Hqiq!2b1xx%dpqP0%n?+;2`g_=oBakQc>$@`-I&BrOF$iJ1&`uk9f&? zYSZw!+hU@#Jrnw%jQi#+!(EkTtPQO$fRzO76{&Gcg!$&ba(&HK~D33tb+3fFhuXWr)%@KVA+W_TnEFSgjCNW+@dZ6|nB^9)v8 zHp1~U+pzVkH>R(##G*}i@j_TM>(kK|?)F`eC)2zzahN|2|D{UWc#jXcCFN}A@bhSJ z2zbuhS)Pa4&aRFf3rZSKg^DfHv6o*DtDTlc6kPZmhAE!#cAgGgNbZkgpQa#Bu4PJR zIf2xBQ~bGYB~(8=h!elA0adDtS!YgQ*%Wuoo30KtLz1j;)FMSoMxb3{C=P$H8munp zLYnzFTz}UOGXCOkP-)aE0^L|r8{VS;|AM%t_r<2_eUaah}pjJ zsF#{U5=Tg(O-Y2{XMP~8_+|_->%%eg_*2p~cm>WLyArJCOoO;nd6>J}ou$vs!}(3`3d9Ma5`-oGMRelpk^at@nTf3fPjQG#Rd`GHC8 z4_5ZI0Q*W3K!@j0G!;yP?{BxW6()ToA}be-g7wilc^U-z)#2cxG=b>w1~6JP6jEBI z!N&bHY-6exc7K(ES)TbdhZk>TGfnHs@*Rxa`dCPA=U-$$^32h}Z!)Z(z7IQo#=tU{ zqlkCvNDt5dp4&DV;uE9z_ArDTk8^{Zd;{Y2@)mjVSPrxgOogzl+q?q$0oy6n&9DE9 z;oTzzXqe3BMiNJ%SaF1)C+q;|@O-_&S`TWhr-hRE3H`9)(p;>9Y*Mx?0p{I5hzn*9 z!nunqs_Pm;VbH7DFrzz`ICe?FDx>}Q*YJ3-)x6D?%sIn0mu&+dzrF0Jmj}7rV-9b- z`(uK6EN)#;L8Lt5v7|gocI!klF1kbNubq%2;}6B-Ovr)80;_uQ zVhE2hhs{~uFgHs8rlM5_o<&t)D9<628sCZozlz8jJ@Kk%=@l&F)L)*%T48)B-%K93o86NyT6Md#9Eh924q=ed-s9P0L$!S*U{Qr*!e5 zUkqNeh=y{3neesh91t5-j=Grvr0?8i6ztW2{4*U)@q0e1-rH4^Fg6udl!n8%{7}rV z=h=E6qhToT!($N>g=#%rWTN*X9Lmp$On;(<^9GFK^N@>S{~aLHJ`6!ow<{zY4aFw` zJ7L?__2_gHqFti#OtWjh z$Wk{2RM~N~SKkb}T0Wcymnx9VX6_#y1N?V2gd=w1IZ-&r@b#vg_^gVQWq7uDv zVkB*`E@BTO9H8B<&_bgA zISdXZ89~LoG<*{CLj1ttX%AtVNy~oB8(LpZ2M4fI69Q zLOjdC3cIdSf~$w(R@rGr<}hf$l6W2u4i27GEVRB-Za4tB+x zqQdTl?8WxILb#jG<&_`9^vNDL`N;!PlC45Mk1Rz&WjOccSTVK<>YzQ#kTmHWflr^_ zk=a4IqIX_-Fzm#1K};|2Df06zX>8ty`{Q4s`!FR~S-p{@2dv`8v@U{MymmaRx{CTf ziAPJRUedQ=2obB3vaX)Cg9(aLg?fc|>D$=;bf1DGUOk%t(N)JVJ7yGHc={OxI_F!T zbgdT@Wla!WjjMq%hV8hqSD)6_mcUf?D!97&rpO>ijysfo6e2b}5}kHE%sf|3#L-#O zoHNT|5?=+PtE#$0{d_nE6r}=aXkx8G3l4NW#3>y6AXp~h#5L@hMR!M@gh!eUPH;C}LL9aCx-jt!&8xW!M+mihXxqfc`NNWT`g`JXb|=DQeCbGvyA5 zU6(`SO)J>Nt^?RnW+-f)Gly=MI|65;e+p&Go-om_#n4$(MT{z5!Yf`2|83bTq54uW z>e$KaW`}3s(A5vYVbBWtQ>qAtRfS<$+)#Sx;t_auL5alMj--Wh32^DzP8hUlG}WFZ zfJNSa5lOG>Xl|uOzuh|u+jJwa<76jy$S0QAMy2B>em!Ho-WALYGsOGjYuGsNCy=l| z4!eJNkfe-X@I<}_{cmP*Ez{KK-J`jJ2LrP~o0*fBk`@@beJuQtHY4u^?^w-1QyRF; z4Jz6`3NvLS;q-w)JnOWK4*4q=T3&0=gs=OdIk6ndZDldeKZ2h7sR{<4dO>`|X}HFF z7H-z`2K}N9@YZS`y3f>TWeKhqg*$&I5t`poaRi_*D*3rBD4nb6YDd@I+7VN)!40c#OgpKq$s{Yajvu8m>^-d%_D~QB%3FBy2l@la4eE~V?9P|rOM@zLV+%6EOB{3&q zUvWJ~h&6!unm6z$w-gS_t%FGEOxQsm5T%j^cGoWm8fEvxXC-wkODGeJYj`CbdPfW2 zH{2Iqw@YF^K58&}r88$J;(3zq&%*l-EK+Z#}wieD|^Ij72G6Pc2MdCZN0o*FXPwZgWE0PyA1{HX= zPkhl@xSymTP?RYFiQAbZPb&r7b$i&dUPt&mXCD)~AK;O6flNxa1U9a&fqn7c;Oz39 z;G^sdy&29pZ_*voc%El?IcvgW^L`L9XaY(29*bsPCzztTEa=-W#@FFLU|E|loY$KK z?_(uJT}Qrwr{fUFT51e+cAGFp?l`Eewc}ZQ%c*vv20srmi5oKgJX4p?U|Rz%M2Cfa z#QecHh~>=DEcz4Mo1_a9PE^B5B`YWo$^gj)N#x*jH)lfmj;_4KuagQg#-Zhf6L+qGv+5NHXdszmGYYhfX(9Gjs{`0RYbQE^9b3#?mU7slb%D3zjUZ(~aXL*$oBDpbT@5eQ!^U~Y1V(Dl`LKF@F^ zOSDf$Q~d-O@RDa@i3NefnRwx{7wtGuS_>0g2BJ=d20ngzm$+@6g`A2U`p$kq#CKC1 zw!{VwgoR>yUJ4rbnZa^@o&j-bJhr=Lve`As=p7UZ;peX4YJ-!w?P4tE*)7Bv-VbD9 z=qz&U6PL>p;dFXMcIyl(%>%={){>P=hRsyq>T9kyV` zoj0UAemr(gjK|ntWn|Rn1CThF=cTIe!&08_bwF_-p4pj!dm3W!yL>T}&0mCTLJ~2W z*PHhIwS#1ywT0D(rUTqe#4zz?u;X(In2xa^v5^YQ3HPI53GdP25{Cl26=2k}i8LDI z3e^1Gv(Y-|dFCL`y*_HrN~>?NC~s*_Q{bA zzWqSas17~!L^z;mC(;)y;PYA^nEb#S7DSf9*unhV!R$rE^kW2FJIIYRW=4RmO*1+- ztFjc)Ww^an9G3LNbJH)5;&RD2djEqZ?6&I#lQ);F9wjsq@AVo~ZNnK@xZ?)7t=GWb zf3<))BTJdGVi%mL9z^vt#mU0@YQdcAilkltCpqeaaQ&+zEqS;CwtN0!uhe)>pluzI zu{leQMOO%>cb^5Nj5}tH1dzcm%{lQbRH*TbeY_rn9NSK;NFeE62NkeZLxqv4sdRI>X9t313) zp#8QCdSa!hP0dDVbDt~>9FCBOb0P3`0Fg;u2>pw96YcXak*Efv`_+A9m+2Aczh(eg zv~3cm@b%VNyc~+W2z@l{HP>(YUKqjWqssoA2!oQwL;j~{Wb^Zp(|fcar1Twn#S*@cQ&ch zV^8B@OFrO^CmC!K?|}OCat9>1s&GeaTgbDBArO>%gS_Llhn`XKoJQgnu+!US{;h8g8 z6rC}MYKOlTWKQ9Eh+}L;>f3DD=z>=6?#2~ZK0cYtDvZUmrN&^|qY8Q&BSgxDxma4K zi6VA||2xAt?doFqVe+}Q>_#T+;n#*0%eR2Y+#5UTRAG4QDmwgECUh#rux5*ILe&pS z)~l_PVBd>7aP#A2>+tY{^t&h(kLmK`HvM!iZ3mDKlWd8K%OP$D*N834OK8p-abCON zjnWzVwK8*4xH!#1xcuI=cJRY~HW_YzLHUt_+Ul2bT=ZCF^qg+PO(@+Dm%yo3<<5UKhC`S2Cfvp+8*} zT+52ax3dn1>v%&emhJ3&z{Jj0(lG}!c@NnW%vs|VI4!BgkTc<6qgV`0Jzq((=0yl_ z6~~&Zk{Dv`0AuQBp>C)Rujh-$IFlOOy1A0AlncYPWg}r^iUzbjJB8N9DOOq6nwg~A zLn5CMkK(#5B;n~MsM}ae8v7TJTOZP~f!c$FpTE$pQ4AlesiH|mB0HH;z~-l<;un4% z%AhO7u?0*=Hj>GH7s$u$d8{U_7{iWc zV9qoX=I-%|Onti$W)HE#aT(pjVu=BMZ#YKgSw>;`J|@)i zgwD7`kgdOh+nz+>typ<>tgupeq4hg?UHn)Oy!Z%ysd0k&TK1UDqTu~8FZ9bC0XIME zVu}_&-)--M$Inb9KeH3?(5e{BU7>(gM+3m(dOtX2Ab~$C&f$48i(=d!l4ix(MzD_2x?9~2rbL?F{#ND znmxzW^ex>+q+aZVsD(U>G$e=jXSf50TkNp))=n7Q(g~i~Mi|~1!G$eN#?$lcY4ol~ ztl!qHutnAr9(m@I+*F{GlT7HX?^npQr7L0lkC%cW!=3P^{5J@d{Y7d*gK*cDCP?_+ z2A`8wVMt0md=gmD=4}V?K;C-j@-d({G@Ibq(!t=;U!TvrbZ0>$nWaSK)6m5pZ(}LN_uAOAcvmUnmiY`p8rb6eYhY(qDog3>@PdtzR zB*!Loz}{yz(6qdjl%I$}?cQGS^^a#`wx7h62bT#KOc$rOE7e79mRV42;{vB_`{NUT zMS48Gf~k!84poW91fQ#bOa3@0JwK6pv9+W)bRe;^7|acPEF#UN6X;i&NYa;f8#OY7 zu%&k{?`80U*n}#>1(`UgoOzJcpL+!Hy2C)Nco6ls7YcWH&4cypteB;Whzzy#;XXzl z!h2d1=(@le?2fbySbmJchsUB(W3vgJVBt{Tk-~jDxmuJ0Z9@ zg6?YE43{&CU_Gxx+uaxs-37ns+6zYX<&R48=Ia`=Nn;J%-?bBKCDzdt$?-Ku6q|U@ zLRnrPT*Tssnlgpc>&W8=Ey9$VBy4sX&bSFHp~7qiYzgs)82vcG9jkBr+)*qFBZg4F zCAT>DNkc(@D!-;MDh=L;@5E*ke>7d(A0Hg}2-)F`R7Y8GONDjdWH1iyHJ>4G~8s(nDv+guu5kWRXIM2h8nm*<1I<_w>|KHw`e3uRrl!uY*>KVBig!zQ!XwT$!lcC-nMb(l+5G;Ks}%jF>NJ_T-n z`Yv>6^uxH#DfmfBfPJe%$U93{9MyT5h^#sE8O)K!pBmU*Q-Oh9JRjM`h%A_=iNevH zg367z(V0#{t>i}xEAk+jPDB62UN~W?6FFKq9_K9Z#S7coal(KC^y>IaaM5NFSR8XB z#g%*c{0Ul$D9XSu)WI>Z)hmks#jT^c~vSh%Snfe|ilNZQijMPe5j#A_19W}Uz>3BxfW z-w-wrb?0+%f{>r=CGU@=Vs4`Y6O#|Y3(0kOsb)HiK}swm8c=_=IhhL2$>GLI)Vi68 zBM#XUK^DKZ{Z<}j*Y9TE*S4a2=@qt$=SGg(W{sIm@npprWa{>(h3S6<5_;}DuIf!C z8|n+NAJ1fI&Z!XYSMG;*Vk)7&QyB}Bb=mBsbi8P^tJ#S+d&v3zC#}{Wq}Ug;9hU{q2hVAaur?r6csN=WzWGa|=IJ>8PXz`hnv<8fG**9e4Kv@?F?ps>#i5V({P#G znqi8w%Cm3=?!q#|aq#tfI2L&rf&W7#m`<0$RGm^5=H4^E$kax_1qcJ@H@HQm(?MPZ5A3?RpQN*Zq4Ze}%+0iP>&>3kC%S)?R zmSG3Zt#1|vM~7f@U ztsjaW*V56lp#~!lHW0s`t9b6_D}MZ8jcTLJaQrP7LDkM&_|-WS#?B}tM@EiiK79ow zSxp*#C|iT#7emneuoa)(+W?;=D%l;`E~^8!XIXFL0(>cb98>27;9dP@LB#WD;XBKf z*gd6Luq{xLX)K9?wFCD+nXWHeAhC>`S|*8?JDfo`?ljTxC}+<{w_<{-xL~KBI#x=C zu;=T(kh=?BR1la%~r;N93`IHV45ZS%vs$r!y%DL!Pe{ zfy$PNIQ`Ti2vpK!OVcSfw;kX$I|3}cwOV-d;yRSh@j>4g;n@3Cp5(_`fYHNPtaUNN z6(#(br{03CW9o49@gZFKY#65G1uzyX2}gJEnvRfFteKx5NY49ety>zXx zX7PAfS#pFtnX?<`$F>r^gO7x!QeNm}I3J%(Fa%W(DY$KWpKKNv;OWiB`0HCLnl917 z&2gPI1EhV?Q6>$ubK`JSRlDV&eyT8m*U4T=P5}A4739qT89c>vVh#HZ5=`5afyCJr zo!@5Qja`jw_B;{qLs&;1?q|4A;S5@Y=)sa)4{}^a8z00U#@1i+P-^5u5-=tS_mc5s zje!D6N&Dlf3-OpkSHiNZnYhY58s&`-@Z8u1FngB-w3?|9`Os2w($E8z=Z+vwlM;C5 zdR?`bjxPAy)R7;PHQ>>?Jd&a|7^j7DI3YS7XIsbNBr%>x^7w)v$Z#jQ`Z5{!ww}XX zwR#YK%8$>h*aU{cU&M0zYE(9eh0xYCG!S12FDiK0V6`V&+r1M=&0c~94`Sf%kQun{ zVLW|1m*e|PB}~=q#)8cnR5eQ-4nGdW%Eb@Rg6HsFU2%{1#5~RH!U@@_V7yrX6ODFRU74v)lcs1f!2@NQCg8OgaqVPtkP;R9 zaUQ3aH*?SRB60ebdNy&mJ^BnPL}lxE{+bX08}~V)c##;MF{psLb3cgPTpy^=|+P~@J(42^ncugcMDsgS7jEqx#h71P7mONN`Kru zHJSPCN+Df*!t^eFY_xKb9U5%wM*|jb$MbiTVcXPeoSyPr-tTrUoG?5IPv(b!)ALF; z^@=GLo2k+L{QT#j3)iuqhZ?)t9tHZl>bT0;21NdPA^4Q4a&JRI!HQ=Ika?zbhMXN1 zt;+>fo*%4!$cbJU?Fvc{_CxNTdUSi1AULY-1*@OF2k%WysGfYEv=*L1k2Q59Q$7<; zuQ);+35GO>~!U1jB{SW{WRQ<-yh{c#JOoOvEd{b z#2AuG{r%Zdr$$I?*#-A!%0ScG3plepjx=9(vdYy8g~B-=YS z;zKW?N@g{59ld~e&%NU!PuWA#k=^*q^%AOhoy6k#Rm3a##o6YC#pLKqLzL#ZOh+#c zrW>;L;Lx>qT#Ir!NgNUkcCN>m)R6{Q?;A_p)KaZB8Qm7{T)rL_MQ@|uq?PE>XnS;= zm;;VI_n_)|Gp(NT9HzU;(1ze5GBY(F+^27W{+<&kY!;&lo=<9qJn4d4x8-Ql=~YBi zF^2emQl{O!Z)@M9YT@qd4kUG53?_{0Bx&mxk!^#rNb}7!<}+amxLI~`XPe%^i`-}= z9ci%PFBP(5cO(d(Z6t2B=2YtQd|c*p1&!Qw;Zw05jdnTC1)6w4mqUO0qVo<}R5FZ? zFjEDQ(;PY=y_^*v8BWc{>C))TOe$_9FPQ!HB9KSJ={uvhdh0AwS^QOx5wuC3^aQz z&OR?54bGDdFnFmnBpe}VytzMpa;peO8ZIK*PY7x`w&KE0WsegB|y8;Y)*wwA;g;72V2) z_xrYE-O6ux?5`NsFTaPJ?m7r*M@}p1-7;Txk6iROVlU&p zVS=Lq-h2O<j19A8%n{s4X#M+foWPye?K zwDgI$J>lEL?=txJFaEauXNwrWVfC6nWBA&Yh5Y*rRsXjCBq^~!&g#Ef)r3DI1TFNP zZ^Q5TyZk*ulJq}DF!?h=T>EVH?_*Hoqx`?kQRbf`{KrAeSM4$8YeDRH`Fn^KzQg=y zRT!K6$5G^EHztey?p=KO`+2y?{bLBzKhI-((tw-ce1PBO?-5!C{bK~PKO?LY<+h7y z@w@Zoj|j^D7{UC{2v#v_eYbm z{4>IT_jgAJX=x+=+xxv~N{;*23;t2zzhC|P`LN`_e&B5N``YrmV@vZ5T}wjc0oy~3C5~6OpIM}+IJEPu>&5Z35qOgo@9j%NLo&#!u%^$Q9Tv2!? z#;>hA!6L=Klz}xjH075&pXxYkNyWXJc1XGmfc)y^E`{y=y`g+5gpLXl-xpiu#zc ziNe%j@nsaYqk{)(t^YKw|GPD`C>%RuPeW^0)DjeSFrqMR9b8;c6Sz3J89SSs8Jasg zqjnHQW@T+=W^QlzpRNA07MBD$5;+DrvCxDlY!@px3kzHGgs>Xn zyAg%q>R|gnHiM1Ys)>V(c|v#;o`qWlV_UBmy9`&Vs-rmp`wO%%3*I`7k`j|3B}Sfj`d4Na_F z4K2;>%~2+IaQ<(hkOb9#U5oJl>P6Y)zsE*l{l^yn_#ehAbFYLbivKLa)WO-D`(OVx zc6K&KwG$XRoB!)a&TgizD5s6W`d1M3Eqk;7h{Pwzp#>*M+%QQ9MNP{lcSFGuJvhNi zFbd1e)yvWRpE2lej}yYf{?m;SbweaUQBhI$8uk49M-I(3!6aO~0~ZbL7X1foyL%3E zPWG9U8}2@o3}hFUTxHnQ+X1-AZ)+q);{4}|sXHE=%ljm&8)R`12F4H5DO&%U!Ls(c z`{JZ|jkW5VHSJ2TQOhumqs%h?U{-^x_tb(I0;!LQ5%-$wn-I%cY2V|}!AwDShAbL= z8f=!MXqvE-TlARS<>Qa#(IW1eqi@BK7{8M~+X#*k{ix9wt0_};od{$O?bfTlRX`}z0W9Ya1|vX-`PA!Gkcl~^-v8?VA=1-p0&)f8EJs$XYntxPI#LWzPd z)ZbG4qA)1*JTs?wCb0Kt)@H)#_|PUakdA;7Y~ z)|B!*gQ~d8w1x#FrU~*T-`1EkDFc-5lE@K%5M;%pC*w}_ilRqYgf2N!8cvqu4XwXq_CAe> zY)q$a-XdnvI$?WchHG|Hb*!&cZ}vw8p85SB1in_Y_cO)c&Yz2G|7k|BKrBso&8)%r9UOW1AnjjOoRVPWCaL|)KqPozsw$&};j*lm=bL-rON6eAokS$%L~8OFe0r%W`f%7P0OhG7)hml}%r?FR%8j zilXUy{8=`ecyX9W=E=`#t31r*2bQQwW@8gBl4WyD52q9UrrP0RS{tm`P+~L4??<5x zV8^IxvCY{p(vy8%BFA>tE6XD8x*sm($x@Tjm*eqh^aZm$UztF7O<(Z7sx5}>OPR9a zfE0rT>xg&Fzst6Gr+JDUxkPW)af&jq3%La+hdlN)8KKUTF^j!8`CdKG=H%1#rnIc@ z$=iCaL1cwo&03`ShX)=s(07(6^?QB!OgPKKL$m8KPcOeD-LY4<0-ny*Oi|J}4CLpU zgljeB)YkGV=BV6leImT^ae`ctkfgm2aie9oRZ2ifj!6kME4!<+J_XX6?qSOU(WZszt14( z{F4$;G)PJCnIT*P89ba5+$s` z55y|J-`xx&zje*R8<*%ACdNWJPMxZ+s>O)QNmC!c@=Ksu!t*4jh*fABp)oRb^Szf| z*pR}WcOC0mC||!3SMj86qRSup>PPmJpEGyleN<^QYd@peCoOpDf-5f1jR0cK>c#hx zq~1ox39j|>oqOmx!PV-nKxD=&8M%e-!L(n>s|Np zGI`21WMcI0_N^hI&rA+Z<@$SVYIjc8swdxC`7SK$j~r^9qYVd`QI0H#)dlt~66P1g z?oMxqc)PjhSXh0?Kb^bXa@#B*ERb*xO{zb4i&c)d#iPKXrNOhQ(j`~1X@uN^EbYMg zm?|>=eDq^A@iVU8CY!tbPv=|vfNy(cdANwNkwN;Dk+#~T#sFQ(r~UcYPdk5%Wxih% zt&v)j?Hkw&7dp%sb353l-$!%A_z^6_yG0$hQ$|OX^EXd+WBY6bebpuIYPjs_UHcv> z+?4n~dR1FfDNZDYW?#5OQ``jPr#foyNPqF?BW`*}&?qE7*wOvTRflI1!5YAAaUZwt zo70pRg+q{IMVC?QiCu8(K#_5BmU>UPwQLWUB>#I3@4;^OBKeDO{)z4Rnj>>0#mxy3 zbZ5h<<#V<5qjBd9+{iPtIyr-7EyfY$rb%Z}C%5v)=A%|&vQFgFn^HAFOI9&X*`nz? z8(bv{Da#nQgVxZ*<<6$R#q$N+J(W+G&0xrHXJgh-)oXOQCm|N^g?(q#i`*h+%KFiR z*M#G5y~uWaZu(VKXdFKN^?l`}yP#`GJ@5yoRau8Bac;#Jv*OS#;bWR~zFBnY8^5zK zcH&-EA?S7KR(B>(<{v43Z}^PcyZzM?`?iZF{x)eaD__Tsgyw)K%kwSy-Ahj5XGEXQ zoLBdVjCfCc8NTW$;HHk|8N9%Bx*wH*LUK_Ujt;0e;Fntzu9dNip{21KDt3@Vi^BTP zf6xCDVW6S8nV>M_f6#P-9AOl?t6_rdqfT_RDBS;wDE>jqSW(0%=xq3ZLL@^}Tw{$2 zI$W(?QRwuhse`!%O73L>o0Wjo(|>@dmGFPTP&o`al8^)|u_$zlC;tb1T1o!@u%{m? zq^nC$AygZ#g%4iAK(*%+V5pEp@}bElY|=S;@>PBW{^e*CV{4g*NZlwbZH8qi^H!R? zXJQ5hit!%K=yk)_y?hM>j*YO%g~`a5It%OsG16x1_rTir!(4;N0l?xanHc$X3WlX; z{=rRL0W98{)2+N~u*s)mJQUdnDlYmM*)dz--4Fa9hwhXEtm;#0eys)Qevf^`c3=)t z8nodrBWJ+<@2NU>Dc3>V)6dwuwxf_+{31fAW(aK9#y7AqECbJM=Xwo{PvFgCYpk{X z1t=t=6tm>E4(BL-D7*|`f>;_-vY{jMz)9AkZc};{N;fPoRcE(CaXE~0>aKMlR_XsaGtw+-oe>@9-^ z;`hwT6BFP-Ez8!QY?k22qHhoic2 zMNM68K%Y69ueNp)bYXsy+Zii>ub%JYwY{7I@&k5$Ho5?TvkvqIp!y9YOl{sK)y2-y}Hvpv&AI9d-Ct)}blj|qHNswB92VYCL9S9P*ZxPYY zLS!$`jknC00Q#Tzo0`sugvAIMdM(LN(SS`SQfnE^Xr%Vkps5YU2f~f)P8X3&kq3k z4w9Y4upwxlx28c;J_5R`H8X#e)x*Wxof;j#$ALgvCFQ-0Uf{=I2z;io+wW$GZ_}ku zKvE7P58~}{SSljGusUo5Ej*VNY62%=D~Tj*u@Hl$l3ORwG zk_e>k2a>C5lBO9spnNAQnwqQtT=6J-(Z8Gpp+SDH_OZr6tE}0`-%D)B)}gLN$D9oD zYn^-2G3&tul4WPNWeiv}_QiH(Ou*(Z)l&r3BT)3KSft#8X_!oK^W@@d5~Qb=LZ9?4 z19$l4VpZRu=8-OuVSm#BVIW2;$+sEcX7dhl^*2{E?P;&OmwYXpS#5+$KWo8?&tZnz z-F{HStybrp*96SMEK6E(24QMO{qyj(8AvQ}ANW?5{km&?5*&<^r61c) z0h73y8`9>paKye3Bl4;TzHsb5c@kF*8h>*I{!yL=)T9SYBv&)w*P_OO<*ih33*GZU z=l&$Pe20^)U^`#uO7khkEeqg}PMv!Fw>hkuPa{ZyIEZ zQ2p&{p9BC?wA$LM0WQh9arg>5f!}GE*`yE0VM%%s50};i^o~tpL+r@HJ9Qc?v^mi* ztOu9;h4d7>_L8>mTAunzk~pmn}J8-_FsLfU=>ZBTL>QFcf% z0n_%;7%;*|0Jc_*My7ZW@_kWmMbqXKcy>g?vl>_kUJPOpEj^e3A~5gMPRTgSnQ5N{*AG7MN_^WB#>df>yGUfrmD%&>Ws>%RYtD`)y)cYur#M5O{tGO&S1>WV3;=K{{+dRKTh)=Rw*|2In`lwZRLv zUrpB;$#6Yjn~GJu7Va|$Ry`4K0rqO~eXFxIkVG*?glT>nR5o~rWN4Nkn3ZilySx~N z%;t?LL7!P*@b`^3g9RbTIgEg+ovwbc8P)l?!h0GNCQr`sUQPmRQ8!zA#yEtW$_eSX zNf$Jx<%?!*yFv=2n>}!w83Meo94~mzi@_D`fKn6oD4@2H^H#NdE$W#bTH$6W3KISNjWBA^Di{PIKdDJ}$&lzG~}t2^QPnXl$b;SBWfctx~YC}(50ua z#xnwObSCYM#CzaWmm&QL%_M;PI6}Ns&Fy!Bnd{#CtO9D<0e7z@hoBsG)R(>TDQNrM zD(`lQFBE*%!xf653o~;g9AA=;!oQ+ZUlVO=fT(Kg7wexXU?}reT)lV`kO-Pv-TpHH z<<^A#-=_3|`#d^^GE%ppXMAGj63_)D3_8>) zQTIkyris-{$5AkrYsy|PSSHdfUv<+g1$9mzWEjamp8;BZon5VJ!(i2L*Z_}Z4Cp;^ zspc4?w>TpYjW(Mi6#a*3nwI14bwMC}ri20C7q7OeQox zcqEMNA=c0j_@lhO-Z~jx?%Xj@?ZbbK|bel6Aen6DdRNe*|-li2_lum#Qn@b)ctyb_* zoXB{=wF8)+Zbn}hj6%FOg?2o$Wzf_l;u{8EJs7HucXi2}18-gl_$Ye}!s034+XK@# zAeUtuqpEHWq*GOJB)``WFqNdI8_uhs*9g{Q`kWbv|E4B7rWQ@4a=P{7Dg6*6Z4%hF ziWvZhrUy(;9^H_F4m07FoeQ+Rx7z<`y&4#jC=1u1?xQjdJe{I5KIGF_;}JY&tx1p?a_n?If}z-AANvNykH5dO<~>6$;= z;3xEq=+=lSK;?YJb=-U#CLI@u9OX>G@M@suhdB)^#D|ja_NJq*T^d6>c}>XOCa!aY zQ3-D|pV$*!2Llo9O<9MdP7pt#|Ka&@A9%sOz3oBM0STB>)V3#{0aKz-jyN+269rRR zRMtkp%l_KR*gFkC){FT@RmTKm*gV=;ALxg{>aE!m?X&RQuKCRH?<8DOl_CdAdC)~> zen~QI6q;Gy)g-f;f!4F`4vMF}pms(4a4HWMITkTN5+~gU%qD%cf`rNdZa8th4OJra zvEZoE!OVmOB+DUa3)OIrAjhKLbr|5<3QP-h9JD7E9Eb*SPJntnhy3BVIXH)9$tH*T zU5OfNtUR{Phc)*uyO{eMz%%OwLRsl~=)7eU!QoO3Og=3Uoval@=IJ!%Ov-7npAy8G zFFOUaLrH3B?S?=zsUG|Ok123C?;~LoEd^Dn2^JFO#vsPCA7Ng>W3YI>P|Pf}5eSV} z>SAP0fSlimR-xel;FgRPk;2dnZuebZ4%jyW_3LCo>D>wNlkjUp1mAJH!W9uZaaa#* z4;;BaTGS6|BQl<9=%_+X)t*>u#fN~C?(IjiOG$Vd$deMxdW0-Qf9m&UH3u;IVQ9YJ z?|^cGno?=x)1c3QpQFqC0I3kbkoxOw4vZ^3*QDpkhpT412nw|-dbP9Je@QUYsLO1gAUCV~E=9q%-{8L-Dw5_OO>4q$J7OTwc`;AL~p z&8J8PslNQG_$xUD>pixXnm-Oe>GzplZe8_A*|Eqt{iRWO$jcs}UP-Zmm*y<1hs2!S^Ss5_rnTw5LCAfOYYrl~-ss z5GL3NKP?!63kNnKRo1O29N10#y7nzBj8gnaO%Vh!zHSKl4t7Hkp-%>_J{6$r!m$&- zZU)#KQK!7dM%`!cLRkx?N&!PzlDeGn4B*x!;3-L*0)?Hu`E)OLL^UE5J}_&~L8*Jw zA={s(V0D?2&^*mFOrzT)EWxaS0_smB@u}OP2S(8I7M&R|u@k~Ng?tKEwrXX1k<*}* zlAz@dB`TzUQI@^OI1FCgEztkoTnC865E=pxAyBYH-v}!H06%jfG2LZ6;0_Vyj6Qn_ zJW&0Kse7g|JJrF6V@RNZIpZw!oZ_UBL*d=vZ z&t4#w^Rvkxg|9fTsr+{y%mJ0ZE!uZedm(aoZK~^Q1I!Z|WQ!6qX$wE)Y&s1a075nS zLAO+M+ET}KBpp*nA&U*C8NX2{EPX4STY7uD75lH~>)kOVC?fw8%Z>80dh$?T6%>wR z7ObbQK`QN`h%b|#=Y&VdxN0;n14#p(F49^d`jG`lY=0pVid+b>;keAljLR} zeu=y@v5!Wvb)b+#O|Q4Q86;X)^6K83g8Rl9co7oWFk9P*X?^cGkS?3=MW~GczS>mC z=p6uh%`#$=zH|bg_XHjvL<+$FpCUlzoBxX<5JN*d`1LHJ^q~n-E3j(3^Tsa(L-diZ z;I|$TpNUrV-dq;26o0ZKOYDrOCh=vWZ(wgDZP|*B*usa(8wS%aJ4L`LLo$!Q)Cm%A zIExSccowM>y?G??=CerUYi0^MM&0)KHb?RI57FR~=ntJlgIGkp)=0Va$_7#kl- zs-p8+I3k0%!ZngJ;t?2Ab`SS+c)-Q)?|XVae?_i-PqD<54)%(x|E}4hMi}QJhs1Sf$EMn>BQ<{`}0#= z*>GL8HWunpvo8$W!pD#DdqNMf;d^rk}Xnxbc18F!qD z%)nsdW_G%4AH}O(FRh?}*!hhE^Oj=>Yp2rN!%nv$riaAC^iN^{kxM#B#r_>>)+@L! zfOgV$%|=qLeewt{uxgTTei=oKsj?)cX>TBF@|+*id=P1~mL$&z(aAuVv!LCn%D6(B zD-VUOiR6fU;Qg5Tb#)L)(_fb&KTv~MvC-bM@d!hNr%Wn1lz&H(_s20_24Vtnf;uC- zSp>wY==%OD2?N}dHOZt$FA;3vwm zy~P-cWcJBAbf+JK3&PcmJfDWagR6-EW1e0R=jwjAexn0CiIEbeS7s8S#4u5C>~04# z+;|Gcbo~gUrC46i(Hi(v$VYOw5`t$dGzvt%Z6H#P`zd0l0%SFG*L8GP!jLA*o;&Z% z5L;Xa`pqnokd!{f+LIju>pNrDd_+`Wk-LONw*+D4tQk7uzGEztFVoPz#GFWiyH65O0~M@B}3;#f>ngFwnx zFG=c9?Bz3;O%kC1SbjqB>(-}GcyW6aG6FCh1Mp)^aIMn+-np|X}MVtc~}FQ zSmthhRPTla)0mUT2@deBwk9yvYk;pBWTZaolmRU4(Ro_dKG3LhM$P@b1~TCL|2DqW z0V1Pk9{O(hLsm7SXAUOSfTz&5*V3pD8pffCQ4AJC%{7q}eUf2tN9^*ptZp7~4u}bs zx(7iM9*$>0)O%2!{|&~ug@Uwt7967R9xySjcb6+^6rLOD65LKn2I)=DE^fac0=Mp5 z#W`q2f)a~}FGcrzA)BW#N5<9#VxO?T*}ba(`72Pk4;(iD-lu7=qg%2--?;NVS>F-h zihO_{zg!IT7-VL|>v}=f%Sp>uN)s?3oriCG;~7|*2^Zf!8iIo7<}-7BHL!Up)#awv z2nfSliQjOYfE;bFghoieBfkIL$ELjM1KoazU6rb=Hk)-hxk1`CICDjs{63`zc>F54 z^FApO^5cG~?mHQRNq91F*DrvJ9AdJ+49RyrG77Pz}tQr9 z5cH_iqUD7>kp1yg;QJq9@cu#6@lP5ENN%1hP52$AsjN)AOLT5Mauj&;QU@5s^`k{C~P{0;_ zdUaCL)`g>%`uqMUFu_nGG6FU5SF$Ks-ChnzNlw5lUTX!?S+3LKydB67MR&E|ZI3|f z&=l;_%u5kbx)R&p%l)8c?u8OPO)H%6+f()shJf1Rg0!N%ANE)vnO}}K!ZRwbY9+24 z5Xnf|?jz!lz$SVnL;JQGa9@ZlCp&5)LdH+*>{vP=-5ak95{o?0@H2Pm&qN2ZeU#*b zMsGG$9g=@TS5*i(7XBE$v#ElWA(n7MViIPfZOMp_m4Gl8mnMb?7X+EhcAocn4S>xO z=Ot&2Kp{wWfMl-=o=1OmeDZut_Hfws?~ zUh9wg;TM6`l;Ft{kagETRQbtx+mY<1O@5Q6$PZmBS?b?G(8f5KsQ0J}$jvF~N#FF) zE~ul|p~6yI3iSoK%al(kAn_I%rzCk9u(j8pZCl`jZf0DALt+hZ5LbWMLU91vU8Srn zv9^Ns{)|y~$6BCl(TDUqD}~1|ZM?ksHjyj4af!=n`3SU}Jvew)53%aHvo1Ae5d6E7 zHT3zhFlxc&?_QBB;DH;mU$cbZ*LtH@!aGGk$Mf6YZQ>gEIgVQTH#;h1Cr9rlyOj+$ z2f}Quy|Q60PC38YS7nj$F4={u%Q3JJ<+t^SydK_qi`Afz+X347k12nkLKR(C7xGK> zL4bGgS3CGmHFR=SlfejRhR^->>cg*xK$L@O@9OCwtbIhc>V!1{$fEShEW(q(_8qB3 zeziJCA<`{mNi+shdgJg4T1Mdh{k1sTw}C*>Qb=)SbPT?X)Dg@OOa^PC!e)Y~duew$ z_B)MyHNX)TJM`e61m+>@`;=t^U_LhRu~0)ew574en_FxH!d<_7oh~{75%dR=6Q4|aO!TH&fs$RJ1e)d46rviQ?J$Z1n-vx{ISak(L+JV9hB3aykr7c3#S@lvo zr_GLq%F>~@AFRY;nA{tD3%+fci3tCwh6zs!)W+sJAeotVt1A8gOo~erqARX~{uYG- zCELOtZx*^?F{W!?kF`?s9MLxzCk&)>?+y}i(sNPw>pT?BEdu>Iw8&Ih2X z`8~YxUJs%p%+}LoYZA`ct8}LGOhIxE28-wywXipmM#rkV2YA+*(sPXU!3={Wp(c%1 z#AlLk$JSZy$b5ZgA7w#*NWrKnts@`?2eE9Xkc;8qCrvw}igf|(nSXMhER+!;mXgPe zS%o@B64DDp*i&IuQtF{}(J)M(=VBO6?1ooXG#07dAAqH@Zg5_+N&DENJdbSeDj0IW zXQW+F2P7@(8Mb&Qf$LED!cmt8l>1>6L@v+?NMk+f4VFeh&bx$yKZe7Q&0D;CCSwe0 zMCteEQ`bOhH(mX4jS?7X^9TLL*$BXd>@6c>pId8SH8=*L;4DID`KN9GygHFEo;NLl zc$D#&yDY;X^tC&o$dfME?YBdQr``f75W1y-S1qt$L#pzXl{frQ%*M|)-UDTK{OKK; zg1{tO{=i^oH`Jb+&0==wgW+O%__wutfZRqIeSUKfEbzofdw*C5d4ylzW_%I^@YueM za_Psz_R3Jbn%iU0ag&nTnSlUAm5U+1M)Cn(9-WTP_Z^_?Z(BQ2P(6h0g@@iEW`LHQ zf5)f22BJ$pG04=*1*64U_^b`1V1svq)|Xxr`SRNwM$!Ey5V2#}J44e1iG&|~;UMY& zbEGEUq_`*O*7!=1mijI+S}o*RmJr z{=8ZX;Rpk@76ap5Om(6lcrgR>OA1V0=(SYm90pt^9*YRI2=OZM%=3c|BM1|f=`{-Aj z!MX5LYxM8&6%-{qFjB&JF$`64Z>|xg=fK;2Odfe}`(QzbvfO(NcngUI?J>c^T*kpK6KCqXP3 zpgm1BO5!{Ne2lsHGW4PrkSR#O);A+i+*WHr=CBF8RKmJ)eLV!o(K8v`bOV8j#Jzjz z-hJ@(oDdz6M;9>szV2a%qTuhoOrj@Hs)2Gzcj#;|2Eekl8ShMc76`jG%H-DX0UXI_ zc=J_xfL%`ZHr84nXy9H8*OM3m-3-yxj;$@Q))|~~ycvRxB*9fq*^S^q)ahYfLlKN_ zmi>OQ*9WcW-?{mbrGfFbM-(@81>s=aB@x=`Jkotn*n>)T9D%0C7{-7$3SXSQvQiRh zfrMks72i1~-~sO(TL;qwNTFgjJ`~LchY1o>N{!A)#mm3=stYKbZV`7vzG?#2jo6i{ zG*e+yrkv$Fxol7~<$`?f`vJ)#m$<#7&;+m9FD=CaXWN(k9AqfHS|P%Er7K3I3P_pi z{(arw2-+pv9_fpWLgmk`xHM#AVDrx-t9+|6MA)Bpor$YY2r{40Me2k$P+i$bwSJcw zVq41h$Ga!N$g4YsSjTyAoLxcXv`YxV9+`h*-k}8cmQ#I{v1$Y5%jjQ8Oqu|}H03FydL=cb&HMayhMhR4;2zpcY%Auhg8zvAmHYotk2>Y0`l)>*@|=^)YFgS zToUYt1>RSVXKcj~N8-i39kW_U5fV#)qRqey26<+JqzZt=`he4hpc63OYW=*wiFJQP!HjZf;3?KS5wq;B70bKMij#Y1I5j=&4 zfmk=O+uIn3#GK@NP*pBu8S4gdfGt~-CE=n3P)c$*m8`r+mJ5Gd(4MFR4(3lHr`l3L zlx%#+C5He~b;QhT;qFH;vXx;dkbeg_Jey}Y#cY6bg&~o-EY*PDv)9ZndmSl58u%NR zvKplO?S5tw=0&_<82|+vsZe}Mc%>;+1^)gr&{(DK3G{KkxLX`30tue&GVlMGPp?k=+9>2VyrcBr@EaRGFzSv%5Vw^8B zo&|esoNe{%;{m?U91RS64ViSiM58pt!OGWh3`VmC5DXgy6dwOY3XCy?+^l#HpKX{J zn{=5#SK;>LgYmZ@>pX>?S}+y7<_decb;k{!m>Euue_=%y(x$Hyz4d{$1OtbE;}}5O zEps~hPie5_dEG4z6yL#Ub7##HdlTu*?@akouMsgqu`S_ofD4EA{e~kY8bSJZbz(8^ zj}W(TgUGb06t4F#?fHBx0ZCNs+>~g=qVrD)-03Y6VW38wmu7PnRJbE{rAwL$^TZY2 zH7ce;&h3o*@sHeK<6mX(`ob)*8A@??&H^9s4z*gx-LOU^>X0p9(aVX5C3l+MInM&V zXtu1iRqtTO{Eeik^9HErLHsA7sTmeCZHs+z90aTZc~Zn}dF^~UPp?d5{Q$lq`)tEh zE2NR}poqio2j?&QHr;V5;CD)II>LHeD@;GV3kUup%SZWIx{hj}2XjCB{^y%Qe!_c8?;_la7G^C+b19Ew)zy%?9nuYs3t zjE3*e+2LN!ff|umKUmZKCARV>4Zavk$3jvyBA7ZEdQ;LA$89_UY`iRiY{+wbrEb^2q?)MaBueaBD^35Zw1|YaJ-wuRrP5 zK`D42qaSDO-U41luNZKXqwpRfhvcp0CP3R(hFo|S0tpGs--_Jrf*;DLp{;5+ltNE9 zdS=}NgPrlI(CfMZbHsubf4~UPyycRrkv0q*Vk`f=vuc8;QP~-NwkRGUr`dq9KNWlz z8>gkA?g3YCXpJmOQXtohSk0Qea$ub9&FwX4-T1X*u9|I~$+* zA);N4`rXMEmlmS<*$}A?dKJVI{p^4?*9&ihcvd{gESOjQ%V!Y9qa8>qPZH5}!tu>B zkL%1KPS2{ zcZ?nINM12Om+)VGxcn1HVpOK?24<70tQK(4&w z?|aC)`JtzQuVX>T9GmCB2Fz9A$ekFK5q}A9FjppDE=t_?xND~tR zUR3Z2iV{>z~|3Lb)YSdG|SAfdeSIGCUaET)4OX4Bok`N5B)Uxou<+>|!1 zQG66M3p6fe;Z6e4%HvlisFb%C?$k=V6B|6MYn#1|e;>Nz5e8`Mqf*Y>-*}P_#(?03 z{q0jNI@rIa@-;;D6tN{HOH5g&g2=m;EgMn7Y&*n!HS0)7j(ik5Wi^bzL?$-(U9=5(RDQu~@C)j3RA0^b_h+e4rsUjaIPh7T7poxLMTBDw1$-MLE5Ds=dSlQ~7qJ z2g2`5SuNHBr?%xSR?~vq5Yd>C()t7*aZn+;{R3IiiQwPH3gOA(M#>95A3V=vfb6HT z0Vyh%ZkWfYsz^YLIXT0*Y<1*s(SfEC zRUSw-^H!OO%^CRvg+A;2(u-`$r&sDj+N!jis#zi!SqeF9aDD!Q@79FyHFX zTbBE{`AQVy)}RQ*U2-VVD_AMESd9>gwGDav?~qdt!N4y?|{L{x2dB8eVweEJn31cd$uN)+|B!eXW4BU90S5cLU% z#~No4*p3wq5>^ZX#5EO$?&ukkU^p995HtX`0tXU|B`QHZXDByMeix)YDv51bse@`a zDP05wPmq&CKO+6S(%@$-=2GW0Cg^jV8R>q%8y4~%WN(jjLT*plKGm&8!1h>!^0#>| zU{=ocO{?h#B@-R7B?*;CTxJFw3&us!PftXnqEI;2^V2ZBUJ8RqH)a2A%Rk*f__z#* z?qUq+Gz%!M(}+XCPXXV|9XcT{53(bdyA7%+`z3O94nQnhw}^wKG1xa|xmX=81q>+s zkbbR?UL`X^ zeJkk$a@zog!Nh*T3tLDP&~mmyQxCAVwSP*_*T9X&LCzbK4G^|92qwu6LbT(zj?aFh zN?>ROa#D=D!6|t~BL*s8a$*H*T4{RVp=(kP-?t&)MG*Pq{o(*beb1RvVIA z2e&|5uJU5M=N|xp&JEvIyl%ML@piy_Iu2?@Z=loFbixT5@n?xfBY;Zw4Sy1`GsNEV z`1u1>QZrITZH0|q1C072p40vD0$-JR?qrgV01LT;EUKj&ko|!k_-MBw%KX66p$Ab9 zzE6>_i0frTjUPpF7&phD;;##a_f#oxZvGUfg~AcP;n9gkAMlY;!dn?@Lq7cT zEThSI0%BA{-wd@uxOHzak?_+X=w%*{D*iqQ%mUZwdWw*6cqo)`=@l>NazqHr`ClQ< z@tB<1tW)68sY;FrovsMcKHj`ve>D)hrK~Mk(Fe804SCdC#b9%>s-V=HHW>DK)|7VFBc&KorxUn9XWm-!W$k_(T!WSgm zi5emEd75V2sSC`Lm?HDj?uUsZSY(fF20=4zi+Hrk7^H2v}}s>gZkW9d!{ijavuzJC# z))|YVH(h`_gYao6Z$C(M_y5?PR}KDVN)k?tbb>z<95?y;`vLkM!?yIhLinM+iy)Vy z5TqF3<*2yFfa~lbn*dk`o{qaerGqt~=IdA}&L?NsKQJ7Ai>w>yP8#sEzI1|_4jLY4 zKe~WNMNUguSpbqEHR@cNO)j1L<9!inZlD!C|h@7ctHSxj#p|{hFt-e z<#(meU4DolP>B6|Jc8n%O}s{2t(hRr?Le#UvOFNDoFD(byBzjBY50CRISjwgS5$^a zS3pEw!uLf)E$X~EuCdYEKvKB&(C3s>0&OM3fB@GakRUQ8&ut+9PK=vVrf54sVS|v| z_w@q!zCrBO4gMU2NFI8L(qRwR|qNTU~aK0LYW#dX)8Q2iA=(0R1 zWN(GeI}&?}1O6``Oerw7K0%kN>H}oOieHGbM!@cyO!XIT)gbs!Pu9+#51_R0 zOjWR_5^gO_)cXmHfb|CtULK%IRc}4r{2p)854w9X7+wf#A%}V2iQ;V}h?J-QjQGQk zDg~V-eUxPgp>I{!Gvljn7+XZJl7r_3i~~hJ;{d{403@ z9NbJm#tK&fqra2_f4>+4+mqnuaPt=BDZq2}`l2FDfQiumd!9hlq{hd(dmp&o^)&4`OjF&d219-l5J0lS41h+fbgA`EsPTYEY zk*}s3{46V6ejd;beV;!n?r|vtaYs}S!pV~sk}W>M&p1`)lqy}t_JM$esjv^ z8VBEZZ~nygdJN^-(o*s&dBINDo8LjRtx%a|v)HJi6FBVEEf8yUf#+xuiH{_Ez>l7` zm8XsYP_ywflOpX9fMK|WE<;&J&0v!B3&bc`h?(Ceg_S_$UD;}H*eGb5H1Tv89)aW7 z{HhsEk%)zB9fpjY0&p6k{wc+GLzt^?DwdqO6W;9k-0AzW8HRstfe+F;;lTb?JX&QZ z^wQ@PohI->4LhFWRK&<}Aw=Ck>t5Vh z)TtAy-_bR`xYPwS38GWX@%hp6r+G~sX?z|yEk4A+(}`+FHf!&Q7K0#CM)~+$d>2yt z)QM_$BS=Y{4$I^%he#5!+v7Sso}Wq1Z;PjXx2RtJ%HP|9e_jRCs1O&R`16|nw^L2P z?Q`S%r~6-_%IMqaHI*LFX=G)-W04Cr+P=C7y~F1_Ta^uQ_;rQReM>~wvJ13pyr-rV zc?CB-{lg}gssWMV5!ULk1aMW@J(O^&1lb4B!m73tzM44K5{$>6Rz8ZeEUdPH(w)Qt z)H4lud3#lI-NoaX9Vrpb&CR?B!DV<$(I(YC&(6Dk%0$ z{CnhDJ-DQh!7Ja(55r5=vYY56;Ft%oAD!kYTJFcu0J)bOu*oiJ1}N1 zwhyUj0>X66#*d`&|9^*Dq|CCTw2fd4PHw;?94b0VftKcT^W<;W) z`F1m092q|;Fna*3K3WY-{%8R%r`>LA&ea0em6!*%d7mK1%D&=@M_phtDWr7fMjZ?x zr?9KkuYwcl0odKAEx>*AZ(*uZ9SC7Sjj0qmKtzDS@hgHJsASGHhTJTKcODFj?akIh z(L-K(*6$T?n!dXH{i7Ouy^?(5##lM9&EFv1a*zTStMjvD@cU7wR}`O~TuuT-T6r%q zy}Gcv=je~OnLl_|r2J6jMg~}ERiM7@oCzfc7U)^nAvmi)@S;~P6BVt{nS6NjG-9`s z_&%Aq6J*XZM6{mkhAP&H(U(~Qka&~%)2F0Z;KIPyy`C*AxkcikXS0XB7+KA5?H4pf zD9NLxjoU@sAk$;n|5SYg#(bT`>}aP3U1oax*XQbZRHOLnrv^i|lkHfZGfvsy* zm=tc-N#nT@^x6%|UENy%FfjVdx~=b{N&F(KzR4EY`dI&82W@2-7Xq{>2{sV{RVPl<3ekX^+e(jh>O*R|?{gu(L38ux_7+fDW2q$1qi!VUf|A2c4G+xs$KP-B&m!Pch@v)A zSR?w|@FU{|dNa8w@F~hUg$*#JT09{adx?44uiz}d6O3qPcnDStQQ&6E9(6XxXd;}^ z56tH9IDgYGg<+G(Mz~@ydVajN5j69>vU}~)36celnXa|VLl5$5`oq(8kRi;`KRCMy zx|forur5KMMPjCQ&A1(Axf48!OHl*_p6jW;+*wc}Cq;Q(`z)Z7zh(Uat%L2Rd-nFX zk|DnqQ|pVCM$jwzhR%K<76j8eobVCFL5p^`Egp4Jxff1dvqBt)*o;sH@}iC~=(Xr2 ztE)VL2HQ6jpQ&tvCsk!HkPnCG+OdOlnw}WkksLC6>E;c3a|(SunVSJ}iYm=ZsRUj# z&l4wdE`saSdurAck6^Ieo&2@$u9)u>_eH~E6X3a)(!dawdeGn1U9l(E1t_l=BroCj ziTx#^J8X~exWnG@aXTKrZMrA*zA&*8Fbg(h7<2Z(C)3XdXYhE1&<;)aoxTS6F!B7( z9h+vL_r6MZn5Pbm_|hJgmDYkhX3EUrvpCrQOb~4=ZiF-5@ei1MKf%WlI5#$`BSct< ziu*=CWETBI$yu@HG-`KJA$gDM(}v!R6>zmE^xI^dH*oG9t!!H z8U?LE_$phAeu|wG^R{KK(LW>_Fu1P1*Dp?n5hQ_h60gIdud}$~dU6xk{dAtM+Kd8B znJ&*feAWnpzAZAbf2Rdk+ClDu1_KO3mm=<#Kirhy>4-fv;W z74YK7iN~OkDzakQuJy!643aXsiPTRv!0kJb-9&%_PPhpjUZO7quQHcYEo_?L0%ze< z=SD7+7ZEqq_WK6gOMC)RI()u7;m6?C*$uwD@?3TA@&;EdOUufq>!5?Xsp>`Kq8w$x zY^FeCCs+`jTq(3`2L5G>d`$Oq;dwqY;b8S5cy{|$sBL#GATeWN#pTw*(R&GDez$S( z%l^hvM{7I$;Oz0#_85PiQdWv1PaG7hBG7UYjRVnCswM_*W#D0euCJ#^J$Misky}HQ z2_G<4m8>^3Lfegq*|aN7;BV_<#C}dUth!FB?;q3-KAj1Su=${F5N?j;qQ&-B9Axh+*#N#& z|J(i6rSOl`hHYSOBj}tbmp>qB0Q03SUb41?m|GK8goaH6s5NIu?$&-gOl5md%Ff&X z#ZPYBtQN_FISR`6cmD(<1aJQG_7mgx{pv=2VxE++=V<1QII9HU)i8op!)c)G+vF5? zUNVB!Ox}{B#MiGMg$St}C&8hmZk+;VeeA@lLR;`iCRk+n!~W+3xtv(A<|$FtTzEH3 zL;a0*88k?=j-lX;g$_fJ?mS$%K&)A1rcN^*q`uC$udnt4p?WbP@Ueqej#syF-qo!J zy*DSTkNON?`~sYYm;6vpP)70i zGg~rZZdQgR%n$=Beo>*}{OJE*zZfTUVBQ)s= zy{;3yits*Ry(Do`1x8tJaI=d%2BLy<(L0pIuwh}~^NYA*m_=4MkYSwz&L%tvGt9|{ zZxqQxnw~rY!M92!Vr1U{`?0U_4Fa|3p~lZpbJsOgo%ihb-|P@trvK{L$G5ulZCVVC zv>YQp39>b#-d}+$T)Xx3)fNyrTQ3+FUIQ!T=Ub1jB!TK83E7{WMNsYIitDw0O56#i zCS-4b7;5X!_Wc=+hA$3S5;c4LVT!!Ud^0}+SO30O6m59}-)v*Pypm6WCFkYus^q7G zfFUXW#r;!o{b1>a`w1aN`XcR?uT&`7yPQTVl9~w@hu2clNlF04OsJT)=X2QRQ0^#Y zSPvVYeXPI|CqSA(CgQ4xyeNsQKu-o04p^(lUY!!Dh6xWC`wYVxfjOx+bIA=QP>}e5 zeZl%`jU2);-BpBz^!|UAxIAW24=K)TDZFX$eoLnp=lL#>pTYNCeXSMhnSZpr*i;SQ z(2J=s5!Hi(i(;;)fH2~@9Xn)j%MV?tx7d90Hxss)NC=ZpkYW6on*xgEzXCCiH%lvr zZxJ#3{+A!vh`^PWa*>#tQjq>O_;UAaEKK917OH*Q0sg!R?jqUGhF;~$?!=O1@F=_F z6KlFDn$%p+XHwG!w&cFruV{2Yin$YwyVE6rP*yLL3_o9~^>^i|jG6%}*7rJ~4PC4Z+TId(_Z!2Yc(FO+Ahfv8W| zNADrLYJi{bf9zil`yJ-aaD2#yv^yS;^~Jko4Ky?DxD$C0%S~Q0uCNK& zJoC}~)A&3QXPPdy#$FyW6&%VJ{@w4qTqz$m(jaNcYi4saymSG_6 z&3mcLroYsy`u)PUo`}8-9*+`+uN{KwKyE#* z-f80+p=1RZX|0gve$5W2*jKm+{69mJIc}aF16L4cCy7y+uEjjsCRAYBsRgxT=L#~v zHbCO;QN*az62#qFpICaG4xt})mIhN9P~u}F{&jT_W>iG+3u&U20MJI~J^ zkq_PQ;B3DBgoXon68?~OCmIKT+UQ<+8eRfk`Z1UDppjsB+*lXI7tCe1Rc; z{WVV&zX7McPMT|?nJ`U7KP&rkEVLRS=1Tfp0T{_1U@gd#0P~G_ZB>IJ_=Q4?mfXMr zMz(V8us7oO`~E`&X<0>ZMeoFornw8Az4|gg;!7@c8s{|C^TWc6mv!lENjI^#%(Y7)b2pQzxuCneCNp7IPKWffew@5nYWB*26`=bIVqlRj~96 zQsFP(1l!mM8VIU7L9SX^_=RLg;D1u08gi!-RI-Nb4QAH@z1)|He5rP5diXUjh8n_A^6?O>2|&M1Hvk& zqVRLN2^{a-n)Z-t2mP<)IJg|!z>w-dY8SqanjFCV9T(FM1DY2t`-Csr8Ami1J)++&lh~5u$ zj|1a-F*Wue5~wOG3Wu?6w#$Gs>ZqPpbcgWrEyTfGyf!}FErespL>M9Irt zucO#+w`~ROcQ1sxZ8yN7&+=jx_0>O0BdNI^gStF`{-3-PIlxV}G zanSD8uyf1BeDI_-Y+#lm4@gD*=BRw*53@~))%b(j;S_mK_+8URa6n;aUowco+h(4F z)&aL+Ht&d%R{vM1<{%}=g0KJcUDmwZz}pEgvmah?i--lJ3Ufnp%iT~?75#WkvK!c^ z`hPuI$_CwQ3%%Neg*c(?H^uw-J}d*9h@MS`Qc$22xI{MF2F8NSr7lxdz%p;kE2VgR zBPcE{=Dt@AtYR0M2_(hi$+bMLQEzOK1G){r!z*9$eLo!Y)8=i!s=)RWJ091+oaAg% z$cL8<$-H{Api>bcwAj;+!mr1+dtyyaOxxH9PeJzFpG}}QeScQ1uM)&}*T`&}HACz1 zsOMp9!EjTDLz&CH8s1%Ks!4mr1JtE^OV^5ipj{1me+tfCwPrykJU7l=Y{$a>@(P8MgET0mHExzwnh&;^BQ~3N%J4km(Pt-pU2v-Q zuC%CE8~kAz-Psxw3|Y=sUi~WE4L5$|>ct5cffYG<@+VbzNsntEiD7L$zAr{A^!wKs zIJ2hKZerX98SAFsufHpR4ovc=g1_{@UiB+W`7PZ*BxTw4?1yAb(8QMSR6sUN9+%kV zD(Qkk=kNBh7bHRqv0(UHqF6{5IF)$)xC1<@Va?5y?p%(S81%`zEz1x4^cn z^$pqsEZ{G>VAYx430-@FCS5);{%EtixN( zoV7^}Jg0`1>$r!(&wpOO+)Q0W1LaMB2;_A^&y3yb?ETN+`*~UtQLYrA8zAO;NnW1)FLN)MpIrJpDKvRGi0d zrk+j#nBs~)8le{WRchT#jyZo6I7RMQMiH&#QqeGg4O0Ober*2;O~##tDIyVkdJ5bd(>_n zJhFD4n7)7mqC&TNtd;A*sq;U6UNb5I^iF3Ub#LKun{=J(8}Az7-81rMpM1AN#w^WY z83`{iEq>U&U*8A|F%f-vCG~JEw2kt^@@F7l8SHW8ZW;6%!?O3Kmjlh6VWnd{&;9%> zTG>B2yQrsS?u30@75E{osX!s#38o!;bwdm~fwB6MmhEZ_pi7~(py;QB;{$Xq=c`(v zlwEMOZNeqUdE$lJwMqgd#x;0GRXeyKBU+|x5e;&}XSxRQb@B6u-u`84^>F5S9noDr z5|HGkR6>$JgLaP-@`cKFLi65xPYa01Fnl&%7n4}x!S&apMqKlF{yVXrSd77W7?yM@ ztnqd&r0C-)pWJSNNTKt^>rv^jf=#7SHlZ5En?7tG5sv}WB+i;5iVP?T6RxjWuoLtP z=M1uQ)q$t}Qrjp&Gg!Stt9$aQ5fY0Z$DNnQSu-<@6Bz#0`0-T)^8&8$G3Mmvma+-@`!57SWhNvWj9Ych_!v-T^ zaxQlc)lw7WbTM)z4Qc_Djk?cjll@>EWj5*1x;XZhu!DB=t4f$~Oi$J%76iI=Kb{jw z?SXNme1FS~YT)-vu~uu(>GAm=*KRpQ6(r{0BTSB5sBoYOebVUQ{@}s6PhI%yA&+o-?)i{bu-noQEL!TLYMlYkQ9? z%>!GDT4h-MGGGFZF{6P`5HcSlDmlL%AfKpt!PY7sP`%{8Y#H7P2m?e`I{Twxt+wg) zu^$y+!*=lIyP8hGGND3nl3N10jKpS24r}1h^)xw#j2wVEF~0d^TnMYt;o|#(b=}^F!Lbw~hXUnxFy>##V*4-)-Zl<(3f*divR&Q%I^;f3 zhbBb8XS4y_b&9olEz}BBHHa0c92&sp-K@Q@jo+YPz}4H!ht=@(;=(Jxkse_4XRgj% zybXG7*$h8^5(?AmhvJ9M*MSF)@f;CRZ7_-vy3lM@tXfc6_Pe0S#dnIpyX7jJt99Uc*Trq!dd_ z)N-oh_jW`~HNvAzNPGB~p5R<8vnALb-~ku`uQ$=N@ZrG4;r zs)^dt=T0<;>$}-cnpzOUS4Q`3wjInvE{9?0kfV?EA^x4tBRXG-d} zViy~s=pDi{gNsS9JZ(H<0}bF)^QgYZhZlh7$3?3w`*@gv z@Vqnm(F6UWuJ@~1Rlzwthx+EjZumy5uqvCN6@)Hsyx#kh3ci=!)6sj>1euC%-f6+N zjDFev7Wz=84hk_n_&(-{!WSn)I>Vub@K7)!?+aQ3#YlG=Y_UE_#GUlU&VvW=Wl+T+ zJs!d|+*Dl8V8;E&5U~uVdTfWc5%|ZP;os?p(&NQM^#c^V*XRk~Hyw3De%i+ymZ2l? z9o>}&TB=hJJ{hcd8qooma+?dsJ`BQ{I{qt7+kH^P8+#NelnLd7!?J|4r{IW%h@hHI z5m2tRBfWTU6rRh~z^MqHHbq<;35Pk+HVM*gRBCsIkka?=@Ml}>t+_)RT z-vv^Ne)6Vxc0xI*e_I>Rv7I*P=}kZy;fR{+1BdI)AVeqlm-DMa=zlp88%)~{4m|x- zc^9ydCQ6oLe7Oxilggk~I)mrJNxOR4MIbE*Vl*fnPdRW~IT6;F`f`wN-xul#IV>Po2{Oq-k4^@M#bf ze!KMT^GG+yKp*myUMdAOHStzEK8>KBh4mZuh9`7UIWO^T3EvDQBz4uAp&a(Dswy2T334ejxXaDp!@W&M zuA~lV4q}9Etu{ct_z#%V0aYNM;P)4wTV3FhR6(Ld4}=_^1KDz1-S8u`P{?s>2axvI zSyaG_J*WmLkP&;9L%JJZf?asMpw>{JEX(;+(CW1jnS)Oj?&~CLqkC=Ot;J`K$qV&> zZrQ==4t~WjuaaZKwU)!2=ofc?bhQC>%-dB0kO)<-E*$tK6$7%_&?t4{I`E-ozUL&f z4itWV`&McsA6g!txkTQQ13wY7>=dLmfh*bDEvb02!QG@$rc%%ivUkQQ-xc%#daaz@ z{g(}}`Hkf}kK$UWkU7#yIs(B}bC>uJ(RJW(ptHuCAFmTtmrE(e-VSi1$A-pQRq%3o zV_!{cG4#IuxADrlCDhkyz=-8nzz*V&)%gQ|P+cJzeeS6E-wY7K|D50C(zO2b_LqD9 z_qyZ|@ss5=jh(bM^tkWBdPXK^L}61v9{=W*8MUqUOX1aT~TCjayHh3<2S#U^|rs`{^xWiZP> zekYHgJ;%GQSpH+kVq$LZjJK7!LxuOD!Mm}T{KqScw8;x*{2!((FaGfo!LO}%gIWLM zr2qTSKSwA{?4LV5euj6B!Q09FTR$DVs|((2<%QE@^Z#@DKXx=X@ZLBY|9$=cHq^19 z{cmR*8|wf3K4q42_NR4K{_6#v`)@NDoAdu|_F}{Je@tEoog&pg5C;=Id-4Ahmd0xm z|05d>>;7o99*ID%pM*PM9^_y%kz+6R*tawIiW3GAF_UWJ$YI#|l^mZA4v_2Z znEq;J8*z#eD3_t%MOy<@`@4z+!B*t*kms}0K<3%5S)8<#$KV%o=IvoZ-Mfnbl@~Q&R-y;2V$GUuU4)RCF=Muz zi3CV`%4)6Nrvt2LDK-6T7O0%Oa2zCBj)szd2~haJ4Qv%3Y8swrg&!A$*FNrZ!9Dh^ z?PA9?G`5Ue{o=z+bmRt$H{rujv_<1qyfeu*O77|v`zntGRJ{NCPT=}9LfjI4A6zE~ z9%11JR~&W_&4ARWsgx6_Mf0UQ6JGO(YQapP+CxGR;Ys6Be}@Pb*gkwf{jm$pfA5;M z|Aquawo6y$HZj6OC+A@v1!DN(1&sxpHjUoT<4d1`WM)!UCEb~i=2R+_t>t#b*(bxpeo9f}s=*u=$CBE!5 zBvst(O8TQoH0Ju2qeT27n#{Ee=;P~J=;M!YwzZ)Z)Pp9$D;|hmblRnv zl0oG8&O=3E-*0HV^wZo~9S+3BFLmpz;x`20UP_8)=|P{J_6m{hEI^vbIeI0?&=1kO|KdX*eS60#+KTSLRS1Yw@JKjRr^jz;(Af3^(3 zB9+#ffww1TkaPAK=;!e^bmHx}yw;+d{1UC`&Cm=&9>=7b!)~zj!tW82V7}Y#&p`mUJ|f zI`AHge;aa7HEKz)HUX)u@yg7OvqvJ?^=(@H8Fk%J%&So5k2MrLDvik8!#6`_%fkr467?$+ z_FiP&wCL-Z5)$;mC51y{cOqEc=N|HD>^E9#XWkaXv59yQ1s$bGQA5MYCU0(bLMVw5 zR)S4~NJMP*YUdOIoLCL1UW{%=Lzcf2xRgFdFMY_qZP$K)d{a0WIX{1d&Tz$$d^fJH z`5j=ouKuzC@$Yc4YEx@LS@IozGSfUqpWkOt)#$T8?i(duxW*FLk5ehw;fk?5#}zmM46x%d0qss-)b2}=8w-)bM>0b;fvLeq$1}L z#f?3^qNmx2TPPh7VfhcFwfE^yHluAcmrmq-ea#G_)tx{y9^HUyPg7JbC{o~}8TGHO zzfMQSUNEQ(!LKNn(Or?SK3nAZ_%4`O8AW&^+oZc?Nr3R9l9Kmk{Yb+0oh_!MY1}h) zTk70*%g7S-PzE(w3KFheeEXCaHRw?c{S#w%fbx5^mpxeejjEwym(5;gVZyJ)NAD$& z!k+?Sf1l%*qT*HK)gXyw^r#{iS2)W7kDs4R*gxlkq?{MSuS-lI%&|gObf!2V^>=P} zTU{DBooP1}PNj)>-np{p_k$a_*#~ZJ6VpRJGcwb~o&juidZF$;i!EH;>3!_-VgnOB77s34>ybt|N+29ECd#=_eJ80+m z9JA{lKTsh_YNv%u7lEW<*H?t=47lhwaW6lA0jKv$HG1XQ3G#&g6eni*5S{5V(rZxn zM{gNL86{Vd{W8=iVJ<%RDw29_dku^!xz?&SNfVAgWtB%?a;Wl zqYrq%-n~~uYXMgvVrrwkoGSvgzA&f7qAGHxx#zTX>UL1B*B05)F^i}a+w zug*^)g9Pb9Z)SGUdwV5MKR03I?p~WCy8LDdy%hAOu*G8u<>zL!Y-+`#1}R>zF+oJ| zr!9l~%Vq|6dd4{}alZ?BPIKC~BlZ-m8ep{l&4#M z5#fQO#tH9zxrSxXJ+4i6#_VrU?X)th8Py9=iU%k;ebo(!zXS27odu1 z;%9q}DMY5|EDh%wPWZVjDJD;d1Um0u4levc0_FVIse?E$G#NHSsLAZce){Zd89t)V*6Y6da zwUAv%dgr?P^%o+Q#-uPKNeq8fCg-q=c_S-%f79qgXu*_#&VWo65m31o{H?%_60kUGV`o7V*6C_0N2FWz}Hj33$csrsefLyyGc`4}*4QLO& zD!4O3ipLCeroHud(c02l?y~p_)ZgOwJrQXtaAsEb<;zeKaFgBh%M!T&N;GGrus1P> zOg&9p*|_!-?cb9(jKy9;7b?_6=${`W=1=J2l{i<>zc(-1-jmrx203kSy`Ek{JI9=^ zCf*%K8LnS!LJ$9-)wIeiUL%wMnSE67IFSj@Rml93_XYnv`c9VuttxRdEfkY#VO6Lc zX1l27Oh2NT+Rm!rYl@V-B8qj$+d{3`biTc2XqTaHGBtjn(12(weMnCu&PG3f;&*?p zyN|yA%bTVYhu3QGjgtQK5{FVeNu|Z?jv`ojTA?3=Ke0rI*ArB(4kB~q@$qSnV=|H_ zsecH!+K^QCfv?4nX3$d}do-cN4aneK|BF{HMk9S!X8CqALombtzA~#t$ zgw!|@#LOvt?^W<`Bo)e1_S&waA155F2`}}b_ugJU64LmMp{CsRroB^vCf-rpO06rvOt5tS`*f4TYD)#XC5Kfvr_#@*n@Q5)}UG}pGUTA zZ8uWu_fY%OR^&2v-w>jnmRseAWr&R0#}cs*`B;%thZ1rc(WuP!u-a=z9NK9|yGhgL zhVZLcoUrq!pa$<&b~(Q6Bg@v6mERO<&`vhma*=_4hB(f7Bq?F_%i#VrX}h>&rFCT zm6xMNS8qC@F_(4kdizTuh~dG*a3Nnr==YYA=iN}0_U>b)oog=0*_YbgpTdi=j+(=& z5h))K_eo=qqUd1s9Ag%VJ&p_|->|E*!Lr8fKwHj+}XH!YsY@x&xT0p za6whLa2PT+6-j)HG!zk6ZA|n*GjNQZfehHQjtFzEcv)uj1GG`@$Eo_O%!q=5uY^^d zKO*r;VK44UEJA?A?$kpQlz!!$U8?wb#PbZsXr<>pO7-{GdpGwe3}bIO$?Wq4g!Yry z{V&Ub=w4x|@YQHv^rJ+h&lagM&V9|g>@VjITJC8^_yIGBR#%BVw4&HSlWm%bB$fJ* ztD<$~bD0bPakx*kk=>5CPG9K%u33ycVq|mK3_L_AE_H>E3_9Y>ZU=e!{9uGrtVS!z zHl+y5-?s}N?1-YsI;kT$Zg?^+w-!l1GNQv?HNUi>6XS?Qt}Nbc2HzB9VnRL@GK* zpf^L;@E-ENTSgA`c346)qZ*z`Uo_zo{M)g9RnY@8xXt;Ee1} zfXLJ|!n}VjCjKKA`p56>!JG#Xd=!35P9$;-9XYBPr7B%PL^IB41UPa+;^rxnmtUD- z%8%cAi^(&{-qUk{;4T>?`Ve|$;*cJivNG#t@IOM@8Xu1?J*5CKW&x1=dODaeY{Hl~u_LX6S4 zgOK%2+_C9|!)Jm8gn2RQX!cbJ63u#@ER@L`X-e3&B0T(qJTYDrSJ`I;#@E6HLu&pa z#g8*&Pd^qxZxZg=uE!FB;J&I`X{IsAnKr{4H%?f(BH}Kq8{V^L17|v$r zj3GeT%WZW@AC#b;hoQ@4{C?=XVrlKp42o83sqem9%tE}!))PNBC8Fo-K32rX*&!O+ zX9)a9&ec4+kb~hWbU`Tom}K*~o7TKDmOVAOmyc9`%C{BT%tyTVWz(^&FRIrtDn#r& zg(!P6Y3U87EY#-1U&Haj8pOykRqZx&D4OhLx>ic{8o@;fB>cUVj674-7Q7!Pf|iBx z)jgy$#CR_x&}8u%ArllAD2vaR%I=XS4$+0-IWDi+PEXf&q5IEIDZ_4Cw7WAq_JwvU za(1|t@wU(jMs({%dwR%QG`VU}+M=-qNfzG14j7goZW{y+haNrurbO^BveD0IbO)VG z&*0h)^YljUF}@)BaM`cFldGdf#xREZ60Kg%LYOZ>~rU%4Cos>i)= z;&yDF+`{|}nJ7)IF2FsHeTmbf{)l^2;jm%xI7_x~u}f18p2t4-7Iw}TEyoS?C%w-+ zQo(Fe(qCJoh{N5d@3JC7YUEtF(#LuBEivUX$GrYb{_=S*T^!$wnr8z zZ!n}c+5xx#Ol8+eJ_pa!abOYUYz;z4)gY%t>Xsh#<@Hi zWT;}E4ZJX*;%zJ?=VZ*$q^59VsURb`z;tE z$ZGx)Y$G|&dKlql?dD9~QrrPuiTbv^scaL#db+y!;I2ju;xx6NVhjhoA5huf#MDg7 zu09S+#hrk+wJ(UV7>ojpWs=&#InqAte$rTt;rCf_YOQCkxnr0bmleeVnr6mp1777K zGu68xq^cJn=}dSv2P+vE=4&@@aJ+$&()uhu&c+UJ+%2qrQ(22n_t3s)ALa&Zp-bG? z-?78xzpZqkR+BQF8J8ChxVd0Oy)#endvA=jsWk0FhM&mCH>ZEr?=gXR?7}UQIWoWn zxuTC%y3kl24mYeG%Y*9vD*E)0y$_XC_Zvk1cJHPrW>CT7ACst_u^j4+E@qN?UVtBb zL=I!FalviPi)Zdj{6(_*q<=JaodzTMHjIaXQ4O^^?76k~kb^?y;bbwdvbtmmS2V6C>jn}xdjc&wa@1C@=0&%Zj z;vQHQP(sfsfBpd@;GoxdNqmDIbUJ#}^X?IVA^HzwGv8@|)y~n5k6;OASwLG;r2G-C z-(vOmn~%vT{Rg+@)e>50qjx{q)8jM{&wgHu_?02wpIdsw{k;Sm)s2JfNluVZCb19n zmcKFLs=XpL?q}f2gxbNEpJiy4)WBDHnu~zo)%z%~1x_fH)#JRwmx`I_c6}?$$P2%e zcB`>Tn98n2_I;YIJOlDkCvF#NPN08|Zq<{98oYOWRS8&kaU%g4^6Ig+63G zm@;Dct;6C=HCK?bqM-RJWGTP>Q$=K&>_v``njV!zU^+hjJ=wETBvUFrqU54~wM>A8 z`s-gP;x@20eL8Lv?Xzff=2fADR=&l4_jE>($t>)C-+LaQV_SNo^wJ*AeW8N=d$Ysv~% z=fL7}y3{3YHqb($Lht>I8G2;14E9?tBS$?(-e1h8(1-d~x3C$%kh&Y;I}CTG5z6)q zi=aamuws+__?I6qjILI7!acJ@JKZjc-j}OD{hF>)>_7X3^xdbU;Y*YGi z_aBxo-s3p~H0y26(sSvcE72zTg~>%UHT!A~bvp;R$rQRiEx-x3+EcF=e`W#c+m^@r z=a_&b$-~%r#Zw@Mxx*SN2ru=y#z-L zE#wW2V_Q?LL~5T^yeRf#2fxkkcexW>#wapIcOudwr_O!Upn)FvtThCv{$K`NIZxGRU(kV^c=;DEPf^23 z$$09Zp>YJGvoUeAP6=&xwxe;(TtePCPapO4I3w=VnJ$*0zYz9Il#Mfk9Pl=8rt||w zEyQ?>Lz!L~qOsil%Kc9kk#gsdVQvfoU<)_pMlhs6lGM2&z?>FP50)qiDlx;u-({{b zt?Ot)Cd2GqBSx?+_@!Q_kP)E~$G(f}I0ZL(KVlt7$dLDuBeAySm^=c&*SGC;n< zKOkHkQ?r-Ypl^D@Cd>6vtf$%HI$FxwBcHrP4j-!~eQLkU0LmZhX~cahK(6`^IUvPf#^i-HA^f!IvBo~HU$}#BuIsXL!$_|}7u)H*VH9(RSC#uN4Kz>}3BCDl5&5`VXQP_N0-ivz zJmz0avf{k^{;-f3KA+s82vy!duSgvp1k#hj7hNegqfLxa>YsFciSmc29@_PGo7y=NT`c<6{rwU&}Cp5E*L6@;V0K z)skqCcb5jpIqH5k+@$~w&QB#I^bU}YjUZ_ec4FXd5?aCfvsOk;!E=_)+q7ngBy3V~ zvlKmi)~(|hOb+wP1PzC67m)<%0Qm8nBl0=BxJeq>Lw&cG-W|=3Aa$xbT-{n*IEH`= zWW>5F=wm(QE?V_yR8r`v8_$Pr#EwS$y@~1udW`_1!CtT@m+-dH<7?C}^zhW>KCT&e zjI4ry%0kBv#3$UmwAo}8G5oNOz1R5zc|;(UK$V-1lCTaWO9d|@cHD*ye{e4_v#0D7 zo@$BVGFdWgn-B>!mcGK94%x-Y51i}eKa+#X$7?UHUv5SF`uws_#Kz^Wm2q)DPi;fV zP9`-m-mg)%p*g8{&&E-93--|ww`{aI-zy_=aR(VaOHXo!m=9~)m8C(9FB#ugW1R1O zGlibl8!~=|r&S?A%<9CHA}Bd8IqwX`E}9qe5NBtzjl%LPO8b|)5Y_~t43nN!1iR1L z9Z@`o7_;2*=9`>BQ=KV{mKxR&%khbz*H3ZP!4fFl1xzo(>LY$A zNq=>y&Hq9L>BQoV-#Vi!GIZpdFXPY*<*35-Z3^J3Mq7ZfD~_7F@*e`A(U!+>$&{3s1yHDbWJ z5v>?DgXI6>c7N{k0H$rUk~94tfgG%deqPqoVBKSWPcxsRy6@kPKb(clZ8JQyXC6ZDthevQY*s4gZWix)a-{(x>7NlD3FQBa34z;V?dVkHf< zdcu28Am6p=@2}1Nz~(TQ%H*uyaK#uV95ANC==_J~Ra_fDs=0YN!p@6u9QP}*o9&1D z*VA5^p6Y~gZW7*3%tJ6X`x(=d2!D82pLh+k8{?7H>moLu+L7#kc1%hupz|pI;(&+Uei*KwShX6dErcy^POIB?%mDqGYCr$J8E|?6?nSdr03Tl}arS#e zR2mdL{vy@^GV9eB<#qZ%Inyl`IR!dIgZ;*x=h9)DVvpXcuSY3&n618{vC~-Bc(EMWv3??puWAR8J@UaV~sQOFE!RdIHc9Jp`vvyV;P+~wwqS&79z1@Q%kQ8~3)S?pzXy<(;;8T!dn!z}wT zJ1Rhm7W=nQqI`@j+4>Wcu+93iIIhZxF6bRR8Ud+Dt&IFGH&q?tOxxvly+{MfI~gUP zN|h%tag4b}M6#n1=>1DM1J>Y-?d%;M{bHo;Zi(ja_h;aj;!@ME=mKQSP7{z0XT_Uy zw61=8e;XD(+x~j$EhlbZZugr{`{yn8~XcLCFik5BGhGV ziKjOZ>p=~T6>F#ia6RtpTXW|4+qMnBfVcM$%*dKv0tqlWn*tFP0z}__=W|22+1H3f50QLSD$}>eJgX;P$7KLP!KZS(d|=Myi>ITrl7M^Cq<)xBhAJ7jyGGN+SXmBE0wCK%&E)`L#D#{D#(m6l zngqF*o(mkwT_=#L`0wus_5xzWVXIFq6`p8e#uE5Q4DS=k1h?dtfs}qA%U#-|=()T) z+Z&bn7#Rt2;<}MAZeIVlMW>GzH)!8@^GQGiFX_C=Vtpq98V0}WVL7IPpPN%~s%%rj z!*yjn>J21O;osR5%VbLELx0Yu%m8Wh?)|ouU|tDaVb0%>RC^!1%*briOB;m&Cv9j< zI2lkLhuwW;zF{C{F0z^NPZSM%Hkwv^<{0jlWB9k&I|$GfWftmLv_s95`nPNrq^Jz1 z+j&C{VYFW4*+f#C5K2R{_rprXRqpp0zBY^lxysF>r8!=nSeggk;!_F(My^1iSx zhfeK07<)_f&}2#!r`8j8Ninqnn(CcZyYlC;0m6?D=%y3U^|Sg_XJ-U-z361mF|Jg^ ziI==iH#Gp?xTfBEgLb6r)#a#sPZwBeBvzc3Vh==5nX>;eO~CAuc!a6)5D*gJx?9Om{l@xQ}2TdiMWhkG|N{vPCLrZ4-oPkg7=!H3HQX%8Kad5Q^S#Wr;z*%6$w8+XtETSr+sBlWje+cyu3bD| z1f3l1o0d{80^i!FTr&cX;C!z-tzQuLqvz=iFB}Q8uVAoacrcnFhO?Yp=V0Edf-}EZ zEGd)ZQMRRxk@ce@xZMZd)*K}%EdRi=Zh%@Ar@Y>3SbQk~8>#R~`miX3>KAzl=tYa7 z3L+%rjJMfPg_^R`lUO$_fNJl*;$@ zXGgKmRP>7aI1NfXbujO*!2!p$V6o*KaL4K|X8- z5BTX{#wJVQEUsGvadPtrtSazn=7X)5wR1v@Qp< z(5`_`2E30?uJpl)TH2;}e0v~z;rY#LPx}E&YYX{13*r%W&vA6)gDfsQoAz4j-DR*P zKv&%FTLaD9@6BB3+W-P?`c68I>?nMG@U)GN6Ma!GFiDmnf{v($*8Efz#63!f+u79C zA=$&Gc%e8^^s#Vog;%#In$UmyB(seGF$t_fijj#It#vx=$%J&ME8F?AcgWe$?wOlw zk}Vf19-vuDty*kIkk62UDjEqVJe$MD`?>L*OUjk)N<64qM)Apg`Io>+uj6w;wG>X0 zboaqwGdX(n)JKJONp|E6-_eZHH9p+qSlEmTS0Qw>__CI@BaSWyQ|w<@;Kau}_#*h< zk0A9X?y}_^VtA&f_twzUFW8H%={I3FSy8!{vtn_o+^EpulDq6rI&{R`$Z|bk1e_bw z88;f?MWv2ZKfJr&jj^`tveVN?V5ClHnl_a(4+|Hhn6^PvG?`T3ZxM8N+*CqB zmj%gK{`oXOixEE>J{WV72vuCWDkA!1n+bo_E*mTFZ%Cx>I1rdbMRAd88}qq~f;c`t zPIii)7ZtYsu);nqfIj5myKx5NL6?}^6LSsN@txlSDbEXcz?5b-Tj!-tShc)lvi)}z z_%WHzi<8xX_=HatSDYBo3R9_bzaER>A8D@k2Imh|OeoVy_gRZGL9YL7LwjH~CG$fPDQE8@{8}QnvmhR-t#PtzzLI zJpTBts*1PjYW(e@)|ilHZ)eGc9)x51o747nZA9??r0=z}D_DoWuiyz`W=)6vdVxFz z1iN}ikWbiZnMlDY-Mo=ik7#JIspY=(L84PmgfARlsc^ZWpFk%14EYwJrEyhqw<5Nt zk_gFjVLEI>Wc-=K$YO{N-K^v)a($fd*mdsiG8^wKk^12oMEUNStfcHlWck*4)D0Wa zi2q1CJ9Y9!g_r+)973vsT#&=Rx>TPozx&fShH6BIu$z!zX4klhggrA$_;||?`MsPd zc3x(-f=MEHrs{kTcHkb)=6vfN_N83?gFH8BdEK-8oAR5P}QfO&)2jvB)m9AX#Dm(@^wTvoz!~)(P2`ZBxzg3DtD(zbcZJ})Oy~un6Wvy=LT5bR7Gr$=!-qjSsK=FtaUp36?O}{nv&?ENg$5FYv?mQzghg+*w8x z^i)O?%^A@5lp}twWx3!UTZ#Ne9v^x$i?CeQie@ZnDH*-T>~H1 zukdugk=PM8ZnPyYK%`8X9Zy{Fd2l8@3#(|JG1WQEiU08bgPV=?VHcmfG!w~IXfTU$ za=sWXYQ5L?sMqEY*kS20ZzFnP4i?AX=EjVw=Kdh28#rRSy9aF*{jUhx0&7 z*!-I={@DQ7Xzf$CZR~-+k^O1us7;X47w^8!+yivqmDV$vu%Xr+8?v#DocJZnQTb)c z5I`q0xaWK+73$5WH6Kuo6VJ1xRE50gPFTwi8IxGsVy(bhEedZo6%z~POBEupm1>SYzzCEiOB|6V{GQ{Bc2XMfAiGTSR z2hPWDvfXfG8~ANym%%F*m_X#j`t%w#KGeuulX0gI(xw{TTK>t3wye9wmB}&Tjfp)~ z-N+B0B|oaFg3RRGhz`Ne;Y65sMVZKObipf7EvQuvzFqfw)+ z*_D@rk)IM9MlUBw@W|1}eCLXZ6yU;9=k^!7P(^W!B0fh39-CUaKlPUb@An#A4di9T z)y30HdnGzSZCXxoT?s9kMRGHv>kc*1{zfp;N}UuJyVfjh5w{O$|DOFSL23ZHv*|*b zH1YhjPv?8@ATSQ5 zeoL>wiW(&HecDaj0Ly`2#4amPpckiJx3O_C;)86#HuBHMVLkJ7)h-cVQr!PH`G}SZ zRb}f-dap%>9xQ?9(`qEBrEJi7<1foVFX8yOkNQ5aoX2%FE)cLmSEq;~pO4u1efg7E z*=MNo@wKB#&;c|a(<0oGSO%A5c`BbdKLc&`k^hQ?NO0pbFZOT9jKJeT4yl(&`myL? zothE}BGr&XLC0G@4is2kGmZ@310z99FRn{&!hiAxL!^>(1fASKA%VVa_=M*3d%dJS zY~st>W{oNtYF=Rfz-x64l$lRT@c$eGJcB$93VcM1pVN;OXBSt%nu#Lm3A02jgPpg? zajX@|P;r|Lvkd|}kL_-r3|~arZF@?kk{6-cQ-AX*gH8~>#-OhC+X9h+!B6c8T|mQY zuk{H#DU6&Y7u|&!VC}I8iFx=G2x}02KAJ~@4mCzA-)6ps6=clY73+)xq0H=-CG$=A z<6%b6y6F^Tp&N8f`$>TNo;Lp$G=>4E6n_F)(Gd9dF3dF5p13Y^ya^o0UITD9#Gdec z4Lm6o!H#OqL&1!D`plW*K$*0lez(61CjNaTuCmhro$}Sqx9vJWs;~(AE7=Wj!#$cq z(t8I^Kkm{#-E|-INtIaJs^0}&?!43VTfYF~W=0)6HUdXt(UxZfBKuz~fBY)t2GDI{ z-!#Y=0DD)qL)ZdwP^|QuJxFy0^of?%__8enGo6lKM~^Rpkz=>KrRC;;Lbf!8BXehcJQc?&4Qr|3y7_ebgrZnSM1l=?`I%QR?xtoSKHuAM4!U- z{&OI(nu7ElCk?JsD@pmJX$q3w9lQB3sTOPEb0m@Q-h+Y|jpg5>6fhf0?YN>#iN4Gr zr7u54iVIl;M7x;xVV!psemyxsj(_%iNSoSJgrqOAs_vLlqu=#i6ZY)4!LIF;LCM7h zpvs^UFHE}tj<0CE3wpf^A~UKD%(A%%500@6GTVA%*UZ^g6_qWZSr#wp==U4g+u&r< zr*WImCBo3L>cJGTo+ME`iyOtIo5>CEA@l<=8u=tq)AXLV>GHKksL?#PDP)HdI1=Ax_IbAqXDm# zU$eJo60<{eoc{nC#bmGBEV)2A?A~uF%6aTQRpj7P zhiSxXyz#@#-Uryw!1;DwWCf~)Iw#4paiZ(YS2i5wvq0Jz_s0!Q;`n{JG@!pkjb8P) zPxo&z!?cdwAY60f##hzfnrm?UfR$IR?U@`!(W=2M+Y2(hxP*^;id*+t#HDDSG~Qnr zpAh`cO%naQ?CX`%rP+sbAc>-dNoa)~Wp1c>v2&c77>At2(eSMca^JbX&h&)~<@k9b z_M_Y5vdepzmbOwqMrA$Sg5UQ9lq!FMEfa;x?TecnpYySz-j&_m`sxF~nu{q#c0i?q z#?E`R(XS6=Y0H0oG*kz-&NX*F{e&u6w_YUEpUXasjn6aeQ#YC)ZU(1eXy>UU}uQ0`^&w zMhhf((YWV#4)>05qehe3ebb#Rxbf>N#qv$0sJLn3=|4|nV5^s~rI9-&x__B}4U7B? z&-}IvXnDecdOy+iPY@Ep`A*8z+oQptD$UjQwQDVuz2@HgvU?HKzP4`={K$jGI6aH= z`$mJ#n2O!eC9VhimNdD-6nwa%UC82q!YXvX(mwH8o(p|*=G8_MIgv{H*`T;~m=)zd zxhexwn9=9!E7Uz=q$o$L2{X%CMl|JW`-WD?2&PBHSTtEbk6E>_b<`h8gSR*2X1EMfv-2u=9NNQ82!X5z%P6e4xLQ@vsT^!MruhPxutf6QcR6{aD@2-CcShHbg8cuI{eQysWH z8+wEEa0G-Z)#PrIbO4#aM*(yx{eW%dV8xqAnfsU0NY}d>RMDVp6FA6OUY@O>WPSa< z28`K;B0?v}ke{lj7sP#6p%qMN`DZr(90ahFZvyN!HSchVFQOe_@4RF7{V$y`<_u}? zm9hnxFBT9wnm+@0*6xo4P5l68SjxZeb@U_txnIvswRXch_B2N)-;4w1i#dJ#CY^A$ z+U$yowI08wX-y^X#f*;{XhNC@lWI2*&7VF|S{J zFu>Jm`xeDG(3sQxLpB%(xip4jo#*Nx7gZ8RWM2%dMAlD6eS8O=af?_uKbwZMcmG{% zYx0Gc`f*6~Fo%PGC>+?rO8`^P$ya@1BakOS?C2pW4orU;h|9@!1I;SkE5B~c!5s=i zw&{XG=v7l`my$IC1bT{EC+a)E?pj{;_p0B3I{x01fZkr9OnvO9NlG2yF82e>d%fUC z70J8~lP$J(KrQT|)=e-H)DL+Gd~`p zh~~6T2CGL@4B={B-rs_LC#=8CssG?>FY?Aoy65YY5W)jD`5S#o-q`(Wc`C!&yU0M~ zlM`Vit(YAB39XO$H#7$pO#dps?Zm)z!NoI~S>;t~ZdzHk*RcZqN?FCkIzkR@?(H}A z>WJXwL#48+u`*tlr{>K4eT4Y@d(;aJZxE*LE2?Z9uaGTf(i$>Nf5J7{&L)=u^K!Yi zeL1IlbQM$922+$bs}X+A(9X_DDWplaF4M*S9VVB0Z(U0vvHaFu)s)n;-H17z4&#m4 zd~C){Q@?LI7t!E3bbeU%0a;nO*7p(K*0>tyu_m~_h#4Oh@w3DVv30`UA4A(gWb@sT z`|R0sn9X{rZb#LNinI@|63>}@2~G6pDqELdVou2+5|4w{kaL~K_2y-BF{5Ss?=|d2 z8gHKWy1CDK69zKnD+cSmvAvglZsM6jnzQpPZ*i5(GK156CZUI(2)A`ihips=f&5%a zG?v1zIS_f*=26Ey!Sq#rlU|5XdFSlT*&^B6AOT-d_7Qj?v+*R))BK(LXR0 zJ20HTw~jH@8|el19m3CdoZ{?6(qRcDYfD}THF`jQg0U@S9hN!NHeCF>gTx^Yti4w# z@hcB`mg6!zk^1{r>wu8C+q(Y)X#WLQ+gM|uEcp&=Eegcb@6f} z+14)&@m`8%MNZfZv7+Gjx($u5dKL@{dI5GR-f_|(&*(A@eqAZdajA3-P`kpP zmZK!-PY$c8rjRYL=Af%rKe_?u98Q+oqrRYVtnCujUpGiw`a15%HRAsCev)D9xjXP! z^x{EI`84=)D~M<6x?{gV#>jM>J?~*PO=o;Y&*XYc3!VkbVmn7j? zNs5bb{a|J}^BvwG-FfHsnkW?c{aM3IfzIq?wNNY&`F?yloB3IxG zg;QMz13cyT@~r9~J+J}>0o+oTZ?|c*SMF=s=-a>rlGF%7f-_V<_fSWTTeKph_SfuAO4a}K_udKcxmX}!EN>9 z^QOYWK#8RAJM%LKsPRd-Hd6N{+?rTnrLVmXinTS$i@R;1)}>q_%K>)qq~Z5xPlMwC z%NKZd@!UNu>Cua7fu8D*p39)}2BV*$t^+KZ*QR<9Ggf}WS5w=KryP@^DHH$Xb^&_x zto&k&B|wp5F7)D}D_BSX)9HJj$Dt#Gfs{SD3FONedA5Jd0w`MvrrLg}z}Uua9llk9 znyW-P)LVUB%uS1hO2o+u4zLzUEQD+VcF9d2-1;`4tUQNO%2VMY7w>e%Y|jDpv9Q|j zTq6}nS}u@y%I(0pIU*nU+G|)}p>^=mjU0vMj6N<6M5(p>x0&yMZ4S3cOk= zYQA`;2Xw43oaN#C3$OYx##&HcgJ+NN_|D});MxD{0`;e~*8V|Go@+XI{n7Ju?C zIR~CTm+=2f0P$z{VKC`s%}(xnZM zRjXI5@pS^!Q}x$gYHtJackegHyR3nb53qf7YYfX;em$e~{9y(Auhe6~@wdQrUa2bJ z*M^lzyuG3?H4ejP`hF_K*8n$KLDQ+`+^|WRW&TXA!lGt^JZMt4z zj-G}P1l|GamQ5feaQ%ynW-;_HMoSEPr@%GG*rT0SwgJQWjMcEV1SpZ#r4V{M8MvM; z^It4l1v&lWbN62mC1_!RCf~`IfZdqKg9@1iATgb)Dx&@yaNNQ**ZLZOZJ_CJKj|*= zFTwbz%%T$(t@d}r#_$Ck7e0~SGcgCNG}0c3osmMrBPhMM=Bk0cCELLIvMPT19a<2f zO~jR6zJ-^DjWpZ$X%_c8WpEL;W%Zi67U&YC`0a|F3VOSoj(I6a2A4a3a6G1Z6#KSg z%%6~8d4!o2wX{*4)F zl$F&h_k!>;RyD57Xmqp)D`a1c8NA>MWf;P5i@e>&Sgs^@>Xr+jFTI}pt&g7q5%X{j z>${}c$C+JkL^=R$3w?$JM7E*f84}$;ZKC*^9j7%Q}cEx%MV`eDXN_JKZ^ey%lXHYDUZK*CdhHJ z@S#h_6#Fyra%g4$_miPTl0;n8@(M?zD88}5QbH+2hJJzL#sB{GLBop4gdS^F^xn}6 zdA2OQfQFB4=XI($y0^WR_LSu)p88ZllHuER_=)nk%Qw4r=v4bbqtN3J$Wv&_RYu4ZEb7 zbAipBBwCyFN6@XIDdqgn)1;D=W-Z*r!7*vu>quOC3cLGU}rE zav{H*S+^OULMA_o{$K?S)V`Q5DU{Caed( zY=yA=N4-k)6)A=FaT4=KM zbDQJ69Z=ZG51&dfh2?oA(tHG>l=IVkseR;gcvu^-wxeDOul`xuH%=^qDeNNG@42-? zF&`T{wb^&DOHovs_7?;sT7x&$7!2VJ(Hgb0`6Yl~EcjH%*?h1*m&ciTD-%d`a}8Nd zd-DxQBr$;r+Q;pen3??FY3K;zsd0ox^AgUcO`&0=ZY5BqTwX`E@_khc;^QC)F#$kw?W2d#~8XP}lrMxB-3~Th22}4AD zzDOu|QKkAQfCxA!illi&vFXMR3?VnZrPtgiEC{7^ge(2;J~TiO8qA3jy3 zOK*a`RCfOI;1yt=1h#%VEdhq4N6hPQM}a@-q+jHhMbPRSdS&6{3by07toW;H3o{8$ zy-O!NfyGUFk?nB(gJ%6(%CBS6;Z<$P_{E1WV4GFh@GYtmK%hU#zvS}~F3C_6Nz}s{ z!4lSU%-P?;mXl1j;aV8bKQR!v=2-y4`b3p4Kh6ary7t-Ncnr4I5s>#@rVya4oIE=o zIYQtzPB=z92L{Hs(S>cvucWyTbj!f^tBgc2L!nF;Njr{p;}kUt1_H z6LT-UCm!iI^G`}Y=Of_h?&oj`X$K|UUiDLW3H-$1%X|7+31+s-rpio}3Rs+fwQEu4 z0~XN|;Y&VA;Mo0hFSxyIpmOcCJ49Bk+B49qE6HfKKU&~mnhsrlOMR-%X zp{;#h^zFYDAed#yMY!uBICU`XDBF+?(O^-1?&JX&H=Gbjo|Fo$?&W0U+kb!~wm%8~ zzC4AEoKL1(a`OR$oJMbyHeX&E`EgwApzRycnp0 z>e5pg+%_k#LGAO^mGsm{>A%e@8Weycv3})}3*3By?MYK+dGB2pIDA&hh z)0(a`pe=psEfNPW;FcHbs9)d*Y-Pedm7%-?hE^w?Y;f9xsUMCO)8;bcLvl~nvp3&@ z-_)^|N|{H|!-D<-^^W71pe9N^;J|{b>*mTX_lV#mtWf!LjR4-8Z=mTE6ar0-S;B8I zVz{78v*ww{!uSX;Z5#DFdDQtq`X*Va9Qwv|#yLPk9JT%|q8#*B6nB1_ooGAV0to(T zC!IT&A#@f=``W(-&J6P$-JBxgn%YNe%=#DN8jPVtrt`dA4q zS|Zo#L-&dFewD4zR~)G8DTT$QKm4d&A=Tx^H?ru$-=fMOPEOoIK)+OpVF@a~)burt zlt!0MaqUTtOQSA>Z1>hE#L=6E3F^jr!%Qd(#Sog z6UpT+{m6D4?JecFTv+*sa>s3j*gplY_~BqKv`6}t;Z3Cspc7J%G9@gD>lI$x`PR1u z&e6UaqM7}U4XKzaSy1xgvqEP|R!oVy4gR|B2MJ>68?L4YMqGUODoszAf#we^n;u(y z*D8Y7Yg&(qcno8i*I0xK!kN*Ft7;U+sqE;Ltjnj^MrqKt{2UJcg&}}wPiW3N@t{?6 zb)FahR3KwcHy*RgzQK~79HTre4~Cw{1#33Npk|KHg`%aLK45Nq=*(}i26Tg#;>^gq zv68G5uZE}Nz;!o#I>L4w_C^26Xm(}B59f}QsDIuD&Ov{@K9-4~xppHzgOP4U3PsE$YzLJ{X&nRiUZybE6n0}DaBk=`9f0#LqCOKv!w#ADuYUs)bwJ7bF{5IvTP`s z*6e3>2QkzoWbrre3+NqHD}lOLU3t+8l`+;C|0At61z2t8j3{{S z1D)Gi)$+9E zA^aFUp{V@tE_k-}{z^hX25ix57#|2?MBBL8?~KBCK(Tb=5+vbA-v}@tO{G!9pL}}5 zRcz`DJsu~j@4RV)9gM-MOAFgT{6W9DETt$q%TatTvzQw_99zQP_=uo+Eef4R!xFfS z&vmV5Y9#n`U-%+mRvcA66rNZXlt8&&)qbDl5Rk@LWerYUFYno%qLrn|sIqxeU;kKlynGxZuv_bOD@mJ$Oz4wW|J#t8`2`JY)(ydLJ=V7|sEZOp#WKccke1r-3YHlB9TpZ@t<{b$(n*w@VC&-6Ylpo2A<4j z!CAw(6Th67#eb2MYFLlT;e8?1(;YOY@JLxfR`y>q_;2d$q$Y3%|MMI5l$o3Yg%Y2f zCkaI9iAwK`;=l^zN@7yqqg;kh`+{EuyNcrT(OE%tx7CTsBk8nJoj!mIM*L!TF%J{9wp{+M|1SFBm zdcCrk1x_}c&ri9K46L2-x@ZZB|6z*!$0T~t_O)Fo4IApzzZrS+a0_JRa9OmxoPm#X z46btvi=ysvjs1r2DNx@Gvb?LG$ne)rD-^cGLgVT&@sXL7l_-?3WTCwzjmKW-LsMpc)4W7*;m>Ag|UQ;{*_pUdvtol=-6TB?Er=v#yCy$H& zV-ijBzb|6dmtT{o#3L4NhtHZE0+AQpKhhOR@E={;jD`cU`1ec7yG^+?c;rB*5jeUH zUOj@55d;Rj?M_ka=Ef2H$g_9Cy*zK!XqwF?F%2^Gqtw3k$wLP8KhO6iveoE0#L*>% zWWig9-SBsWdBO8j6e#80BtLTkJ1*-a887mQ3oYMVQ*O7Q|L^B|ay*d>M}7iFQLFoz zs$0+u;f)OSO;daN^XPTE>xZDF&TC9eR}`(j@RyllaS5cXH3v^M4*?M;ZdnWC8TieS z(KLZ*I&~)L`p<;dDkzDvyn**=C47@qEI+P7#IXCzo=H-^Jf(&Qp9nIHpZf`Eru_G|S5KjCbDv8zU!TPP z(~g<{{j6v)`0u?eZclE$a{}$raCa8Jcnm#QI4i30SqiN@w7g(00D)h$QmLA*+JC?2 zKhFVGWR3b^=aK*1(_1Tj{gK3pCSK9G6qif>-}WHo`qT_Q4`#-%n)m|^TV7mgm zT(OELCX~1{Q&wJLJPmazcbC8@iIe{kPs`9mWQM^7I99`2Px**BKvda|L zK`NW@(dn-YXrZ%J-9(Zk8u{+Fae1x``e?(eTFv_edZ0IYA+J#c_gzlqcTQi2XWSZJ zM1DMujtqVtXg_xxZL4PVbMQEd2HUuDjdv@dC7GHOF(pm7SppXB*{r=DIc-64X zm7=Z__AHz|cSlq4f0!WuF^T>XG#e%%Zu7rdIYg8B{J&TOAI?_hRUIS%myH*D3iUo< zT#R1&^J)}ej*E_bBJKrbt0dR*H}U{iPsh{ORxiPY_e@EjDLp}@u}4AYgETO{n6xT& z_Y=4Y_}_~BYiA>gf04LJpP>ZwRsKZi8 zg4QX(D5~ZaJrM$$da;kcJYB&yPxlG#13_>|&Rbm`8VD@vghEf5JOgxm-|sjo1^|9u zj;IJXerxBXNse2NKZrJW%Lk2|ZYk>%MSqN(|HlTv2+;zzSX_xA&?L zR*?HyU3-(N^kBuGQ%?GcI4HC{d~N&qC(<#-U69462-0|#J5AqGgO@LEUon3_OgM)h8yGv{w=9hYn2U zAvcg%ck!l&-?k7nx%4KtR&pTg>|tlW#}7EUX5RSRJO)~}Y1vORhyhAE#b-5LzX=>U zgDM#vioi6$iPx#4Uk_fD8gK!_N`)U)4UoX$@hYNN7ZMa3 z*XTQGWIzaa%qP;uJc8v^MAd`6ZbD3ECxb2N8Q{k*OoJJ$A;W!5v4yuJ+K8 zW7b;0fQSEs)q@j&IzQq_&zvcEBr4`b9<2(h_LBeV$SZ*6uEmB{4nx4)SGnjdbrIZ7 zj%|44mx~1QrC>nB0+i}eUBQkhgFQX*%16Y*^XkJFbJs~kz~v{mjf2t%y%=GC-or^$@dEHy|=NVAT$8^lzPyiH}Pky7Zt|0KT(_I~%Q~`O4u;A@U8YCo- zq)n+-A6yEPg;AgN0C};^&AnkGAokHg^@nsNLBCE$aQELf!WhD@Epc83Toh#GmiTpm zINYkKBuzB~89md7lrn!1i=4aiQ=yW;Q^HZiCX*es#E(S_Vz?F{Lc zVI3e|2yWW@9|0d%o5PDrO9;BI-_qwQ?}A(GuLU2cc!KzEwWdkz5kMe>aMnvJ9OQ`% z9)$mj2fQYECDYx;;EjQ#q)tFE5D~7FFZvJ%-aftOG$}fcyt-`cr#SuO|LvRcT^Iv#7K4}bYoFI|#60rkp(luTQ?CIcFmkO5I zm<+BgdwozH8z)#7ZU0c&umOLwg&WaWU$8kwNS{61MUZUGtJCZZ0d_;Yz0ze?VByQU z2>n%GKx1k7hLl4TBy%g9{%yViT3SwX22{v{g|d_p!zzF9Y9jgw%~TGEOd{Lb;Cc<3 z%cEN9j(j9A9>{r|ONs^y?Z4%1>>mMYJEsry({I83mp2G92?^k^>75kEMh?(k3klD< z$wn1UR^z##*80txlCw<& z9ZQK1e94}m%d`MjjeY?t!{x>f{y(~|GZ3r)eIrST>{&8GA|tXs=Z@?Y*_qjUWoFBs z*<|lcHf3aQi3%yC&^IHAND;s1?f=F9?epq6=XpNo+}CwqgTD~_TB|&2Et&!WSKl)c z2zmqWqUHWNVLUi_K3w9uqzUJallEtYJmD&xBhBv>3-H`cmL*S31e#o@y@kdTy` zWh`C?;zWk>9XmOUxttW$a@JvgPDK(Zd%VKT!--OzzRCgjL%)p+zC7U5Q*Nt$ zu^f%5ec&XHAp}QP`7MR^J#3d%?yq%X0V<@?IJFhT0~y{YlJkXZkfv6#R&j$6guOg8 z!WJTG4KBJqipmxYGHz&O_B zIqxC|I(Tz_L0SvQceVYfxm63IZShR?_}O7@IHvigrvmtB%$1i>u3!PZf$44i*C8b| zAe!7~3p*vo!e9JK4ySl~Vj}m)A7-iu(q^};fb{O`=!fqEkxHhy;s|pBoSOOl-`jis zaI+~R-{)}>$c?q;P3R@USr_Ajb&FF1NZb6<90Mspu^R)_n$Xe1Q`SW}$aLO80`uSA?1ILR+%9|eWa*FlC z^Sux#s;)dF&Z>r!o$(#V)nZ_m?PQ`-(?Og5-}Ex0EWp6$xQItM8MgT8l#4|PASvhd z%*JXcd=T1-dgAy5h)^UVK8%7e(@BB9N&ZkM-YO8vYzJe?-2v(6li>YA;Tf-!M9{7B z5W$KE;h~Vq-0RjVuy?l-b`fqvV?k@)#i<@}X8#P^VC{V{I8Aol__-4t-80pko^S!N zzHS8v(oDceJfx7*RWKUq(tmKv5;S+ws(pJ5JlG&{v|IskGEM_QoVvQdJVTi((l8Hx{qA)MNiQEsobhZ zY6r!qm8KA$3oI@Cw|+fW9=J#6SHp&aAoXs_&-2q(@LzMPC|7Jb$jJQsIdeG{ys4JU zw1zrS^Y?EV+X;yg;ZGJ+MeCr0>lI8MMVFEbPpCdl|K@1laEOm{GE=t+kl+@`%)O} z7l};;JQc52c!VvY+GJXbKEw`H$A4++vFPhhYq{TF087$1FMi!AtmsE-OHA^6^qYc< z1H+22uldh-Z086t-tPh?6jwRn>dPb=mL7JP?tfj%dq@O&6P!Q3dQBmtQ%ui{-S)8T zTRucoSFSM*z!-4emzhJYm;~C!pwy51sC-^ zn63nYAyRNF&m4M-^aRM(34q&_S8_0)6?_KthHbpVQN6&&|3qfzvFT-cC;n7UP=9}; z({%h8GoI3n@V*s``IqM~XFkK}@jj_Oz?Yzg#npwRn_ozPRqxE9bxH!3)b4!W*i#n# z3*Op!Y?y%C_qnz3LUSl#;*;yEQGn5eBFSd&hbV`#vz&e^dBn<8#=qoFFp zteQC+ENTX^yod3l=H5S08nq^)DtRK7cUJEj<6=G5*c7I0EL@I-Xa}15-i<(0lT_9^ zYWF+EwU}DY0tYPdxh>rG=Am*L5ah=701rSd%uPsW&2c>LN|p^INlP zMHdP&KT(P{-NGhJ^&MNn-fSt_Rj3u9{RK0_ox~J)Mr^9Gaa4sgJ)GYs{f-9}8$k(*!aGo{ zJi}jS>V+zcIH^LTQlOBMQLMK;9WedQGX_JCpd}&J^4QoL(gPRyZFMZ5eGd@^9? zIH=`AWTe=M|pxQk&TRW>mU z-PkR?q?vzrr?BmF6Ln1+4B)S7>1FLV22mxL|KqDS{;*KH>#(Biv)E4 zMMP<$Li_ZSf1@KzeT;cl z7GD}jT*G#q6UjT8cd)Shq|9xVeT-a?q-KNQKQvCJeXdxi6sezyQHYB9i*a3}vKer& zKzZqbV0vZ&>9i*xq60dR>Q1GbC@;j?R-5S!z3BiL%|){9-XdZTynS};GIRwhYU$Pg z#yW{!k7$yRz-!wcov)sw^%ux~(nmc=&IFNJ=x--H z8A9QAZp?_9ZY}V)L*6rO;W%*h`0zoJ0N(||B<}5;!d0Ot@-ZY`i%IEYfLy?HY;ggkJ~IQ^qY_RXm}bEOw(Fv6!LM7#+-8MK_@ z`{;#&Ma=pJ6td8$&*ZQU(Gcph*oc{%?nh1ZnHSr9Lr`M*xYdIgNpw|={h9dsrj)r< zJ#qHsZp0^$#;3Mgk0gUPkX-fp)UfCiN4O6R}y>_V& z9aGR3yB*XazgHxSKh^tCirihIO7ab*W9`y} z|LRaT+w;t(>Lz4%r^jopOB4;$oUn9xm7u)T&MZyM4s@zS_uS=BO(er~EBWdDI<(G` zoi#yHiKIC1{QfypfXI`WtF>b@NYwVNcnPY5f2zQA`g=62y&yq=i{BPLDyv`%bK6aRJJvj6F(U%Y*IoFfP$x zVt7gVb6Mz79W;?Ev{_%xhwUf5G80r6(Ji7&k9RDqKv|ey`sasQG;uR}|A;Ri$OJ~H zHLpZNcVW)9)MgfvW=Q$gj!gGP&n`^nrHWM9v&WgQx^9_3Ve$d=bzXp3| zPrftU+J{zaOUT$sihx~zr|>+c4(d%ei^6kj(Y6AYwR^q;5MEW`aQvYU^86GImAt|5 zp7(noxv49>e?;t?P*Mi|4jPIHZMn!&;LW7icpTi?^3 z8#bD;AV^wT1*ZmcCi33ZLc!w0*5w*6@KoK5NNmjqtI`VkbA)~{=-V+%UY`IRdX6QZ zR6XE__3$-Qxo+&S2-lmx!AZ0mYpN}*Tb{F%R1Rvs9 zKrw6ULGnyk_6yn`)y@R*DgPUiI!U0PR!l;}6b-*$`lPzQvH>iRdW!BK0uKI*!-YY% zBdQ7&3U4Sf<7>?suM(*p~!27+P#Q zm@$CT;c=FJ|0xvr<-_&&yN^KHDI&f>V-b6->*;N>6$NsCuie}|@B@B_?Vj1sEof)Q z$3pyb7>Fu}84`~epraI>9`WiZh=~3n_n_Gg)Y|`Rb|}<={h8g|>1BRMq#q|cW9kJ< z<|nFA<$cKRc4MY1!?BbzZBziChZi>BDj&7|&khMrL|c1gJcctDaT9&4Oc7O%>t`2!WmM+Cnm`0B8&` zi`MG*f!`k?&qB%)+AodInZ(-SRLds`ta+jk<^O}IEBG=jJ8KkIoHvKd>_t;98=O#l zU}SA@)gO#&vZilmg+r{>QTV3={B8#uN! zhGG(_-!ySSFlqkM^dQI^_@|#Nb${T4FE_u=(jT}3vGp9G%{>oz<>GxMs>cDY6%W=6 z?%-OuX4lAA6;$n9-G>di394S$oG4+;{xi_VNHL@ zZE+EpJSIoqw zbN#w;y6Ff?AAfd}apej4E8Ik%`HnE7PN5%3!uf!{Tic76Cxeor6xp$Kh;9e%1>EisFpx~^(EZOAONNZ zf1X~ij0OpkcLzVq%a+T<$yoZ!uw5d>JfP|E8_k){fsh3v{s%uDL8-@kkaIi% zB+9;-dMjJPv;K?CZjFJkvhiZ@pw|upB;=ymkElTMb}gdDQGTRr8&k6H2q1>(5x!4) zGRO$&#*3kBsFaQrf6+_X0lA0us=7r)H|g9$QIVCw+Do zB>ste9`egUIa$eU0Ws-2}?>~Jxg3D0aoAQF~ zIuopfSV*zDa6(hS#DIFIBm}MptW_#kBS$$VCG+ZBqM>>W;Q&=ePaXTPOYp#x zE3n}9J-8zEWxbu<9br#$BfQl3AScsYrTDoxTf@WZbn`!3V- zXAno_N+biP5csI>gz<7Mp!K_7w5VNi)*+>KhA+#?;MsCN7vClo>mz4sv2PB;`dyay zc5IihD6cf)`gm2a$@}Be_~;UheCrjQm=OoX4+qy1aq@IRCz9fU!#zxiWS5vtMjQy? zrTU4gIFtv++i58aLTL2UJbe`&Aion+up~_Z%B=o(5)wEe>lSmp=t?&_yKW~kb~uIt zkK(@Pe)7UZo%lXY?(jg#vCl^Lb9U&|F^1PA6SW9dFrXQXJ)c)#WJ2yrH`*yy+{>=3vYM1C7t633fD|yd^ zzE`3=ZNyd{dkr#f=|8svcEH=Z&fG#s1cLlKxrWMVSkF{U4385RIC8HR7~IJ~ndUFU zo(Cl%$Da-7V$0buM+NgFpWD?)1pl&%iO)rd&n?ls8}5qPQW~(IukAuKH&!lPDSCrx z(4IE*(qM$ka{d;dv?xJQf68jay$LJB`@$W_Bm#dg+E{yh4M5!5DOIyT2NXAQKmPoL z2Xgq+9w~+tuq1&;6jo`3G3h+~?RQ%OP9KK}*|vy+eEQ_b6*m!3DV{$av3Lcjjr}g= zhtY!mRvbfq0s~C2zLA*ZD8OQmYNHi7GqI_n{r_sO&SSO`e+kuHqVn1~$e|NpSHCR? zihfd;f6ir`7S z_>KLVV2D)@!BPGt>#n4FX^7t4E2=<$1mS;CK9l^;52I||3BK}|7PKSu%Zeo)L%N39 zG->Y#EU)A0@Ux90ow%LbkA74C>(Z*SgL zKLKbuDeznP^Rdf{^P%}xo#;Zqr#t;D6p-eUNB3n$9~@Y9uBDN=05PADiDCKS;9``iHA>C$}lAsO^uW>vCthF}$SjVo0-pD{GlzOQP; z4}oh=A)6x+Aje^n$@jt@Sc;vyB^qKtIbh~Ho=+HXHQs#Roi7eL+Jja+QIEmSx&AfY zg)Ei_JmI4kkAA&udph5nH+hB1{^Vg66T%g#CG%HPX0{Kq38D0I_fKJ}V zJjkN0NAzLwVhLuRa4s(FB=$ui@Cp(b8>a7JQjZS%#BO#2KMT*_M#EUBf2;eiI5`J7 zegTgqg_NUeigC59 z-9|*f_wOk5s14ik?Tg<#GlXVx{{{TrtOlQ|%iYJ@Dv%pt{;{7T8Hs##N&S%L0oqIW zMyGQF;KlGTYtupkyu)pCF5hcc{+n#tbnwt_;T?bop1EkG(7!X(v|3GG!f?@#(Gz%`+Gbm(`s!3P2G9xG^O{*wsVYpcq1+Z?d7_BBxSSv73&Ft5{% zHUqw2Pf8akx^zYh*1W3pnXHB(<)jzypC<199vTnBDpm zq7{^gn+rSeNqwInTLGD>JI!_|!9U-j(2N%T-H&)tcrFd3+I+7x<}hJ`wc$KeIYsE+ zmFbzE7jIyn)qZVO?48DhnTOwYx+NiB%3s&dRj^@PUDf%((2pkaR8ITP2w`f9@xB6C zycpp#mOHmSn~>uVsTlVr0qi=#`A;m>i71hr9gp&b0LJK95|KJEhmI2HnWt+H(WcVd z-=-Gt5nm)(_)ptQnDs{|O3&}X$o`{#1-3YjYhiYHW%=F(B?lVSj43rDm|wpp*lCWE z5=!wuHz%O>IufGwt|@f6x@hE%)h^n+E7tes3Nx0>uNOut#)0@wT{88UYDF`}WPYb3 zNwGI-B%{JkAxP5mQvicHIabpwwa)$XGB&PmZ7DW*8l!vihOnUohYzK8XN>oSFg%g! ze>UD7=&WM`hyD;RHr(_~m*O)k)*gRL?TPPs4F6l9&(joY?9w^y+7GpC7&rfiCm)HE zkYUcBKhF{mP}a^PH@v0++0m|cBZpfbQbCDF=}3ny8gq%X9BF4=imDb4Yvajop|%F069hs zA0Mx%K>s4vEUL>(AWefkH5rWDB|nFmEQl67u-it4x+WEAK4h5vT;}Vj{%&+U*)1Mo zm4zxt+2$#o#8K-{+l~3Fv{>^I1+7beByfmt;{QvY#jRpQ%vtZ1z>-gDwY|4H9DY~e z-c;~I1Y!k|CXMm%qGQXkrE?GazFy?Z;*}2%6`t-C;;3C$+pbPk)@)Q*M!eLroe9*{ zUpRN%n~;J@|M#HOWKgZMsH;{822!rfprccc;5aQ8Gjme`N?C(t5BQ%z6eC*Dl6{PV zO+1-Ao`$2@PT4o6cU`c8CF-i$one&q&Ww=zUIsW5u0AmrB!f1Z-)>^kRjA{#s$)Ww zI>^Y12PNk_!J&xv`^&gkoaR99xRXKzOer!4NkW+*AI76qaJ2$4oz*aipALdWMuULA zGH!4oT0-f#z#YEkSX)+f)?sHqB)`3f=YZ0+Uw3ZGN5B@#m8_V#1bCj) z+Md+v1^cevB9V`RV0YTrHvGq3c;a;}`IastR41JA#4GlOJo4+&9~Wq$RB>zVd}tCd zHyocf#!1D)UZ29>JnX~x$@sR7yq2)q$F~N>VZED|CFwY{hN-KbJMF-|7OCV#)Q$^eqyj-i(1-J!99+^8JKjW2ma`Kj#f%dgcnIlq06GvJomGy^k*}wI%ab5 zqg7`BCxx@2Dx4bs{S_l>*-+DB zk^pa2EbHcaIqa#%s}lY2fxwo%G>iNK_;z99-9MrX;1t(9>Y~tunqz`6l6ScGmfwtv z2xS`VUX6HZFB1{)7Y5v#hcJ9KP zu~*pT8Hqv^58TEK=1UQWZm~^!`vBTjzG}!~UWh9DB)({$nM90Q_wlQA<OLz6Pb8xP;O3GG>LB#N~!o!7ybYzc~j2*{B9;0u^+$B zZ|ZuA+WOu*zLOnB+B_Fr^;9NNVEWwmg!F6ZRsMCdh>PP$$M+q7bWShY!;<-y^Vtv; zf6za^^kCG!^^&3ITP`B~JxQ|p;SPF1;}xe&_z2x?E56kGbP6r)YxkNQ)S&r&XG1ZK zM3fcVevT7&9YJShhav)-kvWzBmn>=#bQ4eQTN1qkx;3P;r+>B){Wc1u@gg5V8tv7_ zEdwnmsAJXXW5`QH`MTleDETYIV}7C@Xa5TAT2`1WFTX;s-#X#KeC-F81l_7 zKmr%e9)x~fF|WQf`Q+ZZNi^4@@CV zQQN&pb6RX-Nh1)Y2PP#1?(3qTU6sC}M>rmxCrMV2>>1j-lo6y6`x^00zIS@mW(rtG z_@?sDUhKG@MLBRg0F+iOFNHA6LG5E)#WG<#;@q8@{qe~Pa<5jFDQ}Ep%J;HWPj!0% z)K8`xCAfgHQnNqR%{Juy&Zp!hyE{afo#r9;8$@4h_T-OLa1k=rBQ#ZdW^nTBM(_C+ zIjD)h`k3T`B;2}%GtFmNLbV0`O`xej1Q)jR0i2 zZ)O9XC88;3NKZqx#PWVk;uK1DpOZFdzYD{GLCXBx1(@3&ZH=6&0_X-v>XA$e;c$q_ z6}tAv!2OreJ2-wE{U}|Rh*eRCocu=X#$sDYp^GVOW>5v=grKXJYQ7_#F@JMBL1&O9l)>(X0>G z2vhqP?BkFY@6;V_h<~H`??#X-9QkG1zjU9*R!rQrQcvQ6@v>|}hJqfL^zAhYAM#8Us6B%YK2o8uMTa-VvAlkE(_s<@MLJ_lZ$Iskq z^f|0%c;uxg;02Gd7)YDKKUU|w{vK@*xpYd}(82(6Egg5mpL)Wr$vYR*?8Z>{ar=m9f<~dN-de=yDR_;q3&)dwE=Zq$@(`qX zEy7qo8^ha_!036>Lv&g0*Pp+S!ol`l*LE2cWvET3jnTn5^_S( zVbJ?tUSy?e1>*{L-%bvFh53vw>pcl%0l&>E`59*1_xwF~Y!GY+q1i*FL@|%xWkHWz z^E)q?3goyNYbOZo$-|tZ6S(<+H$yO=(;fJ$$(Igp+JkVf%0Az}JAyHaw92>hYx>Fwsk!L@B{$_ugc9O%t*`*$L9j??Wn&%$+z7i?N6M`6{(3G7wsC z=Xc9h6n>FcWsBV{MLNfib0q(%fwOT}X@&42%F;Nd&Gx(qBIcT0-ADz#@s}3;vvY^4 zLsI9JXQimx_eURzu{`|adG##X(;Rx{`Ymn^%0f%=GG^X-1*<7(pfG%F10$#DoRviF zpnJgc-RYki;J=-|!cSrXg2H^P=W){78#X(uA!Vw-eK(`dQAz|Hgnxc^Iyu1fo`>=u ze3pR{6<1R~mecU%P`8u@cTR)aT>Ade*h2x6Lr;6LV*?Z2Zz_ysj9-I#rxkw;?Kj2*#vUokN1HeMKZo?x(}06 zv7)_t>cE-ISU1M13>TLr{eFmEgK$%Ax!p*4-0v6Ka(5^l-Mws}&+n#=j;(LiyCF)j z+>dP|^u7bEZ(LH&ocDr~CLI!C;`f-d5=+R`N8H@`G1=wOc}=*Gwv)!y(Sz#0d0gk+ z@P}XL@_c^1Ucr{N$i7kbJ%Ra~6ZM}`!r;*sS>B-bAR^Qqzua&i$E*MM!?{wT6WQbJ zx8>pqpea#m{YJqHuBf!E)s5-{)xx}tVxKw$zwj97V)cUxnX}IfJ6(~&y#h)4fNC`7 zn@sn2?-dsRGElojq8#Dgh_3WFsfPmI0*U3U9&Fd0qJBz0g4RVjjWtW$Kp^SAPEyGd zEZ2p);)@*{9FiYUY^pl|{>R9nAj@Pp5tgm=<_JL-pSUe4cbkE^^6k)_tq>@={50)y zggLlB2^{q>aKJbtqc&6ShJ(RZ-lDCXDEK3Yr+v202V!HSn1al4bKRZuxF6_g|B>O3K$m`TWv?jhvOdU{?8wt;P>=|7KX@4#DoVi!&^ z3&1b`J1(#`j_|)`U66_!LsoYSNIyR1g2t)%!=y0>m~$Sb_ES%Tqikli=fnG$hm2QY z)K&xh3>PAM6&eWHM@5vh-%F5;?Bd#yd z%R}ave<7=*2h!J;(WrGZhm#ApLqjR=gO)7sIt}$>7_dFHp^b3+#*^2hKjkR|VWHAFSa z8Z@YRz$YIzn*Q+|nBiqBPiyuCE;8#{3$7=)=(yT^wNDS>lV`tz>BT(EWQOIL?s_Z) zkF&(G-+hOf9sZm$Gb;o!{Wlpp;}ziWv5lI!f(*$0u!OPNU)Y1scZw*3WuQp-d*4Ur zA|U5^*~tGV2-nW8WO(O70qisHE?-^D!tGbGLq=b!gZ;VDQww70uoT7f?5uY>;2SZ8 z2Dv6c){DZzOArAGN0d2|aTcJZt-(K78iuo+ST~mVu1yD_@g~*xT`0H(wsO6}kXRVQ1p6KhiLBvM!CzgMR)f(3WAHIa`r`y>dbcb+V5qKN}iB%79#c)%OBK!Mq#5irWG;w^>F7AprEBS5 zs}4rR43Eh?76Q@Pzi%%qIW;1+nd45=x=BR9E1h_Ft{r7@CmV$iDj-F_MX|Fe5YY~< zou9+azvgsdnSN~2D4IKskDLr284&5Vd?BeuGeJFFGn8Ry{5tol@f3!dDRt87^AnL* z7`aXq={@Ajw7$!JUl?_HJc}CVk4LYUy-en=v>;JytJ|+g>(Oyrb?}EtPc#iRYwWp` zXhM!63y-iCo!fNoa^aIk{o>N%`Z;~b!SLJCUq(-~!F%O#j9Ve9u*mIs-0g%~1<$W< zKS)D9pRXxJXy7blc*C}1EScB=Vf9YN7bg&$dbR$S90R?tqbuFaQ>gRdD(}M@U9gKk z#~Bp&0<%nxcBHvt1MT9;m43Xk@L*kT^St#N)GX&>M(At~XFl;tU0Lr(^4CWVISF*2 zlm6ajQ;QNj^vkPnlNN=!H)S@ewA&cVfJ2~AoDPWMO$gjQPl=vwHq8hOSRy5>x70IF zB(a^1G^&D=MpQ9}YGg{yL5%frc^z2?QvAwfRr_EJ9kH{Q27Ja@5&6@Vt`o_CAW2Vs zE~_k@b-N$y-1`c%dE)(qSV9MMUijr~n0cb-Pj8T)Takx_-YeIh%yUD`-0~?OZGeF7 zzlEo+6=M9q`KOAAtRbVclD8aSDSiikL(oT;jBo|+O`s0 zBg!{?X|;#Ruzg^qy*G%_(r#B>W&&u;mGlxUPsNBwnes0@)Q8VR(k902mT*eyhk!hP z2XZM9Yj|Z=kEzXD2s}_b!8nJl&R!GLhmprG8UM4zfLPoKKcd?N&gY*gZO_nyxPqtG z!cov?cE1uL*QQGtEThPgM zI>#k672R%hzTJDi8_9KScM-F8qr3bnqMW$vi0BARlEmqA%Bhz3zl=^{?7wq8Yt-XF z_{#@UUT$5ec^<1Scg`Mhdo`w*RCvIS8Lx5#=L#l&dGtC(W;op4{qoX8#upNPz9Ubt z?M6R*D#4mE1P=5CR&;cF5Oz6@+Qq>S=nK5uCh&0c?27L9r7xNwZKeBCT3!Pe4dWx( zRq760_V|0Jyi?KrkF|+ho?~b}_E~UBt`GJ{CUf%YgKp$ctT|NTiri29J_h6qa6H* zO`cayj=&P$P0DGA9ofU8S<)+;`-X5Kh5qs>T|bPC&~FD{6sKP+|6`>+5(WgGc@s+u zGVtZfR7Itn7tW1rRr^*^6D-N!-@IXJ1u7o(^`{QCfa>*{jQgDqEV+7S>ikVhn7+1h zt=S_1n_E8HDzk@s?#CHz$25jOXV$+wOmG9^>$f%k^lupRe!#kp6UKnN1ZybguMp_{ z{?YDkmmch!dv(65@PQqV!^(x99?;~F7^LfV4Qf>#{b>1Jan_vui~qD-VX8ZuE`%7T zLo@tTA0T1|FCRsDv*pSGv3L9L9bywOAd^uL8?!<`2tQdg%QhgHgMT({BJ0?dp>xa3 z)D|FUJ6X2bB8n+JyzsPZt{62rvv8j&SH~Eh{Uo5t?naXT%}MbIzd{~?QxLI?Fewe; z8-pt)h$ykSqN+g!OFXA)-I*(gwPT}3&U^^@3%?N7Fj2<1hAZ2`>nIT?Lvu^!h%y%Y zJ%{-ovj`@!l}q15$cUx*zbkyiD~u_3uz#U@C5a84Fb{@bZbXx(*gR?LSrJRhAt$Rw zH42bD`ocOLjKeP%T*ZzuP}NdbvaQ8yguikvd$Ft^EyW!h8BU2}6`{uU-o2KHxNbGh zxxECPJ@BT{j2uJw_@i5Agw(LPjz0^3I$DuO)^|fqZZ7OQ&yxHZ>=uS(FFYr#WW$n} z$@zFiS`oj$irn346|8||`o)UvA+r8>_tM!BB}}b^v9y*)3gfQP4_VB-iaogUJYcQh z8uprrqpz^`A~r8TCL$$th%Rj18BQ^-K^?@BTql;TD2Bmy+5hAgHu1YSInz@KV>9Wk z3C!(48shERymO1Oz2{rD^Hc|p6Ge-PESfMM;ZL6|e_Da;_w!>X_yX{+ zu1LcDTBy`lPn|#Kc1$5k+?$4X44W1$!BMY>N$Su}_T_v~xU9z&KiFt^yf>SArn#Zrf*&T6HsdL5AP1(G+TQHBcxu zWd2s2fiPOk*zBwva6T_hUZ4GfP31YEkk<$XiR3+XCq%KQ6dd@A0ak#E=`W7EYY9^M zv=qgw`jE7z$h7ue2dqTBws;KXVENgHgpN%`pwvnDM$0mQtrtEDqW&<4bVDWGe%=&; z_*B7rPW|y%;_`q{e!L!h5~)%RV8hMj7x~;j-Reg>*V|bSb{eq4F&l@Z{D0Vr2bJBO zB~AEZ(W)iRh9D}Bclz9%F^JwUve3q~an=k{6Cs?X$zgN-uT79TFwuz(sNB(jZ!w|j zT$Re8W$?$cvfm7 zv_??*l>+=ay6h5(uK@aIJ#X+msKXd}CzM;F%wRgKE2xW}2+q-o88A|%qN3PxRx#eY zVA?JhzuB0HjS17!^Dr9$wP2Kh{iYTyhuXK7FQ*{o2z(~jEIr^H=T7N=(uBUomkv0W z8^SxvR_~lxIgnTK-W8|60#;LfhBBw=q4@jVwgVy+_>-5givN5B-Q~R9+Wj^N*>TLX zi_dyt_NeXT&r}~0bP0H7Iz5Nc$fa0txllmHL>!AvdJu|Pw}`FAS$b4nE>`%xY{P0T zD*L*_r!W!8f3XQ&Y%md8(8XM50-PF@W99k{h`^K#-(iXYdY#-x=nI$-8pO|Z7a3~E+X z-5*UpV;3&2<&Y^Uz=2;zm@T~`hz#rUu3Jk3^)EbzT!$M#bY5N>&z}|+ECr69=?lWj zRQvXZ{Tp;%Wx^*gv;wsg@$yKi{=lrvm;L7g0DzT`=ayY5EDS`iGN}^4%2kv^25&fUQ{fhe1k}vT`jtJ8zG^HJS}fi3GQw+ zUHN?H9y%w}%DXJ>2A-wE>L&NyfbZYtx^8VU&@1v*moj=n*=Yk`MS&Oa@+L8T_oF6s z()Hohg~e=WU2Y#L!q0-EJnA;Qnk0z#$fvkX-i)=W|8ctdvJGbFZeOIBZ^xbQs_hbu zC$M?_*oisf8JIY5H+qo8!{ro1h0Kv0K!)Ys^cVmYuz)w zEDTU_8He$=>w)R7<#T6(HZX5V9V|Thh2h_OR5hD;j1?+Xur1@F;H#8}F5=-5lLo2C zU#r$70wY7(#aGt#aPwg4m#t?ltRMb2tK(!2wPL&%FMKY8uX0axJnhP%Z6SCvCp;el zBFyN6=hH##Zqc~H1s_;7?)EsXkqSD}mLmObil@8>_}7J5k0Z@o(Dv2u@2|1&P)cqN5m8eh@ALS}zTL zt#I?gnk-{)8234N&7$%(KJYh8?VWxk1i0OX7IDyRME$kjN=N<@ypCFX zLqj}`*;!nC!i@9#sHvJw;XPi(EXC&;NU$!MPxZ;$~V_(eGf|HHu9)d?XfBep*{ld;CKb^X7DF&qfeW%F@W{0@nPydUe z|Au7=P=-?zUWKU=vfBnN?7*1ZLuAm8Gt3U8Im){+!;>+Rg=NrRHGht`&k)sqv;u0+yJ+q%12lgBs|D z-BNUPq=$)8PNyE)Y*cC#3+MfBzz7!4v6o(iB{!sxjWjDl!Vqs#-69Xv2s4cwrKKRj zr+aIDuVkUjrpj7g#{!MD@ApwHAjl3-v8cN(42iV7om)#Z&=JSfQQp&mH5_}=zQy6e z?k4$bmz)RD`@}k_EwM&)i$i+6w}KASv|bE07aT{Ofd;M=Pp*K5?+-f$IX%=8WM*g< zZ;9v^`2SbenMYIIwSAmI3gt$n9A%bd3MqcS%UnX4=ebNFLkOWvp$v6!icH7BF&@X1 z%B(o12$jqvbQ^A>ObPE<@4ITf&wAGV=U(gDYhC+Vd;hWb{(e8#YFeoQTAZ?aX1<#r z=Jb3nw;U3HU^$=gxNDW@4ap^TMGGZR+o9)kJsgKbYW`CwkthT{lD9U$#H^r7bZ-t_ zZsZ1Qj6}+4$3+y3BKee3F2l(ZQ2`6COE6)6X<}Vg3991D+8#8VhbyF;8}U+tpv&ta zIK3tWyKR5B2obB%iP?=qjo4YlPT17EX8(8e^h=WO_74R#H(O~`N&g)1A4nG!%U6Rr zr^lAfzJbW*h0}$SIuU532AjzHZ)2#TfzWP~xH?qrq$C+9a6$5edt5{8ijb+Ry}&4U z9u6>AiWitKq2-jbwkjBD_*u(rR@@>DK5<=1Z0x7O(Z-k@dz~McD9bMwu#B)iAh(g^ z$pdEwLT3c%dJqj~l3e*MTh2KRO8Yh)2NK~Ut^!{pr2__J{LtMuR=)&90 z4=__vj;!>>ZWJ^bz_x^&t!I5TlKgper}L62?6V3O&vsD(Q973S#(M(r{(byImR>fv zU}sceqoEFiUITN|nzhK#yF^7U;T**6$qZLx&~tQ2d35&O!CvH1JVVU!ND_L7;1q~k zI199|cDAr}j}berGPbK8%5d<0$`>J?O5_3OD>9*`9{o5Zh5H&!{V(FC;4~90L0?-) zz2ZY1!kmy_m%@Jzq+NDx9<*J7^KaL?GBtzk6H^vXl1+dt ztC4#-Rtq+q)Q5kDXux{7xi!yZB^teIl-kmD4r*-0-4Chuqc3(cPn7Zbpo?LQDc2Rg zp}~jR7HZcfQ9I-Th2(ezW|Zz5wKy08pM2?7@>f<6S5^;-|3%dc&wIZZvdl);yJzmu zrRzhWoeZ)(!vF>>IVl`CUHHYBVu*uF%Lvl;K7eDuR!E^e(A}RS=*@f zhMcYeSq2ObI=Ut4JOtfY0}qjaB~<5(#CUT75eSXuV_#FPsrn|y^1(|DNMX3AwJ=~o z)9dF&qQMLrFvoW5c5D`uR`lRIic+8|B4={@emR0Io*mF(%!G-3CQM|(8icdycF-mfAj;dA`V~BaRKXUWq5emR5ryf^MnO3e-1n2o zMJosudN=Xnz@i>f(KNopc;27dx{##i);5OfG!-{W8c^TyED!Fry%PdI9@JQ>(pkYy zPur9N#sNCJKaMB&U_iSL?br0l2OE9!@GcfSQq=K-d+Vqh2+U?Win`)}?H}^Bynx%l z>@pcTQQCy+&IXn2vc*BCNP(>T`$QmRNqP6&dIpJl0}`q|Sm24YXKhXnfrQP5W%lY& zsJJE3{n}Rw^cxvE&l;-(hsF)Bdv3;X!U_|oZ>I)&W9>;SY)L@W4!v;mRR(OvXz}*O zm!ql;dX(!|S5Wrb7KSMvvM|~yJWenB7{Zu*cvhx-;A?3AH-ddK^a{&$FBJzv$f@t= z6o;fhVIPK=(i8)_itB<=N>qLBvliabXW`IUeWxn3BM_2fZDX zS6vvIhR9sJ=+;Z1Ack!;7TfcE=*fmJo1*lgQ2dI6{`OfMoKH|ZpyjZF+Ne{TmOLs4 z@63{{H^cxKq?pdCvR5Nh(_}pPuT;2OTB7xZo)NO1tXnI(6+`2`(s|BX1ZZCJR$VG= zMEL2ys$Hl4pG;pr6wWK#hWyQK94K<85I&g69O}|bfTK)iQ4CZcVM$z)N~muj48PdB z;+vNOdqj3;%yxb` z2}dGKgGRKofUl53%g~+=497k9NtT`gvkJ;-`L(ZT$%uoE-^O{6H8hiYs$B@0-e%Q1 zB|(5O$mg83B>kqvDB*h(QpfNeO|oKDZ4Z74q90%Ux=(!vOG|5+m3btC^b0|f7+~!o&{>qtD>w^YcC8%D_0K@e6JRJcxEA?^Se5#2hNDj`X$XpK z*+|-ToqguF@}Vz&WF#b$3;Y5(N2roAbB>1rz{J%t~?k^Hc;!GXO`Yu~a9@d$9#v7}Q=p%oFxH3P{_#DKz%kXjWW| zeJ!=6YNkQGfsRHw{1m_)dS8RV@~c7ryq zPLGD@EwnGy-22!5N8si6eyu`j6b;^1#m2`G;Z=-O*)+BkTH5qvhM0TMG4?A67ikrx z|3dl_8?OP$RlmBO%xDNDb~;F5J|#tit>$SlLR)en)<s?fP;q5}J5tVc zn~orQV)-AX%GaR3P^ny2Q;M8s;9M~HNP%@j3E{%&4!D~8;MU#!Yt*~y-24q+FZ9tR z3lW})B#1`03bz7Y0Q4AT&JE)rW$}rY-miZ6&gQmTn-c@(l}>rwfs?SCdD?(kUmo_P zl=BX|2ZP-j@5aN@IOyKrIC-}65(M_96ZOl;kjYa->@{x&S^f!c;)$Q=ns%g%11HJK zP}@%UbX}nvq7-m0Y8w=|vu9fT$m$Zj+?&3jDOgJNUM+i=R8pvWA@N=QJf4d4TF)X4(iIRmiIE?cH-*P;OE(=? z?ol1_B(sRmPhf1UuuG;q6fmoHdE-Tz(A%#j{-GKRP4~nE`CmT=BdMp{Psgxu#j*D1 zQyC+;tJ>$I=Hv@u93y)u-IG+sIv1^#vKRFJDEZY;bQ7Y`kl?d&691AN&wn$5v1hNQ z&EX^9h^Eqzhqq(EK%-33&EZYVpLs_UT~~i*>p*L7^5O-bXeisg)O%uz6Lx7; ztLXXa`kO}z>q(9nOo<3_!&Z}h|Y^1nnYMDQV4NoBf^r^ zjBnOds6E|4V`XA0s%~DwuoYWDO*5?8Os+8*J$3Hbbd+dwL6{W18y;e-e$v zRG1VKo1l(oyQgD;2V6IsUVlE;2VucZi>hiJf8vb$NTzKn@BWN~*}Ts>i+zBLaepPM zJJdqUq5JDEeKKKVQO%IX4hw->vHVWHjep{Q7j&FsNu+Y5{|_U$H*s*_c3~dKaGT^i zmiqsR&rb=H8~srVcV36yUe%y#yTa&_bJF6WSc)jP+lm8*@a@18{)2zwGq09c(K-^~ zvhj+~Km`Rp?4k7;3ZyBe; + + racecar_learning + 0.1.0 + The traj_tracking_ros package + + Zixu Zhang + BSD + + Zixu Zhang + + + catkin + + rospy + std_msgs + racecar_msgs + dynamic_reconfigure + nav_msgs + \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/readme.md b/ROS_Core/src/Labs/Lab4/readme.md new file mode 100644 index 0000000..7c20a80 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/readme.md @@ -0,0 +1,73 @@ +# Lab 4: Behavior Cloning +In this lab, we will use a basic behavior cloning algorithm to train a model to drive the truck. + + +**Make sure that your repo is up-to-dated** +# Setup Environment +## 1. Open a new terminal and SSH into your robot +``` +ssh nvidia@ +``` +## 2. Activate *ros_base* environment on your robot +``` +conda activate ros_base +``` +## 3. Install Pytorch +``` +pip3 install torch +``` + +# Launch Learning Node +## Open **three** new terminals and let's call them *T1*, *T2*, and *T3* +### 1. In *T1*, SSH into your robot and launch SLAM +``` +ssh nvidia@ +cd ~/StartUp +./start_ros.sh +``` +### 2. In *T2*, navigate to the repo on your PC +``` +cd /ROS_Core +conda activate ros_base +catkin_make +source devel/setup.bash +source network_ros_client.sh +roslaunch racecar_interface visualization.launch enable_routing:=false +``` +### 3. Start the SLAM from RQT +![](./asset/rqt_truck.png) +### 4. In *T3*, SSH into your robot and start learning node +``` +ssh nvidia@ +cd /ROS_Core +conda activate ros_base +catkin_make +source devel/setup.bash +source network_ros_host.sh +roslaunch racecar_learning lab4.launch +``` + +# Start Training Online +## 1. In the RQT, call the service *"learning/start_learn"* from RQT to start training. +## 2. In the RVIZ, use the *"2D Nav Goal"* to set a reference path for the robot +A loop will be generated automatically as your robot's reference path, use your controller to drive the robot along the path. +![](./asset/loop.png) +## 3. In *T3*, you will see the loss be printed out. +You can drive your robot along the reference path for a few loops, then simply let the robot stop on the track and wait the loss to converge. +## 4. Once the loss converges, call the service *"learning/eval"* from RQT to pause the training and evalute the model. +Hit the down button on your controller to start the evaluation. The robot will drive along the reference path. +## 5. If the robot drives well, call the service *"learning/save_model"* from RQT to save the model and call the service *"learning/save_data"* to stop the training. +Your model will be saved in folder ["ROS_Core/Labs/Lab4/models"](./models) on your robot, and the training data will be saved in folder ["ROS_Core/Labs/Lab4/data"](./data) on your robot. +## 6. If you do not like your model, call the service *"learning/start_learn"* again from RQT to resume training again. + +# Traning Offline +With data collected from the previous step, we can train the model offline using provided [iPython notebook](./scripts/offline_train.ipynb). You can train this on your own PC, which should be significantly faster than the computer on the robot. + +# Test the Model +You can evaluate the model trained offline by using additional parameter during the launch of the learning node. In *T3*, relaunch the node using +``` +roslaunch racecar_learning lab4.launch model_path:= +``` + +# Task: Train your own behavior cloning policy, test it on the robot and show it to your AIs + diff --git a/ROS_Core/src/Labs/Lab4/scripts/imitation_learn.py b/ROS_Core/src/Labs/Lab4/scripts/imitation_learn.py new file mode 100644 index 0000000..21211dd --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/imitation_learn.py @@ -0,0 +1,430 @@ +#!/usr/bin/env python + +import threading +import rospy +import numpy as np +import os +from datetime import datetime + +from utils import RealtimeBuffer, get_ros_param, RefPath, GeneratePwm +from neural_network import NeuralNetwork + +from racecar_msgs.msg import ServoMsg +from racecar_learning.cfg import controllerConfig +from racecar_routing.srv import Plan, PlanResponse, PlanRequest +from visualization_msgs.msg import MarkerArray + +from dynamic_reconfigure.server import Server +from tf.transformations import euler_from_quaternion +from nav_msgs.msg import Odometry +from nav_msgs.msg import Path as PathMsg # used to display the trajectory on RVIZ +from geometry_msgs.msg import PoseStamped +from std_srvs.srv import Empty, EmptyResponse +import queue +import pickle + +class ImitationLearning(): + ''' + Main class for the Receding Horizon trajectory planner + ''' + def __init__(self): + # Indicate if the planner is used to generate a new trajectory + self.update_lock = threading.Lock() + self.learning_lock = threading.Lock() + + self.learning = None # None for idle, True for learning, False for testing + self.state_action_buffer = queue.Queue() + self.state_vec = [] + self.action_vec = [] + + self.latency = 0.0 + self.v_ref = 0 + self.pwm_converter = GeneratePwm() + + # create buffers to handle multi-threading + self.state_buffer = RealtimeBuffer() + self.path_buffer = RealtimeBuffer() + + self.read_parameters() + + self.setup_publisher() + + self.setup_subscriber() + + self.setup_service() + + self.neural_network = NeuralNetwork(input_size = 4, output_size = 1, + lr=self.lr, + save_dir = os.path.join(self.package_path, 'models'), + load_model=self.model_path, + # load_model = os.path.join(self.package_path, 'models', 'model_example.pt') + ) + + # start planning and control thread + threading.Thread(target=self.control_thread).start() + threading.Thread(target=self.learning_thread).start() + + def read_parameters(self): + ''' + This function reads the parameters from the parameter server + ''' + # Required parameters + self.package_path = rospy.get_param('~package_path') + + # Read ROS topic names to subscribe + self.odom_topic = get_ros_param('~odom_topic', '/slam_pose') + self.path_topic = get_ros_param('~path_topic', '/Routing/Path') + + # Read ROS topic names to publish + self.control_topic = get_ros_param('~control_topic', '/control/servo_control') + + # Read the simulation flag, + # if the flag is true, we are in simulation + # and no need to convert the throttle and steering angle to PWM + self.simulation = get_ros_param('~simulation', True) + self.lr = get_ros_param('~lr', 0.001) + self.model_path = get_ros_param('~model_path', '') + if self.model_path == '': + self.model_path = None + + + def setup_publisher(self): + ''' + This function sets up the publisher for the trajectory + ''' + # Publisher for the control command + self.control_pub = rospy.Publisher(self.control_topic, ServoMsg, queue_size=1) + + self.path_pub = rospy.Publisher(self.path_topic, PathMsg, queue_size=10) + + def setup_subscriber(self): + ''' + This function sets up the subscriber for the odometry and path + ''' + self.pose_sub = rospy.Subscriber(self.odom_topic, Odometry, self.odometry_callback, queue_size=10) + self.path_sub = rospy.Subscriber('/move_base_simple/goal', PoseStamped, self.path_callback, queue_size=1) + + def path_callback(self, goal_msg): + ''' + Plan a new trajectory when a new goal is received + ''' + goal_x = goal_msg.pose.position.x + goal_y = goal_msg.pose.position.y + q = [goal_msg.pose.orientation.x, goal_msg.pose.orientation.y, + goal_msg.pose.orientation.z, goal_msg.pose.orientation.w] + goal_psi = euler_from_quaternion(q)[-1] + goal_pose = [goal_x, goal_y, goal_psi] + + request = PlanRequest(goal_pose, goal_pose) + respond = self.get_ref_path(request) + + path = respond.path + path.header = goal_msg.header + self.path_pub.publish(path) + + # extract the path from the respond + x = [] + y = [] + width_L = [] + width_R = [] + speed_limit = [] + + for waypoint in path.poses: + x.append(waypoint.pose.position.x) + y.append(waypoint.pose.position.y) + width_L.append(waypoint.pose.orientation.x) + width_R.append(waypoint.pose.orientation.y) + speed_limit.append(waypoint.pose.orientation.z) + + centerline = np.array([x, y]) + + try: + ref_path = RefPath(centerline, width_L, width_R, speed_limit, loop=True) + self.path_buffer.writeFromNonRT(ref_path) + rospy.loginfo('Path received!') + except: + rospy.logwarn('Invalid path received! Move your robot and retry!') + + def setup_service(self): + ''' + Set up ros service + ''' + self.start_srv = rospy.Service('/learning/start_learn', Empty, self.start_learn_cb) + self.stop_srv = rospy.Service('/learning/start_eval', Empty, self.start_eval_cb) + self.stop_srv = rospy.Service('/learning/save_model', Empty, self.save_model_cb) + self.stop_srv = rospy.Service('/learning/save_data', Empty, self.save_data_cb) + + self.dyn_server = Server(controllerConfig, self.reconfigure_callback) + + rospy.wait_for_service('/routing/plan') + self.get_ref_path = rospy.ServiceProxy('/routing/plan', Plan) + + def save_model_cb(self, req): + self.learning_lock.acquire() + self.neural_network.save_model() + self.learning_lock.release() + return EmptyResponse() + + def save_data_cb(self, req): + self.learning_lock.acquire() + filename = "data_" + datetime.now().strftime("%Y%m%d_%H%M%S") + ".pkl" + path = os.path.join(self.package_path, 'data', filename) + with open(path, 'wb') as f: + pickle.dump([self.state_vec, self.action_vec], f) + print(f"Data saved to {path}") + self.learning_lock.release() + return EmptyResponse() + + def start_learn_cb(self, req): + ''' + ros service callback function for start planning + ''' + rospy.loginfo('Start learning!') + self.learning = True + self.state_buffer.reset() + return EmptyResponse() + + def start_eval_cb(self, req): + ''' + ros service callback function for stop planning + ''' + rospy.loginfo('Start Evaluation!') + self.learning = False + return EmptyResponse() + + def reconfigure_callback(self, config, level): + self.update_lock.acquire() + self.latency = config['latency'] + rospy.loginfo(f"Latency Updated to {self.latency} s") + if self.latency < 0.0: + rospy.logwarn(f"Negative latency compensation {self.latency} is not a good idea!") + self.v_ref = config['ref_speed'] + self.update_lock.release() + return config + + def odometry_callback(self, odom_msg): + ''' + Subscriber callback function of the robot pose + ''' + if self.learning: + self.get_state_action_pair(odom_msg) + self.state_buffer.writeFromNonRT(odom_msg) + + def global_to_full_state(self, state_global): + # state_global = [x, y, v, psi, timestamp] + # full_state = [x, y, v, psi, progress, lateral, slope, curvature, d_heading, timestamp] + # transform the state to the local frame + ref_path = self.path_buffer.readFromRT() + + state_local = ref_path.global2local(state_global[:2]) # [progress, lateral, slope, curvature] + + d_heading = np.arctan2(np.sin(state_global[3] - state_local[2] ), np.cos(state_global[3] - state_local[2])) + + full_state = np.array([ + state_global[0], # global x + state_global[1], # global y + state_global[2], # longitudinal velocity + state_global[3], # heading angle + state_local[0], # progress + state_local[1], # lateral displacement + state_local[2], # slope + state_local[3], # curvature + d_heading, # relative heading + state_global[-1] # timestamp + ]) + + return full_state + + def extract_state_odom(self, odom_msg): + ''' + Extract the state from the full state [x, y, v, psi, timestamp] + ''' + t_slam = odom_msg.header.stamp.to_sec() + # get the state from the odometry message + q = [odom_msg.pose.pose.orientation.x, odom_msg.pose.pose.orientation.y, + odom_msg.pose.pose.orientation.z, odom_msg.pose.pose.orientation.w] + # get the heading angle from the quaternion + psi = euler_from_quaternion(q)[-1] + + state_global =np.array([ + odom_msg.pose.pose.position.x, + odom_msg.pose.pose.position.y, + odom_msg.twist.twist.linear.x, + psi, + t_slam + ]) + return state_global + + def get_control(self, state): + if self.path_buffer.readFromRT() is None: + return 0, 0 + + full_state = self.global_to_full_state(state) + + # [x, y, v, psi, progress, lateral, slope, curvature, d_heading, timestamp] + # we interested in local state [v, lateral error, curvature, heading error, ] + local_state = np.array([full_state[2], full_state[5], full_state[-3], full_state[-2]]) + throttle = min((self.v_ref - full_state[2])*4, 5) + steering = self.neural_network.inference_step(local_state)[0] * 0.37 + # print(local_state, steering) + return throttle, steering + + def control_thread(self): + ''' + Main control thread to publish control command + ''' + rate = rospy.Rate(40) + u_queue = queue.Queue() + + # values to keep track of the previous control command + prev_state = None #[x, y, v, psi, time] + prev_u = np.zeros(3) # [accel, steer, t] + + # helper function to compute the next state + def dyn_step(x, u, dt): + dx = np.array([x[2]*np.cos(x[3]), + x[2]*np.sin(x[3]), + u[0], + x[2]*np.tan(u[1]*1.1)/0.257, + 0 + ]) + x_new = x + dx*dt + x_new[2] = max(0, x_new[2]) # do not allow negative velocity + x_new[3] = np.mod(x_new[3] + np.pi, 2 * np.pi) - np.pi + x_new[-1] = u[-1] + return x_new + + while not rospy.is_shutdown(): + + if self.learning is not False: + # not in evaluation mode + rate.sleep() + continue + + # initialize the control command + accel = -5 + steer = 0 + state_cur = None + if self.simulation: + t_act = rospy.get_rostime().to_sec() + else: + self.update_lock.acquire() + t_act = rospy.get_rostime().to_sec() + self.latency + self.update_lock.release() + + # check if there is new state available + if self.state_buffer.new_data_available: + odom_msg = self.state_buffer.readFromRT() + + t_slam = odom_msg.header.stamp.to_sec() + + u = np.zeros(3) + u[-1] = t_slam + while not u_queue.empty() and u_queue.queue[0][-1] < t_slam: + u = u_queue.get() # remove old control commands + state_cur = self.extract_state_odom(odom_msg) + + # predict the current state use past control command + for i in range(u_queue.qsize()): + u_next = u_queue.queue[i] + dt = u_next[-1] - u[-1] + state_cur = dyn_step(state_cur, u, dt) + u = u_next + + # predict the cur state with the most recent control command + state_cur = dyn_step(state_cur, u, t_act - u[-1]) + + # if there is no new state available, we do one step forward integration to predict the state + elif prev_state is not None: + t_prev = prev_u[-1] + dt = t_act - t_prev + # predict the state using the last control command is executed + state_cur = dyn_step(prev_state, prev_u, dt) + + # compute the control command + accel, steer = self.get_control(state_cur) + + # generate control command + if not self.simulation: + # If we are using robot, + # the throttle and steering angle needs to convert to PWM signal + throttle_pwm, steer_pwm = self.pwm_converter.convert(accel, steer, state_cur[2]) + else: + throttle_pwm = accel + steer_pwm = steer + + # publish control command + servo_msg = ServoMsg() + servo_msg.header.stamp = rospy.get_rostime() # use the current time to avoid synchronization issue + servo_msg.throttle = throttle_pwm + servo_msg.steer = steer_pwm + self.control_pub.publish(servo_msg) + + # Record the control command and state for next iteration + u_record = np.array([accel, steer, t_act]) + u_queue.put(u_record) + prev_u = u_record + prev_state = state_cur + + # end of while loop + rate.sleep() + + def get_state_action_pair(self, odom_msg): + ''' + This function use two consecutive odometry messages to generate the state action pair + ''' + prev_odom_msg = self.state_buffer.readFromRT() + + if prev_odom_msg is None: + return + + # No path available + if self.path_buffer.readFromRT() is None: + rospy.logwarn_once("No path available") + return + + prev_state = self.extract_state_odom(prev_odom_msg) + if prev_state[2]<0.1: + return + cur_state = self.extract_state_odom(odom_msg) + + dt = cur_state[-1] - prev_state[-1] + dpsi = cur_state[3] - prev_state[3] + + # dpsi = np.tan(delta)*(x[2]*dt/0.257) + delta = np.arctan(dpsi/(prev_state[2]*dt/0.257))/0.37 + + if abs(delta)>1: + return + + full_state = self.global_to_full_state(prev_state) + + # [x, y, v, psi, progress, lateral, slope, curvature, d_heading, timestamp] + # we interested in local state [v, lateral error, heading error, curvature] + local_state = np.array([full_state[2], full_state[5], full_state[-3], full_state[-2]]) + self.state_action_buffer.put((local_state, delta)) + + def learning_thread(self): + + itr = 0 + while not rospy.is_shutdown(): + + if not self.learning: + rospy.sleep(0.1) + continue + + self.learning_lock.acquire() + while not self.state_action_buffer.empty(): + state, action = self.state_action_buffer.get() + self.state_vec.append(state) + self.action_vec.append(action) + + if len(self.action_vec)>64: + loss = self.neural_network.train_step(np.array(self.state_vec), np.array(self.action_vec)) + rospy.loginfo(f"itr: {itr}, loss: {loss}") + itr += 1 + + self.learning_lock.release() + + + rospy.sleep(0.1) \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/scripts/learning_node.py b/ROS_Core/src/Labs/Lab4/scripts/learning_node.py new file mode 100755 index 0000000..082e78e --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/learning_node.py @@ -0,0 +1,11 @@ +#!/usr/bin/env python +import rospy +from imitation_learn import ImitationLearning + +if __name__ == '__main__': + # Safe guard for GPU memory + rospy.init_node('imitation_learning_node') + rospy.loginfo("Start imitation_learning node") + + ImitationLearning() + rospy.spin() diff --git a/ROS_Core/src/Labs/Lab4/scripts/neural_network.py b/ROS_Core/src/Labs/Lab4/scripts/neural_network.py new file mode 100644 index 0000000..7d38626 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/neural_network.py @@ -0,0 +1,107 @@ +import torch +import numpy as np +from datetime import datetime +import os + + +class NeuralNetwork(): + def __init__(self, input_size: int, output_size: int, batch_size: int=64, lr: float = 1e-3, save_dir = None, load_model =None) -> None: + + ''' + This class implements a simple neural network with 3 layers of MLP. + Parameters: + input_size: The size of the input vector + output_size: The size of the output vector + save_dir: The directory to save the model + load_model: The filepath to load the model + ''' + self.input_size = input_size + self.output_size = output_size + self.batch_size = batch_size + self.save_dir = save_dir if save_dir is not None else "./" + self.device = torch.device("cuda:0" if torch.cuda.is_available() else "cpu") + + self.model = torch.nn.Sequential( + torch.nn.Linear(input_size, 16), + torch.nn.ReLU(), + torch.nn.Linear(16, 32), + torch.nn.ReLU(), + torch.nn.Linear(32, 64), + torch.nn.ReLU(), + torch.nn.Linear(64, 128), + torch.nn.ReLU(), + torch.nn.Linear(128, 64), + torch.nn.ReLU(), + torch.nn.Linear(64, output_size), + ) + + self.loss_fn = torch.nn.MSELoss(reduction='mean') + + + if load_model is not None: + try: + self.model.load_state_dict(torch.load(load_model)) + print(f"Model loaded from {load_model}") + except Exception as e: + print("Unable to load: ", e) + + self.model.to(self.device) + self.optimizer = torch.optim.Adam(self.model.parameters(), lr=lr) + + def train(self, x, y): + x = torch.from_numpy(x).float().to(self.device).reshape(-1, self.batch_size, self.input_size) + y = torch.from_numpy(y).float().to(self.device).reshape(-1, self.batch_size, self.output_size) + + num_b = x.shape[0] + loss = 0 + for b in range(num_b): + loss_batch = self.train_step(x[b,:,:], y[b,:,:]) + loss += loss_batch + return loss/num_b + + def train_step(self, x, y): + ''' + This function trains the model for one step + Parameters: + x: The input vector + y: The target vector + ''' + self.model.train() + self.model.zero_grad() + + if isinstance(x, np.ndarray): + x = torch.from_numpy(x).float() + y = torch.from_numpy(y).float().reshape(-1, 1) + + y_pred = self.model(x).reshape(-1, self.output_size) + + assert y_pred.shape == y.shape, f"y_pred: {y_pred.shape}, y: {y.shape} are not equal" + + loss = self.loss_fn(y_pred, y) + loss.backward() + self.optimizer.step() + + return loss.item() + + def inference_step(self, x): + ''' + This function predicts the output vector + Parameters: + x: The input vector + ''' + with torch.no_grad(): + self.model.eval() + x = torch.from_numpy(x).float().to(self.device) + y_pred = self.model(x) + return y_pred.detach().cpu().numpy() + + def save_model(self, filename = None): + ''' + This function saves the model + ''' + if filename is None: + filename = "model_" + datetime.now().strftime("%Y%m%d_%H%M%S") + ".pt" + path = os.path.join(self.save_dir, filename) + torch.save(self.model.state_dict(), path) + print("Model saved to ", path) + \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/scripts/offline_train.ipynb b/ROS_Core/src/Labs/Lab4/scripts/offline_train.ipynb new file mode 100644 index 0000000..8692723 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/offline_train.ipynb @@ -0,0 +1,194 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "The autoreload extension is already loaded. To reload it, use:\n", + " %reload_ext autoreload\n" + ] + } + ], + "source": [ + "%load_ext autoreload\n", + "%autoreload 2" + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [], + "source": [ + "\n", + "from neural_network import NeuralNetwork\n", + "import numpy as np\n", + "import tqdm\n", + "import matplotlib.pyplot as plt\n", + "import torch\n", + "import pickle" + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [], + "source": [ + "def data_generator(batch_size):\n", + " '''\n", + " This function generates batches of data\n", + " Parameters:\n", + " data: The data to be batched\n", + " batch_size: The size of the batch\n", + " '''\n", + " x = np.random.random((batch_size, 4))\n", + " y = np.array([np.mean(x, axis=1)+np.random.randn(batch_size)*0.01, np.std(x, axis=1)+np.random.randn(batch_size)*0.01]).T\n", + " \n", + " return x, y" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [], + "source": [ + "# loda data\n", + "filename = '../data/data_example.pkl' ## Replace with your own path\n", + "with open(filename, 'rb') as f:\n", + " data = pickle.load(f)\n", + "\n", + "state = np.array(data[0])\n", + "action = np.array(data[1])\n" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [], + "source": [ + "model = NeuralNetwork(state.shape[-1], 1, lr=1e-3, save_dir=\"../models\")" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Loss: 0.0055: 100%|██████████| 100000/100000 [04:11<00:00, 398.19it/s]\n" + ] + } + ], + "source": [ + "loss_hist = []\n", + "x_train = torch.from_numpy(state).float().to(model.device)\n", + "y_train = torch.from_numpy(action).float().reshape(-1, 1).to(model.device)\n", + "with tqdm.tqdm(range(100000)) as t:\n", + " for _ in t:\n", + " loss = model.train_step(x_train, y_train)\n", + " loss_hist.append(loss)\n", + " t.set_description(f\"Loss: {loss:.4f}\")\n", + " " + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 41, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "

" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "\n", + "plt.plot(loss_hist)\n", + "plt.yscale('log')\n", + "plt.xlabel('Step')\n", + "plt.ylabel('Loss')\n", + "\n", + "plt.figure()\n", + "y_pred = model.inference_step(state)\n", + "plt.plot(action, '*', label=\"y\")\n", + "plt.plot(y_pred, '.', label=\"y_pred\")" + ] + }, + { + "cell_type": "code", + "execution_count": 42, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Model saved to ../models/model_example.pt\n" + ] + } + ], + "source": [ + "model.save_model('model_example.pt')" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "ros_base", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.9.15" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/ROS_Core/src/Labs/Lab4/scripts/utils/__init__.py b/ROS_Core/src/Labs/Lab4/scripts/utils/__init__.py new file mode 100644 index 0000000..0f76615 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/utils/__init__.py @@ -0,0 +1,4 @@ +from .realtime_buffer import RealtimeBuffer +from .ros_utility import * +from .ref_path import RefPath +from .generate_pwm import GeneratePwm \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/scripts/utils/generate_pwm.py b/ROS_Core/src/Labs/Lab4/scripts/utils/generate_pwm.py new file mode 100644 index 0000000..009a2fe --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/utils/generate_pwm.py @@ -0,0 +1,72 @@ +import rospy +from .ros_utility import get_ros_param +import numpy as np +import pickle + + +class GeneratePwm(): + ''' + This class apply an open-loop model to convert + acceleration and steering angle to PWM that can + be read by the ESC and servo + ''' + def __init__(self): + ''' + Constructor for the GeneratePwm class + ''' + # Read the parameters from the parameter server + self.read_parameters() + + # Define the open-loop model + self.mlp_model = pickle.load(open(self.model_path, 'rb')) + + def read_parameters(self): + ''' + Read the maximum and minimum throttle for safety + ''' + self.max_throttle = get_ros_param('~max_throttle', 0.5) + self.min_throttle = get_ros_param('~min_throttle', -0.3) + self.model_path = get_ros_param('~PWM_model', 'model.pkl') + + def convert(self, accel: float, steer: float, v: float): + ''' + convert the acceleration and steering angle to PWM given the current state + Parameters: + accel: float, linear acceleration of the robot [m/s^2] + steer: float, steering angle of the robot [rad] + state: State2D, current state of the robot + ''' + + # Do not allow the car to go over 3m/s + if v > 3: + accel = min(accel, 0) + v_bounded = 3 + else: + v_bounded = v + + # negative pwm means turn left (positive steering angle) + steer_pwm = -np.clip(steer/0.37, -1, 1) + accel_bounded = np.sign(accel)*min(abs(accel), 2+v) + + # Generate Input vector + input = np.array([[accel_bounded, v_bounded, np.abs(steer_pwm)]]) + + # check nan + if np.any(np.isnan(input)): + rospy.logwarn("Contain NAN in control!") + return self.min_throttle, steer_pwm + + # convert the acceleration and steering angle to PWM + d = self.mlp_model.predict(input)[0] + + # clip the throttle to the maximum and minimum throttle + throttle_pwm = np.clip(d, self.min_throttle, self.max_throttle) + + # Composite the throttle for low speed + if v<0.2: + throttle_pwm += np.abs(steer_pwm)*0.04 + + return throttle_pwm, steer_pwm + + + \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/scripts/utils/realtime_buffer.py b/ROS_Core/src/Labs/Lab4/scripts/utils/realtime_buffer.py new file mode 100644 index 0000000..7436b86 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/utils/realtime_buffer.py @@ -0,0 +1,48 @@ +from threading import Lock + +class RealtimeBuffer: + ''' + This class implements a real-time buffer for a single object. + ''' + def __init__(self): + self.rt_obj = None + self.non_rt_obj = None + self.new_data_available = False + self.lock = Lock() + + def writeFromNonRT(self, obj): + ''' + Write data to non-realtime object. If a real-time thread + is reading the non-realtime object, wait until it finish. + + Parameters: + obj: object to be written + ''' + self.lock.acquire(blocking=True) + self.non_rt_obj = obj + self.new_data_available = True + self.lock.release() + + def readFromRT(self): + ''' + if no thread is writing and new data is available, update rt-object + with non-rt object. + + Returns: + rt_obj: real-time object + ''' + # try to lock + if self.lock.acquire(blocking=False): + if self.new_data_available: + temp = self.rt_obj + self.rt_obj = self.non_rt_obj + self.non_rt_obj = temp + self.new_data_available = False + self.lock.release() + return self.rt_obj + + def reset(self): + ''' + Reset the buffer to None + ''' + self.writeFromNonRT(None) diff --git a/ROS_Core/src/Labs/Lab4/scripts/utils/ref_path.py b/ROS_Core/src/Labs/Lab4/scripts/utils/ref_path.py new file mode 100644 index 0000000..634f912 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/utils/ref_path.py @@ -0,0 +1,280 @@ +from typing import Optional, Tuple, Union +import numpy as np +from matplotlib import pyplot as plt +import matplotlib +from pyspline.pyCurve import Curve +import csv + +class RefPath: + def __init__(self, center_line: np.ndarray, + width_left: Union[np.ndarray, float] = 1, + width_right: Union[np.ndarray, float] = 1, + speed_limt: Union[np.ndarray, float] = 1, + loop: Optional[bool] = True) -> None: + ''' + Considers a track with fixed width. + + Args: + center_line: 2D numpy array containing samples of track center line + [[x1,x2,...], [y1,y2,...]] + width_left: float, width of the track on the left side + width_right: float, width of the track on the right side + loop: Boolean. If the track has loop + ''' + self.center_line_data = center_line.copy() + + # First, we build the centerline spline in XY space + self.center_line = Curve(x=center_line[0, :], y=center_line[1, :], k=3) + + # Project back to get the s for each point + s_norm, _ = self.center_line.projectPoint(center_line.T) + + if not isinstance(width_left, np.ndarray): + self.width_left = Curve(x=s_norm, y = np.ones_like(s_norm) * width_left, k=3) + else: + self.width_left = Curve(x=s_norm, y=width_left, k=3) + + if not isinstance(width_right, np.ndarray): + self.width_right = Curve(x=s_norm, y = np.ones_like(s_norm) * width_right, k=3) + else: + self.width_right = Curve(x=s_norm, y=width_right, k=3) + + if not isinstance(speed_limt, np.ndarray): + self.speed_limit = Curve(x=s_norm, y = np.ones_like(s_norm) * speed_limt, k=3) + else: + self.speed_limit = Curve(x=s_norm, y=speed_limt, k=3) + + self.loop = loop + self.length = self.center_line.getLength() + + # variables for plotting + self.build_track() + + def _interp_s(self, s: np.ndarray) -> Tuple[np.ndarray, np.ndarray]: + """ + Gets the closest points on the centerline and the slope of trangent line on + those points given the normalized progress. + + Args: + s (np.ndarray): progress on the centerline. This is a vector of shape + (N,) and each entry should be within [0, 1]. + + Returns: + np.ndarray: the position of the closest points on the centerline. This + array is of the shape (2, N). + np.ndarray: the slope of of trangent line on those points. This vector + is of the shape (N, ). + """ + if isinstance(s, float): + n = 1 + else: + n = len(s) + interp_pt = self.center_line.getValue(s) + if n == 1: + interp_pt = interp_pt[np.newaxis, :] + slope = np.zeros(n) + + for i in range(n): + deri = self.center_line.getDerivative(s[i]) + slope[i] = np.arctan2(deri[1], deri[0]) + return interp_pt.T, slope + + def interp(self, theta_list): + """ + Gets the closest points on the centerline and the slope of trangent line on + those points given the unnormalized progress. + + Args: + s (np.ndarray): unnormalized progress on the centerline. This is a + vector of shape (N,). + + Returns: + np.ndarray: the position of the closest points on the centerline. This + array is of the shape (2, N). + np.ndarray: the slope of of trangent line on those points. This vector + is of the shape (N, ). + """ + if self.loop: + s = np.remainder(theta_list, self.length) / self.length + else: + s = np.array(theta_list) / self.length + s[s > 1] = 1 + return self._interp_s(s) + + def build_track(self): + N = 500 + theta_sample = np.linspace(0, 1, N, endpoint=False) * self.length + interp_pt, slope = self.interp(theta_sample) + self.track_center = interp_pt + + if self.loop: + self.track_bound = np.zeros((4, N + 1)) + else: + self.track_bound = np.zeros((4, N)) + + # Inner curve. + width_left = self.width_left.getValue(theta_sample)[:,1] + self.track_bound[0, :N] = interp_pt[0, :] - np.sin(slope) * width_left + self.track_bound[1, :N] = interp_pt[1, :] + np.cos(slope) * width_left + + # Outer curve. + width_right = self.width_right.getValue(theta_sample)[:,1] + self.track_bound[2, :N] = interp_pt[0, :] + np.sin(slope) * width_right + self.track_bound[3, :N] = interp_pt[1, :] - np.cos(slope) * width_right + + if self.loop: + self.track_bound[:, -1] = self.track_bound[:, 0] + + def get_reference(self, points: np.ndarray, + normalize_progress: Optional[bool] = False, + eps: Optional[float] = 1e-3) -> Tuple[np.ndarray, np.ndarray, np.ndarray]: + + closest_pt, slope, s = self.get_closest_pts(points, eps=eps) + + v_ref = self.speed_limit.getValue(s)[:,1] + + if not self.loop: + temp = (1-s) * self.length + # bring the speed limit to 0 at the end of the path + v_ref = np.minimum(v_ref, temp) + v_ref = v_ref[np.newaxis, :] + + width_left = self.width_left.getValue(s)[:,1][np.newaxis, :] + width_right = self.width_right.getValue(s)[:,1][np.newaxis, :] + + if not normalize_progress: + s = s * self.length + s = s[np.newaxis, :] + return np.concatenate([closest_pt, slope, v_ref, s, width_right, width_left], axis=0) + + def get_closest_pts(self, points: np.ndarray, eps: Optional[float] = 1e-3) -> Tuple[np.ndarray, np.ndarray, np.ndarray]: + """ + Gets the closest points on the centerline, the slope of their tangent + lines, and the progress given the points in the global frame. + + Args: + points (np.ndarray): the points in the global frame, of the shape + (2, N). + + Returns: + np.ndarray: the position of the closest points on the centerline. This + array is of the shape (2, N). + np.ndarray: the slope of of tangent line on those points. This vector + is of the shape (1, N). + np.ndarray: the normalized progress along the centerline. This vector is of the + shape (1, N). + """ + + s, _ = self.center_line.projectPoint(points.T, eps=eps) + if points.shape[1] == 1: + s = np.array([s]) + closest_pt, slope = self._interp_s(s) + slope = slope[np.newaxis, :] + + return closest_pt, slope, s + + def local2global(self, local_states: np.ndarray, return_slope=False) -> np.ndarray: + """ + Transforms trajectory in the local frame to the global frame (x, y) position. + + Args: + local_states (np.ndarray): The first row is the progress of the trajectory + and the second row is the lateral deviation. + + Returns: + np.ndarray: trajectory in the global frame. + """ + flatten = False + if local_states.ndim == 1: + flatten = True + local_states = local_states[:, np.newaxis] + num_pts = local_states.shape[1] + progress = local_states[0, :] + assert np.min(progress) >= 0. and np.max(progress) <= 1., ( + "The progress should be within [0, 1]!" + ) + lateral_dev = local_states[1, :] + global_states, slope = self._interp_s(progress) + if num_pts == 1: + global_states = global_states.reshape(2, 1) + global_states[0, :] = global_states[0, :] + np.sin(slope) * lateral_dev + global_states[1, :] = global_states[1, :] - np.cos(slope) * lateral_dev + + if flatten: + global_states = global_states[:, 0] + if return_slope: + return global_states, slope + return global_states + + def global2local(self, global_states: np.ndarray) -> np.ndarray: + """ + Transforms trajectory in the global frame to the local frame (progress, lateral + deviation). + + Args: + global_states (np.ndarray): The first row is the x position and the + second row is the y position. + + Returns: + np.ndarray: trajectory in the local frame. + """ + # flatten = False + if global_states.ndim == 1: + flatten = True + global_states = global_states[:, np.newaxis] + local_states = np.zeros(shape=(4, global_states.shape[1])) + closest_pt, slope, progress = self.get_closest_pts( + global_states + ) + + curvature = [] + for p in progress.reshape(-1): + d1 = self.center_line.getDerivative(p) + d2 = self.center_line.getSecondDerivative(p) + curvature.append((d1[0]*d2[1] - d1[1]*d2[0]) / ((d1[0]**2 + d1[1]**2)**(3/2))) + + dx = global_states[0, :] - closest_pt[0, :] + dy = global_states[1, :] - closest_pt[1, :] + sr = np.sin(slope) + cr = np.cos(slope) + + lateral_dev = sr*dx - cr*dy + local_states[0, :] = progress.reshape(-1) + local_states[1, :] = lateral_dev + local_states[2, :] = slope + local_states[3, :] = curvature + + if flatten: + local_states = local_states[:, 0] + + return local_states + + # region: plotting + def plot_track(self, ax: Optional[matplotlib.axes.Axes] = None, + c: str = 'k', linewidth = 1, zorder=0, plot_center_line: bool = False): + if ax is None: + ax = plt.gca() + # Inner curve. + ax.plot( + self.track_bound[0, :], self.track_bound[1, :], c=c, linestyle='-', + linewidth = linewidth, + zorder=zorder + ) + # Outer curve. + ax.plot( + self.track_bound[2, :], self.track_bound[3, :], c=c, linestyle='-', + zorder=zorder + ) + if plot_center_line: + self.plot_track_center(ax, c=c, zorder=zorder) + + def plot_track_center(self, ax: Optional[matplotlib.axes.Axes] = None, c: str = 'k', linewidth = 1, zorder=0): + if ax is None: + ax = plt.gca() + ax.plot( + self.track_center[0, :], self.track_center[1, :], c=c, linestyle='--', + linewidth = linewidth, + zorder=zorder + ) + + # endregion \ No newline at end of file diff --git a/ROS_Core/src/Labs/Lab4/scripts/utils/ros_utility.py b/ROS_Core/src/Labs/Lab4/scripts/utils/ros_utility.py new file mode 100644 index 0000000..55ee237 --- /dev/null +++ b/ROS_Core/src/Labs/Lab4/scripts/utils/ros_utility.py @@ -0,0 +1,27 @@ +import rospy + +def get_ros_param(param_name: str, default): + ''' + Read a parameter from the ROS parameter server. If the parameter does not exist, return the default value. + Args: + param_name: string, name of the parameter + default: default value + Return: + value of the parameter + ''' + if rospy.has_param(param_name): + return rospy.get_param(param_name) + else: + # try seach parameter + if param_name[0] == '~': + search_param_name = rospy.search_param(param_name[1:]) + else: + search_param_name = rospy.search_param(param_name) + + if search_param_name is not None: + rospy.loginfo('Parameter %s not found, search found %s, using it', param_name, search_param_name) + return rospy.get_param(search_param_name) + else: + rospy.logwarn("Parameter '%s' not found, using default: %s", param_name, default) + return default +