From 232af05548edeb046dd26f81406d9683ab02574d Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 17 Jun 2019 14:29:30 +0200 Subject: [PATCH 01/13] use gitlab-ci pipeline from https://gitlab.com/VictorLamoine/ros_gitlab_ci --- .gitlab-ci.yml | 44 +++++++++++++++++++++++++++++++++++++------- 1 file changed, 37 insertions(+), 7 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 15537df..b88217a 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,8 +1,38 @@ -include: - - project: 'continuous_integration/ci_scripts' - ref: master - file: '/gitlab-ci-yml/catkin_pipeline.yml' +image: ros:kinetic-robot + +cache: + paths: + - ccache/ + +before_script: + - git clone https://gitlab.com/VictorLamoine/ros_gitlab_ci.git + - source ros_gitlab_ci/gitlab-ci.bash >/dev/null + +# catkin_lint +catkin lint: + tags: + - docker + stage: build + image: ros:kinetic-ros-core + before_script: + - apt update >/dev/null 2>&1 + - apt install -y python-catkin-lint >/dev/null 2>&1 + script: + - catkin_lint -W3 . + +# catkin_make +catkin_make: + tags: + - docker + stage: build + script: + - catkin_make + +catkin_make tests: + tags: + - docker + stage: test + script: + - catkin_make run_tests + - catkin_test_results # Check if one of the tests failed! -variables: - BUILD_INDIGO: "false" - BUILD_MELODIC: "false" From 10ec2515bb4bb9d830266f9d0907ad46321fd156 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rune=20S=C3=B8e-Knudsen?= Date: Thu, 20 Jun 2019 15:03:09 +0200 Subject: [PATCH 02/13] Change to the front README file - Change to the introduction with a purpose of this driver - Add a comment of how to report issues - Fix a small type in one of the examples --- README.md | 17 ++++++++++++++--- .../doc/initial_setup_images/e-Series.png | Bin 0 -> 208062 bytes 2 files changed, 14 insertions(+), 3 deletions(-) create mode 100644 ur_rtde_driver/doc/initial_setup_images/e-Series.png diff --git a/README.md b/README.md index a7e7298..febd98a 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,20 @@ -# UR_RTDE_Driver +# Universal_Robots_ROS_Driver +Universal Robots have become a dominant supplier lightweight, robotic manipulators for industry, as well as for scientific research and education. The Robot Operating System (ROS) has developed from a community-centered movement to a mature framework and quasi standard, providing a rich set of powerful tools for robot engineers and researchers, working in many different domains. + +
Universal Robot e-Serie familie
+ +With the release of UR’s new e-Series, the demand for a ROS driver that supports the new manipulators and the newest ROS releases and paradigms like ROS-control have increased further increase. The goal of this driver is to provide a stable and sustainable interface between UR robots and ROS that strongly benefit all parties. + +It is the core value of Universal Robots, to empower people to achieve any goal within automation. The success criteria of this driver release is to follow this vision, by providing the ROS community with an easy to use, stable and powerful driver, that empowers the community to reach their goals in research and automation without struggling with unimportant technical challenges, instability or lacking features. + +### Acknowledgement This driver is forked from the [ur_modern_driver](https://github.com/ros-industrial/ur_modern_driver). -It works for all CB3 and eSeries robots and uses the RTDE interface for communication, whenever possible. +## How to report a Issue +Create an issue on the [Issue Board](https://gitlab.com/ur_ros_beta/universal_robots_ros_driver/issues) and use [Issue #1 as a template](https://gitlab.com/ur_ros_beta/universal_robots_ros_driver/issues/1). ## Features + * Works for all **CB3 and eSeries** robots and uses the RTDE interface for communication, whenever possible. * **Factory calibration** of the robot inside ROS to reach Cartesian targets precisely. * **Realtime-enabled** communication structure to robustly cope with the 2ms cycle time of the eSeries. To use this, compile and run it on a kernel with the `PREEMPT_RT` patch enabled. (TODO: Write tutorial on how to compile a realtime kernel for Ubuntu) @@ -165,7 +176,7 @@ It is recommended to adapt the new package's *package.xml* with a meaningful des To actually start the robot driver use one of the existing launchfiles $ roslaunch ur_rtde_driver _bringup.launch robot_ip:=192.168.56.101 \ - kinematics_config:=$(rospack find ur_calibrations)/etc/ur10_example_calibration.yaml + kinematics_config:=$(rospack find ur_calibration)/etc/ur10_example_calibration.yaml where **** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e*. Note that in this example we load the calibration parameters for the robot "ur10_example". If the parameters in that file don't diff --git a/ur_rtde_driver/doc/initial_setup_images/e-Series.png b/ur_rtde_driver/doc/initial_setup_images/e-Series.png new file mode 100644 index 0000000000000000000000000000000000000000..34cfd3e6103377ec51faa1c481c5d15cfaf157bd GIT binary patch literal 208062 zcmZ6yWmJ^y_x_EDN{4`ScOxY!GIYZ*APgYg-3=n$-O`MN3?0%4(%mtXfFRvn|LeZL z_wRY}ykIRCYvG!6u6^!(?9Xvr5o#*3Sm>naNJvOn@^VsOBqZdINJ!7xQC|YTX-}uo zKtlSABrhca@m$=`_V}!?*>o9TbI_(LK4k&&Mn;qW8;lFWYNOLkCk}<1d2MIMDw`{bz7P|W5#=zt>op|+edAmT$0w6qc>QEKLW0{%oBwkzKV!?ty+l1 zQPa@S7=69z<-n=Rcj53EO_$AATT9%)S(BW5NZo1>sH^f?wZZvQ(&%d+cXPHqHnz)|TQi*a=v91t{PEEcPQVkh$jjTE{l%YnuejC< zOmNm}#XGWQQ_a5}w7&|teK?@tNV52p%*LnpRi$`Ks3BXqSVOQO#!N?!<~RsR9C9rY zz83~rLK4SBljL7}_4E0|vPiqrVY`@h+7+)HyqIIA844sDkLsqe2}neTgWH?n(e zdv;)=p`lgsymm^7kLTv}UB}09JngC7SrAfckKZ_yrLy?he)raH(3CRZG-BcA+a=D; zyu-vKC=U-rjq54#c@mj}K6WF1^j-YmR(uyoEsisQ($zAyvBv9>G2 z?q<8;6(8X^vF2zobEWNZNo?1{*6rV1)5)Gkso4)d{82&cauOwk?yQpe)g(nRvyq1t z2ex__w0?+2Y6vQn1_jlM&NeKS#fRH%^x0+>bX;L#wQb`p*X!UJ)#LHV*yP-*vaYU3 zTelyOXT-X?@X`kTTbcw31oTMG;}tY~(R6{Xu+>N79+qfx1-8S5&Q^2Q(Nr<^|-ks3F(w zVcRz-fpL4yKltMkCaIr4e>iu)s`BnZSI|lb8uJ&qqjI@@Id-N(wSNeWu&X^!b*Q<3 z$xc9@(Z05#dH(!45V8pqY`zBNdPfilV?_VJBqXmnnr5KuC=|J&EVw6Sa11d++Q`cYkj?4wJ3cy4)@`g}rw@Qx$lB z9OY2u@({K4ssLAxB>}vC_c)Z(EwbW7LS*3kmI9w~t(lV*g5v*y_$5l9>KYpee*C=g z(V}uo{mdH0C>)zGA8ZNx98dkm>SWbM8aEgvUv(|)x?PqyROXkJS&j*A{9gKK(lRzy z53*I?&l+~?dRDqWM%ZG9?7+2RJl3~P;h}rphI#2a(P;9#uYD_N={D)z_{}f;jRz;7 zgf)}?SHi&-@6M~u&KNHjZ8)DlJXiWU-`g*D(59emKtWFV69+l6i9J7QyTW4b`1?^n z_F^WJ;6rc^`HwYfTc(h0FJ}0NyaWqwzvUN#*Vi->Yw9lgtbbTx;E47>|ChI~{!$T} znifTqF((_C>@5=RH>?rF`VGmZKHiT+z0q^Lx%&cA$kW4NGBeT@&~3E;12f~AKp>)K zNf8Y@fB)ve;aD(DK6%+;kE5vifK-p=RFg-PGv zm{WN?yAnOtp8APFw4XNir|SSAP?_=G#9bA}^CkH;4Lg!d=o;k1e9I_vG zB2?>D81H|Xblk3c2G9eyrk;MC73lhDh4ou^9nDEmT!Ja9s~5~nlrDk~4?&fLDqC}Y zK@4B0i|R`|W6OGoD(_gXp7y_!dvs!|h&^D|+#pwMBU6X`YOpP0pgW)$&$M(lWfaRf z(ttylKbB!)V^6NG%06{c!xGRXh~aynT=1$&B!xy*a*Kjxy#`$k2o;`^3Rd`CL>{m+ z39F|@MINd_hHJXz`dwb&L0kA$ZQv;jyH+sG61-sOceN0xjdDpH7!>sZ?-tqUJW1ji zl#S4agD^NB6sADOm*-0Sk`y#lQ^%90K?C6VKKnl$b zZkLr_mlJ!|l5HK0&M|)$9XpC`jQ{rB1uUKA!r$D!ar9t~C&T#&Im#!wP4CygO**<>3JdXPaAEhA%T7_L3Cm zs+9750T14z#4xH?hYezuu8T)m)|fNugHV$vx15mj!4s>cY0Dk6=cM2?GbNKa<>GC^hx*!{5_P>f?_G`%Cxr7%O*&dk*(qADhmyj<$b! z_$P=PT;-oUTGG?ET37eoJ);Ny(X4YjtkL>VhNGUug01IB%?mv(!qIW`o57fZTA3?Z zZNxIYJEcndG`!?0o_pU_EWeGO9ID7nD03@KU7(zS+sp}(GJW4@he3mqYG#C>*+~up zO-a!qffQUsNR6e7HYy7clZ8H_NTg(B8Nz1hhz7etHFhvF!QZ1Ji>u|UJa8#4%FmL9 zf{N*U-9Vv#4|t?xG^dJ z-I$uE_B(DchW6z!KDqPoMET*qSW6RZ2W1Q=T?ihLMX5c6P!UNmAyWD+Ms-aK)W2kR zkU1DO;yP&TI$S~b?D-Z~{j51D0m%f%5a`>c_RV<>VZn`a^i^qW`IAm*ym58l)~uF* z-3kgRxRjtC8Uw8dRcjY%eW#%{NN!?rndH7*{p*Bo(oA#$lR6iKod1yG^O>@w80!D) zB{Rlx%ZV)US92mHqbQ3BxQucl*l?XN?xQ@|2N`z`LS=ZX+LUhDZvu3sWtWw(_wGOM zopj7PT7hI5ccCO);LIzQr{zCEzBZM^uOlZu` z>+7m)*=}|}_YI*3dbj*_LSvP&# zfoo?_tiSFr60kZ1L`-U+g^L@?dRq%(p}46BfndV}-Q4t$OjlNET>VcrG2334SXeYL zzV}>&=_M$H`X5>9&Av6jZqHKhI1}yry&82GiW#hj%N+t}PY=dS=yFM$7 z&<*qDr+`o+IQSG|Du^}3e4_r|W`Y<)>~u_dgm^NB%cB@SNZt{E7w-S>Y&Jgu>89VC z^%-wyJ;Kap-sXw~W#L|gbSjZTQ}BSl@=v^1jPDKETuqzJtH5oVBB|M8Ib=eRzSKhs z6RUs#8jae-trB|7huOIh5PH`K{A&p@&Y#yAG7d86CpCZafP+RtVIa<2CJ0T=wvo;o zi8T$@6g7q4&79y!O9a#IUQ0)e`TpYD_S|ZGK?-sA>GTf#i+v8fADDMvwv5Rnh>hi4 z6u?#?A7m;eTxb6Nsj2I2;Fx5|f+8(|Oi1&pO-L6)Q%@c}|7kk%{|X&WlO4y1Wj0QG z{ydsA+B7E>6wkS^_7C4ISi}R4-?PrJ=4@xIjau?sBo15*wXPub&;Nz*F?!Gyt)mgl zH`vWarW58e*!fbd-B7YZ+;Sn&o#A-uX^dORpPKX-vsDVe#AoiU&kI1i9ZQ3^?>uwD zN}_-+^7WWUqZ#+4alHra}fo)WgwgT8I+|h85xWw)Vh_apNvl?-DJjPfkuEZ{pv$@1Z zE&MyaWQ(-yt*~;_fEaQA8whg{9Nm` zaBio!Y-kvSqo4B`w14820Gnv((!Mt6(i>~A6`eELn}yfa*H5fWNYLam9gDHfpyzBO zQ&vyh|LJvi5vkaIeM=KaNF5?oiZsUi5HbUW+qYL5DB1)ko4l5m?SU+N5@PiK;EI>K z51+tKFc~={4U8L8>*-N2D};h#_OjNk@l+oQ+zPwCQrFp%WSiFQX@*o2jl>S--~-PB z>z~ue%`>#BvA7%?$xdp{wBGG|oSd^|ztYWAdOe*VIwA7+a>khI+b?jsb|7;=pGXE9VP+H}$ z6VNB^xgLj#wopkGpS>>++scL2u%MiroaVepX*qV>;OLE4y~(^}J$%-RJp*^?%WYK1l})VmCji}sFwz9VnX z94eAySyiq<%YtwDhjhGb;(?S?l9s{7o3*4Stvq8(=jgAcd9@p)y)47WM-#@(CKNWp z7)2E2(DFfwNhn;fXv*)sU>Qr+aFm?r0?PHxsv@WWjnT({4-~B5HA^(h^TRHFhD_j@ z8tI|Xl zwWZ7qPk-k@nZ%^}jZbvg(Q4ByPS(aHlN%M;cdT;Tr042;eZ{MwUXAZ^D|j+vSi`>t zQ7JKENZ~bj!p)mQwbe35t4nFgU(~{=^Yl0+%2HeziF#Dh?@}i&>Ph` z!R3{>uw=KBG=MY3F$qOw#m84E&U>6H<#_M1XmRO|N>E*!RA>Q0GvFukXG>#-h!;up zZ=i`kkhoLTsy|Fx;uqpZ;OM_|iIb7qVZIO@?IPWqcnvbv5wMwqn~W^h^YQb)b(*AS zXOY35=*ES~c2xN6)K}bnTSwE{_d^fDrRbeId26(5#K*xys~kdONrzMqR!?jO;i18* zuMAWjKbDLy#p=392n)vAS^F1kmn91+lX#$6!_}a8p@Zcg3yCJlU&n|4NOr1w#SE-& zMDa@h>r*ZDjVJfH_Qt1K6^2f-R*PcTb&Ud94!zxFX%{a@g-oMo&7JWrR9N7^#L(kZ zWlia7;P{#xv>_-*Lx!b>`+8|`gH0niWR%QvL?ELa#5;3KCHEOQ_ zd%Y~S{11FV4?#XSumk$-B0|K{$|@h;7Q@&Pae!#l_zsCVj$jlT6TcEw9#I}%GQoNI z^5yW3xIBH;I(p{Y(A&RGB$eqmBJdGoY%4~2lM4ku29~0eD3%8vgY;SRU3zH`A-3@_(c7FpifGVkPJ*#m!0zHrl2`l@TM^9FABqA0!`+LkGD_#=oT ztFg)tA&{&^fG&O7L_S%wYqkByIpaWIAHqfm9J#@c*Xxx2n^MMLj>~0HTN?$8aK`!t z3ZzUk$NQ8eR^(EfQ8{P$)@_gOExu~d@UH!S(D#o=mJcV0W6_2Ct&(HtGIF&@o2rvx7d zoFmx3Q$tmJMBih%XEa;Hi98G<+!MUa2rktkrX($DY)pd)D+{N9q_z%#b(n#n$v03* zU?jGJ!gi@DqC@l?cgkYeaMkY$25ZV_fAnWZ7$X`E%5_>&b!sp3YF*g)=e}=?TPZIy zQ}!{T8a1PvNHD=P-z8ws6uvgY%XXcnG=RZ>xrO;z*+rE$fZ4JgmLhPuh=>0fJW)ZN|PN?8Kg z(s!Juhpk>fu`()WN=XJaiOpTiFSI4Kx4#!|bUy_&lXjy${B4)bNM^l_cD*&B&tVgj z%l0TuNRWe1>v0#xaQfSzQjOwj_Yv!0JDT7S23bv2y=F{OtDfRRQ+;L$SCFd0hF>K9 zW=OS(}kiEV6l%S<0_2qYLEz*LeH&bD!o@?Nml| z%&kpTu6r)tuHC&)Q3z3hb!~BEd7V$ldR=qjoUKPGp6KNgvV8=06p>f^0Z7Wq%9!U@ zXOoIt)mNW&=aSYsQ?pV-x0+K~geafw8mSz|i^Bm~nJ|bB0nrR5Pj63ZJe5PLR=La}fbbdtY4!Z;4fw z9iq`HU4C_q`q>vT#`@E)U1fr(o|DHPz(!K`KlI9JWZI#lbf8uKm(!{HU1v!&!`jZ;UHr_i#o_t#J?f<&ulQM*}~8j5p*;!r29tm2vs`H2CVc zW-K@@Am88eb=ho`uU1#bH^g*8}JuQIi6o0t`KpT zm)NrvxP1fEDsBSm?E?xi<{ApIIDZS1hPY=~pti$d;Fa z{PpG9m3>PtcuZgrF~?)HYx{=6lUbJ1iylY({@63X6d)x0^g{navS5m0$`Q(`;*+(x z6(tiJ47PW6Kbq3V&I3=Ftl&T~i&MaV=dhz*38l} z9*azXn~yJeyO|lr?SFlpoF8H)&prfFh%n302vZ30%<1dwL~3hmGv(D$5j;Uzx!-!n zYjdTOEIY`qe@iRYCWeZYC17X1{wsp$-^Wo z@|=O^R4K;XUb?q-BH3I1oSYqh&hU^NQH{$=jjHrA)lPSQwxmA^Y^dmR$CK&)mQjWl zm0(g{gLFUpA=V|%W>5c;ds%gPpgi`u<)I~Q?pUqm1g(nr!}-bMJWwI5|5qW6#W`l? z?nt@hcL(n?sQmV89_vi5dR855ZA~pL({ms8Eyx`^pPiq()^6vxT%W`R3{S{%^`40~ zx3rx2QL()z)V_MxW6)Rq+@u>M`yxL1wW30BGGrMT&JU(jR-CPWL9rr_f~+$)xX&c0Mo4*$|vKh|3&Q_6_p-lxh~N>?%;Tk`hkfrs4hdw-riC z2}Y0itX6U#q3pY&Ns=P;uth3(e$@Q+jdukYgrkw6PBzSC_nai(9GL zp7(u^?q1A+*)BEX5i;Lr#u;4n-I*i-td#n{X`pG5J2KaCsY#A@lPnZS6lz354XoJ7 zTfGL${hxdeq*YaMn6h18Q{Aq;8rVKVLXr4f7aXDMsgw7k;zuWBr^1pdGkAV^={&72>wGA*tzHVzsrP0G3JUsBp;)c5YC)EnMM;#!|IH7 z%3k4F4;VlHDibCll*9oloK#rdWL2Y7d{}L^D;f2MVsJ@p+gLtD;RYRGeQq7T?(P0w`n<`_`F*dfK5ob`#X{QLzBxQb+}Av{Z+30HX;{Mzd}1HC2og2>FjSK5{X%%3E_Pn6|ap3?Uf zO-D^6_IL}VCXIY~_hox_x4=fpUs9~=XE|D7q9rvdzeMsDwv3?_%#l2d8)D%37_$91 zKCz-cZi)I6=lPcpNq}Cy`cLXdZhNU)d5_x^&UaI2*ANR+QQV^rUw!QjlFtdx&4qOE>{ojx~j~!ES1D()o6+b1iLZhi~#N z6LpB%SKnQhub%4>8xIrma@T1L|3Q5yyf>5ICLX-*<ZEf5Yj7IMCE8(e! zf8$u0_afr%nTZhrMnlO87wP4%-$f=iZc46S7&Z#TDd5vecEjW2xEMr~N;WRMz&BH- zni%}qx;_$YtyD{01XdBFX>!&uE0(cwSg-#EPRLcv zOp2Go$ii*Z>c!#De>2~p&t*qRXjiCF{6kMTT%l0;wXYlu`iu|g{Gyi1CEY`1^}Bef zX6qD(&1ak-aYNwhlY1;Vk-LsdY&_s80H>q-?{w6t+8suIro$>1m{`~e1LpmvHSC{S zuRB_E;tO)@E2b^q889Xp0q0f97Ko8gVw_l6Q86*03jqb%3MdZBKWD5K!;}o>K6w?J z9eJaevvhc|bDJ-E^C6+9V_NBvbESe?|Tj+76? zHi#ah6(Wqi9(lNg%BMdz33ifWb}DvZMN-(7We~MUn8DQwQhO*Yjr> zGtl32$vgkM60sovY&dd|%r12VkAB|vMy1IR^LbMW+3jfm#J7+zSy0*(Vaph0rgMIA zdAf8qR_*`b4S0F&+r|sna5#rjI(J~hr2u*pIaUuXE9AoUDnWq+CdrPV#SCgr8*~R> z`+oq2Ex-`IK{)4Z%#g*)G1y?r%*7k?*AgE@jS?rzuagD7$oBdLF0!*}o|DSa>?XZa z=W;NQ{)m~3L|FEhz!>6INHAG5V8#o%Z63Z#Da)1NYcwU+PeYzic>5_-!K&JS89FL* zW&7zYbMBbR!AEyf)@2;ZztG@2e)Zt7i4l@(zfzUJjVTWU1B`FfT5I<4C)S88P`Rgx`pN|MlYVYl6q_~_<=@F*$gZwD+?PP3 z!A&&-3jX&B-)4#B9}6k1Rv9(uOppG4K3E}P;7=*`KKIu74+ph7^G?E%T31nivZ=Qv zDP6A<0|Widm9o0hDw-2@?VCa__U7K&#Od(y3#{L~7ZVdB`Pd|0n#?AfB0G3wYso$< zI!2eRfal5SvHV~WEB<(W@+b(Dh~oe94Em9ikziP`Godi7(I-b1@K+$L4~_L~s^SlP z|5$uY+hZPu$>uAc&IAvyH!|LNaB6&0V#pd<6U0`q0>Ims&(;R5ACsW?`_&MHrJ3{U zbd95Oz@j@}gJ}Q!E$vdX3dW{$5uIRZ6XetH`F-?RhS??igSz-b2_Z9N6ESHCDl)^z z^wR*( z&D}W(KX!2q;*%ZbOYxH=|x-@3fVM zj%zwqOOh3z9SK;;*(^LZZOK}77~_jXiy7qNe%3AqoYwx;n(er$vHe&e84Y|+>>S<G5jA>%D@N z@FL=C;LrRkvD3dMv-T~@hJ(p0Pdld_*Ed{(2X#|Az)E-Ixh-)liT(sQ?e0OnQW^7H&+&}WmegCwROD_ z*XN?2%BiownbqxN3w&O{j1gfeN@mx+d@X@%h`^S>jaMk1fBO8qZ_^;~Z7CbwWmkV5 z0hSHthWotMeh%vBmkoSFy=Ng}%58n`+w&vHH zbF0&`2o4mt+DlFFf$G*85r+bMmsVt+mdR+250BR_M8IK1bcL!GC^^=|dP9H)apnUB zGU)h%!usW_mq3eC$`M^yZLW85G&Ibkdw4gz4{Q%2H-{b_Lp#OUy)B#p?4Z%ggju@iMcsh4^Ce?QnuV52_S!xh3WUix_I&gBY*`nqC48zc{av(IrG;RU-#QKwji^zw(fEQTfzY`tli)hQ?tO1 zg@skF*OWLqs=}Hwi1?<&!G8MuX;O*xL9Ya`7Uljpd*;Y8W^eu2h}~$vJ0v@b(*sc2 z|G{!OmJA*fbj7sx&c{2d&Sj6~7~F;3UgfNJMCc*08N3$l`=>;Djx>!cw`8g8Hv|^h zes6-F2krmerJaua{gYZER>m* z1yDAI+_8iKQwbaLzMlr#Va2n9naXh@ z8V9g1{1q0n2Z$kgI5m7?O_dnFRn6X#^Ok|#NEGbsDrPA^6wXbMTDM`B#}dXkSRL7_ zyYNlR8u4-MgoK6MGWP60oPml(a=evfBC%&hTXDg{G$dGiBv; zbzgCCDCZejdWHksN1?l$Pe1@{YYAA_eDNwUN87BK?;kZvlQSCU^tK!_$C6aVLQD{w zXD_^clwLwA;=3EzftVPeR%{V8e*~puk?|IPar9R+T@-QuJdp{M{=)X?B*J*2FKwl* z9+rnj2Ro$TO%vdMZ&cz`BmG5z$Y}MA>D2qY5v%uO@EFFHC{O2a)x*`2t<;8KlT@K8 zVboSq(ikE_GwKb8F=AGQFEdkjqld^~bD)o^Sg#Zid|-Iu*q?NM z8-cT}18G^=S3RLGPZ#tyt7`^KCjlrxN*0s8yT88){Ee}rWq1TWQ{rfm@=_oHP_piq z=V}!YKn1aq3D}wrrH=5uG z#de|Q#hlwJblz?~FlW1iC24?NqS^>wvdU3R^_LW9)}<4-JdOT{X%me&zba`{t&Wj zJ9201iaY~?eq&;He5#^1e9Y4ITCk?l4Bk<}poc5*&wvv2U6l=qRLe*TlptPf<_`^f z89`gxzwM%w&6DCXCYA=w<>TSnvGK)81w}>02Pa{5iL>!F>X;a5a48?fft|O{$Ap_# zl+0i2B#Euv50`#E-W^%AYD*xoc2+acY33@xBkhWn%7Ym2Qh^+UU~CZXmrk7BKLa0@ zvqFdo4V;u!#LUD7YhRmylwv$HKZ`8Mnmgh*k=*f$j?0$hzh$Vl4O6Oq)(AB#(#r?4 zOf}WUz2HSGIGDfkYik2?xf~qG@TvkjWiX5FP;U*rJAq_E3NoUm$_{Z|g^mS~R{`7k z&hhbaiP$9X!K(*0vP{y-fUTWkwC?!cZ|1(M8$S`0n_WX(n*d;=IEpg@b^Z8HKZ0;W zE#Xa9D?WIsGooIn1heJ(%5$R!kne;@?N32_Ligcxf|uzgJ3EImHgu_}T)MrrWADSX zGJpT38TB2}`Rcq_s-3C~(*s~04)tJ0L5?S9QDqV&h_G+od|Rv9ppHJyc)su$K!}M)-Dic6Id)uY;fYuhHRNOBg1O z(V6(Nru5b@#M<$+)QxL*b=5E!;jVeT$HIz{V?nJ4F-y$xdhqaP8?E?9{pD&Y;ilF+ z*nou{=4mr?I~PPOinIL+9 z+`aLjt|aH#gBS3m45ZKK?=2b}R!1MtaDK-HTywZ=4-4&2Fy;8VI_Bl_fB)#TSX#XH z>e=f3Y@^pkk3*+?F>_qBp?uV+UH1LWVawk=vJWgh(nR{f$%%)D_Kd0-!@;p=^Rbe+ zFDH^^=eh-ABnLcmO(Et>bE{)OLFeqf^*Gd9L?D`;9(^)|-AH?kB_B@SkVT4~_7~bN zwmOwm!|iqrJyfl#0>+7FLa3AE-?|M#z$)lmGo8hi?U98m7xh`^sTN~TzeKp`leosG zR#gG#s=2|T@60bWG;|(FN>}Vn&d#djtA$^X=b?2Wja|evwdVLSocQKK>j#g=aY-dK zT<}AD1M`2=_>S==!RorVl*uycwjYPTwh?L0S?m;Ejd%F*D!zZP8Wr0nFNeHD8gtQU z_kBU#zg;UgglsyUh6+;H=%_(S{bQ*6Z6AnG{t15pXfy>n20*&&bQnEn(<(0lTogc= z!Y`aVwhZD&VFu`5KBs)ws<~=yL+i?WTsmyp&N+FMW2A32{y*OPy`nkt;c7K5)HrZv zZ`NVC0e+T~dGsWlHexHdThb%D`q(1Q4SXHnRI^6qyig+YwwgsR&NXc3s}f>k-8tLN z!M2F4NyXJ)z<)9Zq#9#!6Kw@BENv0Uc7ypF^C*ahf+Hb7$u-z752k$7`}t1`ixu6K zJH0{Pam@stA8A&ma&ayX6PiYB_bK5JFD;})Dm(`OtHrKY`+0njg3{_2;^zy^epoKp zf~ja2s@op90SLIbx8=j()soB8qgPp-0RQ;>l9FU~V0*j2=xTAkc4q?zYYLA@OUusQ z&d&=`(XnDJH+3itOf#1_h0RPxW)RhCVrdf87mQ8LBn{;BhPSX|uwo!({QroI2Dk6p zE$8y7;y1VtZOg4U6lpG785Ve~F?I+5Ujw~BR#nxZ?pv}P&2XtK&F+QJ2?57r2S}=z z7ABSMY(d_~m_4Wl4B9tms8}i1gkx92>_fuhnB5hx13 zZhNyaSA9G*zX|^vw818EVzWx3WrU)0bko*0E|N|UG#GC%XY`H^#>B2f&$dRS74Tj1 z_|MPX&wiQ2Z3tpJbnH{`@$tovm$jFFb?DKSf9TN@wJ-{E& z>v*zf`IC9oeurL%Yf2mBYobAC2gfHK_gZ<3Rs69<*0F_S;Ctt=ZE&3*_=?JJH+W=E zYslGv2uP1Rt_8k|AIYrQ2{op(JFrvA6b*@JaT`~&%~N9sj3zk%{X*a59Btguq;8Ba zEh%wk@mJ&3liI`4yOPC=r%1ZE*FuPL`s9mQ1O!ZkSVUo7BRbosnR8zy7_)h3<*jmj zZ%MS^pMvbNrar3=m$D?K%2-OT_|%d{*U+#3y7nwH<7A8JR4DEz!T`RY^?7XmIT#df z9$0H*ZwIxo*j@%YsSz%UIaUN-XRXDU3V0d+|8n`9MgxfqMQ0p!^#aw1y5)gycA>9c zE!4OT9ae0&0W-_!bW{FEMbzxKAjh85Kej8)DHvR>@c`6PW5t@9UF-#V|Ig?QUO5XM zQ(mi=FT<)hqFfnc%ydmBt!fsc(VhqrA0Pd_y<0N4jgXTVRW>`HZ`VFO-u?D@PjNtD zT0;ViH$!U!^pM-qcHjKY%L4>4IkD%k6IfNVjBs*?uj9IhOS{>X1iRngIMp1l1*Rjt7MRU#vogY5>}nJL#~&JOp}!x{Luf0Gl15Ai zig-6MUPNL6^Arnc+ZuCpK%94Gztx<_>NISel~S}QwIiE(6-C=Cpsma~}5BSf?` z3wobSeDydK0`%AKSy9`e^`5j(n;90lyp1tJ@RALUi1ZH{G%~7a=tj=KJ;%>kck zud~dP$8bja{r|n)Q>A!4+t}WtF3Vm}*%-z_Hpk1yrxXxCr7PetOh}r!njv2-MPtx; z=7+M@#0lUa_S&njBY+)aZfJ;0lP3!P1|j`s(uGnti;0aju>@R?qJk;cnwtMqR~`*G^YPl95cd$fZu=hK)f?7+ z=lc|nXmvgt)dB1`ZVeFt>s4nTuK0(Bg#irg-}wDpU+0?P!;$q&nT|u~@ARag2`(e& zT2j);a-FtNAQ6!?wjB?u0RjeZD4N6H8QhvfGqXyYG=a=!yw66SR+nQ7g zZ}iP)%ox@3(OKT01E&X*a#kbk@zId!*z34^Pn3j*8V(Q{qE^liCyS}d@Le83zI)4R z?H}T!KDR@XI5S)>2Z;2aY@9rBkG3 zwfx?^@;kdiytF~QJ5T=eiMMz$X)%k;I!6%>WxymfB9>VWGAAVB*eJj(pXd)2gw)NC zcgALm0ArZsMh_d|{*S{ipTy*JG4pY1e!gE07HuMu%tn~XVK92^h}Kt)*8Q0p!szzt zyZSStw#(|uK?1Qp8<0McHm-%UIu2>f$H<0*cm)`s!GY^`Vc!LGA{&^&#@$Nr@BE*y zoI}1)g=U7jlDej{J3vE?%XRkEqFjk0C@^9_u>;~JTqbelD1HPCeDGBacF8zYUf z=VO5TyEw5sW^w-~udm0Uik?Gr{@s^^s^T4gB1FV5E+1M8SFangw#&GG7{)DIT&m>0 z&-Q&U%bCWIHnd&@)>hwbE$vFU*v-0jGIP-xOyL0t$A>|u_(@|+PgE8Zz*)!Q7~wd- zxS|W8MwN7Tb^G1K83J1Q^)8sk9!^g+mbaZBVV+@#G zmV}nlG^LT$n9(0Fl)eUox5S)ijWqkW0r_p#d%i>Nx%P~_)$rL=u_{y22sO-C) zvb}ig8$}l0nAvisX3)WOKgP-R#1q zc)AU?y*2FMiD^qqPvSmzrH@9N)nEm@&@BiIUGfXJRO#QbLC^96POGALbIow1{KANj zwytqOs>%UHbp=zwsnV>37q8!tF%z8SNWyQ(&BVCtK#;2vGBD6K(%fc@1>{-3E(^7tDV zlz+Pj1I7QGg5qFb$Vc@Jr(XZFSNmhZX!wrg#g_7Ww+WN|S3a-qG#VHtj6PpY)BTX> z&rJKY9*nO-d=zI50LEbYeBiZRqqJK4Wno;I@uDfKE^fX2WZ|V6+u(6a!ZkswI-n0n z`EEDwdEQs|2?8t9-y^C{CtLUZ`JaHTWMwrl?UF$&W{MJzs}1@>Fm0{*$@8~Rj^8B- z_WNsGo(#V3ZhQTBc?k%z*e#tJD#q$nRgpHL)(g=Lm>Flwd+jz_Zcoo+@dC03%A5Rp zBwDWq6|ZX^h%v4ZK^>x(%;FE7Db}~=8B{v$_dVMdqhD`=^f(c%c6aWqX1r~u@DkFn z&)>euq;eVb_Qw2+U2ALs2>t6m2zwpw;K%k)cm#OWBW)y;$9zm$4$z5Rjl+G z;a2rY@$4?qGzA*_V&?|!}o-16@IrNixa;j9uu?Jb%_j0lM0YKL|zUyefrpD3-Q2n&t zEynjJ0}K#r{?M1oamE5!(&!r3U$;Zo>!Q|ndP)$x7p*y(ZG)#>UO2L9_uum8PF!qx?J<{-0$JpLI47*mQ$$5aD5 z)1^q@4&87OZ?L*~B2};qUvTC!qly$;53tk$*Hr>njg<4PpkU`eiA3#=K%!3ofv5CJ zAITEfxP3oWJhnEip-Ok`mn>j6>LlEBbZ1(lvtINJQR8T%>Fwjg2{;PRr@pD0SbC;E z#}@od^>p3$w7vZhCjJyCzItK7*|yJf=y|K7B5I2VSW(Dv;*azTw(e^{XzuZbY}HfV zMA2o47DiCtQ|F&++F(UA{M*0a{_W)86_2cM6x{g z*Y@XHLjfWfdnNmh=68Vdzft#3cw3{{LzF)I61XUJ4FF*up85N*Q6mpQivlsX$%fEFuHLGtzAXiCas4F zY=*6dm|6T?BVl_T;io@vyEcuaov>2vk`#mh3{6T(I$+L=BJrVKOFG0_B41ln=(v@M z9C1iVNnW%x)vYc|r3^^lkxY79zTXCM{~8gkwEtkR)(f};3|K4j1D_@9`p65HvJofk zp&*Z)^_#iKA&fmeC@UvR6A z<0XHrN3sD8Wq)a6M6NV=ui3PgB)INa9|uvrx8*sM8tl(q)#kG2m1>f9KUt+CuT`e! zy#sq1pEEjKY69S?@2bUO-Og8!l^0)KyCQ(WW;Anopx?1-*JbbX@V8I=Ym?WId1hwj zvyo=EJ+Hlh))b6S0W=Q}50=9b{dFcYG25x}7nV`iMY#hNk&LS9p($oM>WOW5A5+ap z;s|A=ZrW8#o_A5d)@79nLzg1(qA7{uC3#`^mwBd*v!<>hiksv`oWf97wH?m_A6Cyx zpvN#P*MooZ=l?&d-ZHGJt_v4dK^j2;32CHLx)G$i8<7U-Zjf$JDQW5MZt3pMO?PjQ zhBNVb&$+(uFTXZx%{As2ca2Q!Ai+^{HV%P!*<4&4ympD)1TF(OfJxxH?WFf%(yr7#VChcRJifNuvDfPVBeD>Qw_w6SbKW*13th+Vr)|C}Mw4D0v zfYsGE_xGNFkPP6m-x{AD_l46;)Z*G%@pCjI6`j>Z_HPHf=!4z(mY2x@4cV_w9oB&c4llaqU?nPwWEwssGz!F+p%x<3(@tæuFX2ZuMeft1lLojBrgrUXj_F95^Z0r< z@M0KCx@zmIHFi<-Au3&^^p|*gG zJZ4;7s4TM(S=amsu%kL>ZoF43ejdA05OBda`@gfg!V+Am1iGKB&6S|ldoxO?w65I9 zSPy<>9l%7qekhvxOV%rL6omDvN1`i?-{N4nRXt#iJ79J1^D1>(bVgzo?-%uok!Od) zYKrH@oN5P<2!3f&^FdNj_>+fcpwHnubeG%NRMe1qX9f2&qa~H~GaU<`RIW6KUK7Q+ zXOv{MBu-#Z6)Sr(=2e^0oVL|A_+qzfETz-fBb=M}b)NX>qoX6BS)qJ?=l%a6?~yua z&BAP%0eq$LU}q^T=S%p73JP&EzIC_d7-E!6#NZ6g!Vh{v@a_lY@PM0O)Wcym+Eb<@ z$>@tiB#wP%=Wv$s;bl*{qI7cIyDt473)ZbE+6*H{EGD47rz4eTp=y2rB~-}Wy@!pb zv1S4~x$Z#6i`go_a*><-CPi|w`bl2K3ms(9cHMMOU`qFk^4P%J8d^XmA*YRFT(~z8 zc$`B6xPBCrH!W^jRT&3en6w8W?K|-a;wPDv+e{2{k}^wV>cKrZq>xb6Kni8n_b7uK z1CHk47R^@721b8-9px{w3`o@C+2e-xxIo1k;L&DiiiNyk&t*4A_7KmW({v?^J+P;|v-=dU6+V)oLHr0#z=D6UX!o9cz+}Nz%opzH5LGp#g^E*cXDwabk#{D8zpmFK z-c6sa+&h1;-=b4CLpT!|Zd~zIJ7=p0KM9vQ*3{HguPfBZlpL3EFT2=)n=;L#DUscB zJ~9)V=zelDzI7iSprHjaiLBRGTX9=?+l;KZsu$tZOnqwK9ex}Jl3$Q zt$D$wdoYA_Vftu*4m)OEII8d~?;5L1yOWfjeVj#AJ-^q2D2+45k;Fu6T)L-10|01- z%o@B;5O9W&qdY~t!0_dL4}Qqw^N#~*1{}6S^>Vm5F(;?(tmf&+Tfxm zh5hzWHY>A``v7d9SYWwjqgy{U<>Q`XDPO7n++V>sBcnspV$5y20KqS^l_H`?#3w`E zR~_GpZ*GYZPBRnn7i`0KDh8EBK<7q-`f$=mndW`(b$bL|%#nGAgNJ84yx4pV%2(T+ zNRZv~^>)<4eucdW_A~6})ghPEjbJkD@-J;3%kEPubXqmx6LJE6)}FUXQ67IM(!7eA zo9|El*8DXds5tQ>enX!*K}P1LZ<{&B&0Zt6KRMe=xcM2;>`tD7zfDNfw_Ho1m{kvR z=!<`xz|FS$N9w^)b~hAK?udNSN_XuFzIhp(q@|%ry3H){To%wO0AH5or)teM=pD6U zCg={toE3{zfsiQKVO#>(BU;;P zEE2UeHL5MHvvO*3Dkl;Kx#ldqyy+bZ$p^j9$Gk7rrM^x6{P^+*_2!w%0;Ritma_h4=;oln&KIDgalKuD4A-{aTQaoXot=77KS;f0{5%MR;GORn zykLR|y{Me;uNmGFGzFWN)CWd+o*SqUIbG?cSy`Eti%F7QwWy&zzwm^d!{6|yBfS={ zw5qnG(`z!T;5T~HUHH;p5+m@rAo@x@VeHqgqTR1-U#IXS3xT~iT0%@@%oXXH^jauY zpI?q49>8#*dX-y3k6j25X{m+z_?8j4kj*qMOc5byc~b>3k{v)sUuL!Brdp&esHTRU zx}RR{HGSDERXMjPoyF*-BEfF8P-$y?MU)gR3zO!1n zgX#i^amw)M0t8^a*|YL=Y_&B4p8eFhcX!UMt%uWp(2gp9$W3cI+gEGuo-S&} z@4Kd04J|3ttHsTHopSG=Ivc6AUN~LCj_1F;cGh_)F^3NdOf92#x9O6Mj%EcS0;Ddu zn_D>bvJ-TqYy79#u;aoHVYW#|K<=N2#H0{(g%6^15e#CRv{`}xzwW?CqeZw8{ z*w#UCco@brKa|K6Jne5ME!jX_94Utsi8olS%7}~~u}&TC63VMkV;O$j-pRg0Rjm`C z*BmeZl1B5jsIjv__G96&;Cj5$e9;@3qB&E43%c30y1?rSW-G@C2FT4AT_4_#TyQJuUp412Gy3_7=`(~@Br}ve^ z-0{br$C^l8qT~4}PW>d&!#14?V&lpd9}!+Z!YF{8pK+UQqT?)W>UDR*sjmS?M=2f~ zWJH_5CE~wdKS_fX8WDkVeqq~%r51iU@t|w}*L=kIKIejt_Y29)8G~i#i+km<lK1$h`WlJUYXPCk zoOt6=6d8&TFGPAc5H9Em0xeW6);~ciinQ}yKvoGK7{-`U2|YrRE`7*m;6QPW{tmV+Lz0qxp`bL%Yu z_Gg>d9E(>{!@N*7(6hC9+^rL>cMv`FvIP-1?QCmmY2i}GpWe@&Tl=ff#kI?mWal|^ zN}AotogTxnD24K=`W&yr^G|)H50yFrhL(#P(w-Vy#aHzfsUG}t>EAQeEr{bsl!9U7 z*0aJX2j7?)m1vaql^--fXe0gP^#IcNq$=njcXB#5TxxJE(yab@sKax@hgN)%>4oz- zP9irhpXogi*qTz6xoy&oUdn z`~Ief9Ui{Bo5B=TQ{)9L!YOaO<`V+aQ9NbCM+9+xEu_Ej7EJR)zedOO)5X(GeZ}lu zF}M?DvxnMXsrP9`F-kw|wN+U1aMuxM{GNPPyQNSPJ~}hglOvO)-t30;j>AenOIwtd zElb%(gd*v-e%rM!wa4rBK&o0(Pi*E@q-N8vOLG1qf3@I${loh^WP5-JpZtMAI|<}? zBBpM+7+fdF@hfadfE>2b>9)HXa<%$!d*qxLEvbY@joaa3h==w`1gH2S1}SqQ&Q=6f zoU~NcVQnP&d?E*q5(QYxIQlaR>KRJ**RBcm(0jhjZd7ss)hQ^hAgls3ob}qN+U#N! z(G;6m;eW<6an%+3sSGEDO=oK~G^P#MJ)*v5_X8)M4o_{R+vZmwfs*p}_D=4&NJ*F6 z{Uj3*XxDG6UT5?$Jq(`aM>CKddVt6;iT_nh2kiO0M$f%Y^T#{i23x23mBm5 zqd~QZ5D6k|Kdgle$EtnivfIQ`TfT};d+0PbGvmt1uh;NTm(Z%sVukzLtBZA;21~J| zV}4q(msW1AHk|IIxFpUjy{DY8sg(|J+t@<-Y5u6C^O=o$Fdi&o!9;dkLHu z+tgalu)MAZbR#bp;!bG(b66lgt`+IFzJ(C2f=glmBTArcHHc^!yYXD z+92-*5Pu7z%f9ZNffpK8yLPAK(dxsT8V4Tx!Li(EQh7 zfyhZ9GanD^A#@L4kK{=ux?8ygWYX#UOp6mB7H^kzhk)A5SW9dFGe~CngNCk1{K05| zqC!ygd1fa0Z06QqDwit$E@n#9Y@=x>RYUP8_m>7-Z}a{LGj{$!l}vi3h?RKTE*v+- z^CmkO>9>Ib+q_)f%SlKf{jxRRo`xyl-w$=%oP9&F#3;*{9{tIOTKcAb2N2ApWh7#ZVg*T{l|E87z?9aU% zK#n^MK;9o{9xE`dEe|*Qet&Bs4U!U*L}wffragszx#6$-{8Z4WEJ<2??N;@bvS6ep zV=vi_DGwjZ@O1bCf=BykR$Y*f^%2=y8v|o~;~^YpjJ*$qom5kv(iQHDKBfyfcUY9 zo=yOT0)KZA?fPd4Gs2Ep3Dw0#vYt2*El%nr3-(WdSNcAZIR{wuaw(X#p%dsB3p4hXvU zdoy4p*#flDtV18Ub<^QD7_?tA%gg+<@k6g+MZZk>38#NvERwN~_@P?|6H5jPiVG)q|E@3sWYUVfH^2kFNj%l;bV~y{fHYF zqZ7!#6aV>XFie7!ag)4rieAjHX-XI$^M-OSa}fKC_3b+lcp{k{x?Rr&YjV>9QN|;5 zWs2_eZ#kY=o)(m{XL)MvdLjwd?`z2K!hZhC67}~cn=aDmNP?Uhd;N`0v)j#%KdVf; z50COZFwpim6(IvE1fbkGn@AfSAFrs(FV~>5q>wBxMHKZ^mrS5mSvr?}?@pR_JD?h1 z5WYQLA#DhA;k83$qx||NXS!FI!(Ra(R=A;0x?&H5?zG}K!mTYFA#5h`bOWeVx2Q0Y zvLIpZbj;6Gqa$oKMjmFOIF79zH{i^PN=_Bv& zl1>3coe{GJ4*YsAS(M>1@DD9OuGxWSUfZQD0L}BV;h1lEe!iiuIkS1JhOYh3r6K=BzfXky4{OH}4Sz@0HVHUJS55UjHz-c^S(b%WK; zlf5}5fF;??F^E*#AODMl0l)d|qyr78m0Y*xOk6J;m%E-?AMKfSwo)$7d#vM@wHm(5 zq#X9wkF;!VH|V0~9($AsViTJ_AB3b^1`j?{ZBSz(i%TgMtDN#O2BDXt zdbC;s(Uv@a8q^bFa$!HfbviiVvfG8dONhUbK$(XB?^%EQU%!@AVY@E+sbTQPoUcuk%#WPDe&XS4sw1Ypw!d2^j8a~%79Mhw~0_cHn4IVpt9&@a9# zL#4!hEElpAfkY5L0(FZueY+kMl`2K#iTrbgbfmPHxC67~(SE(ul_2j23`X8d{DoR; zqW}L-uhhGT13nget=0zz};YK%lQG`1YlMMVmmsY*!XVbg<<9G9Z7 zXkMCPsB7wCbd%&|@|S!tL+#APp*Isz;roF`8=a|6_j6!NUQ!`n^~CQ>1Lj#f6GEeA zMOSuV2a=~JAYfQSlw^5-^rX4?HXb$5Qh$@ZV*JPI3JJXc`MPUkVnoJM1z6e-N6zIS zl%b^Yh#LfD^ymcabKb{hy*$pl({AElq#+2B$)M=LaWTuhq z+x|RKG0pA`27e7KNi&fo5reo=%7!44bR-1d-=9Y?u!VaDDpb z?7iPc8sw-09iR|NR19cmKvmIrX`<%AQCn=k|H-nrxW8B#$4=*ODo^}~_bReWD#z1B zDnR`YP!$)?s|59sd!FYBdgZ!3s7&B7kt2K<(5<^dwZ?f^ffqP0q*lt^$?5LS1hOAt zj{?TOdHeSV5La8+C+j@i|14|Si^p<>m`Lr?)MDc}dF6DSZ~ zthWh$VfV|t4?gX*Q1-_qF_tChk55>#>>-JjRp?DP+jgMv+rI{ZfttG=@9^G5LHUkD zl=&g+YBU!6duvY#9iV6cO$C>>%W5__6KOrS#Zp(4|7&9q88dTpgF0UEgaZR?kTgX{ zwslJkqxUr}D2rX%PIE?Ro)@&bt`*Ih>v@rpe?7bh;U@`KQL!~J`0YC5e5sW|*kSD{Wtdt$I9njLs2Anh_#?mnz^tFqF&Ly{S0@r;} zPnYQx<$wMeFpGo~Yt_CeJLbQ&nE@lm9SqtA{EY6%0_4GI*!zBeruCwt7Q$>joSaZ> zSqwe9_6;!~HC{65%8&?dpu&@)YZCUzDEpk`Ct(kt1%gYFNirgZ=m*`H&h+xBrk0fV z!s9-MXpo*WK%r!in9IPQ=PC&VC>g%ka3j@-mWA~Tn+t)1udfSmD z?$9p%D`1B5|2w^#Ytv^zyQW7Q3G58v4fU`wQ{KU%$sdpwS+wSf{8n&~q_!qnb_!#97YdY9;2~aUtQT z81$#f$fcKr<h2^Tt-*21YjY*E3W6akCJPl8km|+nc6+kJTrCIzMwoQ7V{4-JD zLykvzU6W$*htZjl*Fi*WpY8v4J1O4vyn}QvT`uu0TkEuQ{uhkl@BbJF+(a_xYyZH5K@JC2;bUF^y0FM7v!wov zW4RHWi~+RF!BCv&kR)cjAfEXhW9+p%o2c|ly>H_;n@V)Wd!9iTY=#?^%zq0%tmd9( zcjGN(DqkvdifgOf*6% zSN1e1De)}_2S?v5ypaU54?Y&#FO_s86-+{IJboJga7S$P((}$=`9A{;v>X{#@R{%e zLx~X(VZ0}I2t$fYr&X|Jg@PN>mpAMp0;9W)J#b5rvO8-CfZ+JrBNDK4iqt(07}Eu& zLwX6?PPRDHgxIPD&O=fIb=%ACpcV82toc1E$C3jEZTPpsA z&EI+x=qMSQU2j{^2~dd*h+u#2ycIZk2okuR8{y~D6YBW@I0V!h%T;*2jeI;TIZ|#3 z(;TTc#VV6x2%23v(49_VTfNFW_sSxw5t_Fqrap>#F=1G5CQ*;OVbL;i)#9r5UeFwU zoTPbW9t@}1F1@s;ROBLqlR`1L4fUt_t(pJEzm3)BLK7?RFd`y?Q6}v}N^YtL(l^MW z8*LJY<&%c)KQZn!d6Uq8eK5)DW9P{z6J?qMbL+!JDHl-1Yd?1E@9yobEkcKN9z)2} zZiXiNl#HvZss_QBLlG^x?^fWBAA}yy(2)n;Rz;(zs25$fit-KJemQC!`Myx!RhcxS z9&a_03QoeZqo*$$J7ETY*PHUuFvd^!mt$<{OnpbdbeK|-MiCIRO1b(6+L+{Ss~3w+*Q+b;OlIH)cC9YziN}Vb9A%?+HRl$D_NKl$5zO2=v4s(EGjN8p0maGWn!J6B-t-)ZTK~g*R^BD&$p$V{xJzF9S2Led&7#v|5P-AHbI(} zr8-pA?^KvpIgcu~YT1!Ww9x*&vE<*17hm&|R@bA0;*6s0ESTp|0Q6+RAcYPG8nkxe zU)1#1+z>Q&?69s)@VSwnzz}+z2zq%!>3MGtXn3vvy#XEZf3hmD`@sqX82)P%RlitG#Gx;CsW3&G|Qvx;6)y_5RnX_U85+dGC6=)#;+onY7%a`eH` z-V>91kCS>l0VO~Prc3|zKt-N1jZ118_K9Yxs`<|0p=VxxJ$2Kr8pkTl*y`-kwcB_I<3 zW*cgD%s%5vf5DI0nj|Q`yKz;+O6l{f)A?HLWS!{oSGD(x&-~@! zrX8%{vu{`dfuSzGSY3@th>BJH6W#7FCu!~XJbi_TEeow|YKu6XND_sp1Bk9f)kTB` za1O=fkP>%-W}}RzhR#ntY1hI;FR^dSvLe=J6|U`lgwli2eSxIt_*TT9zgF=yY-wo; z4cMxvAeVE_X`T|<`0N(y-H`;I|Hf^}ibB7^~emGB)W6&Bt0i?x9?`bm@Zr7t(m zW|?an)$`;N(cM&4zS3dNRt_0R2Nm&9WGt!2EiQYlFz6duU@1*f67Djg{5L8mK{0dDVo^D?#4?4-2jon|*x=+Zijku1&oX^-+wV$3*6}iKtKZ9FawiUK znwe7ll+3l|i~l<1ANe*cpreDygCcF@(&6~vDZ*Adku?m>>x8dJtJY_EIrSfjA^X1? zQzoTRX^i@evFYT67``j)?NKG;zlfQG!+6`VF6<@m!|ECSx#eYB2Qe{sKO+s0gJvX# zL5CZLM`n>hPaG;vY-Z_?THd8I(-l`$v=fu2b7?rW4#A?ZU_BYqls8w(#=xuOkuMz% znele4#zqD=QvP}!9Lr%vw*!VTvqoqa>6|IITCp->hfNOpn#at=vb+a)7DSMZzie;#nl;i_-S3fbk9g^ z*yjsQPUVnf&$?A?4x6sV(lsqetJBlH_XyLsL9^;T6w%u32U&E0$(IiGyo99XOgj}x z`$$F31z9hi@ZeMWz0Emmhk7(IeK9rlr(bZkS?FQh=+M1lxa6%)1hULs>n7h@?|Z*f zFUcoG_cOpK8vTL5fc7eO0`9DW*`wl?1pcUtFDmI6ns`oH^6M(?m+X#61ep-Q?)X;rbiP$RnEnA zctG5Fjd75=f{`XZ9iGw86M}xKX-j3?;KQx~uu<~$N{;n;; zDGH$C8EW@4VN&vCTEZ%KQTv!zz11UkV7O2tOX#)o;WJ29T2Z4tk1sgD!QYyTWjtxX zU|eZPYU$r2@^)=XvwHf{w_u2_(1A!7`xz%7ySPC7(sd^#e;ZKs+zuK<^4}x@_f1j` z+Y?U8PV(CeeeL#nDv@w3H`43kjiO#6Bc8|*!{8_)(H@lQP{~xkXAo$0)C8$Xh}VZfvb`XrC>Z#Z#CYw&?A8}+khu|u0a;7 zkhLx&;Oo9j^{Y5oExdItKbI|@bU*OeQY&~XU)aFP#!=Bj*a+QZ^iBvObPMhZ!;ZSt ziaQZ_;wK)xyEhsaQIa;UB~darLQNupd5c)y z#Q;_n2QJ4C9cEjAcaqr`YW_V!3 zx<~``e|WGEjUA&F%^q|ZyyOF^MK?EaI|qwTX!UHF z7ulzdPp4T2P;XZoXwO?B7Bb8i%)6|3b^9fafLdO^S0%p#QH?6?-XYV8a9=nd!X9X< z3~}=U&QTf<=6*!;z!&CP5uPy2@hkIrbfQws*C-wDS6B|j6o~S}(!WpLhL8O*zU}<# z738EPdaL9!igtZNKMNzB33Th?p!xE_;doZI-BqP5FK!!|AaZuSDSO) zCRfgx95=h(_2oXrHC&yr&8P#GT#Vmw^zM45s-^~M=HkQ?f)LB}2N|>F7<^TN=o#&Q zf@w&~$cSRd$z}U-`CM`C-4)D?IwQB&uNhiEETt-K z9Jtkm@q}|t2y}LSuCF}+`4onzcFS&nzBc^nkU^dTDIVWUY`!FdoqkdKGSrG=m)&jy}UY6t(MN9^e3qCj}e(u-3Ao<+cQty>N+K zj@`Kq&nK>S#00v5H{Z4!h|z@Bj=1bCrIA8?f zS9~XW+z~sN9qR&!eC1ZORNS4@URAz(O%3bF@aCDno`XJDSzLUbzE zh$-=bA@kNAAM6ZyML_=y#J8PzwhAKHwh+OhCaGF^mDM*>-_4D94|gs(trt}e8%OaO z+szrp+x8GR|2teFZ;o?ILd50)oQ6cC8x1MQ0+5lG(V zkWJ-PVXtLnwEAihEc=Qknie<+E`N(6NZ`EuS>Tp&YwG<4UlGr!QOuV{lT6eLY&=0E zMp>WA4CVa{793`H2?f8i6@H&MC_uITXROYjyJYBjIC>>rmeGS=qGWd8rrlE{f+QCR zm@VGQsOGQAFSh+bbR(C8pIfR~JPrX7IiVmf?mGy12Fl78AdrOr2^PWuF=p)$;eEXV z!N?+d9Gg!7frG}8T%x5kZ+5uf1f6tzx1;~A*-o4s@`M>ht4CZFzI%_PS(%QC=)n$?BfU`aw zghy)?uehsJjbxs-uA1SVGVw1(}Y4&#Gn=VJ-%lwld&Tasoz z9@mqbsFsY<4y_h9mf?+;S3L0sbJYGw=>0vCMrF)gyaI+crvBSAPR!QbR*Mg-_D?99 zxXaXOqW$n{Hpr)13uD}xNV|K#4Un8$49i?+)V^|K#QpIeVxZV9by5%r1sT(=xMie%#Kfw$Q8&Z?SxL0_WbV z?khe2A#jAL^TM-VC4N+Lg2|P=k;nyy<&qzP1eT}9GTnY6uyjPrW!C-CZb2sa2rGtL zZDL|c=JBJzu0i1H7aZgbXO~-t>|^g)c3h1_{`#^-28PN1U~FJ^6Ku^$QN{M@(^=ApzJF(|M}}r}u7a8Kx>DrDwcopg{m2f?9`tgzabZ z0CLOm1lH@OgwLDy^*gM3KH3aY6wyEiWfiolcp|6f*`5Ftauk@DX|yXV7Y*)c&GlPC#-_5Em&jX6#nT|68IUR_O^^z2cQ9L? zF#7^t`)3>R?=Kp&%!9Z6UOBZzTSqulACwE^3ljUL#Jjp?e7oab3GoaRY%-P|l;7?` zs(hPhDrb^4q|=xaw&Ey&HK)iF_V}8gEE_a!ZnMjCeceEx*64-dwD0iBd&y{!@5+?D zScmIs<=A@JyZeZx*1~;96u&1uw=pO+mGGddV={lD*QjzQ&v44HFFces`?*o4%H5|z zhLWt{7I@;J)+<>#ucp;;BrJDNVUSdr5y)!?Dwth8iFSEY2qx1Z0=H}jjJ3H4U zZuUKWnNTzk9>+Fl_G~2uJ^Um=pjf{n6bt42z;HW|jn@r2v$t9Lq#ARtn)cY&f~+ka zdvQ$U$gBg~+JG?Kn(pJHB}>ZB!VbvW{A&vZc-^9InzcUkK_o&<3GX_+`G+fPE! zIh4r5$wtI=L{;7{=2R7PX|5^?6gI(?895B6%kwhe)SfQU7^tyK0sY6f5+>z%4mP$$ zb`UTE7KTuR*h6?CkMBTX#gL#MLDnaC;~$@XvC|iaUN(viC$wDV`6tu4uKi=aQ1%vR zh*W;0XN@~qs|eK%8uvvt|g*Cs6i9V6b9N$eIa`j1PUwZ{GY>_u8V_KeLR(P0OFRq(hU@W&!z zIDbM2K@vm^kZ0GVk|&8I|MSz|hwGG#9y$M$f0ew~x7Zp)4}?$g4%~i3H=L0HqrSxG zv;H7_K6;zp(51fx?2i+$oORx^$~~SQ^w-Fgird7sebOJBi!1-JTh`4{8idR=U8^dZqP6-K4K5^>`+h@a3XDSe-{@Uz8_i*tBO*Dcjuz<+sNpU*}6pmUozpUCLlGqjT2nBbaVeK(mFE^cb zuoxc@f-ontDBi)^mP=1|M}eX3(g%hxY{sqhf9%{5E!D2i_!? z2u3}uGRG!{y))%5WS3Ga+H84O+OhB?f?N!G3D207UrfLEf~6<3*z|zm8!@XZGcY(& ztKl%9PE=Og1R+z8YQV>!^_Vy4EOy z|F}yBk7JKd&xiY8VcSL)?xoT#04O2W0j~A%@FL`;y`^+?Kd)*{1x-|95o!lotbu+M zHBnLa$5q;6?c2!xBjcXw;=8|4>&*=`kEq7hv&d7gB+#U6{!l!LE%k_qmg7$tVD!cg zi{ej|1G40`J@b<50}^Dk`keauzN@UeZ}RUtT!v8d8VG?_zx`Q+5YjqstRe`o-TS~? zW90umfjQreK@}aALak6WQ?oFE*%b20yv#BTY*=Ja3qC88W>5u`e$vPf36nvjapv?) z+fEn+vLXwXu8Is(M46a9LL(bg)K|cR)wRcFuHNcJ0K%gcUZP*Rr#fpe#A_9@-knAY z*qrrIW>%G?g*O2Jz2}zxw)TnOW+WR9LX6GOEMa41$08&+z2MjJW2jCPqyF}^@%2`w z)o_ZBqim##J(BkZCsAwR8O8t*r%B{0c9)sWT^Jf>W6{XF_{ddj8X0Eclas<5Dw-*p z!S|Hg(uHUdimJa-?Vpqevy4^iy%SjQ10tta7wtzvZtF(p7X>{8PSI#z8x8#;<2ijP z+8W7-jiFWU&o%u?o<7<-Mf~B<#Ay|E1_LUpA|7st*T?xWTl2k(x7oPt%jp&etcBU!qJ|Vif6%a)5z^Tl0f4= z3uUtNSZZu(bMJA>qsHI4ZJQc;Z!c>`M+})er7x}bf7hqfbdCNdb0yoI^=W%|P+px= z3fTUAEk<}fR8mrMswnyO!VOaZ!?BzE&L?`D+D1VcuZhIl$f7OF{+6w$La#c1WfE8$`CD-k1BVRpq| z{fhZXe3Czt@nJQU4+J9q0NJV_!Ty!Dei{7KJEHv-&1^_mExD+_#_FC7D= z2Zz~iQf>1KXum@qb!J(a{`hOlV&mqFg(zlb`#ZF!=U5QB?xK2~#ExXt&~Keb%Nfoe za8c#wP3^tMKt$mQZSWCqCN(hN^QqBeLiJNt{uWWeT}CPr5x6CadzdM2x+zDJW&k$) zfarMAAH-=RAB+z;;oxpw_kTnTQ53=!d3@fG{Cfvo>)Eq!&m@EemEUxXVYAk$jmeQx zv!cK&A?y7XB0}OCN0ueGVV;B=*ue00AQ`Hw(LTRZR$koQm&`u*e17p!0c||rBmL?@ zY598Dv&C_4jI!xI+F2RtPv>}N^}H!GSgKH&CqBDgtxhnd1rc*7*dZ75WeT|dr+JCDbB;<$~dVZ z9iCY2-Dmya)kBc^j_peoN||*ujgZZsbu-4PAo`k559g;exddl~g%E~ONbinv#tY9@ zH-WF}^Ek8Zf(S~`4zL%BCL8*yvT&}>mMnXGluGJXYiZqbJiGP04RoVVshJ6(OeQS9 z>uoYFO9HDA^V1fZ<w8d{uiOL#Yn+e6q@w`)IJu_5Q~o}Xm8miFR_LolB%*#zn)U`k6H8mjg1Vf5I7 zCSOKE;jHQ&ZW?AhqCdt&ITgf4%Hf*gm43NkNGib{ zO_4OT&Kb8AGiCmpGb4M}F6;PqggbKLIEVyhiUt{bum{Qubdi;{@dxxi#PP)sazY(a44@|@L#4tpi3h~&QYabO5# zPY(CZ^J~~AW?0E-f0HPl{KUrnk@;&7Ex--I9!itB@oXy0^`0n`Rp0BFK*@4Pp>=La zwh|HplMOgE{j7wv(6i=X{1h>6YUFbX7W`VGz+H675ON`20bv>m98p`m(A9mIpF6Gy zJ_J9MXg>#=&4JArj&}=2V)rgCJ0oSmTps z^7vxj>4EzLY_k?p*1W(DBmp>L#%XH!r686GI$rrUmcsKKd7AfMuX>=vx_vclQnE!BpWLS>hCei2yZ|is%RTE@})fNm*h zi`4WY1|^fdHndTl^kL)#JG9%ZxV)U&1Ck3eRjwIcy{b9f`KAKtLWnT+8~4eJXw&vv z=0|ybA8uNS*AlR0Ap*nq>6=#iR@F}jJ5Cy6OT;~^Z+gPHT39-?lN-(x73ixr>BhKl ziath2_yfW~o~Uv7QH(i-p6w7P(R8geYJjm7|C?5;7p*~e_-21$$r?-A119$8^H%`x zpLGW@h2E~~{j{Y`PfHehawn+2Uf{u!H0I6>L6w14js(PLU!N@-vR2DCun= zb(ufc;#m8is*4hnU#~wbF)^VWo)G#!zes$y`Q~fpDDj@@OF{HQYHCaFuZi68qxh;C zv{)H*0r}D>F-H!FK1Nzu!blxVpsVnYCXOEX-e){pWyTU~=UVhlH_pTRfh>yuW)5^R zA}^T@^`&ULqyuNt+^wt`=LFaiyHqefV6LdY4MZy7yZj^*%2z*67Xyl)%$D+mj*y9U z*!&DT={GD*q@{QeG{L=BZv#6+OU&@##+jI8^j?TgvM(%1EeT^hPP!Z$#h-b5oqQ^o zVg~koMzEo%)^-!VbkPRzlBss<5owJ^ko&h@McLW0n$>VVQAWZB?WSl@Z9n3ZQ$JDh zO2SQ&9Kq)}=*J(X;A0Wtbr=%Znim2H8N&%%2I3*h9s&Gw8Om^q5?Mk4&t+K0Iw7xW zJywx#pz&6#Q)-{LfUa^gjuFxxB;a9bbD^TRfDyu3++1cW&S20_S zWwIz7mZIrC-Sx$vRrs$j3fQ&_gHSjZ5M%p`*+{ao?&jTZ4Q;m927i#va2-(?=^s!f z^M}!v?0T}Q1pW-AJ*ugeLi~?!e{_`HM6uM?39@RNhqx%`)k_nj3=N#2Vn8nQ8;yn( zg6H>RMbs4q1uvQqrH0m`m_oi zCosf;)&WhGdSl@=Gx4(~;?eilq9(GeoZ1o5h5v`9vy7^;YrFQXNJ@uvNH?2qknR*w zO1eS1OS(b2K^jE5J2ukYA>G|A@GYKqeE;~h2jhx$oiXP;$m5~J#SnXE$xzzuF3MA{ zw`zPLd@j~C<8mjL6;HcKP86zqEQ?YEuenoHiBkWQnB6^8<~g6i*89$0?BG-&aCdv1Giu z$jLhhsWW#hIQ2_Oq941+I&K92b9Kq3{FvSdsUHU1=%%kDjfiwFi1UEslDubKgWfEzb%ER$#`q<#Tu$>-xjtGW$_rKoaup-;0=w&4cC zcf@KjNb;|W+-LcL?enOX#tWobHQWKijE)!dhucZe{Nxg|D~a$Y{jlX(yjH}?*XD3GDi3MqUJ zBBh#MK5PjKp64<&cC$JzcEIoPBJNidI1@*PnrU+VLmO9n%Z0IVx}juxS)@23yd~ZA zxLH^bIWXF^omv7Ce;LHY{J~YVPzmQpCg+UALlxo7ZEQDBz0WgA{ZfF_A1|RDz`1Rg zd7wf-zb3JiPBtZTDS~bmsPMDB&N>Ywn!LbrkfC}8v*G|NLzl!5gVZ}q_;GG7`EnaO zsA-D??w-pXW|A<4RJu$0Pj0T8KfBvS{0&WFRIYm=$5&RKItZC-t;r9P=8lzN%X z%#v_0MnLtw?kG%tK02wDvHZa3z=Nl`D7*`kB_0j$A9Bc?U!W+S6j7yk z6*3MP3K3%=-!F)0-XdpX=0cCb|D}%27bW(BN|?qF$Rt%RpGAP${xa9v=~w8W7*&z zF4TrDetV#orQ06O8imEx?ug`G?km%2<^ffy&t0g}^63ByY5Q8#yn_j8(y&R_f%1TTS=X+zObnp3a5cz5|-^pq&1fRJm$;?w+SRr;oHYT7B(h^*R18g&wEFE>Hp zH+U)mnxvNwdRuzXm?gYlWGHlVIjMvZ^ge0>U;{>l7XM~F(U`ph7ynDGvmjyJ$r`Bf zS|CleJSI;<4n?z;l}ZVT|Lq$fUOwaE*)SL3siW?{mNWZ`)h(o&XdUy8E?(8K#s$K| z5ppn-Ta?ZNg)>J|7PW!s-%_(M2=B|HT>QK=#M|yclUfvyyf13QtStWoEs>1ogB|#x zcEHTEClFPvl)mr)rzU_J@nzo(HAU60(_SH(E7w0yAMZ_ecg^Jy@?>|(?0mIDI6ke+ zXwP@{5nfLl78fjq7OM9FdWUoW=L38^GG(=1;5cr3_*V9KT6-Yuc@(U4H)JYw@#pb+ z@#KDHhU?cfJ^5*WUhJ13kzw{?0%fUH59Ul#gAnwO77O3ikoc$m$ctGS;z56z=`S|H zP$4sZ)Z%LBitInq|1zERsLbE|K;pf5n5jr3BR(I1f+PtIXF#aU_cyk9`V3v2sydug zp0BaORP+N21?D8vrKVbtYk?WG770>$HZk;zg!C4#`BrY|lH^(rbWTL+B=S|)fC>4} z%k$5}0Xlqx!@rerM}j3^o~OLFjb}akESQXnX9Po#(D7?KJ{grl*wjt(p!XG;XaRV~ zSmvSy>OIMIpyeyba1I&}vzo7g)ek`6)NaV;2-POM$I$i1fcvRRhpu8rxrN}b`iQU* zl{&UIj)G$V9aH<$%B0iR=>1)vcdo$K7!S0V{7u|t#c%L9nsijO6)BKt?la91tR^Yd zkcuxurkoCf%opV~DoAgZ9cW~FbB;L^{1rIPZh#Ds|G$QtR1m~%Q$dpVr+A~BwP~rulU+_B-%b_ZyQKtd96eXRT;6R9)6qWD$ws~^jAfR zrXQxQ>kYX!9pu1J6lHj;5H3!ho$FAgpg_ z0!fO+q_7NYlF?(Lj=;^is^=(0imZy64OWV06k;xtz~k-4P>NudXm&+?QY$#~Cv4N- zkb*G37cJJ^b$$DAev%GI%E`EXDEHhdkz&$mI+Vc=0uiwC&~7$)wmr&5`7kxM&<#qF zN$)bc7UJVglMG1@accGh-m6MqgL{FHsCEtwFd8Mix?VyMN+&u|CyCUzZ%-YYg5} zG~Lg>=G`NMB9~uOV~Ta5``O^5LEirpLa-sBQgfHY1+!aAcqm&;LgtXzySQO_N8dW z61r&|^|EXCx_J<9`%(CH){~aP+>n4zx5fa!>0-0_jVihS?kTRUsJWpQSDm$fs$WG6 z$o6Db?~=!aYuk2Br7k;oKi1}!Ns1ou$*8DCnFhg;@iThtS#_U0Qm>4j)ZK4c&@9A! zpowt(0{2TFhgDSpFZ2hdOt3tc99Nd%W7E~;)fGn28jX_B-R51}j?Y+4X{qWyw9Gh7 zTG#%sd9MMghQR${u7}6o)92jzMo_dqy}j1|cgs9A0`E-HV0%3HAKO?4f#hk1L9;(X z4n`Hxv(FW2NeM=y&$tcVf~r2a>{AC$1@akPMJgG$zNBtlcq-e8AqeS_Im37{2b}*L zmYlg+8JE1J@RGYC%8d!e=c+J{8Ic3V$wDMoa5dQ?$1*jtk7iU9 z$k*q=FqMOQH7%Rc+4<@o{(g@X?`L~?w6E{0pdeXLR|<@Z^#rT7l9H>%hhWfQKqdbr zQ#aFK$$&JEqa$MZ{nVi@*thdGD_(#U;R${J#4%a*6%o41I60v|4iJIV^71Qw9O<6t z{T?3k|Nq|Pc$unRq0nyb#Ju8_)YkW^+vQB?Pz zTITtb0x}~i?YHQ!mt5Xg?~G(O7ivY{lAkd6GJDET;*GF!5Qr3Rrx7h&CH16H$IKx3 zwU~z`W6k{3;B5HV1rag7<5XP_ewCQg!G=Qb^mzwXvXWao`nMfT5M;f=oDR0s&Hp;0 zpW#Y?e>jwJcc{Xyay0(TkU6$=S9KY9;!M0)CRXIl8NFv{w0s z8;R4bm~6hakpN3o=^2O=2XYO*gf8dwhH$F*4?*s_sQ&*^QK@g3ifW1SL}3LhF4jrV zgMw->X1GlMB5^ogE?;pHa*X1CTCgQY^4Qe^OEcJkh7sj^iG%kFsIhp;-gebMP#6fb z#kHrTtxMy%yuI)D3VAmHAnfc9?#;F8v(DJ%%gZ&}c24z9ku=;|1EF&2FRbnCLlRQl#2@_0M&~DuOgYwJFyG?|Yb3 zyePtX3bxE5S5oo443 zhxkjt2G^r;s+j@H8i@T}6Fl)^Da>#tFl~KgENeJKYC9WVYyi8_hjL&TZZ1^H`UZS9 z6z74SY8__PD*Ow&Z~Q*cFEND)lyns}qo||?njI2K%ENOKa3KX1GvSyy?q7AP2I=P! zS=s*T+SMaObjmU4F+2P;?nTS%N5fAJuZ{qB8vyuR2*v8bv+ z$ZFcaUC^iIa{7;5N!7^%*+T!g&r97@$4^Ir7nVlpF4cvN&3**o?%{&bngbvN1~z(!~Ym) zeq{Y*luAT=jl7gGLHrC+=k-U;lq#OfRf1?EaK-{4BO%)Xxr{^(x#0fW{Hebs5VCma zpN|{&l1ADKKl#OFiZmT5LaPVf^n}oT_chi`)ytBN8I~x>&6H}@6qDuchy0nRRWD@k z(Og87546XQw*KfU7YHv_P32grr_=w+c48FsE9CttqWSi#eD40uzKahUNHTRu z`P2TmWdr1a&SCD2ifziP);1o5?I4Ea=2|Wnd?{mHcRPb`g`anxZ6B{@9j@n1FCuL` z{Q-QvxG??vV6pA#it40sGuB2Sjqj@4kx!vk6Lyi@&}`EQt*sE!^`1(}a8%=8?8@^C$@?0q@3L4M93 zC&3Tn^Yi_H`Uf7BJXIOSK{zr5QHxsoMHeg6jh;wG-L`aL!DkxPevTK7XE2E~EkHQ9 zW(Gr$e2m@@ z=W1K+)~gxA<>@7qkE0D}J0OfYTz~4&Dql$)QkL(5SZ_6P3z?7T^X$8RL(Z5+lXUm- zlrgrqbGA%!b2jtP-;$vpA>Z??2Iy#z8vA^PI) zh$b7$DD6O#&Zp`Z7nO>Wcy*)CAvxu(si}|Gn}AOi06w&!cI67C5jVBp6il6#BdfgNv7#N5_Fljhl93l6g@W|^hBinJ| zd3uE>GYZwHvN{PA80DBV~$da7@0 zlNt|>b!`v90ows{1DFOtx~bGq=Fv@c&N( zRaLJ`4Z8M3=vI<0YDa$3*MS!cVmM1%-#^%k#~z^41vqEg zW`PT;A_($w7lM|Y87jLE%p!OO(xKS;lmRMV!0bRK6?H(j{ZI|&~SZBspO%H&*pkBf%`fr+eI=%2Cw+HLU@36 zoT6!8o+`-F!YRhCwU{neFL~h18J8cNn0%Al>B|WujIM1;HcF#;qVJ#ctQWHsZm-Ix zBxFC*vzhZrM#GUUe$D&K4w~Y-@-VR37Dq1K^jGrQCnJ=etBZ^c1BO15mqf;RwU;8g z<;dE`a6CtXGOl>;OaS2}m91{0`~3(?1R-~n-A2zV+v!iAFZN5yPdA#6*Js=BIa%6n zG362&w}3(XXKQW-m>z=Ew$6Z1tlhoiD2IE3r!W7}6LG!cBwzjjWB0unq9Q7>sgk`l z8tExQl{20lk%QqhZiE2SE5pW7BL~l`^?H&dYSX-X6P*DWR+P&X`+nh93~R`B|HN0G zRF6u_9aN#qY&5&hyPZmh9mVUF=MTUnXwy;|?_@cvLXXzU5;sJ=>Gsr2wCKGNSeTVl z-X5K3@K%-%#Q1_+hy9WSz3g55@^ZhEB6Z*ZX|p6rI?ni{ZQIb7XSqJh>$+Un`SB`T z*m+6nIGxLQ0i)l@Pjl%H#%qeWF#oiYPjMhVdG8$(!fS=z3VEX<HlZ=CS+9hEG=J7_Pf zhq285-t>##(4L=N5gx1eKwD~di5oU4zD9`wk=WA~9v*Jb7G{_WX(4uC4GM!@prJq& z*MIYnDSU0}vNBw?HJBpchD6$O?yv2#~2`d3mx5i%1$v&8LbO0y+& z)Da1cMo#%ks_986sfhRF+i*RGku%AQUTzWhnoI_vq&JM337r)y`9sEZIw^sl%b+sE zI8BY=6Hr|h>f_<|D<2a~bKPGl2TIe)P-5P;4PGBb+n;vQfa<@g_0irOv{95#mw&Uq zR2smd313100_8o}*AUk)T|15N9sGWZ{_3)%RG^TRXl7%n6+gO-V2n4;gq*=m>nNo& z5Hc4yRnoi?4WQ}^Hv*f!yj$00RZvyXa=VPG=cOU9c06d8%llzYXraVMicK5x{ngCACAPMWW^q^Y$)3D~Baj{;0j zzLNpA4Q?YS)~_{xoS^rBTMm$%}of!G=wTa)gYPL zyVfs;R6+kzTzs>M`O|HIU(D`xq@9trE?uCg1Jl0`n9?#6Y`e>o!<;94accB|ClBK? zW8Ib3U=&a)QJUwt#J6S7o2_h`P?8@CW^GCU6RAWOs8z0Nl>#6)i^;-1uK*c)ZjmL0 zI@NV>{XqAbkKr>@Az=4_q9zv10;O6WmT(7Iyw}2`9}ldbn|^`h@LdBrRup%JiCkd? zM{fC#7rEpPO2no4Z;^DcCDZ~jSPg?9SF=IXt#1j4=Jj!Ma9snup=Bak+yU8B+6;(f zhO!dS3wk7-X|)gxHF&bNNb^)|Elp6F@u(O`l&V9ktY1vb+ELm<0C)dBPNo_lu0dqw zOAv^Gsp})r8__X!`p?W?>n!rM%GI8ymd8iNR?$mKk7z-%y(Ldn?uOTs@A!*406h6# z^s-jCrLC>4pT8})@Cv((Xe$cc8G+FZ2{E9g&VHQe1#6)*i7jj&1Y>>sV<9)Y(JiL4W)v+Wxsh1{K%43YQKgiXf|lzAW% zCDl)LEeqC1AYX9z>`(TVpveBJmwGRhuPR-Pc-7h}NW^E!LAOX9(WKY3^vysEwb(Hg zG#G)RuZpn~?D1D_ZWIb)X&C5qs~H`F^^>i>)Ti&U@4SWpd@&eW^#Due^|f3fD97zx zFUO@cnw^OO5SHd$`!xYD@9}0m4w*J?wt@tn+-U75U}(Kt2Aa%9FhlxC)EgB)_j<9e zLYzWIR9qb{lI%X{PiF=9Cx1&$t3E4n;=4Y3YT2wYkJN3CAhx`(UeJ|WtFA; zBs_kYBfC6GiMvLsNxTKKwAf*jnsa=STFqR|QqYou1FsU=qK_AW&z=ZIH?}uQJ_G(f zw=lVqk&+lXlaQj>{Y`s~*wF4Xq^SL)JumOeT@^2XfB*PF<5qZC8T2>LV-o8B+k(>w z-Sta$P6=^vI2r>YxjP`$oQ>wkgQ+3$)~aRMcbsBb#=$V6@1=b^e)TMRjZS8PA_a-ASVRjH(S6T^-CJxudbMB5RuqdcMCad@^(J+U}}2b19b z1M%{2C0G4T5ejnMG#*pd1#~DRPn~2vBqf9F13ga0s(4E$mstFEnJO? z6eNP1HBdGT*cU7n1|#C={AhzA2u?1)_5c2EKDBS)rwR$@;1tDKqCL!0i!_%U%Doau z0&~cC)tChFnwz)2ancaW8Aec8-=0bdiIOK!rpR~yopmpj6v`?rDS5l-Y)fPsYfgZB zb?JBm4DXHM+~5Anf^meC4(Ob(+;vLcVIlgF%`Fc8TM_-=Ej6|I_nRaxB?rn@S^|Qr zGh)~@@Pnp6;dg-f=Ih_YI(gzfJq@nJCFKZl{LdERJM`}UvjsGj=M|}yfY%lgM;6r5DSXy^S51VAQfBZ*t*|m)ZzA|q$Nh0J z_R>S(-vvO4%WkLUY+1RAu1>nXrG+G%bhC!W^JJ>eik}HbT9@1DATCTPVMP9ue}jH2 zq@h){(*61?L^~vsu>y=&br`kai|cBzf$(7JfH}cpI$qy3=-^YY_2T5CtDMkDF7^hE z{OZHXvrsYZy}|JQw8sP06xjaC2wY5kytG;wU{?}`T9&u;=mRn?C+OM;|e_o z2DhI@E+*F2){-twOvGX!pI|ssK8`p9J0j+rI4J3h&4JkZxkK01^7)NNz7<@qe%IopL_N z`nWRU(fzm4JGQHtOY%%4PCUI{aYtFIjyd5b0 zTr&%M-Pk%f6!yP`5HD2TsF~pHV%#=e!a*J4@VcF1ljTBnV$7O;djS3 z$9n4lhyfz#C&OE+DSPY%tRCQvy?2+Pj{9HSJyD}ols1>g+40g6&GB3%$a^fi8)E^w zBN|{%09(^}PZA}>Wv`29Ja!Xsbx80VF0ZdvXT;b--&hk{e+hkqGizw}vpds?|F(07 zd1u$KY^|6^_{PPD_(h5FpY5aqH>(;w2Hg98ar@us>jTfOX%OV%+5H&&OthbIf7vyv zQjq5(y#2ZUdJ~$sst)wcDQ0EUej*?DD&PMCDk65`y`I`*-%KI`Xs zb=x9?kpWoefOd$9NkV=y?}ds!D@iD-jSZ*oB4s&fFniNE7X6mW4t{?qle@Ve3dF>% z0l-USSPEMxRQHj-H_O)GL<&r$%goseXn?v0*SNZ|k5;2QeOhvd z7FldbA^H##FXlaME_5pmdq_q5%Z7(!_a0`K zqKJ6*IrvZoV3Zn~nMu3EAiuizEMdp?Wi{+srNnI6X+6;&Jr)G3OmuM_1{V7$;hVn> zh6JG-Je09uMfE0BJl2Q}0A)1>t41CtvodwZ78f7Z8|)0>ag=|>^X_<&nr^pv^&3}z zNtBUWq!n`B7f@XAAqZwl@17ub5}1{swUv)c93hv=yinu=ftdHjrq#RYH)rQ3-sdhJ z#4jcGf2G*}pkip_!aRLVD1@ef@1Q%eynIdF{;Ok_LeLszRoM!hF6l)}TBbK;f``l1 zX>Cv5ps|TO{ZJnusMO0oW#KfC&*m?d>X08!(rV{g))wg;XhV|#&UPM3OjJ;vb#b69 zEG(q3IT5_ZaA-Z;t={1Il1Lm$$HchUQ{}kde8iI+6pAx^T1uO}%<;P~ORj{(da8t9(sUkcOMX$ zbM5c6B}qSU`b<}*H&B$tlSLe22mKL2$!Ttjh9Ivaune1_b5Nr~1=LC{X6kre`R?q& zRPA8B5fZ^Ola(++)L%qJr0IO=MgaLeL6(#2L#cYnxb>&sIjCJfjM)0SL$U6z+aC#E zit7|1uO@G+@s0h1gAHI0F?jk1JN1jxO6p|LeN>@4;8t98rQUeHT4B;%$;L*hRGay^ zktz-P31Zz&0m<>w3VOwGuh$>N7S4^fKKm;bh5@JS0JG^8Oaj|OM2dK=X7C5Qj!@i+ zQ4t!4K78DZf!y|gX=OeRjJNNk3b5HY*$(9~Yrd`B01vthHC#ziR2* zb`DfB^u^ouWD7e9{lJxG_u9wy>zLJH!iGO=7e)%Tp0BCHw&UYpS1~!XnMPoVRC075 zlA`E+8^}VH9bmtNS#-RIcrPha;RSWPQI@V7%7UL=lf;&N$dDGewt# zVo{rVtRDEjiIiMrt)j9@6$wY_ZBAy(cprje%}J)dIeoAykhd9q0U%TDdax=2Nz)%o zaLmuVKmoNqoaP23z%}sGyI?{mLY?*}s-;|*gA~g^B>b%4V6}EC;2dQKQp>T;&R*c+7YSl zf!!?0VqL#cHCPMA4jX}~rDKv{UHduXUZiD;-6h0g*BsFTxBPIy zvcMdo%(&TbST*<~`*^{a&HNt9SggEy_ev!BJp~n83Z*`OvUB`JzS^OU;i9@cc`akO znk;;$W&s#mlY^0js+IoT0M4cJ%`r<13!MIGrxDu~g&3ZD9$5#P*E{025G&?ED4K9f zz3#V{iSM68rp1P*4Q|^`*c}JJ_OV~FIoa|`(r!8)K>O-;*#2*@-P37A$U!)LbQ?_7 zVqPn0{Y@^|{=jLE=uewAR%wkO26m-rR1*{FO2qf_0wguog!vsZ$POm3%EjtM%}yYW zvQ{%vvsMlfz8APztpgsaUzZf2lNh$b;l!gM>odOp~f2EYq95;3W=x1S7kwi6bURy zMGBd89>QdnPycceu54i8HrA&U_}0whRhOn-)jAD{!=@$oj& z_yY9?7YnA_@{5Jb)gIh^KL+#yMOg z00x?GGG=gU?>Q!JZhSBmZeIU)G4e1X1Cqp7u49153-BvAmzF&6I4zJHwcm|i6{(lR z4^nvwcd%U%Ql`kpN>jfGn&ap)O1MopHhLpLgB4y@#{3_b&3qSVV8H}Ri}sz?e-ioH zK>Hjdo4=y%HI1_)bTM>MQ-fVRy?=RqZIBE{%Yng`hOb}6EuS3xygP^bNl8^6VWed% z@~qzbupyd=mD6W@VM|WR=5JLX8> zq8Gx$1EvSrYV>D^)uYEpNjgBfnSbUBJd9u!lLdn&@FO>hFRUE=8=rODrWd0H&O`Vm zqe+(5B#j)3DMiTWKK}ytDv(&5xid+|Pxq$ITynsQLa_u-{YFAtl?u@xebm8D5SM$Q zz9fOKOlxvLVi2H@ViZjQaDhUkMXg43tv6ui%L~_*t4ljx(1VY_Vg$(;{CPmdunOU!p-EkdC@x z!udvPcIP(#z}~FE2$<*s>qA%PZ!0}@rHiMYOK0%wT_cKS1HtC}Mi;R0@n3?-^zni2 z>f7H*?n}$^spk#1-mFH?;czAPvB}|!o5%D)o2JMumi9iSZ|-O(cmGD+&Ju*H?%PP8 zKFu_0XtxGpymEmJ+)A7Cs1cMpH+g|=8{ zZf$NjbEv@~P;=~aDw65*1j`5&r}wI&OJHb!yf3ZKbO7o84(Et82vEo;8yi3_)zf72K*qR98&@6r@s6mCb~x)AV_6beugb-D4M9Jxn8)MPpaH3OF+fxvdw{8IuM< zVfbqrY0Ew#RclsUA^(TIG})Co{iU`a*-z!ZO5+3PV~gI$;2O%L zO4al0>yv5^X3u)oXKPa{v?a;Ds;GXAmCsL{-sc1p5a102lrY9wN_iQO0)V`dc|l&i7z~#mGjD7ciVN)zK7Y$_nulk8Sl;Z9i-supYt}}^^UV}!x)iI^ ztC6D>ks)A+?up8ZR~i~54}HU<7T-6`aQjt?QzNPz%>Q}7cwh_3sa_Hc6I8kg*hwMce*!{NiEq!v@Xrm>F-!~s>rc`oTv zeI}9qbL3pHHT)5jvffYAHI<|jHMHTZlwSi;+T^|n_B|)S98w%JX z3UM!aVp-0X=H|BQ(6~rjAADp^;yw6X4FYxb^?nMo$AsCv|h8BDCQpT`6n_nrv4p=6HCN@6CX$%Sv^$W(178&a&I-_Rcy zRS4Fzn@{v62XKDt)Q9IP2?Vhol^QwlvZpAHDwxo@_;qcW4Ftqb(H6RKaI^wgWU#i z^Nr(2mji@JvQrpwbj+Yv^a}w%+m|7G)*MV)pju3pZ*+fY?s;9!{gQTOo@&IdA^#Ce zaBv#ws!47Y{#K>)-K_|=9LAQRuk#nGqQo+1WbI`W(&^TC>%DFxB!av?`FL+ zpnNq41c07c?zuWAEqa8mlLXoPKo95Re|^bk8!Z#cp=x~4hES|ZtMHlY>(r~!p7$TKRI{Eg3x%DJq{_S=e~6(znwUySmF&2=BE`xq z#Z)PTSDAmn@f@Aatu4C14$?Q`rpS%?8RoZ75vafM!)$&IF%&B(uM1lQ9jJad>IZKs zt%8l%#P9;9C?tN8;{Wi|yZVLGaumVtdb<|vwz(#i%u^}nvVRq4sAn7EcCpR+?JrNA z)x0Qu2DPC^A7m52>hwWB0LpYW=ff{>O)jbg1nU(pI-`daqk4luwTGJj=s_oRSZ_;m z=ZG1&%q^&N@<((rD@Q_E^=(doh?0%)#k-N6?i(*ZQqL=OMUS24{%waMWtAbG&5v9O zq9Y_`=B;H;Q@bu@I!&7w!Y#+Y7j16$e*I&UT=~jA821S0PQ6%b(%^%#|J2LF_3w(Lut(L1&Kr#{P zV2yM^9O&LcK~S?kg1~I}Cl8Uiz8+N!C0f0UZKju1muO{2UKuk$IKJA;)Fp9`# z;V>k!bExHj5(uB&w8Crg9oQx-Gu)__O;sLtKOcs+x%0ZT|7veJu1f&%KobiKT_9#^ z&UD%HtLs{zAa2{ky2G>W%HwRAM)UT;V*LqZAm2Vdx`-E5MUow4XHwZP>Q4_O}qDyjtz1cn1YAXxO*+y?=E(#-LEVH&|l_LlZt|mh0o`A zENz#*48o@;anuTYuq`lw9=dh3^v-xm(heg+RY|YZedZ|nB`P_R*+^y!)Ple`TWPAe%ggI3*E7Q3+O?_p>;;ox z(+eDNMYACG&D(+cqs*@aB&|9tZnb+KO zW>C8Vb_xaAHcN6M7x6GIQVn)^a^knv+5M~WAaiZngoRXv!o)Ws=yAFw2}p*$`#+`& zNY%j(f%vcI#qj^qd;tt)v+FJMYHEp4cl%S8jeSo_;f>d>*z7+?K;cQ5Nt_X@)>x9U z2+?JnB)D#mO`XhBqZp7Yl*Wr}nWTODiH%5`B|oD7gx}>br@kI{)JcXiE{`pRc38Aq zKz-2;Z}%jhgQEik%iccS_yc^~d@# z4`Yf|K4eePd})*Fcv&2aGF*vVPWdlaCwatPv`(=p{noj?x(!|j1)tzaJ@!+h%-`Pa z6*8|^EduOEn>!T<|GapfYywd=^^k9m=SglWR7tk0ui$OhU~zwp?lf~-FQ2vQLe~!v{>fHpNj}TQ zspJ#2LgrA>2r5`AC7NGMO)6EHZ%AIR*a%ZA9Zv)m2SktvrY4Gw=GLRi)Mo`w(o~fY zLB5n35Wpe$fAGWI%^6^0QjHSps^owlM#qCo28opljKoyfRO)Xs!{674IM7mg7X^hg zI(kb@)K#FM*JX@sYB6iqTiM;r>tv5gw zVzT{P19%t!e`hJcKSZx6JOmP@w|jWF`5orE5P-2ZqJ&AH92>j-#EULJqLfM>ibR4FE6kDO=mrGx1FH~o%*6dfb(=>o`a?RpD9p-DubEMcH2YC z&C|UYY1=Pg0Ua;fNhvl0RMcfXfbp4&B7S^okCiXnJs=F>mx)v;Rxv~r+vRRAZk8x8 ze*Y$>Ka(7pBTIy9Dg-487X_fM8rX|?#)ZPO-tez9`WSqk^-G*d3Fu}#n=vhsE}Z0Sou2|Q^q z@C36spnI#*-=GGX3~_S&Bb9Mqe4Q_d@8>G5-_BbF33^;tI1dvb1(K@zXVrLD-HEPz6g zEPGq7Mfu@rYl06J%0)OnoP~-2I za4DjL=H)^c_BZcoGVko|{>m4e_>gIRE+ymt_S#0^^5S{M{eNdv8_4JWdj}N42@pc|f zuZk&EgKoV)w5rp@$7&1p{%w4KcwAe_Pm*ViV%+la>Feoz&sGf`&+YvoONA);uX!BD^*$8{9tp=-EdU5*l@R<=Jx!sGJ3hkK38pu22bpWE=BA^3FhG*Pkj_o zuCICO+S}{5ifOXCAqv2Tc?;6dyJToG`nDC)417`~v7MkyUxC7yXOd$>nsBgY{k42r z?|~@CDYWkc%l4>kWYHTc40) zF<$Em6u4dWPj_7pUHYu+G#w2#W=e8eQoWu1YV`Eq)QIkk@l4`%e!WG+ux1-KLi>n^ zK{NI9%hZ!^iF%pI&9M$2=FrUXUZS~ZO(9Q|n9?XoL=itw0L!YH3vyZg*!Cy;Akzeu-Kq+*NqusmvvWxbFu%=Gb7)}iqjTb!D~LWy z?c`njnN)B2*R@clQJqwFe{m6!Cg5Mnpldqts<--StM_Tpavo^aR$o%ST2ETVabIPa z4>ZG0Ca!$4sQv8YeKQJDf2v)tYGz>2C#bxZad%?1_Ujaeo{XEEX?g>&IS!r~jaWEa-3R3d)0~Rca zZ@X}KG%C^H$ zAz70!42Bjb*qRwGZdUPvS4D;z6WoVi)2UR(w_Gb13m*QfDT(4;Hxy5w8`VT*{?wRH z&Y5O;rAoXMNw8oN5d{18-Tz27yM{iSFelCNi{GBPnOiqig|6n6g#RrqwpSO_<{PVI zEBA3R#-sc{p3X8V%D0c!B1lVvL#GHMCDJL~9g^Y@(jeU+-Q6G{-AD*ZBaJjecS^T( zotyuA&iUXc)^fo-^W5>plgYyJEavAFp5j&`%;c9E=ocZvp*+z zBAh){pg0_;B448nlc<-BbKhjvCHzK!cUL*WSte}`yXwdV(Ee0Pzap2cUGFV$l$G{p zopAjac`G4ev_x371RKO4hHA+05fzw7F7UtGR{Y9Bapv&vma3#LU@`u=uX@aY@sRfQ z*eSMBs-VwJ>9BzK)PS47U3w$W$$oO>!9?MMoaHq5+B{hvyU_PDhk&b^e}Z+^q5C}@ zoQ;tP-MD&&A#`3;Hq=D7Z0VP;Y`&ClRVG-m0QSsl@S>AB)NL%WX zR%}YzA}}e$V%-H=Of}NKUpim$ zDim=C(2wdCM72p5!XK5f{*4$_RhDE_zvXWc=9xrDziSH2oiUKk+{x$ail=r#@QUI~ z2AEmzCz}F!V58FG!sgMfA0@EEkmd-338GC`L{M=^p{yL5&I2&7_?>-Mu z$SrEwjk=?Zu1+?zud0j`h8KycTnJWKN0$NZ4;|DPNB}xs zT`0n%;a-#)J116;G@bj))436SCgBj%@CGsZmqGh6j0Dj)CxIw;N0;H>PrW}c%<*nl zE4?}W5$<~b>gQeZAj!>4r$EH%ywT9aGZ2P>P4!aDx!kx*6vif$!e!e6=l+2O7n?yTte+_WAvV?7Djmo zIWukJYF_Vu9j%IVzaO42-A?{|^sr4gn_}z7(^uN9X-4r~GeilTC}(;dY`+-d*^iK# z&KX$bAPym;M?wUTC2pS}Ds4_{ zn8LHjA_j7so6?jvJ^^|ToWDoX?6J~-Q_o0*0V$9v*316zJ(?@Pm0Q+EF@H?%c?T7y zXmvdkFcX2wZ?&e|KmBE33A1e#f4tp?PJt{H2wXLRu&C91Wh}-}>zBia<(scS_r9aN z9trmTG2G;qT30vOp<4Wd>&iGFZNzK@JI~n^n=sH5fj9{KUqn9-*xknHta`*{17TW_ zt)T{87jT&v_{tl<(f_{Ea#K-t+fn@e6N0LkLM%Ul>&;Z;aU?%KK*8KZr@+S%2PJ? zR-t}B0{fQKJjxM~ScRwf=V8?0=1>&%w-B($18;tcfEyD~qUd_a956wd1`?wG9V?65 z+Hi1s`(?%&UC;zicjZHbkals39;1eT2*q7_?%Z6R0yLE_Los%60~r4a?6tp|i5+=G zyO%50>*avha^~U(5SJ&0K)$IKV+Pj;HNZEngff9?jzwfy%J8Y-y#{@5<9kpkv{@;J zy;0eL1#1sL(@ILz5S`cm-uUzVbr4>XHE1UJ^>B~EbN3GpAz`xn!&nHqyMWQJ$%Hz8 z9T0CeE3)Rhu)Qx4v3URC95g<73*Ds-2ON40zohiIJ?>eWSeoKakS+L3h63jR@Vk?G z0g&%iXAfj2tFEUBf`P06u(kgk@y9m2{dK&4$_ygd8D44q-@eG^|9KP(K^#~6r!(ia zqmCL*i1aZ#9qLp2875iAriT9I!)5WxZ^DqUe#x5_5od1sw+8{wU=YSPP63JxV(sr}NOwdh z*oMO!)Wyk|CSqXR2d_!+(;C!1%@F}|LsF6^NK}a60GH~K|MI(6i2{92yQ~H9VnHCJ znyhszJccCAJIu3=`IxZkvnzeZLGXntKlmnPCvo_!H zFEzTfccNj;&gwKW^-D_XzZ8Q=KT~8^;EETeVqA9^NdJl5mGpGNLgNL6DvX5Qdkfy| zfgMi7{P;x|7Px#e=5&>{W#jz zMgd6Adg`h6^=!QS(k3cb)A629!-v7u60~>G&uZa6WuPFlRMzF2uo;{^pp!IMHdAA6 zZl0~j;;U-Rt{uR(y}KJ(Q@V2o1wM%BI%`r=?lMzglLktPAK*{1t5f9F6M~gm-ziv=*iyXk?pk+xi;qbI{jLrAa zeu%uK5)abxA`bASFOd{iK*X(maEhIv`dun*Jx%qS`@nMAkwd0M`I{DlVJiKGJ@L;E zl%^!z9(QchUlmP~2*RKFy)%uJdC7Y^;J}!SlFI8q54g5->8vwgDkEojyxK+Pu~+pd z9z6T90A>2vZ~^YUG%Mn~femBFG;@J^EK1NPl+6QL6!S@ZxJrWmEO)?&Vwgyp!I;5m(b3RN$@mu zjDrxij6z)(4>?;f5NvQ<9oK$s;JVHYEjs=R;jcI2}=-G?JN4iP9u~|KgrGY+)J2N zpo+#w4bCCMgH_+eMXmsDJ&(qPv`AG`6kqO&!k-VLR`mEJqA`7W+AW@pQPxH?&T#C~ zQ2KK`FaQeLoxB2B>>&kiuPCtgpFHO1ErmSG8*an;DVk2Dgg@|?)ST{la=ik7yLGxe zpTbn04B$EiTXBiit5W~VZI+O=>i-1)I|$UZH()ULa6M=X4$x=QN|HAr)L{7#r;+i{ zC2iRR1wL{#sq3pQt)SFhkYK8O?HRSKA0=`?W_WyWWkcpGbK>>qP7rm${u9HYc`@ue#f!g#>$S)vYKpowO^^V{f|24I>CvX*QbE zd{+qDRJ`nB_34_RZ1DY=apwHNd&2}+`UxIqPQdx{-T*|yzjIs7ufM_%UHj3K?Co#a zo*$MN+mKG6&Cz*Icr7fMdlbs2P)E3dnpQv`Elb?98L;wM)(aBUk#3+azO7)$!&j(c zjO+As^@ja9Q0e1k;HnI9gC?jQF{`5vB@q{~9Wsi++~4>wnkk?J%uqDhYaRpRzXpa{D_#Y-++zY@f;m zhGwvx@nX7o84CbHqr^iN5>fZGUZ^7s{C(?nzH&a-ItX0C=GNB4b?i?bJ!hCenDIZn z0iywS*ew#^PI(q6rpgYMQwQKmxIc5vjDAU{X~!XVjx_Lf#Mc_t`69V@-JULvxZ9ba zk8Yp4`233&8mhPuz~+Rl*)c8DlR%haW$Al2+1>Mcj(&}Vbc$!I)2X2)sQ<&p936|3 z0ONid|=`nWjJ`pA-Ds>-VjOs#A1% z2?t!{IlJDP7E#B8Op|t`;>tjyV)?;oC2+2~wi355p z-2=o$*}(fblbI{KR!}teTUhG8_)fbdgi*XJC4|qdSRqNm6W-y92meCDe?^s_=kxIkZ;h$L-?^c@=H`rU?^hkl7}kCX8~ zwCZcKjLy^hy2%&RcODr8R$M(>lV67fBMu5u%>s0TWj~@zwAX=h7es%PuzJjG zbw8>EciRZp7xe6^1n5Y!u|moHsw7OHn=w^hat>*`F{DvTwK%0f?&YN*AMuFXnrxHM%`>i-SVG?(!@5mR03e{ z^7W|I0HNi9*1k)!`>vz54;?wwxNWt zH9z0%|8!_ad-d2R4V+-MpBCp+nY8P^CM8XlvkG0zFW}QV4^}c+CaJ38)8@X(_Vp!^ z8Hfn4z#Tdem4lTPwT)@MNYkYXzw_hf}+@bT3`;>19}<+n=|--GM~yE~bnoB?e2I^V}mp{)5X$86OHo8(nM_vXz(YZkD# z#yCyd=)D)bj1j9i*j~Kr+@Ne)J(Z&H`Zw?1OmUM*_Z21_>s~9%DRhh(95h=ucv-b} zdHG7H3siAWYQEkW9>}n76HIS>UuCmz!P2lrgN%%w{o!?2^oq}006~#GxbOO2fAeD4 z{!iaadKafEiw%3Cy;h$?>R^i7^TI5*gIV#h`aw2PTqNJW8mZ_npAUwH4QS>EF!056 z%P63FS+Fbfw2%J%k`!p7+mNoo35H+4GJ_vkm|f4^5Hb(DUiHZHi9zGLIS6FUSxK!E zsjHZXB|e#9CDGEjxO9vlP0J?%e+Q{;(@@YEDKKkOex2n#h;h%qKQQL1E&K3Yt#q<) zeN1{d+CM)X5Y<|RKe(Pe`y`*$gK$bz={REu_=F-rIBj*mIp4QUd%_XG41mhAgde>2 zoj`jQtH1@>#q9|N=xug3hFFX1sSKY&guTf?x##d1?_OmGh)UB(nfNE5!aK1MjT2t) zqEMVQL{qoP&=GH8q;Ql3zTD-a#T4<_WI$)O{;^)oKp3^GB>@#8PF2Pz->Xqr=-b(+ z6orgT>O^3r@MVZXaik*{NTfWTSg5FUI4H}6f=w)nd@zc<5kN!r=$?e(v2aLW6dQ{V zkNh4MR0y2ASKq z$`8fNq5feZkOzBhI{4MC2l#qj9q8lDlT{T1R*=qJC2b&8wDn=C6VJj94l-YY)x-c= zu%16A&oWbKLTGfs%>Lcd=l*EKpA3K<$(*NG>|!rk$y@Kv1of_dyNr%5c7wqPv7kFg z>ur}mgdVU!&%3O3e+s1!{*B_4&!rNxuC(CLn;{-*4&(l^yL;0ak44)F1e;^;m-O$rB!H!GWS11afGGb67z3G6Fbj zvL4BlS=9pEn%ui{0fFH{opNf_ZL+tSgM{g_<{|H=oWxKqKY01-lq)vWW_a>(l3C-6 zWRp(?Ch*j?cptV=rK*RC3cZM=I=i2N+!4KZb5V#`o{;TZZ`8Og)4BpKGYSkb% z?+@Rn9?DzCk{zuUKKN{5`?OUv=?$+%yd7FjS&IU91o)$K6x6jQ>68Ns9VNElzt6l0 zu%(CAx#pu)xia0>P<{To<6O!`fPa6PsMzCs@&rWf&(E>`4rcZI+lEj3Jlv(Q**(=9 zKPE!W8(TkXyEqom*Sh-f4#bZ>l&=OoWyBPPcZ!~D8hFPm_;?4Pw0L1C&AU*FIVA^J zTQ-Q(9f0t2sCBxl_dA0JoG#H!b-vI|w=d$*?9k0fGTnUM(jXj6Oe_@_K~Q^KHIU+& zjdPhP#g+VWWg6JGPuapK}LK_R)9-{n3$y6~-#qiwuRKhIkn z-)QSJNGM%lrZ;>4`?61eBZ?D(Wd+WT);w3$xNpS>)qK!y$SYZ07TsRq7djrNFWrMJ zp9s`<_RZJVTw@Dcjq*MMcV5NyjWf3#n#bkAr~*4fx}759<0CMom^-L;Tr9m4is5@s z{ro$aY4lGK;bp4j(5J+Bzo^;O17P3ENuN>*kI=yZh!UFmB)gpLHYi6~7Q`Uyf_eg+ z>7=-x-8qzaQH5*P43S5hSJ*BT%K`j)w`1;dU;%~V7Ej+1%p0{ znrvPvu?_aFBpMV7R~&%E|95r{Qptbz>K%Zwh-^a@P58)2Y?KQ1*b93Y8`Tqg$_Z`Z z$ds;QTjpX{A($KfLi&{1Gpdefs^5MXHNeayJ{l}hS738c^#P5OO>C%fWSGtF#uOIxx0>>j#2;!B3H3FVt#Xy*87R?_vZHq_ka;L z3|OoTMB!G8O`*kVg{PhIK6$DYz&1L)3I1J~ait5+{wSMdLtW#pfrzZD7j6A3k_tcu za~6W}OeRB~k#aTUtVWCP zBLD-#Ktqfm9Q9I-`80lt-#37*06vaIX=Bw(5ouk^*Uf^00@qu)Uja@y55E2Bi6iJ{ zAYZ-_0xLQbctQf_(`)vipR6aEoZp%9Ej#^(1}nyNE?d}cL8Rwe-FJLhi5BIM-nH5M zX1!w7ffqd2DMk=7l8?g&3!pXG=iv!(E=n>=ynmnkS94;gp%T6JSGUuyYo_8>kw(xK zggcb{L)u7r{Lp$a649NY2Sm_`OR9OzzQ83i+;8V)dnKm}I{6$Y8(V-8(2_tQ>j=Vy z>P1}{uF*RpmIgEwrpm4d}cS_ zsR$?dNTL#HgQjoHx%!^U=2WMk@B85$`JGp@d>U6ISkg{LqZfbu%$i(60{E0?Pg<|` zzk|jya^TKJb@)2~1C3#hQ9GV1XWWZC#s^<{m*nX7etKknH+m&cOOyY)oI(A0&ZqTM zlMn_i4NOu$9h$$U#Pl81Bb@&3<$##2QyvsY?Y(Td8}zQRDH!%-h6zwZAEyVBdQ5WK zxJrtp_{?x|y7*bwadx{sq$|Cs$w|#c*R|))2lKHQV#m1+yA+?7yntJ9-!x01SiQZP z8Q4_Sk&#ih$QG`IZ%esGL6Vfv(ZvNmHz(D6Pz@?~0RM9ozHGpv-;e+@*Id?m!|z*8 zOr8=0ngg0xb5BaU@i(6@>d?VhDe|t0jK(dnc)nUOTP&mgyvqVIlt{pS`8PpLu}dZZ zEVny|8M`Y|YrnyTFS!(iC0G6kNF54?4>sNqbDw!OR5bgd8A+~b%KZY8#h0icd+|jz zRVcs+0`;`}0uia9lD+na&S7wYFL5M-m+-gT+Gj5vG1GBovllKzK^YChI(r_R(Np+c zcHy%mlM&vA4C^_UH*RCD>f&a$0s7qS844ZZjK1cxzvw`G!ywrWQ znbrD}vRxRUn{V{Iui;r^qi-IwX6!ceu8)gv8Sz_>f`L@`^PR3zq1ZkXn`5sG$|C;~ zQY4kZW>HRg>0F*Io=*49kP#e6dnX5zg8NS{2kn*&|6hYLy8 z<(Ri$G8&ynIlZ4w=w#^HHYb8*b2+O(ZU#IxU2yi|B4Yh8z|YbYvbfmtzH|Z#Y>D6W zijVf*4g>$u&lq_+N6j+IkK)hd9@?ltV(~)%S_l~h#qDh3J;LX>sPmqar+KRD7;c(n zdcc5=ZTi&?s4HQMiahVsYyV9*Y4P>O{LuaOy5i?p)QQyrIDHtxKBj`HiVuaBk4rFM zzv8ss?c0JtIv)zzXDYzTgYBifX}WHIO$ECRI3Bj1tJ+uER(Fpz(Pm~xe{OAzg{7;_ zu}Yj1V>!C~jDu`Ossv48FqNHYpV+_iLM%@mcUwI@>JP)~O5dOc{1Ek^SW}|Wv**5T zBR}8P)|=C&S1L1nghX1k&uYOrmNstguagY>0ofkc>9-YtNXu67B=yDj{C6N;wGBBx zcLomz!Q18V@Yjj|d!~#xMt{Gyv@G%p-ycT<`>8E_Y)rHzCfchk0H#a=%}!XY$hr-v z8R84i;CBWu7BJ#}nyOd;qd4mtoGx45sEz~uM(rARPT(S^0ZyulgkxG$=ixJkWaKwr z>0sVufmVJcoA?a=lS!Ik^*<;&%yj_|WwN(l=_9)DrbmD`MEgDfms!-1WOlx$)h9-t zUV^0%aZ7?gAD;$C7KL3d;h>4wPq6V~WN}mxf@D`HFDt>4Z1S-(Koy`LiXT|samDBC z$xt*usHo0h=JrHX)JA1~o|`VN@z-lgQ`oJca>*cTJI*fl!_7aJ2SmC z9moS=zxM`Sfk0>y-G2HS6{P0CLaJSBPpGf2Pp8HR&9_(As~_Lt6#cGfcXB(8Uquu^ zpgU*A`lNjar)_HkLDZ zXk#?+UXNtv>Ejrlcj)>559if9I97X}7-g;3e;1H5)QOvco7PyJu>%|Q8oAfFN~>P2 zyAvl6MlB)jG3@Nsq}l2S3or`;fl(L32Pm#nCMK-2inoBR%38OuIXF9N=os<#oo$rJ zx8|RD=x4P#YE~WWqFo3h?DzG!SG^D*Y5;~4xCO3PYlFO{ItxD1Z;|qHe8tcD4_%IY z6Z*yKfY&XW-BzGL`WWc?lVGl(1ccGc*G7QT1%6krd5=S{c}Mu><%Zye@&F;FoJln+ z>NuKoBBz2sTLO@(;FFWx+ooTK0QtGC6Ai!5m>rcG0-g^r>mg$Cpe|jwU2hjwG3lEA zmb@ycvsNqD)M|8QUh7e!ij`L_POuY91{X=U%B;!a8^aW=?Yu7KiNgHyjB`cIj+(fJ-q+_p`}d@#skEQ+ZgIG_R#03&n8lp=$iT;Qa)qe?#< z(@8ShdT!i8gUe>V7vM+MLcRk3h6#8`eW#xj6?BEV-gUiFmZYCqPDH~(7ntCWn>+azK0MFqJf1?_CvKt15R5?q`TOp7Z{Kpr`ly+s z)cPI^=z6VQ6_wj0K;K`cFnc@77DBc_%c8l~P*BXRtlwF@auaci7Q9bFl2In!PMzEj zADi_vdQ~(D1)UCJjBXW&H-Vh}M8a>J+l{wxgn&P9192lNh9X)SZTDe_s_M!Mz~3kdg#C z7PD(>0|B?tbZouvQ5ys(IY`d>^L)o-KnyQQgwFl6HJZOf`|?eXMUC-!%paE+VoqXs zjH`D@#-Fj7ML+YMuN^_P)wp(wYtd%nDZ>R@ln@$Jr*WOH9Mnjvpx(#W>@!X=9dn?k z06K?+cyb6HtJy6Ua?;3+#X}p8sx05E?!Wt2pd4~;3~L`bOkIvYJMQ0wqcFWPcEXJZ zs$Y!o!c9l(3OnWWVxo#d0c<2PBlVyfO|9B_Xq6E)h z^e3}k)T9pBMJi<5p7;%18n zA$&XR2$2jd$=0;Ggh}vztjaE?4st+)n*-)#y&je@YH>pUWs8ql&sJ4oL*`Aw8c(wb z&e+0&7)x^3sepYw+5Y}MxXZcOvMPbAQ%5c^V}N|vsOHx{ephOY*w22r{1~09Nw3P) z1qP=-4sT5r54R2}dGZb#kbIS(sfOc4qY=b!k^6rDdjtP2w+--uv6s~NgK2NjkV-Dk zWgDU!AT^5knx}%h{6rTJ+SPLk3)2CN#L~8`#k;*N*XXZrQ5$V+uk)m_7dEw zZ<0sf6XI0D1)-h+b!KcdV-_7aS0i%gpjK6g&wX7&3LZO!dG)f8-DMvr~w#f4d8Kak+#1kZBb z=oWVZ@@TG9bhb{pGRYQfV8H)g_w!*$N2H`reXpD{(UGooN+p&1#!9 z9hUm7_^+<*p#rA^Z-4ywVRhGWcd;mBJ^L>;2qwQjOtyz@Q*rVw2UX;tOePIw9nwu2 zMCMRQpe+ICSlLljSHpMD4EclB5yFNV8bEGu4KH;bZbvW@#bwjq|9D244h;*d*fwS- zCLtjKYk!!D3V;l$bTVeX-~fA-m=ci0AFD+zt+Ms1r)x`niQhgtO_hB)1E_DywSIl3 z2E$am!=_U#(BaGAbawWb+e){+SMgu_)tbd;y^~*3@+V&vO+mwO!j={w0cc~Nblx-< zSH+4Jch1?i_79QInUhX*r`xv3>{b$irFaOaC8J9V6gWZ#P(qMiE=Yp?t2?Ax5b*m~ zc`WWLH^zZR7x_2H-B{Z(!6K%_`K|IoD;*k*OjM8aL{yV&Wl72U&2>>}DL!5+1CoqL z;yX104h<2F&J-oMdRRU?VSi3>6@r4=v1jXFR_WXKB_$ErmQ=6TUjtOS%2q#f<4r^K z(q+1^fI>x${~2qu_{EUM!_<^d(JzvAoO_w0HcHCnnZnGCLgD7X#>19$Fk76g(Cz@9 z%Uz}qO_vAYWUPT#;8w&WS7q6FYk|P{_Z-euX2L=G z-NdL?NValwVBom0RrSXNh-I)$S9{DbrZ?te#-D~4{lTwrr|^9fC+O%fr1^X{{O)2Y zOTTee``2d#pW8J`-mCR^p8LzS`kMof^QOHqC1E~?pQ$MI6=GG&;_xnnqKb-4b!aGz zZdEKffD#Ew zgm}FQ6a4;#g!>1p0kGJmk&-?MrP3r(&F4`jM+@sHq?9CpieA=O_Cz%lTPQ-mG=@;Y%gFCIlO2+G87A-=v95f$CNoi)a)rNRv?=*;$bS z6pW2c0kF>7+#$<$(a=gp8K3Q35QFJ2xXUS|b5ZxpmanOsU}+_?hn3)Kxutc>cNJOE zJ2C^thTKFr%5b>6&My zL&4az@(bOOfV=stUl^JTjd%?~Wefz?*!>uGdeO<5u9q|#nhjV2+s2yr8!w$(u8^;8 zA2KNU{#(`_j9r0u_p!KuXC)8c^|tTTwCSN2=q*YE`u!Wj&R*td!Smij`iLyHnUTnC z6$q}3N_nZeiA*Tl-}}7~vv(fN?qT6x*Q@gF-kh-V81&qfpUZ1*AAE+W@u*b>R>C4L zLy(UuONON?HmLsCNoKpmAL{vmR;PHVi5?3wN93IK~*0bb(n$_1~_IU zI`VO@2R|-mgpUc=`9$MeV9q&FwfxcDH7eYiAJhn0&4EQGRJE!NsEwb=f>m-QtK8u9-BF}c z5TqYJ5AnEIa;!hBsm|2-i-(Bzrp%zk4LijvrXf{_0hTlSKOH2k#GaWf4>4H9=p28qJeg42zla_45iZ)xt~CqXTL9IdlppicWgSZTTBbuP?N1sqDWO`kcCJRl?$QkSV` z$9M|6@`ev0i>bQ^^HI!eqJw5H-vj8(g?QEF5mQ(b-Fu9>S z2ti1@UA92IsuIfe{7joe;f3!|XRKkYx|-g5?7$Kxqb)-^t!gi*O^DH)mAlVIkBRoo z$s~qSthJS4|JcR${K>h2escDz1*+KPtM1%rq3&q!e_}#s#Y!h&Wf&V98%S>TeBKch z{c(QlnALi=;cDBF-RW0>`Antz3GJdlUQyNqPP#9iM1Y--Tx@eaQ z1mO})b2e(m8+xcy(6D=^c_w0I(cMb0Ce{Tvu1ojZI=<$fbIRL1w%8FDQ+?n7heRM&vZwxx~ zd${dHpnt>~rKhTj38Pf?cZqr>d9Z46#2QadsU9?bcQD%$s#Yiuga1{KPhpD%Bf>u$ zU`eBrTm2|u<+|r86sz&^q$OCjcau$>Sb-b$WncqvHbsbQdO5v=P?A~BkGi(v`f{R& z(X8-c1&YRYC(*Z4g-GzTUm4;qU6|Wg(S_k0^CDVXTKG{Gf0DA;f(8}fisK1Ngi9y& zI=KkCj1?+fUK>!jrfJ`>fLDnkx41k~K`!}rqLvt10oHUM1Yj&C2Vd9UdY^y4f-GR+raUQJhmrkv>Pw6whK(Nt7h0{3 zVOjyj^JgQd{R4Ms`eAUUd1vPXxq|A3r;5ji)hhM|8|CCd)v1v$6}!_( zpqo}k9G5aYr*b75P&H0KQzy-l7so=|sTVYny>Y*epH?yga?(lC-pUMclRcoP?`j(m z;hWrUDm|~*vH17c4w_CC?@xtWudW<~y$|$(Imf5F+Nz;}4?HIgT%%tBsqd!L2{Z_A z#2|Q`zWsG3utuyz`)7b&&lDc^Qs_Mf%hH8RnhaDkF!O+ggp@Ru(-ND@dcJM?cx}4M z=vBqqH*+Y}`7;SkP!6#eMb7b@va7eRW_x>DgfF90iXH|@38Dy=!M9aG^v}q}cHDR= z^HjU5$~uQ3ucd`WF)gO|Y-3bC^}4}o&wy}3;OR5ga2?a;2C3~dSy6Z_VWM8&?{h?} z{=XZA500XTilwLc214;KC_JN*?BH&f9?AE@Q>OnrzeyZ{DdmVjPAcW?I?4}BTa$kw zqh$-flC*0+y$2seWus<=p0;ehYH(k*JPtDFrlU-f1!v+nSZI4;ngMFgocdWyNeP06 zgarH_0+NQ^hkts}l_XjCl6FYLU%r@XOU7QC%&1IwV2pMjZW{WQ^%gZq(kB*VxA+=E zLpSTe0`pXO`XbZgfEOB;^MX_1@K`WfwO(FdU$EscR-QhXY$5o_HWYM`os`>pg)8~& zzy*%i@#z%efn_in&=FoP%*}ahG8TTlu3vD@l3soX9oQig|o14Nyg$ ztrk4@4;;>KI{rEx*4#Jim+9WqD9wAG`B+8URag!lvZwNn#r<3aq z3jo`4y9XoysRh;Q43t?#90|M_J}tWcteq4?Sl{}&lq6%4Pp>mQPjA;X6yM1&=o%TE zw5eng;|9Yidy8q5SYQEa(h7D1Y(j2aJ4Ie&f876@ZPiW<4g?N=x z1N2$VRKgIk1#fY{oPGlw-ZpxKua7gc9#&su3T)@aW808&h7AoVx_fwhCVL^FA`L-q z$nL?_LKn|D-Fqffv1T|&1jegX;wmP(giJl)<+JMfeHtJUzIh|A5^(5IR1yY*faREv zzcJ;l3rmNN?$&-EIDex8)J||o2}4>K-B~*1J=Da0j+@<8f}{3IY36cn&gO0cWQ_~y7!c7`e6sY`sW!lVV9 z-2Cho1X`GKv3funTbLq--?y`g%|%!H`GhJJNPxikx)IqgBOd}OSakCRnDQlp5fb+K z2__7ck`Js;yk_?zKd@{~ZtC{GI!$UbX;%llFz}2ewY^npIRmfWZB5qA9wjJWJBr(##H!5JB<=W@xt)P#YOdp^KZ*SMwj^UgX~7F4)Jibx`lQhH_m6HPHQ@FmjDyh-E)5yVhouJri>^>8`%B)*Ormbz(VvA9|J4H{t z5}J7VEwhra7m|*I;@%(g)j#egF>fkOD6k zN@o^Fvbz`Os63z`69>5^CE~Qc0NIs83N^~wTQ%*8>>{P+!iu-g0)PSCeNQg2ipQ)2JkR%@3q_< zh!y0DT}m&Hh+%hCGiCbRyHU8U;{sDW@7_qqB`7x+oOQ|&&UBvb8A`30`j8OzlCO~u zlrjFQc$Lul=BI2_2GB^fn14lu>yuw;6aFr)W@0LhFqzA#w6`W3etF~%jy4g9rGybo zeRfn$emTV)J{95fI)u0F@Y>Tj-dt_oy-KLI>-rbUxe<1=_az|1ml5?Oe`A6svjvu)E{ymd_Hom>f*$Aa&b4*S(k8{lAZB)fMo& zr%i3%;&%^%cv-%DW;Kd~>0zIxZEM$7U7fYdg57Y&+fVYTsnRL&xoN)(FBciO$jXTX zMV6-&UGVJ7s&T=aTozeU#89Gl`U@}b?Azbamtjm*p%_YKJU+@vmTNMo!XqcibgK%< zI!W1OsLxdN>oS9`-8mF`O4N&{3CVe0{_EJg?ZU`htn~snAOrvr2C6PYSkN9x&=G5- zOgz2ahzLp*s7*Xy^sqf>xv^2?-{%1BVoctir%FU090p%dg3f06r|2xUOudR|a54av z;+8`UyRaOpev3hSs-rIIUMDi9si<&9Ih?82i75^n%RDTZyIo&pRkQ+qE8oPttpCfO zZ%$GIy;MNc?~$iBw=vI-8D47?qLqrwYsvOyK-aGPi17I4R)dB%h#ia`mL?;ch<-lA z$-y}e=P;p2l*L_Q$=&5cSaub{V=tKK*6G__K7J0W}*J*jj} zDd>(0Zj{2DEq8Z^HJfGHR`WkniQ$FE?We4O1w+B4{|I7ncLB9H*a z*486xtsoo#MZPra!wJ2G(WwXXuBcwo>%GD`y_3%d9r z(8yHuz4TSQOuTGi;LoU%Npz?-Q62W3&EZ5VEfu<`pE5&gLqmgB&8O#w%@-8u+_v3y z)^sxNJ*RhX9Tjv*C2)1?Y>lkuwsee@9=7$R+fB41-cbTm#N(4Y0E5ThAF9FR>!EGY z<8Tm6On-wyn-o4LsBOy?J@_eq>(!tw&)K+I>u1p8?7azEGihLSTL=5ujiu>^#UY#S zRH5@DMLPl%$N-CXc=apO-+GQm!yOj_PnUWw5M%!w8SH81A*ds0 zz(<|P#iriiq3!Hc2Z;27%S38z4^wv}xl*>)Hy}m2EPAJxes4*OrIpGqvbUamfrJ1G zQSLT}a$u{O9E1F5OBbl+LhMdwW|DaNaAoyCV?dbFNSNL&sc6YGkxRB49`^nd($`ou z3=2=?vLOg#>LFvY825*M=Ln&@Wuu8`8!_I&V^1=vse1hoDA`9gC3VN(Zy(g5g9&u6`4!Sj^6vBpCdkNlQw z@9c{08HObO(lAMJ0{qcZqefJkQT@0QURdpq>yqsvJ<^N55={rg3;!oer$^0CdYmi* zRdGN`ZJcy%GD^%sskH|#6Z2U*>QfETW^?-DQt;3f@e%S>ai^T5io)!j37#F6mNd|( z|G~jMo;HfE^1cHvZU-A4gX~jfVy?14Fa#%ubGU(Tfza}n02oBQUH*cIwG0e|E7!Z< zHy^vV!9Hj5sEn8j-=t1XOq`|H3=3^ypbTY2mzX(ToR7iba>XE!)G^yz4kZZ9!5Id# zl=nxaR;AtL)l9)*8r^kPdQ%-|;yut14PTlp^*w~Jym9rmG$@~Dkj+O3THL2NW2g)W z{-?^bdtQFt+1&w*EpYV$V_=CYEn`r<2`p`=e_nqdnVwc(Q(_GBqeRm3?i?RgaBP0y zOO3^UquafzMY!IED{InrhA1H1hK-a+omjjU%kM4sXXf{x#PraAeBBCUVo+GfkQ8yjIZr?8c2rAv(wKUQolF}`?G~$wigmi-j1CUAjqlr1w6y3UuTwB9;g{I|NC$I@eaqT#bkHe zRR-+-2TiJrgDQ|h_+h9_A!0{0NL!=|zi0E)Q3?KnzUH8{ahwIAex%{K<_mr5U*Qw7 zZ5Ql`Q5h zSYtI@07OktxGs$&*7<5Py~DaN^Y_`yId0Gl)O!7gtT4;*vQ)omwVt!VC<4Y^png&8v^hG1zW7?k82O=Y(^aR?K);UHlaDyveYj^!U|supC0=cX48Ic-?1y zf~$x>iS86B&8WHdEQAi9K@cITL8dR2ZWF7XV3QZg(H)8)kGJY7Ckq5nib-L80csu6 zi2)n)hE!8E|7n*A^Y1%BL6FAxae?JPSFt9iAO{^y0R2>~*X}rf=T<)F2S2>A;hZX& ztrIBIW}{iYS?FQNEAf%IwG~X842dMY>fX6n1n)qq5|1_Mr6l*XvS6UU7Kg$2P~Zj! zIOeQ|Jzna|@vO&d+tux6#Y#b%{q=NG>n#n=Bcj}FwmTwQlQVvIH@6V%kc&ePQL1QV zeulKaUh}`s4A(lVsODg+Q_VMuqMBl_k0Kz^IcDJ&zr~e3z7dHSl#n$_$U$s1;!(ts zCl@HPS;xJxQee_D=gp}HD+^$ml8YvbG@JFvlyB!}O;m!!Gs#mrK7FhVNM+NG(13LE zHKXtX`5T=$~d&)u3<4^*!?9%R@Z``6_PCj5qO4^Qf43bmP=ATtG~#R zAw>w5&aII6TFU|xN^ikpPQV*XPk`hp;!|CM@AtEu)7QBfUnr=0FjS+=c7M-ekBfNJ zeI);OEl2vkT!89-!$veW=w3#%uU|IAq!CXiVqYjMvx6{ac+dk-h}l|i9m%5M)qR#> zDn<0900U7V9i0A6p#nZkhVq*7Pu`RUY4<2z&Nw4`b)|7=lX^8rZZR7i@ki7$2iIsS z65|EVB0;8}WGVUAuYNgAkUoJa_t01RaYkk#!7%Oq*D9$@k*bk-nyfy<75KJ>9o)iB ze~L6nfXuL*4uUh30$%^NJR1vCV=O#7MGiT{b{ed*G6;f~wc;T9`0tXLBuT-ee3T!n z$ML!MOz@FIAn2Js?xt|~*hBRL{5&Qg(bK_dj&@C)!CUTs8W+xWKZ++$nNn0TtjU%L zdZqJ!Fw5r~b%$fHuZ&pWDXyqLKB>1i;&of*mRzO3O{3%9@k@0nqg-%|HjG< zdELk&O|V+mi6tU3Ch`1MU~S5z3XHAW+QOU&;Lx=O#7v;>d`$s~As*XlZqSX}>@EX!T_)*Gc&<`y#lu zI8+oO69H>qw-#n3nGEGG{t#TYU73f_C$Q4k6LH(*V6Q5Ga>_$&Zf~f4thm=YBwGU|;|q zstL&0$-{q&wUUMWkN`;^_(6hSE_%f?DkpwJ?EK-zR6}_i{mz>-G|GTJmKGH$80!NN z%S-h>3xUUP?ni(RsWIz$^VW0yQC#H#6ODf5(z}+M`9o}Xqs`AX!@@T|?{I|vlht4$ zR{nRsvDLp`q?d^6gLxE9aL7e7warx;$XXO>0VVp3ow>Wz*rJYnE%}1x`}JD}>b4Tc zPfZ1Eq>hDb)~U&s0U$BT_V_-=zbUjaB^p^&A0&mRuYr2|>D;*K zQLxpovnA_aFqV^+_KjS$Abl?4cJNw*$Z}si+^I`a*)r_Emp_oLPBrt&YXgI@k$U9X z3bV6gRg9_3x+59%r)2tqXyfS6Sq&E0{UCR9XdNZG4qSI3Dcsa=Z1zwYXpD7>^{D&4 z4Un+c2<5U4PxK6L)b-# zseQKEcEP~z=1VGfSsp?YJY62W?jaQQFlGkD(eD2)`E)$*LPM9ocM-F(;ra-a)F@=L=;K^G8e>VC}?oa#x z{ARsX;$Rw-!I1Hh4_~k(Dy?~W_pM)pc0nG0yipi7QoA~#PUfy@&uUAme}WwV9VYIF zc0}&3c;78*iS>q-YRE$P6`TgSr&W>#NZdL`fP@Pfgluc4nk&UjtBw;!D?#k|hI9=$8~4)Evh?K4^XM=YDJsio zM`LgwETOSr%{R=Ed7E8vtiJguIlXMJ8NMg0k6Mj#csEmRw^!Ap9VKzE2fC++_VjB^ z^o|#PlkDtPqwF@0;s$+=G3u{g5~T~xqg`PXT@0W2Goe-CVIy;+fvwIJvc}s^l1bo50deeS#`N8Z;BMOYf{j945Bi= zmJ`ltIXhX#|ARj~-jfn}#d9IMeD}@J=BYpRE2lhT7D9j{F`KT0RmJ9nTNfPrx>qLI zqtf8*fw70fur4C&;dXN%OCk$+iz5MjE_LzY-oE7|;h`Q>ut<169QS06aQk$AG+Hc+ zL~?Er=a?nVDBzB&gk!J|pMIni(Rl*rgy!oQ&9qz3(~Rn z+lNX64lj7vYHstVxX4939VZ(r)>g43kpb_mY>#qm%<4iU&C_HwKJjl23UMlGYB;Ms z(N<%5ijNDoJk4$LBrPbEqo=@ESL9JKTi4W&5Pe4TL{TU9`_q!12GbjK$M~7$GzJ_sWg}Ec;cFBU zxIvMJo{lVh0wLzC8w!2Ma$laa?l4qN ztdrpP!*#aW(Qa9GQ;6P33=`>=7J}JzQz{%s!isK6SY$&VF{4157gs>~q(CcAi;M?7 zqUY0$EivDL5o5&DR89_ZnI5Ho^Jf#W?c`5&Glo+e?Jqj3(YwswXKld^D{uj(kiybQi_c+(``@m7B^ zi#0D<{CDcH(k2hOy_e2x7xz0fTG~(^equ`CGl~Rikmr8nlwP$tnw?!Pz?HoKe39kA zRkbBhWOd`?thK5NBV2Cegpr!gP!shKFgzb-KsVCXkGLX~?H<8$F)kqsPzuG4{}@8N z3O6m5Y0%Em#A66&K_A7+$V;J5E6Z)kjtcI6zQgO9S5lA*pQE9SJepNZwp0m~T`OKc z0o?!qdjLvK=jH~ShsB1oLpV+6E{`FY3=3P?TvH)=z3FZ{#s4 z0TvkH&zOgvf44QHG%zBWIx{u=8pDmRG|!E2`;z|z{>$%y4LZ&}_|%eKvYkID1PTUR z>Sw88Pm8tDI~2ZA2qSX31z%LN_{G>fz2ZLqO%G>DfVayo5abSx=E?&nH;__UV5D(< zmZ-?tnxH~W7J9YDETNdM+2%SwO~Gz&COrtLZ^;H9+hCf~t5Z084-NOTo-+l_0(Fj$ zgJ+A&W6n{lh3?`ft&I!+Z&O+%&D`X%SrZcXpGXir`@;up4WQ@3D`n__Q|?Ekr^VUd z2`+)jmz4R%HoWkhdmdOR)4z@)IXC8mcVWbSgx-2#LrJB*wdq_?s5%kRCxy7DcvA$q zQp4b@`I+X=3HCbMjB(;>ST3Ra_s+h0Fk(iXzrhct_C96-U;coW7V$?&nu{?*T3={8 z8#Ukgx^uesLPG?V2(ju!C#$G+PVr7=H6ndtVxo5U=jo7_!|vq1UZQH%yKE~JDb}v^ z4$kGAhs)=MCT>_YZ$x9O#-r)T{G#>^?enXSoj7(yzBHEt-$MHnXPkE%nS9&R6Kz2x znZxt$iyh!-?zc#K`}?Bh;cm6!?zb+r`1;p)W|dU#SQa?Y`4>PJy#v>k)RTTPWuDraxe{6}hp#*PsgWrHV9I(x( zz%||p#uJ(S(j!V%$yZFt`89@xtU9i~GQ{sRR|bE2SZzs58GX;F&vf*2S_J3hN)(*S z%%GVCP_) zi+IHXN2D;@)sLJ)4?fi1=UoqHt~6hVpoFrITZs7r)zvbrUHvk~-rabZwF1JOVO=wh zG1BCEB+AR6`)A>+9?K%g3lZ#b?M01qMyJhQE7c@$rP3KtJ%M?@c7T_n8#dv^9NTPnGG6@>OHDmd~{pB_)Tu_U5@?I%*| z!cR2IW@7__unU`P9jCIHFEUnSB+yevyOc&<}<|8@!!GnxYw!luC z0`!u_zYzw9i*H1qRsnA3TjOd-jqi%v#XL5?2-^Ma{CtXIdL3c?^KvDe!>IlfXrZx6_v}u239fR*CSq$b&j7X#bPiT? zz_3&MH8{g?Efz0iv+>dBLJrYZ8duQ;zU@y7Ir>CGiIwcXu)LndYP%)=+@y(GX;`&i%krSAOULq^Ft%Sr**=#A}G?6?dHc(ntUAr(E`Qa?_jNo zLk2uHV5gh8wC6koix#u00-Y(G*PTJP+shJF7n!G}44{;+{KtZy$ZyMP3?ls)8g1xW zxU51T42pd~;1R$<@f4PBsumd!jU0?!yT{!^bOorRHwcw8`*@k=*i6i+CxT8(4uFfa z?5bXuiIV}`Jx$JR1i1!b_6KrcFa)RIJ(|SrG7iwCH23`2*4B;ZGgLD9!_@pvw17&Q zy}K1GNxzW{F(vv6zL(sCj(vfi8uH#Z-;J{C_u9Gq$}SF2sOe^>gHu%K71gVMe?Qz? zGTih{J8kvD(%j{*9^c4`PVRmppV^u9@R1@Sxg8@~9Bf)d10O6n#BbFXJa4EL46EV* z0U$1MLkC;``zM;)r4ZEwrS%r)VUdfRFW9NkDGDpko~%2ifMcb(xp}1$Hhbxa@)A=T z)=A->%ck?HPQQ|+r~6x-#j+6n@9v9LpI`Og!rDLQ5U3N@cE^rEmrW8BQuD@&>pvt! z*b$F`WziTJ4AUl6aUd|NoPq_RS!04{bXp`Ahtt8$iEbvXB@x<6T*%+K>Z_Po#S!iz zJO}{sm!N3rQ;Nbj8}jO$Z@bUSSKp;7{tx=)`M&Xuv@|l7Di+RAy5MOM_$t{)w*OZq z`COL?95@R3)6+Gdr%XJ2M^{9LBS2e?eUQ^J_soUo9k4e76Eey}oQM(09ez zJ(Ga13{?D=^B+AbQmf!^jND4M-wBM0$stN{p+g!n;3^_}naTa?I~9nA%Wk9`#;X)e z|Fk9mzHn}$9?5Z+-w958=bXz8)VcCMs{A^hzY$+Im#eFt=-sd8&??ss4fq6l(ec5# z#R4DshiFtxUlEX%i!H9Bgwhx5|H(hU8*Ja9gd41;~ z1qVEzb0z%vo9E}hD!)4L*igbwb;fQ?SxF(H@ND{-!Z*~Mny3|JK5=(}bB>R*?EfSj zP>ILEN*WXi-fpYmd>k0yL`=dM5l2{^2k9~P=bOKs#)P#kyp!WC?PEV8{9sj ze4EsgzD`Rah93+%n8k=!?{$*DFvX({$e=UO*=lOb-o3uJs{MxkW#{zl1D?S|0K!WF zU3yftg!+3scaAn^)n;Z5NWl{*FB&UpX)%BW*oQ~oG1$!Sd@lxqla>}iWMt&aQV+AP zLWr~zKO+Q{uu@XTBE7mlKgrKa9fSQ6Wq3A+Wrb@OeSj)0`^VnMTQYM(5kMPbn@N2{UB=qypX#hayOzwbNQEBh4(=2q@p_Mo+QrY~x6cG_-1lr0}0 zmap(fC~?5s9mlom(ffug{%|$y42tL-H}~BgSB~W!d*=P$?M;u~u8_QZ>9=uGa-hmI z9_~Bbfgvi&m8V_RN5VcGg`6F&5(<%pxG)G3X@eab2njH#Yxq3#`?Tu`9LT`EcGV&d zN*JTe2%gdfr+ll;PjO-E$ME-jQew*Exx=5DMlLh?u7G-6s zZW^olc(RWy?_p!dXE*yzTtQM#=DAlyyKon)DwUtXgG7DZLKmikNBQFhj;cUTrPmvvp-xc5(lfPRzA5cexuv z6lcoW^Z`-X8j8k1DEo6U5UwVfNCX_%mhVX$X-hG(5P=_c)vQ3vr3>$idk&Z>#MC|k z@lAne5wEQRGdGkw6je&%o)Y)DDW%?vq5uyL(&ssmRGrz!?buyCj<&%#G;gxim+Due za$WVsSe35HpV$JhvDb`vso6<#JMHKQ=8@6)PaLyUkJ0wc$ zohU=7MIdE;E=j%yV`wLd9XI>3*cm(#hrBg(QBPyMH-hdt%T5-o^0Lf@3 zl|z!%i9sS+WLs7cwlBacb49W#K%2rTo+i%MWNdK^o2Fj8cyHZ1rkO>jjU`$VQLqcR zA%Yn@e1n}$`AX}Y{jP_pLiS&4VI6{v?6Of55?_);+$u{L@MO( z#uc83cX$!vjjv!Nj7jzyR4J?Cpdx1(RjF919bz;r%n6KJ4f)xf7Pzkc6)B>4nVMOa zW=$&cIrFTf{tOX~b^hTMkf0!r^R81MKLc?)_}gXAXXOMUg3dk0?p2`tyvFA0x3qlp zhbBX4EmKd`@g450YhMxvdKYih2kE6;7X09XTsH7a=k}zzKD?);MV0ay2IHzy5K@;@ z7?`?zxZd4FfmXK0Anm%(%M7#J{Q3%&yF1p0TknSTn_yeQS=avx$pjED1o0Bo1rl0} zqQDyEG@r{i%(N=Bw5Uk)(~8JbIjXn2m_PraLS(Zmeo*vR%dCYI#J^$e%TtZ0Uu9Cn zf2L;XtV`|nBi@!Q$dEOse`HjbzN{pIazRNjo{d>$Rk!4&-EG^yx?@9cb|PVs8`9ZH z1&8upi*TlsdFH8;D~1Bh^Aqf4>0h5Qh>ylfDxCIW<&Q?PsLe-LWYa&+p&8xJ^fQAl zD_3{mz;Zmb9Q;cqi)Y5&UkwI*hN&re@vNTeK-U2E$!Aqt(u8kvV(^t-_c(sETW&w_ z;*2s2ml`0MW73!l-P9KQsZbqAe4}fPU`n5K{SpXn)`lG$p<&;j(A@rFsM!yNjFa@zAUTY=*iFe6Fyt^y9#O0$5gz zcUFsXqn6<8<@nUP+x(qxhRb(hhD7Dp?IgVge1K{HeS|LFj+U~S+5YaS3lb)!IU2qt zx}pv@L9oZ$K$%#=(>f5FLr?a(NoD8pUNCFVM2SoFqGhJ!$tpKWDQ}_Q&uGT=`p!Se z<8;X_KmMIY^rl^8ipuMV`k>r+-gcq#vm&3{>P2*G8{Vl^P2C5+9~rG5E0a7>{gIhe z(tE!bYt2-n3Fs6V*gJu-?$24z?+*#~@GK3B|7=msMPr^_SD zcR=#EUBT&|d5CJSf9Zh)oLawekc=c`biYj{jGztel?S?C#RgCn|2$rJzTmU_;^#q` zIZONm;}}{{V0o?$df<`=brcOu7QJralduolS#BY%q7&?<@nYC6P3WxcjC~Qd*b%jn zz)Wr0ZjW-bE^YYy=IrsAIQEzn1|mOL#E}Ww3URfb;5QwLhl5(>FnMavfBmY1k&CF( zN0b!9;0Z+So6p;&NjB^llaH$!t0C~r7^oUQM9-?_1|(L+YlWw-7SZ2j+G z1m&bk`CJcH&mh&_I#v6_e~1k-k!=juNp5m z{QjN?@H1K9N2YIKu7t_MB$ZT2w7ACtegjn}qFg%nuco7*r{8{Jl=C8)XK1&{I^D zxIekvkkF=K7_R#$E$3xUs;RC^iA`&nBNvf=*!B~k(hh=a1lP#a)Q|07$eUS>j;jSf zyq%jP$OWT}vcr$%4EwCra*c+q+=jk2K< zbkrEynNNjQXwsvTE@znQy}vMI&y3mDwt;~;?B;NIr!aFlXf{~kLi%!RDM!tyGrf7U z66mM}Dj5TRCn%D6oXH>GrL$B4lt{99w+aNJt2C8F4hiCg_=$Gy4HBWb(2<>l0haXcb4kkm*Ye=HH9_Uwemo2n74E<|LL;z6~M*nOenK#o# z_;ezdnYqPpSj4z=raJtU7Sqv=H+#w}U-DtGBW8Pwot6jXrN;ok{mtPfxK6KvOwMBi z!5)vd;Nru=1up=btyciDSKj!>zzl}*OPe4l5GBDQ6r6D2fp3T5Jd9{7*lf6L(G9P1 zq@?I~1N~XEc=t|Gz%@YM-Fd9*hCj%wH)|4B*8&?GC9>evy3#@vX`)o+vY`15R`5Ywo{dMj*7 zu4_Nqh#;syOOKSd_YL3S&#HfWuv`OSM#YutlJb?1#Vc(2bPs$ki5rg3ht7cagLQ84 z__;LT(N^=W0|^v#I7i_p2?tv)%a-d5lbW3%`DDJ|?t;y46Go(xwT8=M zbO>eXK6216GNve~+aJn|t9B0?3@|TT)13r6+8W&tysNkZhBEi%jQm4xt079zQ3{F- zW|M{O*lrFbvZfY2B9}W1e~2C(A-lgx74nSEOGzh{#Y<(&ErGM7$Dq=GG;Wn3XLfVP z`QkUm{+cae?QY_*#`FrE-xxVivACS#9|$dd1t>Af3P2*ZZJ?FImBG`=ml{*~*t^nI zYFLY;3ZLFBefZ{g%YmKpweuKh;qRX>`(ba$@jd(kS3~roqSvp1jJ_M<;g`NnoYmgH zjvim2vUCY>h!wu)OjEj@$D)M#atVxtWXHae3R1e(HnyEOjFS%25d|z5O&x#it^BtO zP`F-Q9etcX&rl&12(YMlVYZT|SifIpJ9EIz1kKSPQ=8T*Sv0k7M-Jq@Y1-tYwI9V zt}iom6#QlZ1%v08)lgCjiK7pyNXv}OUJ$Ud=&hpH1^!Vi23QP#JcvIOe< zC+j=bZp3xEa`ZR=p+we79>td^q*%UVX+wr}M0V^bMzV-=JW`oJsAIk)!On-)qUGI~uD(lKl3v4F^q1zxKidrxxuk57%)OPhjys?_|U;U)=3{9PLr`=ZGgKPgkr7*|!PedSpTdN?nclp@?f%BfyZ!y6ks4`x zwlQ>t=bO302$Y_Dp&QPn?u#f|9T=x*1Y*K6+SIhonXt@rHAU*lhY zTzT5VXaB}=l+wGXN+ksG*qn75Q$0v0OwrrpnntkZcHeTw8nVdIrXt=Ip(8koP>8s| z<)^CF@9w!AzeVyZvoSsrzuOvl{|BqZbDf{n>9AFK-s=2>DV>Vt*+Q)2iu;+$53_Hg zM2N;Kb_3G;wdUvD1(r=i(Ri`%;xfKV>`0h4K$m9L{RMMKX0>yTP zcgfF-&HZ;iabu`XN~M&{d_v^V_GzmAq-*?jM+05)!Znl$J%DO!VFXLEs04hjJSPql zKe~oOzf91pNad6i?zWwB)i0Gc9n{xU``%znAwi%ytm87k&GKQH)@;sM+RmT3bh zT3s1_I5cOJ;IyQonK2*T|Gog!ZX_Ugx%2579S3;>He0MICH~Si=ap&Df>Eqee#8e| zb)xJc3P6>IL!1{MB_D2u{J81FFBXQNNHzhOkmA6In+^;~0-U9ttSw%D?d|L=fD85C z!E|TPVpDV#--YE6YUI@9o~g6d+X&p^-+zesRom2|n5uiSD|cM>_!IPO@Rd7S1hIkC znRc^(Z(LwD>-(x_fixuMsRc3WM1*9v5}jv^91`Y(e_bQU7JC1%5*!MS@1*Qb?Z3Oe z)F?Ij5f;7?T|wk5P3p7Pytwf5YA21-zx~+gJf;6~a;mipq{h1iOs+L&YfY|xi!o=q zj6G=@{wqf9E$`FEaEoKAi4?0_PGG{BO zF{Rs_;Ye*Tsl*sF3gl&TP6ZI{h~>ryt;Ovs@4Agk0H<_JC6+tL`aLf!XIB`G$U&@l z>IP9Fha(Ie*HP~LpaM2_Wh>b1?236nFixXvRc50FCHII)>U*cO?xp=d}iOsy<`) zg&>5rUR@Vd_iYe|@?|D7deM#q7ksl-Ga-}2{}t21lwA9t`B5zABh35mGx zt!>aOM&zLCbi8&dwNAyPc@_6E8uu`XQNd?PWo`_iP2_ zIlY>cMD#^%&>C9(xFDC?R@;P?<3CPguOp<)(J;Yy+_}XU3UPtbW%t!K=dZ}>z3u&5 zyPM405*f>2SfP{_c35H5l-W=YDc-b-h46EOIGm^T_o;7y4M!x+ zk{7+pj3cG(EZ&>lI;vK#K(-N_rwy~fdk9-J(d!e4W-%Tgb&17cxh)A?_2Nx{STlVP z!~k=HH4`^}yNtGmwmG9cbtliOfYLXEHHhnF6!E~No3|<-NsKvgdm@UwqNzfk1VIy) zIQw}MoEoh9H(ppBia8uIoA~Yvy!BsoJeJw0HOi}smxWI7yUc1%!d1sgYi=vqPdx|^=I?J*x zdv_8v$xv1!Hupb$wQms%1pU?4DhlTD!Ue1wlZ{9(Too~)vQWYSbDMj~LX)E}3~D0L z+67PMRbaADvhEj}zck-VUy2;#(~PBUF$7=?i6lj5_=tW6Q%x6dYFgUWVA+q89*O%{ z72(s`+Ff0)&`__q0!8}RZ=CUY4Lr)e#=$DaVuOQ`|JI$sXEkayS|o8J(Xu<5LRr`S z<>@Akg7OCpiH3Dzh`yA@#N{3P6uJpRENz*bk>~zPvYLlumV9hMmo-m!EffSk1#9=u zuMyTUiaWHQX*yroY6KF>N(rziuEgkwnJWfFm^k`2dYyV?GHZW!OfrgP%t2*~3g7oC zst)A*vWp_rBDAj@7g(&69Nb=iysFm(V^46p@@{BppW|VWKb}BYG?mffQ)_)-nz}o` zYI{56Z>W+k6xnppn6N+VUj2U5^x$FqF5PEE5%?VZLGbu$eggEfPTl)VrdUOii?|uR zpsCO-A4%HH1%bMQA^YnSPmaPJWg`E2&O~E?8v=qhOM>#sRK8Q>hxM-X($on_Tq#tj zg%0$6ez($VhJynp{B|9>1f{sa$yh~<6)(Xw#S`8kcM;p{#t)rz3)PfBtCta zUQO(5J$&Yd()jtjb!_6=y<@E}9%SvLHTeDRPqQ4)Uu}K_J+hUsRk`lyw4?SroLgAI zzFu^S<6C`U>#;fYo=YBvzC3);yb}5Nu>|WbxgWI}97*rr+nSHkVKkhxPvHkY0Vt=Z zJX4B4&k+SY4hKdpA19!fs~h9B&KSNHAs2NnW?STqoTz7w@xqGjAm5%puj1-C6p+3w(^c^y_FGI_Vhqk{9uKjtB6DE z9aD);`3hf>UofDT3pig{akZX0>%Mhdb?l*%mzEZj!E4#nU?T!9g|Yc@RW&uPE=|Y( z+?5ES<*Vvdfw(zF2n3QHo128=eAp`;*d7IAAoV9o?;pi%)sS#$Z+g0)#hOgT+QGm$ z#+Cs*q6{fYaed~ixEq9h$z~Q?jme~nE419|YZF<>q@5{QE${6E?}+6lZVU&Tl;B$q zdWxSsRB9=RpTZ)S7RKk#PPN{MSqy=8hL<2LuF3Q!qa7LNHnz&FJLlWS4p*8N{W&;T$K$#9+GeZ9-iF%>N*CnY&phHN|_#S1cb@U9$gnt!4^Kh8xdbrtlChlyUn zko^ul{Zwn$8l)2FS~f1S1Xn5=T0%De>gCh_zVwa7x5iYAxJPL2(?(pGr^@wVZ-JL^ zb|xyDLbI+VTY*sYrSEao++D^8QbAYp`Hb1^4~yc{Q*F5S6nY=;&V+s~gx=Wk!lxmM zqRlm5zVKSVF4_wI?_$wk0!*wH0Bp9DT2ir*nDr2$!60{XUY$RX#`gm_PcZyjeXdTp z(*`-en(;Q37k`f=?@Djp__o{VaVR2K(Q^MB`0@A`uQy&kWSw~#WaDc)`zQ4`I=#%FQ>7|8*FnmioaG-WryO3YUBwyMyPfn{>^f9QnC-b zu8vr=P8OpF*f2;L{onCR1v194PgkSl!?-%V)lSH<^u~cehN7AL@--cb z|800p)@9e!pk`GB5s7x@;Us4wH$KEw|KMUH1|n&m07>B{q}Ia21EWiO^&+F$nGXE71FGtpkw=qMK}6sdD%1kF`%Q`_e{Lih(mSdIit zn;-<9#F?g=Np@0n?R78Or$0d8QUNS7P$)g5ojWgPH*%lRM{4n2%2)98(wj@{bfqup zZQpG4L*`r}Rs`j%;0%!;*ypv6m_a|((&v*;LcX|^Lt=La<$GqHy**T=wGM0ZgFk53 zFF$w0Z$4<;WzqTl^LWTmB~3W;R81%<&EY`|^yFS$vsbjXn9prh`D>duZyr;~43yaz<(SKB1+!mKhqHoYj;&nrJT2_A_LNKGCfTnW#jb-5-TIyLmZht??w~W-51!G1nk#GXu{O z&9$58inZUlme}W-err`13*LNww|Zc1Xk$z=8USY~JNRXZB_6KS8jjk-he3&q|J^R& zFWP*ss|$djTg_IpCc*(ebZdVwmW!y0o%n4!-qy{Nmc#C!Y!o1;M};x#=x8^}g1gg3 zD~NZ7#sHgSJ%G|%=_bn3<@U0rmYZ$0N3+3_A#v@ueAcOXd}J{6RFz43dwyvWQ*PDB zLx)bO2!vgjZtiekcCP?o5V1fw9_+g@^tW7X)|0B$Mh*;zk{wd+f=h+!2)kJd;EPxp z_(Hl&pQ01(jZ!5)abQQ>PL#bERApu4E@^jT^9HNfEE>3RFFK=5bz%O2U77) z#ewB$r>}=EdehX<6nXtVWqkcq9syDn;_7bs}26QOf0*#C~b34T9s zq|`X}$>D}O_Xb{B6Q071hkIOY@q?pE5kfjeKTijcCH$`1W-X&LxKql~1i4MuP|<@Z zK}1pS5nD#K_rVnPfkYHV@0Ze&PiXf|tY}pgXT3uoFZpcTQDH0Qxz=rAC)UfkU#?Te zJ@!q9-IJk>qmoTJ6|1y8U~<}&Zp6S z5EX1_?S=;+<-eyAj9{<$8K+-!{%x)~qs*S%JYmBn0P6dyI^{dJ)*pfD;`&Rho5k_F zkmBi#X7X`7sZW8JMQ|0|U_v+}rgV=Aq!Y%4kCbSX9ayfAr^PC|C?7Rnw62#=8H^WH zttyxhih=k~9~#4`o)?p6{f!w@xXD{ClAPyuU?kq}e#g6{w_taBq1vo6>2MJVK-`}L z3RoI}nrOaD=zsfzT)IZ3&062lx4g6R5HOozGjx z-t7e&;Bs5l_y)~So2LIXk;bhEuQ7S^0M`2FvTjvQD^aV_#uVM|B4+D+!r^37`Z;)I`%l737C-YSv-WS zNVAroFWB({+KnP(ieQVKHtyxu{)E3mWgB0q2_z)c-*rhaM9@o3NlyvHDH05y_FC=& zsBi{I1dWc2yk5Eq)CdJuOJxhno~Txm*jC7lM+*tbhr7mK2pR?L4|lq1Me5^(lXro{fnU8_>Ea*2=t+ML?_AW)7n@^{YT zYP)8~?>=pcf{e#T$gOKVMD4|g0Tx9i8!8?E%2T zB(Nr>5VU>wrzqCvZr9|obU3AH|2&op3_L952>sWRxZkYFe{;igot9(*2p_< zYc)TaxGm^Jt1#j;gW#L<=^IVuH#CF^luV&>;Yjyf_?Rm)CH1d*idXMtTN~`5(Z6{j z;HtK-bjhXGIGGP`7L&9?)G8H{lj(rn$?fv@NtQ56EBR2G(r{TwCZ>yoE~`w%J?{V+(S0K=r^8Y*5Z;{Xw3UZ_yKdbb<0 z%LH?_wUA#Z&Frv@#%o?{`aWLJ-Z}nIFDIci^`~d5V&)T!R2#nD_O>pX5E z!)O@%^oj3ckFyv@Q-Im*bkvK`{qk@Uf=SuENcDCC>`I{U1qZ;TF~Qwqa2~x&-0S-5?^J(k(fZAl=>FJv2xQ2uKYu2udT} zAJaU@?n%M>Er*g>EFhFP~5AM-{G2QHlK* zNdsyN(-wQy|D!wCzG+EaT>L<~hCPexe{wDMHe4j9B!&t@vmSO^;ca?fr*Xa-9ev}Y z^{g3k&zq)&Sy@@HZii;DKrO9gnPiq0ef0o~N}oQ`B?H25nJ)Ryd!*`k#%ZxwRN`so z7Q}W9bw_sDFZ&xD{&+#O+ND3MzZTw- zqq6H~GG8XRtNQoL$}I&Y?@Nl%(SWdf_Q!Jd1LG>aZ;=}1;by{(^}y=1xgw|2sjbI16(9?Tk1Q79pXajHe|qdTW^prJ9_qh$BjETpmF3&e>@O!@GP?$k z_%XDm>`sG^mv2tzgydKo_A<)n;c{cdLUc6x={g- zXmlj%akI`Tl2S2kz_pm`kAQVd6qCR`-`D7(Wh_I6OrClT4)zFqn7dBgQ}Fb0Artj| znz@B&tx>VnDAdDXp>gp3U-dODzN`#=!3u8_gmMWAMj}H@w#%|3VP(&{l5Yohc`c0n z6EU8?#yAUmyRc=8TFBeLKao?m*z){F4d?GysHDVYxz^Ay7>sXB;d~Mg8jXF`Hb8?( zOgqf|s_lvv0AT0abBULiEPB-#dKHd$ursmtP4u+)4`}YVVS+^v2pieA!O&wl_{t9v`Uy>N`xAi?frxiwXJzT@s`&YhGN|1cE6}tAP zO4uu)uLTT_gq^99*ABbW)8XhZj`SKFyGOxn`lDNmYhzxw=;fbbfQ%H__^7G--Fm{< zh)#+m_&gQs?sJ}&A*Rt>UR-2aU#f4v`lO-I*pFsZw}2yK@!lYGYKw@A)l+jdR8r476B5FKi%d>6uXnnHI+@)q=fS@yCPUcgYEH@{=r)ky?MCL|v zT|la!oHQ6KYU7Nh9R|EeYZ&Qc?y-YyhxhooKaWh(whUJ0Ho5t?|DeSf;EEVEoLpT2 z=xnUocby;LiCF(Iyr2&!?dK=Vrd?@#eX?QTvyt`>DI5b{e`g3V<>^)FC-<|j`ijvV z?AoNUMM3K&LqVPCJ7$e|LW%z&$6*%Qqj_t9?FEXA3=&}PSJj0)S-0^18gF1oKmP{P-I zg_*GINbUOyTQi5{XC}kX+B6QLX=KjM&KG^|j+yoaofa4E(mCG`5#|2~jiL<9TuT(E zG({dMY+j&GBdlBj6ZN)cWrPW2+X-`abtJKT_n)84%Gs$ANR(_bOR zOH~S}B~oG$a(201$!Hos7~*brn665@qG7x3u9M#9y>~tf{f+?&SXg+3P19 zl(Tta0RC$#D8up0M5HU-NL=_;0`A_8p#^vQz{U( z{`|dPz_-$X@NfbCkuYavt^c05YYXqeDTzJ?u+E@|X?w0eueUs3m^gubpKDD|Vp|Y! zX^}2n)==ccayDm<83eM_7Dg-cfg&TtP#Q*?nWigsmLe_wc-kuf_UGckmeN5U3&*8I zHM{4MCy<~o7z%B46vQE#r%6>X*(PnHLKF0%e}Rk-CB*RB7f{43^C&hz6g4#^LoLko z_@ISP)eWR&c++YRqJJo$$F@*>{?z_m+YE7d4^UX3?Virj7pz@O%N|ay!>Bg}oM7*T+xfAI_y z=`g+)tBx;NKqNuiY9+W9eSs_e~+aEZ4y zT0Nd3q~RMhp2)xi4NCr4c@->M z`4^)o$)sD~+Udx==j%&zy`;rrf$!SjrXgPje#+_2>{pc9k0;=w&EeC{r-ie`jK9s7&kOE{|+%u<>(oHxSw(Hk$? zaQfD-QSCrkz7E;amaaQwngUcg*=A?KS?E*UW7}=J`;q9S>-9#)sayYMjU1I#SNJiI z>#2nO*bjrY`>~@H_P=;BpXg#bSbiWN4|d)PZkjLXB5_NLi_=Q_WC3>A=D*pY?Rq}h z1QMX_mO!|h)KD3HpMmQFa2VLCSnhrt1Tc)1<`3~p5RTnx+b8ZL_XHf;C^E_FgyAO3e)1nTmWl8z7ci*iwNhg-Et&as;}q%V`AS50B+OGPni( z_>uchj9@b`dY}I^CH%X?e>=QEo1$2|zP?hU6CbM&w$t=)p|qLqXpbBNwP*%Lrw{r- zQc~T1e#7MJ>$j*hubqpzYO1-9o8lV+boDCdx>&HbxqT zQ?=bzF0s+dZARXxVZ&WgEmd{i2Ja=lcxj}ts;&Gtgt1kkn5R3YpU zWiGmJ@XMfJk4wl#8^<4glo8mFJEo$Y~`)hs($DKC*baQ{=i#t zr^c0==kEX+Ro{e220sldQ=s-4#Loc7yVJrjuhYR13p@u)a%{UK~nzRj-$D6WbDlB?*%~ajmk|>SZ_}RJi3bg?cw63+Uf+Yg*ug%s9Sdh#))vzQehPz`fYu zMh@mk6d!tV`KLc*7;fBulV?5mKv%q$Ff`<=jzj2F=5{XLxjR!~LpI-cYo|S>yVSV$ zRqExzb;4UX@F6qNC&*CCT$HKU;$AFlP`)NaVpSAxXGlR~Kp#6*U{E3NFK8*vnB8Pt$d-w_%BRxAHjjCLw@?+7vkDH=N|GLY z93IHho~AaP`_O{>?`662ISgkNOx!SWLCaA5W+L%wlfQisWh=KI;n-Nf0A@1((vQOS zvz5QfV1Gj}0FP=9H2R-yo~~oc0GAj106$!EW2#suC zvnz!D_T?o9y}3-xf$(?zcgEaVJ@VUMQdl&~-A8RZ|3!6Wm7V!*%{pKtVi;0)U-f&? zDQl>-1Un0Jh^_)h3z?yzznz(|o|#e|;Oeq#$?bHRmMNBpEaoj9<@xT~7=bN#rEXiO zf+pkXs8b-|;WDXbymQ+r72};#dQ=T*Z)zksga@|&LE0z7R{-EHy_f$O!PV^#LVL5- z-IxBAP)KS(Wb!h{cJ|NP3hm>8?nJdEwK2fPnzO6^LBj7z-bM^s6j58v)C&J5SL9re zPe@70fbkxpu4Z1`mr5#+QEAAc#V@@=MjIz#K`T>6MqBlK%6WGLimCH=5; za{_G08X8V4P0vFlMdU;(mE2ipO(`6*W_g%UXj}Qd0SDMg$fF|rEV151*jkfhcXPA{!k|nvKaornV=A$lBomc%mMU`7RTLKR z=kEPld};nB+gSB#8j5Z-pa|n zN}1^DyEKyE-7B-R-(~vVPbbE5vKA^^$fQG^^D+X0hdcm{qtY(=Q!$IZ%0&`R6XBW_ z4o~KJ5jqUnla^;TL930UlJ|zoX$FY42nhk6=PMzU9!a77Z0;;q48+7PL581xJ( zudUChlGO#4EI^`S($M{GYfPz~dv5sR6_O!B@4GXN(!&YyJCPM{%D{De`}xgSouK4@ zq=?(ctA6pe1AxTMGwJ_d1d<)OQ zbKHaJzgaqL(8Zhn$b}~Tnl~6uAZs#eT9Ew?ukVu2b{;}#We+vFB-Sb9O11b8ae4s% znV<^NAS;(()j~$b=U{v?J-EM6m)eah_K9lg+RX8>_uyajk>@HWmTk!;iC5)QTaUM6 z0sCO<*=p?FPUmwyaFNI^`L?w$`cJ6|cEG?5O4KbMJ!NV{<78ieRzc!m|wqUEJ?>$iKoJb)`CZMEw7dit^ zb2cuk-z-AJv7P1@ErKpwivJ70QOd0I5eLk> zyOExgcVyPA`JC1C&siNl5Gv+!xNRPKAe3IUxo__|wNeV3%!{0jOMP-X^r2;%#$VZo z@0rfyq(f+6y6&5?$|P?Rj_LG$+If2^DdgTbEK0=X^WZPl*;z(Iu{4-{<>7lTZp4~P zR{B?8h#%T2xQfdur4iX93JhunN>Z(1ip$TbF@;eOxZ_0s$!Md8QD4AQ{`%){rZfH) zZeGJrARvqDlNdXrI{dhc#&}pMlO*IA`o;ffa7Mz=lu)I+1m_~q$424cKm+lW$#0^`mT~x5qmYX@jirfDKp>|W-r)8aAo$U{CBzs)KNyj}uW$G}PI#KiW;XISj&xlqLHG_OEEZAG^=1FxyvPc3bS9)dc z|4eF<6d7L=phhN_sq4U|vTOs5(%#E3H#_z4pe@}+ zCpOWW%_d^g{!|C}g>654&q@1KGlTbhMIHv$_S^ao_XCy}!+xASy8nAz1usmXfS+re z|Np^rpNM2S*{{|UH0&SznL&3}lKVhlAm#6&n$`r){an8ofE>Gfde(wO(P8_e7=Q(X zmf;-mP3L5S-s(5YgM>8<$;-*&qgqfy9RD>DLLW;jpKc*CM!ZPv!XtZr9fO)q?p5&A zT!CR$?Gh9o66CDLdg_zE`vfM11)G}&48_oiI`3jBs20O0U<+8Dn)MNV9WDjavF;&NAe|q5ntEWVYzY!xjDdt0i zGYCq(@!Tf?>DE*x70cn-s&684K6g8%`6P9|qog2Dei@*pVgbZct#_+NnJt%#_H$p6 z#@uSyg>l@yYGP$lh;q=YJVefCZTk-SVh8*4gUN3`o&-?+JwWfRLWU%>5Gpdm^x0hQ zx1_S zN;YYZZnHbfKM=f8>rJfx*8I}M-tJ!DUGd}9N$>4QP81x|!$&&YLGPoY#m&tL02i#E zqCkraNhJIzC6?FxKE#(f&cEAlJX~%DK#Dt<7bN@$bJ7>W%P#Asv5!(-04vliwxNxY zo^n@yqrh#GqMZH3^cLk!7Ht;KYxie#CTI`UlSlQGy;9&@U9ArNY8TuWNSVv z!JH7@&`IcKy3UCEE5+Ek#cLTSrZ!X=aaGYSXYyKoT=}NdO3kYrUc&j;^I4oi_%GVY#D8J z!lsfDOsUtjB4=N_1^#wiw*m^}9T<0*4W=+u>ehsUv;0LKKkgLIuO_$WO$OD}9sN0( zFqm#VSc{K9?4xJu%h{D^s}&|zP0JN+(`x0?U-ycQPLc$u}8C_rd-8s*DEe4rByH`5#<9`Num?#T+K&EUbwN~4uj2<4JQ z@G4p;?PI7*w{Ppg@;V1LfMw@HMsMQ%5ur>kCT$_}+jtr7Div(7dgN}cgDC5FJpmaQ zG(a&`7LxIDqT*1&_O7XuB$OGDCMoCHn>{kMlH>1=yK;} z^^U)~n$O8VotU%ruOw&NIv6IA?QCx^Z)AKRAcoN&Kit~MXM;N=4}`YaOt_GPRe|;@ z>mk@u@8tqJLwXAFWuVUdZeSoCT=IUuWIz0FE9ij<^v3DI@Tvm_IWi+b2gMZjwud@0ftzhJ zfr~k_tZ!T7?uI!#C=YBQNBPC&q)}9!0*WN<=_x(`7%X6_AT)=VXeW}5pmWjo8IaBH z$d5GA>hSE0?;zW^x~vWXKe*ao?9K4g#gnuW_Q95TD)GFrzzYoDX20#h^M4vFv$b2K zZ1`!%{bg;@k63eVb+S>Q;waW&bfzFjBns~wM~iEl&0Nui{)i=Ssbtc$8crN8k4$So{I^?e{0S|3zl+*x$0lG4pZf3aa)-C678^)FK4w09 z7Gn;Le=mGJ$eVFGSzX=Da#5IN^R`xq>amSunBWg+kR|*xZ3OB2?_}GNhiQXWIt6NM5>w5E+ewuR6S= z6yC#7F%l`Adoew2XNpq0t$L2AcckLS!tGZZue?`!GyW5HWUp?!Va?leTZte(8B`7Q z1yQ1W(x4V1sRa*3dV;d-`m(Aja41!;6MvboEm6rG-JM-5;L|osP7u1qN;BqRAk@+< zJ-#-;$Jw&aUGgqhku$@r7fMu?EejL^^$sT4=+UvCZM9Rmc48fF%@|DXv}9aL&d44I zQwSdQ2#MA2|9pr2Rx=Nsk$m!2BUuW!x>|J8pq%RKSq6g(;2-17pM$9nFtn4A0@QgI zT*Y4Z8+1y{lT^phgW=B~QIYGBZ_@~V=S80_*N5vZW5!haIOK1ZqpOWC63jX~F|Do3 z_+uKUTs|%Brkh08k|@p9N9!h;`;>Lu81+mT_PbtZbz5_OuL&5+FCGv6&MP!|hviy^ zdogvJ@s?1gCeEPKrD}F}e*0=IaVH(ajRsfLS-h!DB(h-b*3{fg zn6sIEeUpH8Rto+)`$mwVme6WRI&fr-Xkoy>2y8E?3H_PJhz+Wn-3g|~kHe@FZj(?{ zHKD6ybzfc7%wwPyMcbs2COt^4v^rn=&Og#mXDZV48@eex6)pJYzJnoK3XM}qui@ih zNZ}3bIBdDCqE(bEEj6w&8%_Ft-`>TA1#et+6SEq9z@`I||X(??Ddj1?^o?caQUN5PcCtu#MP@zJ|h2ZYmWc6pJN$Yr#}& zC{07;rTeiVRsRbYKFGVNj%Pk~^IvR8BjIL@1eprS&okc@%QO7rAAn(&mJkE^+*DSh zA48l35kwa&Mz;=4(#4th54Wm7)$Po5@>f1o!pqOphtqxUcAteUpe}qvCHPasEUiw+ znsx#%@yEXxe?|6L=~No@MOYbvy~EG711}x$zczmvRskp7FMiDESkf}6dVeWKU1*gu zNDqTinr3f4r+jf`x>CedR(=@HswxRxjV&&5$NOfA@Bl?Qgva*bVI&%OkJ5tEsw~*5 zfq!Qp=xI}cIhWG>etdF?EQTN>B3`=X{+B4yaDetGaU2|Dahhp{~?^h zs%I&Pz=<4xFX@Xmi0Y}y_aj9Gt>A^cBy|C?ro9k}^0&?(Wx9r?`8%h#Yr<~yU^o}F z-!{mKBz}#@uaG`AlI64Ma|q;%G7L7^;dyc@QgpxoE;>qx`4JDr3?7( zOpphhP0$6r3s|??ob7HpjR-1rOX=yl6B(RV`I7ERV*RqUWw1t5c$Rz| zSzu@TK6F?RpwZ`AeKbFwEdz*Oq=_0k;Xj8k@EJm;itHPL?NymjhP$VEk9nv{UrYZN zczpX`kJB*n6%tSpsF%;_)^o65O9U6NPJc;#`h*mDK;Be?LjgGiaN_6kqHA34pY*?= z-HiO5y(?9kL?lIm_SUA!6n}_2MvGwVG6@emTa)FR^UBj9mD_QMaN=*lsMUFfF6#aL zQ4jT0`4v4ryTiu|d8*o=G9hrW1YKru4m!Q{JKCtzF1|GM^Y&)^j z_}*CJRK?;aE))&yu^<|{dr;I+9c3T}s&3E@gekVeFDZZ&r4RhhYN}`}?8(cofz)!d}BLCtfJDbhn$=0ZzOa%qjO+GrufkQs5O_+j^9J@k#L<<4aB!rlD)xmpXh z{QI*R9)6z5sd>654in89>K0luy~^|?pfss6sv?k}Db*TGHa9dpz%)RXj#>mevP(|BAwQ))`fU8UkAfVPXm z5wDP$pjZRc*~8%lcF7~u7$5j}>V{mB2?b5JQJA61y##C{zq7w5Ng>muu$%0X5+uDN z84>lSd2u0v*M%4H#Q#yOmq$nY#_eqf456cWI4?FC<=9iv)Ra|HVhKKL6u_$>0Q?j9 zd=85vI&F6rZTF*2hv0o4u(tx{5PQpiJm;%0vT*#xyVwayNJzf4S0~!P`}`8j(DJsH zg-lH?-oH$KvvfRM2$+@$wMU%$y(36dUFJ;40qo1Xzq)M;f#Ug^TfH7N0 zMJSCnSvgrgx~>3bGsB^H=PYjUo|I`L9&ZZI{glY z!$$sqMrLHq;KS^vMvy?6mBba9*k>qC^R7N>(c$Qg?Pgnet#Y}2fwX>Y5}vpo?Udk? zC&5n?q$RYlCU|l+dKpvS6=f=neC~Svd~_{ZM((r&Fse?++6Oi=j1<9k&k6nk;8x;# zpkk3GrX+OdK7NNX0fx^;Ra9C*4#Ji%-^a zLZ;z4KWBe|F=Dbs#l&})qyDuH##HaJ+?Zq0f)0)KLlB1O)tnY1-GUPgHaRyZV0Lxh zJ&vs2V1;Ry#HZ-iL1?I*Jnk3!aN zjch%*}oayJ;5UR&Yxz$P#Hg zN!)KYrU{^G<(iDzrz(8OuKV`=d$Ru-i2iu80jCw}<)RyI6jk6A%F_MArIXlhS<(7R zCdw<@N{s7IPr`642Z=EOWtDvxmQ83s+*ccZ`zmlQk!~TpjkV+Q4_W}1GP4*vpTm_9 zm!-B%HY2TlN+>K(k)c9jxP*mKFA~2AX@(|CLD`L1pEWVqSzc%3cEXt&Lm!?ZUF62r ztcv}7sSh=ti%=7?suIU;GXJwgWsg6=^@8%7PPNaGsAtX_GK8D=$uFj?*8!;glr45- zC*tL}0Zh@oj`bErHjI0-Re-9X!I^fiy zEtWLh)ckxH{b2XPi!RDNA4-YoRzb%zJPH3Jkd4IgN zClNWK7u&>m6jQgJPPQ?8E`hDB?Z9{*M?pn0RnlO|>gbQvWY?27jCHjReq@*8f30u? z*NrX5vPR8RMLIi{gXPr|O$k|vl1mPoC{x%0@jgo#%A(2WcJ{j8dBLUsb>N*h{TIxB zRcpP2=PL_b&QDO5ydv_HL%VUsKba+pdVU$JNz}6Gr;;oB6IK(zFq|OzDSP2F`MQVE zxumShr>M$Ix_gcXO)Wg+){Eb4B$2>_#u0SC)iRnbBPKkMWtA@_|F+l^`?cTGao+gz zJ;cPXiFYOSc^dT@_D;kS%mr*T7D`{M*010MMn$2y(@X===)AR(ZUJDjt`5lX2qt7L zLFr@*#bWMqE$-%gjOVTsuFSf8*HD>3&l>U?#%aR;&;~X!K!jgKNbd(tlnL_*7E!V9 z+G%JKl;e{XD^f{GGq7I!{qZ1gyLp9Bt8YyfGobr$d+7HBd@=L3wBg|1ZM53F2Vc9q zTx2u!ytWW;dbrth5?l#a9S9n&W|g+<0IAHI+uNNnoTRZW79G|`c$9@6h@i5j)n54& zE0=3^)K+dIi2TQ5Pmqdk6~BB-fuVAst3W0^o@q920p|_Y6m_mbszNE?_D#=1J2u>f zUf|F5_SO0ATDT_(o@(9-~O*YfA5UXaBD?n=3-y2rCR@HGhw)3YD$Iu%J7B&@5e z`(Ec@<;=wBRnLxNCKRb4Dx_>slfknwxsg^%gAtG<4p^Ir+ftF-{!@p;5>`0-j&QhB+`+H)HC z*4izj1fDTTq;BahYHekqjZl^rw4_8f55U4N5%6Ds>i-bmsWt!R`98m9tite7Ee)@N z2U?UU7R;3IZ}DZUE>ZfxYod3059gWLUNYrf-dR{=u?ajNC*MA6M9gYrqiWu()9}&h ze9!2S6h!dkS<`yBlnoGBX9y~O-!p5^{5Lt`;#XY#RFCLjTn^GEF)$nk9CUxXbK8qg z4a9ARru}_h*7kaF|NW}#<_%mtpy1AxGDXPJeB&hUpnIZIwDIG3`?kekX zzJN|Cm;#Y`Y7_mjikY>URlUYwh$vQTQX0Y2`3+VZ(Q{c)(Ur@tKv2K87WH{WGv{5w z_Kn-ArF=lpFUR8>vU&NL=~EYYjaiP*{ke{A?K(+<$O$uuG-$zFcNN6~&P$o@=iBe+ z4S{N9Qo_x0?7y3EJl1qzeWcGJQX4nmQ!OBALCW1WneVL0wKlbo6K|mFOVfP@_4wYd z`HW5`$yV>>e^wynCA;qaXZ$rb-P5padX3e7b5?MeAdHTX4h?64@BRL317TN14=pPo zuoK5S?D!0O#P$ju$8jO+-W~IDMZv%nHevqWdn|11Y`mOP3iiebhxr1BQ@-r?vZobB z4^Vf;?s)N*WUBjZIl6%D$MQWXULD}(7~U$YDlc}EV*=s-&-L}`Art{T-+Ail>*^*Z z7CZC&e$u5WPR`8qf;o8id$3OB%;+BXa93f<9UT8Hl)f`%rDkN5=x9x-h=TeY6=*1C zYu3Q!_a9$Ag$0HFza_7vq%vJTpgmU36qv{t52{uP3kVRJDrGB|mel5*At5KxA|oUF z5*aBA&;x>KPX%e|Kn0jQ5-(ih{L+j#G5R^0*YEfJ#DA%8o=UV{CU925U<8d-<4w@@ zxGZ{*kgX|CuK6#mB%3fD63Io+Ki3~Sd}OvlnQEOY649_^7+XL_9yn*xdUi5gY1j}_ z5-AHBl!XSYWMk*@#gkX~CWy;tBhp-ie$*j_JX}tTAHYNeprGDVw_W&JIvfAxo3Fw7 zHk3B3x$~XjtIL1pRWIfvfdlO?*ty1^U0;kDnhfkOc{*RCuU$2iB95n;m=sK`1hEo! z(LUBG@cm$2bNW-)c3r*8-+s*jz#BAfo;jluQRK>?LjbmzyW66kOW@YEvzEbWI0PkP zt6^o>Jm5`i&~A^g$;Pu`g2?oq8q8L|mvakVy^rpt8EhYjMZG<@VYKC^Dm; zW{rlAf5<9fp{H^wYoL!A--u2njzs`Vm#M<1_QDBL42^_9_4@`)ENSu#;q~-*$1wG~ zgiuHg>do_;u^e8zSvs!;m*<9txp5Bv$sy_;ZAoo)Jr{lG0_MaC7y>eJF}jo5MXreZ z;;H)6GCp*&RsZnaxp0_IV1J*Mtv*_maO|J2J~}FL^0%8kXw$~^m&oYoXqK(oEOOufjuvU=+r zvDA^67f7!MT+-7s=GOLQrJ$wi&S)4f&83pePjs{yM%{C2PzjY$b>gpXKSq63>7SQy zfpgap^gcZelTc5OVst;LxWK;*d;na(j5P%R8j)vUKMI@PP z`s2)-t-tH@2bDe#6poEIBgqf%9%=04yof<7pRb=?C>y-Cpfa&9ClFJ&xh3kOM%R0Z z9BI%-xSW+0lhO5V9Z7TN5E0w<&W;2E`?U(%T28X6P+DP4K|*)+&FgZl&}?N=x+!@j zH$&v}_%rQeBfP$&gaW0{gfd17Qg4v7Wd5ydd?J&rki{Q_Y+!3|z?#ydFCi`hI60REu3a^`mMMKY|~u z&f4Kn?sQ+a>jMl~s;XGlOofiy0L}B$?V?2IY4v{4uUzPzy zQ?fiNFMb6_F6%JR4mI15(ihDbakHEtVNbnHJnyR&V(+soD}ae@_wThc6LZOu_NKDA z$YR&P*DNb+=SgQ1qb3l^^k7fpYc`tAYqeiLUl|`37WU8e243u`Rqy%77eum^IGbFV zTF2ox`G_b-IA_xt0XWJG&dt`i8Tmi-HoS;I2DBgykokXd)cy!&ZO4g8L|GA06hEg~ zG%I}MR=%oRRyM`1A=A_ElI?=+HtMy1h~MFljDNH}8_m+%c}KUodIz>%;B|IMwuqoU z^Vy$}`zgLY9??J*wD0m%CTT3DddH8smUhuTg+AOb`D-HDJ)X2~v~CL$+MOiVS&a$L z4R+yN@YR}fxA`w0tKoLA>U^AQ_Lye~xDS|1h=s72WMCr0r2?d$0k{!6S%W>* z+_kOt#^i=2AL15`K97LDM5=yc&!o;y3Gj|8c9lUhwm|9TDXUVLQqz%>3J?Vk2z@FG zRyTDPp{htE4Z%b*JwBWHuk~8J*|tY9HXXP*IOqw~uMKl&Ftav<7s%pWmBFrR>Pyl? zI+5~xHnWn&E+4L0vC!pi7o2mt%3r;`TwzWWQ{X!2I2=!2nPQ52P&NK#h=O~!gESlT zH7@{XE(%x;LglFZ;)<2hzuL~gQZKXlk5r+}r%yz&p4I*$zkhbm3?165uKu?l6XfOP z6}j$t(FiA#F+}fHtYms^A+Y*M_02|7>UbFUV6!?f>7?*X4?yZpQvU5{mmYrKzNgOclG-p#_6_~qW4F@e*4&)=FaEsFQTlx%k5kQ;FG8ZwX9;vV)+0*Oyc8;L#ywPcAeK+3xR6U(|Lgtr zWs?3y49t$pu~Pa(xkn9a4J}9DC!-_G|Ec(-R>VV4`u83OEdhVf3w#=vi7EM>K>;~X zzDc9)`bGX#j|HyC-{7U$SqVEkOwc8{TYfISTszFUret(8DNl8is1>liX}g%`=L+s} zpk^$X!&zbG)Fz?+Jv%G@CT*x6ryI zir?u=A@hh@#zLPsEmA!l6b#9fHz9`#kM3l$(y>Z>wG2p5pJ~S zY4CF7Hq4Z`LS_*lV5JMdc{tUYwyqBNk25#KU7KUF!|>g>h+#>I!s=O8uKZ;9zu}|F zE^g4(GY?)5cXxN^hti*0EsqaJ2MtSY;yNE6mBU=fGr-RdoIVFF zztIz*QwHp-=Y44V1hqImQF;ZTgPW>Y>@V8>H$PPV=*pI0SkP3C^hQ(FEuadIM$Qe! zMbOx9ot~>Hjikqbg&eCm#pCOHqYjB^zWL4kRWI`G6Jo$v(W)sQ{en!-qyG#?uQ4*4 zed$smONh4|SO2U@?pA#{U_;Y$F@tk60 zu=G<`jZy~qg0zG@cl^cRw2`cZuJ_tm{WTVPJT<}37VGTr!U5!v(5-7AJft3$j|^G$ zk)KF~?qTqo7yuuVN=`$q_n@g3#AK}`-Yd`bB*sbfdRnvH&gp2*kQ0n;SAf|%Fgjld|I9wmEY{P1c9a1ch{J5_B?Yrfmq zdpz;@DRxT^AS(YXFiCHMPQkIM)q0|E-I?DQ4;cvgFi;ArNk=vZHfjlDLyatiCA)V8 zaOyXVg^9ovk4M|H2kwgA^oJI1JD` z+xxwj^FsXkRyyYEGP74PXLt0&d+nTGujvF*qMARHEJq z2m?3lUen{Fo2L;b14C(JuG_Ruz9|F!H>92w||HN{(T0e-kw_IBN2nfii z3JBsTHpQQJ$pSRsSWwNiGV+he(qx)!E6Sk`{++E)-v3gcTSg)S>q{JYFa7pJgv5BT zC?dAQlQ!ZUh?yTu*Or3L~y7LwF9m-dfIpQluHQ(*?~!j z9nC~dQ5aw{QSjqHlFM~p)>CwnJLJg7QNpkh zdSw2j*2hVl48finSFM&?0wgy3{@!hsuATMv^5Ye8s~30Z)VdQ{YanJgFdv8Nj#RUHwh|=d#C#sCNWevT*gei{#+f7>GzQG|RdM zNs2UEADaU;s^-7$f_6GANpsN70bl8p;a9m{%Sg{J;Ck)pv9B7F{0{Fahz*>@R7H*j zz@sTL8TCMCNCh1aygx^LEBcmN|C2&FhdV3bB7uWKScox^O5DW6!2ugo3OCm^-xZfP zWgV~eP0US4n+cy?K+(tw@M(pfOYTQ|veA_YV7_EG{(0DT zVx>#U=i!<-)G9CFBKd`?P~a_KzPatceGC>6;OfX|KauhOC7tq_FW2(Eo?_&a5WY(4 z@%>lZrS$(of0n}r3NT`rti^3|MZ=et8$J#A_7q(Wm7A?$eUI7(4c zg_P~1BLsVeYwOYNnw_m3WgRb&ZK%`vk+8OJl(e^rN^QfmS;%CHxX43N`2WBoJ=>)gI$B6rL`U% zAv1H$Um0^!ME+L1aa+3$jHgr zosPD@cuX^Ei?pYlW*ELTGou54Gv9DVHOWr*V=^4~2U+t`n|QJ^!{2*d!awbdxkDot z_fH^1H&LA-NV|J`gPX2cSXf;37VO~CzOx0v_d$MpYCtUh7jVDW;alT>{-|&#)91ch zYvu&7ZD7l|)C8=-qa&b<`5@pCdMSEA;0g`)D1@%{Li)goVAEp?P&NOq|Tu zRkl%!JPOq6I5X%nUa7IBqoH#ZPPj=KQpBsMOe1De2BVWy3pxqllHFWI-tkWm9_3o> z%`Gk9F~t7hyMqEAICLp(wv-zdJ)9*BhHXv1|27g{K6X4&`^DRP(>@(kdn|YE;x#97 zwVV%f6)Ij{OyCzu4Zs2XU{y(fx_Qw1oA)Rn0PHm$v*qc(vgiE#>FK$@ZNimNtjnqi zpWENIFRl2NYrq#vuQamYfb-32w8z7ceO@v>ylsd}MY((V7fABfA+(QIV_$vVlVm2B zGrZ0V+q?dBw&TQo-_bkQMA;Wd8D?KHK>uRkI3A~fjWNLor+Zf)rAJDcnZ@1n(73Dd zrN64RdD8#Ube2(7ZfzG<0cq(5>F(|Z>1NZ2q;!WMAt~LBfV6D7OS(a&OH#VK^Ie?r zeLv3d$2sHZmS?Z$Uh|&wn)$o8F*=nZrMe~YwOz4fLAAxEyM*T2rGBsEEGl)#^Fkt_ za%|}7Dn>t59@KbSC&fzB9VL`waxtgT3f=RRf)qWK<6g6S2TrS)9B zyzxFf7*L>$g+nMBDl1Ia~rkv>J6vv`cRw9BOo8X>DtWO zbLX*!Dk}SvYQogVNqK`N;pcum#K>5_BMR*gUD$~iK?om|rEVEc*fA``nJaLa=)tB%*!1;^iPKqF}Ad+tqtRxZ8FeM zIUGiW<8XAh%h7f9BxAyIDQ8eJJLz(l%Z#Ew^8FlinYH2lCTh zN`d-~#sxjh7flJugvsOk?}XV{+Qhl^a+uA9GFWs3h7)YAf#OQkDZkYik||0Yr6L>b zgjl^?Zv8*KLJqR%U{lnDL}ZQQOipV7+E?B??i%L}r0G&0Ki2+wBQ1#=OkMRuTMO(@ z=-V%$`Iy0!`_QLckwc|PKS;{~Pf8TnS%Wg*=iH9VAO2y!-5+p+@T3O5SN1hq-{|Bp zlbnMuqu+q<1OC7UT~g2b98@!xuMFwo;o-VXrAkx$6^&Brmo2ZjdG7B9ER@4YG9*n1 z(pmt$`Sb2j@YU*%0WyCm^+^QW$0&z#PWpNwliUkIcD*%n+sK)AD~Ji`n97c1R5FNmm$q( z!3#iElt;67iajrdak~3FfSW++Bl}eD_6vv>)6;!j!Cy~$5>!C1BA)Ye7N9S!$mlE~ z`~F(yD~Wp}7jcd1hW3W@m|t!ah!ZE~4b-OUZ_LKMpQ_K@vw(el@r|yp53fTxWM`EM z5s^QfC?Sr*CC-XQ6`~Y7lXtuUSdtWJ*t5agFL~nt59eKwt}1lz=k;Dc`Y8E=1bW%4 zhg~fP%TsJE@`e*@{^>i2e~w@kZm5ZEsRxh!U+>FFD~)CSc3+aMEEg7!r$c)lhlQR- zr?uH?r!`s9%NPhyVB||Ld*0}&6%0lnXlQFIFeK%h=$>C({JRr5sxXXz6u&TGEtle2 z%ZWCy#0Z!bu}js#i8!#cQ~bt;G2>R!94y~!a=xtwJRZ{(ppKQXyczm&%BI3t`|)wF z;|aQ&VdLSzYeVWAGo#how^z~n2Q;krWqK@GRp{O=1>YStJW-Y(ks302W#CAkpe{C2 zA>0$F!(v4S*OBKms$yXdVS-j-a(s{{&x0a0L)qE*zU(z)NA%LA_v8M{jaKq86!vAH zmk^?4PBu>6ZVt(XQf*L$=T?KX+L)@5ipB)p`_B*DoGHH-F&G|=y>wf~RbD4!4t>f& zmIaN0w3UW7Gq5(=4^PvikB+Pktrs*TB=exeNl%6ooJx&{^c_A-A16I^_Ju8 zYANMeR`+|l^5fmx+x5K(9`QQ~Xx%z$#TxH96Y8u8XGew`Gr)27WYD5g_ptr;=>gA> zlDQ;c?-S&&*Uwjxo~Dvm^8D#K#dOdB2IQ!uf!C8DD4vQ~g{0Us0S!vkp~l3Zkl_W! zDSm;XAW!Ze9Hjvt8adgr)ZritD&HtxLBb^k4aU$oWEw`%aj9<)$|KR1RkNt~Lpi00i zH>e5#xA0Ii3OO4aModf)(51{~9i3bVvZBewpplJNpF%)IQ-0I+LJ6`1UW?`B%EvYV z-@^%Hsj<$l(2noV7)eLD4vIaNeZc6~x%oRonvzH2;^D|A+kj`}AJF0(+8^w)^xD34 zqX~Wk!=bt0(Qx&BWuX--L-^@w*4gIL*u(_q5?Vl$(_w<9&xEWj28_)9Rxh7kT<~iJ z2sf7!?J>-W>!!eLawT?4xx&gFWZdCrVd!GB^JFD`cqG)yjDx$jHj*6p>4!H4w$46# zR{I4oDX_vD&oU3j4;Y`ry*JrC-%(5xN@Lb{x2kfV`s3DnqkX)m@2BM8z&f1l6JC@o zDkqTiFIMu+CJ2ADU5`ql`GDPXJ%Q9)1DTKTi^8oaD4PR#NQuML;h+K3Buhd>MI^hs zo+*G0d+(U7<4kDR#s+NPf)50y$m4R0!Lkvh`@?kP4%pqEE`2@%_~sG}{_5OVMXK$C z9h&|3Bm2Sq3Cx19T5&;E=s_#+0B#|_Z&4o7DDyP19mNpT?|XrkZ_P@L`c%o_FPu}7 zuSg;)HacTYAc{c1q)U|)8-_~n#lRumZQk$xo z;|JC4lGpHqZ!Dw}qadA7DGkOFOl~b6_nvCZSXCm2Pc%lgAy^t@^y8I7U#Rz>KcnWi=& z*li{LwdC`X#Ev7Q$o#RWkbNkY%bSe!u@p8o6;r-a8+)s?e`pDk%1o~&XYk> zg?9+VPymU)BQeIW_FeRPBVzgTs7zOZ#prueRh&tcm^+&SDCssdT&zF%ghp4rz)H>x zNzC!_v`v$am-=B#=e{KsEddA~sAYs=drd6Sdn-+Elfsz|0;^`7u6gnI#LYZu$Gkbx z%+9yR05}bp(C`P|L|+;>q)}B#jzvyU(9rcvUNG>2IN6Tv-}CnNkVVK->P3msL%4(Y z84+>IxsJsV&$F`v@XYk66fyMcz5T#{yUebn@fx4_*ZA0+xQYrXSkwU4DL8tAf0BK~ zJM#q9+Xc=T!_}+QB=u`6pWhZ*aTs@f(u8!^XKvqOAvAuhk}ag^KDU|xHeM7)EhPVP za1e+Yg4CPka&5E|;@4*SGsjvkci-3`tI!IZ3r*+Rc+%!7wAPIDcib8p%U?)^fAvH` zk`hS5<$}Td3kpoNDqCNOg3P4T!x!7R!p<*FQC7{2iC)MXYp#pl>WEAX&he3E7_uBl zj)S?nls=(Pn{J)bcqgYN6{o?h-u^}p{S|z7r8VGY(GE5etO6T%%TJv!w3)8sJ;}*A z_lImKKw`P^e$S;j$JFGVY``KzkJK2W{l$rr`mqFIx0%vl*J+^o$TI*+>Mz#4Tc;-E z%>WJ0A$pFC;m1WYV3zeOLDac4i)$U>2%DoV@af{>D58}jr1yMRkUPD|4qZ&Rx3%YN zO-M-e5x=66Y>n#|e!NtSKG`sZ*SgjGfU#=o|y?{*6;Y9p% z@O7Ce0Ap0@SvTopD7fjQ0s~&mxea`eeV4u`n7Ez`uFKa{%QdB<6QBUfFbH61YLz5= zb(#zhfJ}@mVF^9_W9sFi!(B#3o+GtpC9O5aO#;z~GlvUMg^dzWhIH)6jPmP(`x?3t zOKCY{;A?{4Snr3r&^ge9ci$3AB_~Tt#S9js6G(i@$)aEN7 zAh>gIVE*C57w;;mV%2=rfv{o-ImmhyYO<`poBq`AriK$th7w#V26@iqo4$+5HJSgE zg;!M>l)z|2r#hoL@@=jqPL>J?8(Zv3oJ0SxZ>0sl{3#bz8-Ru;?T$x(duGBE!fpZC~tf*(;`eFF#eDq#2C8yZH`CssY z^Sqt+t_I%mu+d{YtKZ4+^6mbX$kiF}8KmvFHs4lN)w84whv8?~Cfh0pv8D`B`)gHZ zB8(XuOV53&2YrzzP3zJV3@4RuGjLYBX?S3vxw%mJr0Q}aiy&=un|4=uF5NW6cU)S7 z*qdyzHJD9EVIlDB>f|UA_r^aNa!!yaW)F^E`=%~AY&YZ{sX+x^e&sc)rqU=+%${pD z?;dAoUR(MLtXBM6S;Gy$Bn0+X>>v;3tX1xv<>0+W^lVz0zR1Za0cuwSK&^+%_x7C` z+76FX>*{ehRNVYZ=MOXxQCaz%8X^Zy5@4adZi}H9<|~)%g{m?nfv@U@bC^V1$K}Di z=hdRe^ZBc477YGJm@_VjtJt1mNf7yhas8{stN!fvCNFLuA0H~k1dzZq%{OYXUUck6 zT>#|h1&|*7?^jS2_g|eyS;Laa=NqHxMn1( zbk#C)+V@$1&a{)<4D)q0RX{q9E>yWgNL2ZItfM#Su=}7TTOp4)z2;6$mwur4Oj?+x z-RJFjd~0SHUlMcAS1EKhd>=a#<3xJ=CIr?ZIX@k>UNwRk_NNtpQJ3FaBEweMLP>k= zPChlc1AaR0kJZRm;6%)11K}k#CfsLH3RuG}dMBZ=r1I525{GrPsD}`0t4cYdsR#~rj(3G zQ-kK;5b?w7@<_{`-2b3NPKQ)=$9xy~6k4QaVhMT3+!oizPZ8tF>XkU@2kUm)KP}g* z3eJInt&>wxtJ~5tCwHQY!!Peh2iW_GYZ#aINxzHKUhG5*9+GKjC$iHz9c(nAH9vZKp0{b973 zJtzHs0iFK-P-&jRw2v-L*-B|bH=H9vci>ZmONfjB4@GaB?}3Qs18AlZi$_t^$TMJ3 z*U0FsxBL57FqO}K0mm2p5kZb)HS?!sP!Ew@d{3`_yjiS-_e?iw^6gvNwwC(9QaV5| z-`(A_w6-oRu8M1J){7s^7voM1`A~_E$fX1W``B4+=R7AqUG9^O!>E1yct^T2>n@jE zz)0R`sOCyVF9vZty&(n^rDUD89s_)D|k+bvHj)s+` z?aD9Ck#!K6wgA5gg&^dceN^kDQ2dn*r#T6U?AU zdxGDmMMf4EnNRN|qdMPx=1MWR;_i#G&b8H*7!&)ZO&9jX5_XonSS}wGM|*sm@$N{! z{vpYA;u=2CfVS|TX$ym~DmhNH31dkU@a)LkvOWDS$;pWWwt`TAKx^?nO(=4{0F*`Z z6hrq>aD?CJ#~4<--litA3;O(Ab;!^77QuMDLL&Yq{-kDU*Dj7A9PK8^Pnwqp^ zU`S^W#rFDn{S)Wr3r1jNxZW3XvEtPDzCfssAdcuuZOOE}Iv0EgDk_2*7ly#Vxrn~H z=)1+}auVD5`Y4bl99>?P7BG}ynHeldISjA5ktu%mkFWT{H?9OAJK1J{?}PDGBWV3tv-M<@fzF|%xn1SrSZGO{6xV? zjP^0h2{%~crIH3%e@cf19aKvds6W1Ii(Q_apO6I0YS7ds1O|4>hrd2QZr4bk2Bx%) zI@M%I#Qcn+C8`E`POwyQ;QHN+X51bIJFa44she`F2T{LfS%jPx^bjd(nQ2N(Yj7Fg zL9heJI^6deCVHK0tMrmW+%HdvNLM2w4W^8Dn&l)-DVg(R0;$GCM=SK}U2>U9u(*}H zFtIDt>8qVLkbxjx2?V+4f?Qxrrq?Rf@i)eQ)zeTS;_L=O5+@fGeo??08wbdz$-qPy zj-||(MW0YaH=La5akW0EA%exbSH1^K$kH+&X@!Ny7}&Clz>k;-mkt*xF&wTmJXLG1 zK5(yPEWtD}QD=rrQz?)wzbYp#q>zSVhbwwZjYV5EPZk3V#l(2S&X)GpW+$uE z3*Z)wjZ7UsD0T7LVq4(o=M@XEtBIl#Bs_Anu5PuA?&^>2_Jv;QZ0De_!oNjQ)zpYg zuP1UdrBUb7OBHtEXf|GHlE5RBQf3YQlE{)UZpKk4|6|vTq^WEr*l78BDItX`I;&Z$ zs)j2KuG$?_(p_x&m@0zxZT*Za>1MkXiQ8n{Ky??Or2GM&{m)51=?KuCdOw1f`UU`D zrTFoH_X_>UBBTYj8;TnVrO_5LyUS{5%gcMX21~i@?S-+yvk}n|u$3hs z-lxs{LpDq}oNNfzfxgO&S(0D2IVi?2y~up6y%^2`P?Mq~X78T;o5eov_@q+ybdDod$c7khB*d z;IY=cbkk=-3u7u$lQIxNp(%u=H8n5=B|sLCM5m|=`FQeX!jzn)rG%K^er z3${j4!6$6tg@96oy{g>r)`TFl5ou*bo+%#(%*|UapKsnfM&<^wPEB!N);D-my6xfG z&cBN{BP1jQ8XEY1a&(=-wy^1vrrn-pKPiG>$gfm(CcWCwB*yHIW4Y462bK5vaaWsH z7#zW=lxsv$cJuqQRe_g(NI>v|jg5_L`b+PtU=wydnB*RTejFyjWjrV46E77BomGgm zxJIuOd7M1?FeW0WxP~dE1&6o*ec@KtmgbFPIP`@I(s^cbxcdE=pPs@Ha-2iCL28DqNo~j%Zt`gfA(f z5m$h&;h&!q&(Uj^x9T4w^~c0>uDGAY*xZ=7G>;f2wn$;e3M2FyiZ8%GI zU6fvXR%v#H6>8v=1OUJTj$pVnCLLk_MUbPg$-_-IVS1xg9JManlO_&if{lw3NuNiS z29xSH_)aK;405oea3-$ClN7K9s^!A#>L!=$wdv?n*BW*&hDs8b>>@ehCtDBLAxSdh zP8~sHB?ERHlI06T0X9aT7KAL_6o4`X;4k?TR&Ce4tksVHjG6S^Mf~p9NM&v-kD%?) zCoPwYeo)&-^tfSUb!58+Tny`=q27EUD2&l%t~3|A+XXITZC9;FRjYGbIzL?zF=Kyk z(xnUo8tDW_eUj6f-rVO$5vKRmLB0J<7Sq3U*O5KNR^z^sZl<)~Q^UZ(>^B^V1c{?x zqOPmVF4ecT6t!fKA%MP4#w7V*9LC3+(FczuPg?M}a}{O#3fS4r?;IW$|@8@F4G~V)f0;s9dL@X7-$QfMmtXr-k^H(zTIHGDM^`$_B z&`@k7$1F^4owy9gU#Yl+gu4KNj)L+gnuPdQR?A`FMev%6&iK^WSe;CP$#3uds{VSz z&j)qJEEy4PGEvO}3C^C{pH4(S8+t50ALArImUjYcpc?BbB3VpgN8rr~j zDJ@=C5SQ9it?rPD^V2sb(f$5UqZ8zSuzL<-6W5noKq%uh_RPkyKG6jf0iS*)!bH>T8y*D z<%>&~X=kuBiaF1D%t)k?gZNB6Kj=PJi!vhFTL5gbHLk##c>+#=`?#7B{yQuei=#+g zN8uQg99bUPS_sI;+1kf?i?GsYoG?^Uy!uJPIIhEwYmYs!FW}Dok^9)^CmoGq^17u7 zbsmF64d@|jw)l|#de98Bn@f&XgGybFgJ4XtV8V(cjjNDeN2}TR`wx>#PvG2(b zKjM&t+HcR;P)gn$@>y8XRtZSjh@Pymwdvu!5vT>-pQpUvKCOmnUtC0{3kD(ww*fgc_xC>e4*6q#@3UeZB^@F3& zoy^7^wlilZx%sZ0lUTplbfd}gswwywjK2U9S2*=+_!{6L&}1<0BBP4qDlRF@Yx2a7 z`W?l^%@wOy$c{x579`iDXp#=rY2<@QZLBPMAVc~)gZJd`UPYDh;_GB4!>*s6pTYC& zaSXoX$A5rl%Vhqtm#h`fhz&3bz+4UT(jwVJ|BdKqyX7s1tF;r#rT{h{2{1f$HZvR! zOG4mS@9c}p@MW_%*xNGo!4YH0E~?2(_*2gE?BH5QUXPHV1?}d=i3)1hjS*XjW6ej+ zvN@4d$dUH=>`SYv3#puDG>YK2OH)K`HdalL70 zk}N8km=Us#*KNPUG?P}G$w!An8!QGrp^5~{r;pz@d*)P<^t6eprTZL%D)Ye!_FPoFBDZYvg?hnb&8sQsD|k>?~qNqKWTV|nB0HLLGQM7wV7_V$>Y zTb-a!G?>kif)S7y_&)Y}`muybe0sx@8ab3E^J;%DtFM$a3AO5e1Hv!&dFip zs)L3w$&jx&F_57sd`2+M%t0?zsE*ugUJUj=T&Oao6{^dtiSk(19bORjpv@TOFusS4 z7TE*~{r#5Rr=myw1jaARPmfoM>3l$J9*9ii+=&_32hrB|oW5O+%lbGa#^_gB-PJhJjXIr&y*FHD1=N8lX7N3T zG5Y-B--hlr12kly(Ct9pi!}+p6gJxoL5~p+z|94G%8r-tqZ1Q>cJuk_#Tam{hfp-5 z6a!~O-eqUb5#c-HFtY$44#k59`Ppsj1itzWiWxiyIVWrV*#%aTId5PBb%DFc(&h+o zoWDxskl80T{Y(`}9L9(l=!-Gv@TXlm8(4jZrJ}@bC^@BxX@O$s@zXiOuasnWD`HU-ZteS7{SVFVVxTh?-nq83WLh?#|QGS zq)tObdxG_fij6|=kUAgBBL8GT@`D6>IWc zBx+pWu=;ia$H{N-93!`#WgguRe*|vjjA*@Dx=eXg>6@N==qJ?F;jJJI{*(%iQKsQ8 zs7@k-Ig>uZEb}~6{;kkV#A^F0WI=Vino5qYiU$ILs(mOl{*eA0RZhaqy|@;_0}51D%E(A+8mtkeJXL8!c?q7L(RS ztA}Rly#7efnu>}Hr3}#zAfZs@zIZp8Z-dzNVTSNH`}<>mj4H@Bya02<-@kgc^MyG% z7!zFdNsJ&Y0pmS#r#V;tt&mRM4qwUWi}9j2)p#`K00h$O{tY!ecd53X*26R^q2e6n zoYUctLA{478?-n~e(oQ@%@gm;>^tZIZySC{j#@DvAaUi`faHjgUvOdHdXdlaT@Gn( zGBf-#8kiejwKpq|xsphSAsn=QXx7n^j+_Mt^X6+OCU{*f*&+=tZr+K71u4LPsH@}d zA~2<4SIiM*LxIta1L#A!cuNNd+Dv6m5C}eOy?W2mw2rAbAr(&rT0wgPN&e7d=<=HzWO+WgztB}HdBgl~2{kV))Dfg9kiUHozFM%q| z*nacdfp6st43Ipr8i9>^7oeYSpZG4ofSL^)fy&vOJr$S

CEdk!-xq;Q~x|=^n2n zMx1Z>>}#PRLr%R->&^DAZ(w2Bn@wkzF;t-IvJFMWdO`Z5y=Dw)0QMA@CGS}JODe#O zBFq>+z!0aGsn^NQ1c`fc;GncD{6_2587OrM(nrW`u|X*|DXLpWcVR4jPYI|P)dxn) z&ch_xO)CK|`vyD;c81JN2FXep_3XahjPnf+%e_SRw8c+FH|O9bqEMyNcV!3)|9&Sk zXMnH?EeiEJUY?q|mR9}*MOHGDHxM(=ta2iafDT>>Rcg6YYN~m+OuOj4Hk#qxQ;#Ks zhptEDOV*3a^9hHf;wjYTTQ6BcM1jBcKKUw8uyjY)P0qCygX>3h6ecx<;C>Q!{7M?6 zVK<*=A_&{|l_C&3WUN<8d}4~OU+w1&bBRQ;W^TKmSdeIn0<6CZLt1Wqc@}$~%-F&L zhye)ixME8YcAkJ&^q^*V6cO+0XA!^)`wH-}(HbiJNmAfamRShsIXe?Y;74G~W54hV z;GKh6P%^YFJIR&G)51&oV`lv zz~Z-@N-ZSAK79eG#nQ4(IvTWc1@Zaua@Kp+y_)0!yflh1N)wd-nn&k?jL8Z$Z-fBb z3u4^DG#n)UWzCC=YZ8E>B*3#|4+8EG(DXts1_eBcLKjK68n!r%!uQRX#CtI(R z9}Db@DY=MAp!l-SO_(7Gsh*kRRmoO7Esa)?acy*7`YE}z8rZJX=2d-JRK!m$+V6zj37bFTKyfnQ(hvG5j|_w5vTG)U6yh19bY$ z{g!Ay*kTLglDJWkSK2?kzMS(A$rLu+hQ8-<^T{L*QP~Y!C(#ECma;w1hKuuy<$cY4 zBR5y~2eXBqllDuJEqX{Y?-Vb0bFWESVS-BjU2n?vAZqRaN3U~Oh2KR9<%8aX;a`vIS3u8ddVZz{DEOYP9FXh-GakUSM<*x?AnGPR*QT|UM1T(! z14N(fXKrGe*i7w7H3jS5{`N1wJHch2gR%xK&=Qu$ZNm$i9dcqz2<%&SNprwYQy`gH zzmLeFZE(Cm!E?2$|GJ01h|O&Xd*dGYPrKDnBK=Gsp&WX2$K|Daz5U`JU~k?g-KHg- z+eB7-|DnJDm$#eFo(f_0i*8&BeZaE0rc(YJssu!E27zrYIZgSXs?oBTQlYY<7N-?v zVOZhLKzKkTYhphLCtd4|@qT6=2Nav`{p18V!I`(5iUfYTb9fv){h#TdIHc z@^@ZerF%Cnjbc{czVH>nPWPQhaY^|j6G*y7NAs|>uR8w`T2lny8y1%K{c-b|_jglw zDQ{a`_Z@$|`U2uzr_w;9o-<5Er*gYrH0_)sjc^a%#i+J!DQ^b)aDaR`pl<@l(2k~8@Oi0a0*~SrXTm*N< zuCXGl$r6p(MttkatT25l+DreGdM#=WkCbVA58rlVx4*N;-{fYy2Qy!9pHors_4f9) zSF<}HIE( zgu+(_{Zml5M2aaVx1mC@I=L$Mf+FE!HUGbX?svD`w?<{4*E2Eu@%$aAwPvKl4hL&A zV+fPL=N1A%>&cJZu}6B*6&u62^>$ddZ=u+^P^9YI4=6-7{b_m|&S?@=vVMM|bGEp{ z^=f9piZn{5k}!GiVl04rqc)O2>ABB_addwEcbv>y(22D91JLX1eTWihl=5Br-)tVT zrvTSxdaw-p|Ho+m(sqk6vTrOD#}mF~xtENJJZfAK&qDyeCXCT_|`hMlc#A zVtTI;v2tZGJ3DrF4lM@bsrOq)+Q3CT_lGo*WfjH8Zp9&7L4SJJ+EJCwza6N7i$+<+w&aUhTy z-dq9SKsnrEj*J`Z96ag*d#{Qigx5V9Y#|>POO3dER!Nc}(KgT_*8ZYt6G>KG_8CY} z6-Td82xvx@Hp~82yNX#tX{OO4A)tdU2w2~GC+R0Zc*L};=fry_!swkEcX)vb?2A%W zrbK-F?V`NAz=QdQiKV41aLQhLRq5Q{Ocqaof75>^4B#GTLVeLz=KB3w2A@+_9{g&2 zZzqhZui8EzU+N!KKRw=6Ijz03_>j9VL6P#hOqUAUaHKW=%jRTb8>l~+-`?Lh zb5yn5F*#|5V63i%Q@^MeUxBER#={zmL9l-Ou!g`S$Rnm$bC3u1fVDiw4ob1B08*b4 zLP!!5VKvz%TrZlXv0^vwEyIjc6#zeqpnb`)8M{JPL43yj1LY-|#W285aB^x|+hI~X zNRw}G-vtcKxta{QdjidcY8o2D`GX1jpmy4*%4FlL0klN6fvTf)FhsGJ*ClzLZJq%1 zDu>76LY&A?zm#;4QUlejG|vMs@3J>%|J%>RfFR70eZRhg<#$_?z2ww&LQ5=QHJ+a- zLW}S!ynq56#uD%GiKR3kxjIaU(>ah%2JK2>_!bI6#(tM7W(CI*Z}zfNA<^4(UsoY% znEWBk_)<;(fpq&=Hk8O9{~X}Yr!WSK62O+ijOzml1XoCmiES=IhAb`4yB#t}gAuya zmr>)~i-8yG@ZyP*1n7N=a8^2wNJ~-x*F%JONSc3O{sAY=%3=?kF=K2KQT5h z4j3A!7g68N*jt}`GN5jlJe6NMiZkfA3<@0opAZfPwxr z0f;4^eLc{?+9bENEQ)mD+Em1^mpdq4N{@3-{{4o<2%0jzra|=$N0Kvv5~8Yk70+0n zaBI0uTnDCs_UHwCjV?fJ5fBpt)2y{M2VJ$qXKhxcDAd%D&VOH-*Fh84X0pD$`D(r# zAWm7^SYO|7iO47k$dU7Yp$W@~-|_-w=H}XTxZx=4;pZREzzYF1@O<1@Sy@S$*qLMm zXDCH(*O`==)XKl+mLGXf`fmS8hMP?F4$I)H%K7PZhn8=Dw0qWW+TM1q`X&STmnw+L zE5OG(JbYVkw+sk~crbwvxy3`9^jdQe-143nXbAg0NNFH8+Ny- zDpP%Wyqf!4ZC+4I{sL2T2=0&Q9ZI26n#A`4_Pq?X1UE|yOeJ0@yHJ7uTb?q*-^ePW zgO^HsVh}{Csk6Xi?fSLHjJ;Xm@~zdTH_i61UM7VLkF#FLG>d@XxHD*wJ-N<{aXDW# z)d8&lLbuy%`+gn1_v?M6Ge*8+8x0MSR{XxS9eI1empKT$Pdng!$(B(j&=TH@nWT=L zwbx8RHFH%G1@U%KTSwRYpuJPbf-nn_`EFS`Zj}?k{#%N>(CqrRZKEJ#q!x!$ zAdX74L4W6!bl#DtuiGy5;Ftgn0$^O~wjA_bwO<+f0;4Zb3t_8p)y+^AL4pY=-UF+> z5x`FI-EDvN4v$6X{1h-geingp?T5?7|F|gpE}NrMQ^8Ebzkn||AMIrMXWKj(S$izE$|hjm^&CO*|ME}x>28au%*Cu|_-n>gbr zl`@q`6sYH7_s;PF8VW{_@5n_ZGxEq)uQh+@xmTQ{VLa>$T?!uNP*+65DYn%@035@T zQ#7Q-31&uiPa=3Jj)mW>L)5oPYOELP|NXHNA;U5p2XS-FLO;MVTwqeM_lfnBmegLi zrLDf<#|Xsay=Dh@5BE$#>;2Ta0*Sb44Js>(?SnaSB_-kXLMK4Ii8}wc4Dk#6J7w^I zHQDVUs`zzD+=UH^wi1MO;~pRFndWJd*wEf|A2;C4XO9{EV2fp3(G1^K|5DDlon9GD zi`j*N1^Y5GB)agZh;TQqKkVjVQ*^&{l z`}9swPD~;FK=r#OgLe=J(=g#q${nRPs4y0^nJ)eJyzJYIO#9igY4}FZ5gkCn&tKl{ z3qD=mHs2C-i?$gQgS-uH0m8ZJ0N%jnYtSy2C@;-4jFD?PAHo(HiSd%WtBqyYk zzn9vLcK-X_y5!0ST*Q8ZkWAC|DzfKJFJ3B#CzzWD+x$U{M z-uvQjMPd6*nZrXrXbyM&Q`&A#*Ugr1z@k0lcQOgpVF80Mo5lRw%!cBy2y9ov4Y(K7^Vk|*o5>$2crLyPk?EdXM@K_kE zb{Xlq5E>6r`*^p+YADKABdVSA`TG|L0~!3A5c0editm~;b+Y&LYo09C6chEWQ6IDQ z{h`)W>Q)FsTEH|GY=ZG+n!bkbAe^=4JfCxb%C%HJEV^8z`L+hU4`<6`4jQo)q=6YB zYY$wKQibf0YAlZaY>&|pE&0YQKb#Ae-VYzeevzU$$=&;GG^)9Qvy4`02d|`YLK&5{ z_=t&>Y4IHVd2fJDFyWd=c-9u4x?KCC!(ggqRycTiuH+7b&%J2Nc?Wd@Nhp z9&hXS#{d46=ZO0-G)YhFd`$iTXlO+q=k7wn1#U>3AAg%IHoHBqxtEt!z}0!8P>JZj zYcU&&m6a6;d7%A^@w=u3_HhcM$02RLhscSo_fM>VZ(%kVFDw)Dwsm6bQ=3YYCKPD~ z87`-eAt^jj!TcpmSt4bTbAFlgK0@8f%3om7e7Cpw0Wdy=Y;WlrE#=p_rl7eOpGZ>W z3uFsHttUquR9OP9U0zyk^_@ON=tu<{ZYunBR%jh!u3J7|QJx&6v^cy;Q+=WGt6W)~o=GR9E|B7yE;)yT!ogK()j@}kU?uzdyoUxN#^zReLqzA7EX4Nvoa0vFb5 zZoUnE2)*TONT<}HcV)&R4Xg?nJh?e|P84Cg`3#wVR5cRFlZIktY1mL3iCTn4^o z{%FuQeKmHZI zt34{;JSLQQ%Sb^-VFDrTIOMR<&4BSaIiirvl(SKRuS}ZMyfVb-`8fA+uF?WEp6dUj zjx}b3t15tiQRJZ4cs$yy$p9X+#&T_LUhGpi3{xz4H|?HUr~$o998a|6pFD(&OcPu0 z3V8{%fbWEOlycRhGJ{Cf6k)_umV|^Ya#)3O0+d=`03%sz(2T?D`y^o6a9K{BeUL4| z3wfDC%2^WH_BAIAhfR?cM^a+#N|CsY_(@fg=V))xhshsfuC)y=GnpQFI|6q{?W_lO^PfPixRq^Y*Nm?h zQBk%t0ttz^R@vga^3``3f~$zC8bJy&klYWNke)cp^bn#T6kH}AhocV@@HSP9)E2*% z0wrUF@GIgs^i#eKW{e0cQy62y{$sAUGx}jg*mjfy6%Z!_dztsHu0OfJI3{WinqE17 z-fS|w5&1+8I8vm~Kb!B`l=>ZHESc!1_=>KVi|C+@b8sT+bWHcg z_+Z`pDeKd!lYoGSwz@C7byWHefrWKby-gXV>!N^keo? zdn5P{60+C7iayYP1nh02)=Ry%V-S%!1LoL9`^WoMa4(yzW;z8KHSa6~amNy*UWx(} z@z80;q)IGG0t@-3G$#20=+F#{08Iut zfiwx;o^;h2Akm7)CGOs6{60p85gMsDtquwqk-2vsV5+M5ApHIj!uhVpj1j@(4qjE&LM_)={#2Y3mzgPt+y{3mzR1z%ynMCFwNwd+$A!9jo(nO zH)P^PN{J@>T)ssf9IL#|#XYGZ+6g{$uXzo!(8@cn$17ycpdILME538Kk zW^=SlHguQ#i!mL_8+Y`ON7?qtCr!6`y9TGC%Aq-SxkQPYDrO}YIvtv$6C)~BR9yELA4n*!oaZ=G3MD#I451r;&NrXB& zV3;@DwBhw`qhQpS%XLsuBc8Nc61Hs#Gs=y#63^chKp9kC5_Pd{Uj~vX;9G}S?Y3>v zgO$h-HxHNZp^WJ5Kj4RO`vb%d&%?BjX)XN*JPXbK%Iyh(Xo8>e(Ti(@Rr15?=qUm&qQ9mO+!`E+G_oI*XpKttv+*;!J;H3|0+sxo=%+8vuv&^b= zuu)2!)6|QlnhbK(%MpB&OigtI8V{vsa_~X?+20q(nhDJa25Pcu|IVhvj6;qg?FS*H z3EhuWoiGc=H!tzFr1qz=X6To%DD6^SEQAEbk(*ks5==~)zPcN&wf?BHtz4milAY91 ze?WQMl zF{=PQH`zRnO^JA>V6~CTZDaSvO@C8vneF0O|4Ij$7Q2F}VR*VLrsT|Ay^r7ocz}yU zZ(o`hgpAxDzX40vxyHIE?_TO8bejx5^Y;=$Npcv2eA7~?A<9Esvgw5B(C;NC-lSxl zI!?2V#*{=$elcdv$=%WKdlKa?ymt~5JU?$F0LQ*ndxQV!;H$)JBsGgQm?Me|VN>Rm*m{`N8O26oFee(DA{x?uCAXeL-tp z;Nv6tU$0^&`|u5Qf)SS!ZzF_WpNgSN465@`R_vw&F2IDwRLs%jkmE?ouP-b_f>SDp zPYuygiExo4eCv5lZg(ZT$>W9jTggpnG2<`qWuzT`w^~HB$+H#dt#CS6 z_X=cMj0j&5|KB)9FhAZ^#L^t<;B%G%c5VCypZ-aEUo=;+{M<~pvDbB-RMXhqeMG8R zxl0TWh9a{W;Zu~QD5#m5>jLJM%&MD$n0T+=T$olf`^!Zoz>cJo3;kk(K za&w3vQ4oqa^neS5hFICud`t>P)ftGBuUxJZX}Ub>$(RY26rbXZc9hl|I0a_+hv4zi z-3oygq^FUJ0!J8uVD(~eV;`SIQsiI?5)u-{R5pKG9t9;O)Fy*N(_x4E#;NknT}oBI zn_(k588hpCH(8qa#_~Y(yGe`jubx?F8Sxv6HhY6rP6|Y8>Epx=*9f<_cXOaM#joi} zMd;?f#QX81pH!JueoKkI&K8!%Ic)L%q|VDJWW{|H${{{QT15^y7>F918_vWi{Vh^> z*7^hYQPsZ(57{D{RDKT?LJk2V;Tv>k!+ADLIotkLO|`C!F1EKnUN;`H3~WCc34_L* z=X&p8Ag3L7zu5|-&Hiw7^Vwyr0FT!9axHraZ1t}vO8QZqD7SZaP4=ekTn}f({fvyb zWgB!D)L2rgm=qLCUin%2P>g?!i;FcQfIvpMs{T%JLDn^BP^>BNE$!?`K#v!|f-_)X zRB_jNHDIEuzkm(pilv)OV;g_3X7~LbVPCfP4|($qeOFc}A>0Lp%QBJ8%zKWHyS3sY zCkTj+#Bs9dumPJS739=%5((zm5J?TxbQ{8L=1WeG!?&P>5EJ%g&BqbIw7ui402}!X zaLQ)n;gSB1H;w-Hyw-##aU~OdJW*-9UX3Uhxmqw675LEk5?XEz=!I(nV73BH%G@f| z&!cYcZFYi-*?JU7g0 z#8LpbX`l?%fYpA*H>!ys*<1TXHUr(LvMaQZI9Gad{U^z3&*>Ihbw(QZM-QR74`(4) z1pA~PjspKj(piQ@*|lBxK@p{-8>CaD92!Boo1wd;8>B&`C8Qgqh6ZVAq!Gy>q>+Y^ z?*2CKcO3r5fqV9S?RBknE-aXr9Xh+P3uQAbkdAV@c`3(S=T&({MSlaRb*LVCcNtL9 zPw5qWvE-kjE^;Lc2tY=L{#O=+Z2Dkt`Fhj9eQGK;%Em$1<&t!)fdX6r&DLO`HPQ`` zot4>gDo}PK31UL_ejxh?9(c!f@}+CYxwsjI|N9l3)(LToFTqc9O9yDT$C9P``pM}@ z!2739lQB+bh|EKKgDIh#lG-ecZ;huhj()Gyb*gRkPwP{js2g7LICph?ogHEbortX! zmO89+Wg0Ozhw%C0W30HWNh?c{~ln(E}2L8?jS(raJ zEB}LNu}trQh3LEb!a@sMVG$YE6JooTu4Z?{W5Wno7p<0-dGJ3GQ7Vi%<^5iE&r?4t zOv7{zvRTH!dH0yW!?|R`{d$q~X=C)A_q7RnjJNe|aWmz=+L>&dYVFmeAo2PN}`A*m=Zg^!_#IPri0y`qoHN>I8v;g{s!-v~!~S z-}`X-xpH9`xu<{ug+2a>&XUde#sV_ zt?To~j$xnx4S`DaLDZtm-=#B#&t+FTpJJ_7G%gDqgww`eV!=5Qx9h^b?^kCVJgrt zbD*a)^lWsS+L=m2TX9Q6H>5T5eF3yjQu~%5QvP)@51kPN#!$e*@ zn7acl>tr2I*#&5dM~_Z?uq1OGrTADo+J5u<#|GG5=(TzteG1qM#_0YEh9E#*G8#}F zkcO8&2I0U=6y*jDGJsb9`jbpS&+{iQ_xR~8AW8Io*1~?t&0UkHkzoi`MLyJ?;lMO7 zS0+V4h4(1Xg@z*r>3|_JIPLuxiGAm{#4Tcy`ika3#7o-H(OQ`wuQ1KKFMH6$ade6M z^4v@J)lhZbOPbL=rIJ_EW+CWk-rD!M^})Ub)-rHHfn(o1$InuoHCY?{PXS`sfcr_k z?VC%SaV6UOaVY^EeAgo+0^muA$a&6PKw|aPG>F^~jfBoRJ+aq5;Y6%$P z^H6EriX-=%R`+KAsolm<=_~_!i68%3kSzxD10D=?c2Wgvbum z2KBw@s?}rd8dqXC_z;ZzDTQ_1GNr;$=@^NhLqURc)UvC6yvz;X1E1v$ zyd1tGJR`8(3TQhV3&~F?nN-SI^Lo{5s#^Yl_RQsq>AaYU2~nsP2V5ES>6){Z;)VJ+ zDk?KLsvlG{6``Z}qTFU#nfN3)<~m(tZW@Zlgc#k}wws=NDIB!#t+-sCr*B`6J^l9L zJmw+B^A}0g(>s&7ci|*9Q_sU>4j83LD{P(;tdVu8gs(n53M5&E81&nJ)ZbE%j*eEw z1lTwZJ{bf1H_7&J6{At$h|zAaoBiK&B3574bR9k&Jgw<}RGVXhjKsgZl~9zUq^yjU z5A1SNOXE%Fb7c2z&U?cfHv|N7rdw+UHV zzaRG|HV;o<8V|1aF5HBPIBk-AIAk|^5HPwvCVBuCi0u3NE1!oCz^guw|3&rCMU)R| zsL+L5y+(}<9WGu_RkJ5Yr+?u@PBw}+n`;<6RLnD)o2n@rj-m0hN^Q*TnK)5%NofpA z9QI~7uurnccHwt07XK57ghlqTGz<5_p1(&Hd2TpmPkJqWTSt7)Ul;i@FYHCBI`dys zg01}DBgh^)$3q z!bBBDJ#?bUR8hxELNn3C5V6dEUfF@~<>by>%{yxh1UybTY_GLJ9YFZjk9B#%^iq}O zKT(y|b@sZkaiu2vKflc0F0q*FNKGa7O0gV?m#M@&3H%hxpY-?Vb4nnGemChx848D%fuZM9l7PEAcIzq;p7wt!DJWPz&~U?lbeV(XP}oUia}QyCV( z`2Fer%zE)6p8}ODo^_g9uC6rBoJ4(wQy~GAhNN*kGkKSVBVx%#<3VR4Wh<_ukVeB% z{KHFL&;nVLmsM1IYNcntB6l$9vau(p${LLtxnWJe8dOx>dS4wEIoXAAn(1k`ocqCs z(?ej^tU5L31z58p5@3xm#9n3kGsq8cE+8oeF3dCfCuy6_b8`vHdjs?=DB$!?bljfz8&0~jR4(8R%k=dABWTQegKF^dSat5&FSeDpp)Wk!Q1$ret? z1bcdf>}BwB+CI>#I9|V0Bc>Yq6{Qy7QEo$=1)aL>Z)H$OeGe1>zz*CREXrQJER;{< zcV&2FSl_;KJ--BzU_n1$P=E{~@Bk(+r8V;s)E-=k8J4@S1if4L60Y3B7}~{45Hm3h zcUgd7Lg8cFitk0$nQ>vFELpJ1h8P6~@kfiNj0wZ<7ffYRG^+#u0<}rBG8(OHB#B)s zZmojoG0n6hL=r%b|C8UC8^PC^O_wW+Gk5p0C2xeHcZ-jem7V$g=9^5fX`M&jMN4pZ z_{DuH=NsS6w>f`71c2m2win?eahb@_?Wi5(st+7v`LDO%?UH%)u_Bu=ooa-%Y9kTK z1&tW7sIsImgKG}~QgU<=G{&k@Xte)ApA!kQOQxA_x;-9QZc5|7(mV+~nWs?oGK?~b z2|AM(c>!F%UMQq8gfeS}l$PfGLW}3Z|3?x0Y2XlDGU3(MQ#3yUab4m6OpkBA4v5BN zzv#Xsixzw%tG^t?fgNYkZp2I|pAt>ia$cnJOFf~oP-Os=(gDQ4Eccs5=+s<2 z;q8klr_ROXVLeboi!S}j9a*oz&ZPHOQl`%czw1HkN#$}wedAuOAHvdd&j(-8hhhYs zy~=WmHh?Pe$xD$FQyW`^(?7Y>0wUBn+Q=FjbZTd&2#$z>_n)`GwuQ<(3|D6S&$}17 z?F^Fg;+VN~CSKIZWUGI8vIGTG3j&uuk=I%(Y=se#BejRb{=-KP`K$={G>A73q5|y1 z*wZ0FnzPH#u_t4G0e_>EvwDA`V_9Cohd^?2DaziSd#1`LVC_$GvNC2-ML*`*bjAGk zwpCGMW9(1;WK&_~672$wk`*7}275{BB~@*Eh;w3r3}~*2NP_KHr4ugxi-%g7F(gnY zjJ(kErBQ7=lC5E7_;1RNhnc4I3)!60syA`PtppyW#Q7z)i6C~Cr8exQTkv3 zFh&=)xuPd9D&_0r65|G%#qe8#Vmt3N#M%d|2l!P#%i4Nc3WCx z9pp<}R@8}ncZr@;)KQgSei42mTFowb6-eXR^qv!_D{}OryH(mC?f~t-3JM2{{@i{{$@g40N(*EVy2|9_x@Hk!7|v(t_ms_ zci|1M@+nqPcQ}f^;b$=4+mupn5%qmlMdjbEGCi~+HWOTWjgOWB@=G1~(zlb7(<{wv z>A4AH1N*C5d!<=6GwZvwY5|HbJ^WH=V+Dc~$#{?E^&I}@$+HRHfP4SqXrtYt?y|^N z`i$YX7Q5z#2DOBeTKq@9*n{#`X9*jiF+G{9d22pF+=V5jsSu1pHyooX4N07YitzjW zFr;{lOQdAl_lc`d2N3F| zc43z$U$+ES6R2Hva|DB=Xsa+NZZV-{rt#E?DEWh8*;U?LZ^Km&e8juEHsH`InAiyy zF{c_r6Zb%2o>1>SKmX=!hE9vk#JR>Y(G!0Ao^v+7z>|_fbLSui;cFk;L)9zcRQWz zfT~1tC8~4{5J)V!K%I3OUBb=)CQ~|#IPVySBFFE%B!luSw4iTtnpia5;^li^RMF#q zb0}Itoe8pR^PFR~Ce==biGQK}_tnXM3+ri{UkXoS)QDy6=YNe4NI=<#dN=zJ^E!|} zZfyWkyZdq6Jj2p_d~v+TbS(GwZq^3l9!L>-K6;_r&eMzZJ;#gMPe6lfz|m){>4f1; z5Mu!3SjbyN=?jlml{^@X&|v299eXp+FR_jl?}5lMnI1P&ok%gaeD`>Of)vGGMm`dv zc4KTF7l;YlyP|ucYT;asNk?r*;BQSSk_gsJiVpo!3hZYt=u5WqUNj3j3y8c z^#Wbl{HMkF+Gi8;0Gtr?8EZWn>X_+!`1AP#PnyCs=0m1hNzeJ7z1@6!QsoF6wLUw3 z-q=RG_Od5US07dn8b?%}ir5g@__RBw&J(zdacXlozAUI=Pna~fk(qfh@|ENnS6MnC zw9VXt zqN<=q{yGvAUv4R0BVjo4UYBdEz9j`VM?eAFQQ1nWTn0_)qfj_-2X6l z;S}+(0=neZ8s-Crf}Rp7Jbu&z{npFW&w6_OcT>yw;N4z^2^D6a?kiLaF;%4^0@Z>g z8n^{#k>9EWW61cQyu(S~^Ma0hV=D*b^+}diB2DdH(ZisoQz;x6@jLja>ezScs;>%7 zh>2nUO|q0)Eue-iz(lvDD<_`E2Zq`{5aA2IR`=6_MBO8^Ybk_qz_N!Ncf1lKGe z-YEW+j#DglMm93(LZ~jc$H1cY!GF5qCa|)SE%}XLY}+}h%OM2-4ASY4 zCifFLf#2}o8#a^eK=Ycz$u)k@4!^5m#SXD2?Kf=)&b=Ecly_i&zT5oXjg|3Lw&>&a zjqfs1G*nnQ7eK9swThsxycS)*dfICbKWo>a}(u%z(tMqdx1V+qIF&ZiC{H<;C~ z|1tAA{TtSFIw3E8T{jDT==}dD2AH9N(aN+pk^oHHr-y*Detr%*`BpB|=LEccZh*=B zPlI@q21B^@u1RXdFJl z8{|>y?r@U4c^N?kkM4YOc~>+1Epg15{iun_;!`Hr}NX)KZ8yQPS9Bmx5hf|*R!cw`b|4W2d;`z&C zT&0TXaLrHLyV0TH)e-3@mhi4>15n0%wuqdQ!@kOVCix?77O!qpaJKR};G0G%*ai=^ES<4EdJn!K z1i&SPVN|$fXHw6h=_;e5;>}P|fFitsWc#3~r6}X)Cs8SBX+ZLrL`2I3FLYuFf%`mZ zsi!-x6oQmF5*-IYDh_VWPvHs)L$E>fx9hdfYWR^*q8ZWCVYy6kn8N9Dp`!nIF!JiZ z@?{}ML3HnX;lVvzlx6W|6w&y~%tHO{OHFn=oF6aSrSnb3mzI9M9kpA(JsI7)=yWO&5$7@9{b7S=%rW*|#{(bMhpU<(@ znXa?zL`$-Xma0&qjjSq}L3An3;p3HgcXzqIvzsRbw62|nlU8d}XOi*Ga2aZ(80Z*2 zAji=BZKe)JfUawT=)d1~+@!{)^OH=(cueDP7M<5TJ2t0~sk$B42Y@DFRT=nY@A0?TKzcF$>%0K*TN&M1ItfeSct ze2N`a0F#o+|*6ZsvVq+jPyjAqUZqlU!l*fO_xEv?4$&A)vhZBmEe0_Uad08Ufx4 zPGO*bEcy=lI9wI5zMeDqxb*XUPq2%>c57~LkKznO7&`(E+9{rz5WftjZb9vSN}W4x zHz$8^`?qm~{~^=W(536Bf9DGkyZ=%S0SeNY6z$;Ca?MhW*GUC9RlGK;W`;z?A(nXa zgsbi|F;83D!jqNPf6;P@Q~k!qrHNPCef6BZ=(iPSaW1$J zsYz3>!9OQ`elPR~_2e^qQ2ZUUmUX;3|1+sCBel$T#lc^BE=>aQ`$$r#Yf7=N+im&J z1uZ|iEp4!)GNrt(tFKpKQ+DYk&^iX_{@|g?Or*~vlMjBw5H0r3bT;Fh)KnQ$I{leK z+YxetfpVSNbz*+tZR2H|#19hC0S{4LLwx3`62f}s&gG+xE*90TJY^Y+RSgD0aj{b`Q z6*P0Hf6nOS2}c+gIiHJ|&p&s#Hn!-m+$&JuA+kRmJ_vYt4j|}49tTU^URzm1AOy&` zbQn4VpXHa|Lm+M@YAl8-wWhW@B>VgOw}tMb{Cysl~$Xf*zr$DZZ0?^Q)fLYiAx*s0Zi3_ZYmxJEtr z`TP|`P(VPzfOoE&N}EioU!9LVLf;Vpa5ij0K)Yjeb2ErZBa32JAUz}2crk+r8gt|Z zY&A{!Cn;pf1Qkg3)hKQu#)}u9Uku_3B1!HSBaiP2i+K`1SQ$OKr>>lk=wDL;7OLtxI7H(Wz|A zRI+^8fk#&+;Rj8rHKUQ;DS6uhC4C%kz9i#rTiev{w#8#)?NJbi4hHi&7aN^-c)z<{ z>9$*JjaD3WSlu>@wd@X!E;ndN262kZaMP00oF=>Tf}LBI(GwC<(r+y-VPFL%B^An? zEH}9e-K}qSa^!y*gOKEG_QaNtRhVP!BBz;p5Sr2J~n3qH@P+X6^FLAthy>&E%lD zt9GqM6&N$oQg$Qd#_cz*7bhT{8z z{7z$zU+ww09gnrWy(Ap+^Lwdg3AEHy4*DhE&IZ-FZ5&&D)Ur0hjMw>H0BPH@yrz?A z@BsD}L2)SqObj%HSwkqgIXD&H*;EEsvVco!I`gLsnL^yT=DhHTV(mBmx}`F30t=PC zI(Lz@E~z;1`wzqyC#3n=Opf$5e+x;LMi;Ly6g{`GhGOgEu-b`YTEp+}P)Db2po; znPt6KWv%Q+1GCZD$YW`!5xO9!?X?jE5OUx1rPL zJTb!Fm_FzK+AdSgrtiwXj#Bbx8BJM1Knb*4`Ika&wB6=9ZlOmiqHEAUV}Pq z$x&Ph8Dt$C;7>m@O<&zi9uBwb^c7Z?mq!PvEiqAu7WjhURt^osqmB2(IsLk4Yrnyd zQdJ;^SsNOY{^0zD5;aPxBO1SvzUAdOvQ?8a4**8>y3uY7pDlC%I>c+sU>N*9Ka2Yf z+_Sjv*&24AztLlYmXQbCI{Q8>9h}@>bmVBY9YX;GNF4krBFpx(cpaBay1T_OFflnf z`K#rV*O!d$cZrU-w~O6|-ZUadvV`gJIKCv%c{!Yz){6D46&gn;+r@zai~-;T+iq4O z4%+*pQO1okZGh)AW>YU!p_{K+HEsp@UJlbn<*6vHK1Ob!HOae**rAsT7EP8^r|bNN zWB8K;X7LmjLdKCH+tn)RrY476gAmX~&W=u?FlEriZu+l?i?K*^UUu8%);ZH1F9qUf zL%^*GH{A-cRq1nIR9?EdJ7~2ScJ9}B%KLr_V#t8ya@j-oyrtQ*_t{$RcV{M z&(utaA4zO$&yYf4aYN=-0xtpQ7ZBkj03UX+$U^qs4jVa?btn}E;?H{9`};5rmM3Cm z@aZKsh(?2Wn_7YE?D)D%h*eFl$gtei zGN>eVhHP$+Oc+&<^Sk6an{_pm8#0t8U3OP@^izysn4jKF`FTHR0tJDM>|r92n_ls| z10ghv$7&;Q{ODY$$8YXz5VCsYEOZ6D(tj2=RwGB6482+^?*wnItT>& zuk;Zb0wKAmZ!%$}pps?FTa7K}!*uyb2{#*c_Q6|ze%U4seDyM21%pPbNrbj0UVnA< z9z!KrE}@W!wOcS)Ua78rw~!>j;SsBIFeUcRD+BZf^IB`9jA3(N&Ci>SB-YfeLyL-| z_zPLm;n>URdZ5A}sebA%uuAK}q{Q1M1D_7Wtrq9GcB~0LxG_t%XyeHl4cHi<)e0Hb z#T!iQyr^bmD6X$_+Ed`!P`C@>t|jzE(jX3viit5zH+_;gVri{Q*rXq0TFrNmc`|yX zjJlIKXd0KD?EsE=omNjkvu;Zk`JK_fz5OEEo1))&8-cLcnXo8uc~+h)jN&08Z9606 zHYoa5At=0@sP}@Q$%%$pVc|W24vOTrC!hZVD>u#HuLM+yV!lTDV-uFaYT@F_6tU%O zZ##^?yZ`=KpYc24i@B~~F(ea{EPMX;OkIgDrs-r$m04?h$IDrv{87$m_ZfW`Merrl ze_975BlG_k>N=&R9PZdkzVLPZ8RVs<955GSX1D6w88?o@z{psfTsBGSZdXQvq}SH- z^I2Rwb2`SLYH~(tsd`L>m1IJ+gD0@<*s)3TB=kbgwqZr6m{U~~Dbk!v2Z-c#;Qc65pBV)8 z4x(jm4Vk_=iL+378s^qV1syPhfl)_AT#W!M94nw!n(}!i8gAxqqiu*M?NjtR4i$y3 z*&SD71P@lG=N&d0^c*u<{BF)4{{8zWG;{GZ2Gr{;`kZS6Qy^Apsemv)|E!KJ)g#X{1+WY*D?hfqPPE{^JyP~3XNkm3mtw(qYJ`NZ6X*0UCn7?&M7ILIG#;_X z7eP1#Q9xmV?nVp5tT8z02u^E)F=CCOTH@zvQfBaO3;CFD{E9EMf1+voFPVl%K7uB?}r1x9cLeNnJnUd@K z{@n3)O1m1;X#{-dblRoqHyAN3?l&lSS7-dp)nVLkb6l&0E>v>--=5JFg9DH9$0OeL zcw-1$Ffqw^IBcg`kFSIx^Ne9?e;WKW_4MXv0=oen2XwpG`S0@s$hUUmzP6Ikk;F@* zhQ#qWoR|NWrLmEtVx!}RHd3d!pSL7`FdoYPZRCervA0K@{kgP^Z}7#tSNh0etpbWI zv_on%Zcr#xNJeT^ow+&9asq|ffJki0s(Ir|c<4h>$)8uxU*m=i(Yg^R*tDx%EbI!h z^KG#fjeq}2hiWimcvy}5*j8y+1(?lEd)<_qfDa?4j;|zg=a%j5-5t@m{#MYJPc(CY#{3>c3ohElYc`hOTBmIP% z%ep#y(7blNCdeddXam5-QeodJUgM|=z7UVYVpg1;>OQ=J7Y8%r_t=u`T)if@-rZ#Q zLgr#Dxc_{_(0iog-L6O!w9(3%nF9jpY}~&`actgi?m)Brxh+8MW6mBzt7JB~yT<3z z%c2WMYiY1AqE5pHIsE*#tcK|)6(Qt0>it+I<)-6S0_N%{k*xV8XhVdfYurU_qGofY zB?wloe)8_j2BkSYU70O-0URazr!dRs8|uWPI*1&CwI)R9u0bKdnz8@(w&?cc?BRES z|5gi8+nzn|LYmSCLQsEPF7;G4nQ;UpZNfUv>#MlW_h;eRgO*b^6@)ybXJf8y#z(8Y z_n?95pKbbP#~Q`Kp}A!80l-o5C&>*qSIWzLl3-$vq%o7mQgz+*80WUF=0gq!{t&L& zX(`Z%Q2F`=B4*84(7`;&2`^NmH7|q51OJ*uhfv)LDmmq*CPm&_F0B&?S4Ah8s3udH z8K;@^{+)&vp@36OVw$dM8o5Isf&bi8J@iLRFpjQ7#J9d9j@L1*5xgPP)bXsEQ!!=% zW!h|ulM@rV4fYveHq11-T_rljI?qQ4)VkF2T^y(N*}(1v&Q?)gv~|9A{vp9z?cK)4 zrj{Ox;5(RbyHgL;WFY_&1-l?9a$NrO)a~PiN?D@U)N4Z|T;H=8!P#0LaD5d24^;im z<;RN7V21i!RBx{j@vZ(YlPRN~)qiD<*&qAOyC!qpNwy{k@n?{4`9eqoDhukl^+{z& z1ezX^gbApT8`r-FS;)st4pm|m(Nf^Y`N)wY+nz^LJ8ru-8)}^XT?N{#M=;*DBNfWf z2lqucxZ>lqzNQ7Rj%Auvo9#FIYd{J60Bq;~ma5l=zof9;)R>TNo>rAi?Vg@pjL*yu z0cnvo-z=!X&{3so1`J1$_0g#siq`1`OfGcUrQ45T2F~B$LK5T4CeM>VoiUU!WI=QH zh1pb!#vdwkC{$!ZEcTvi-`SbZ0a7SOT5kO>mrjoj8~-xgi2IKn&vK$%q5txCR=H@J zidi1gdI8|(-ds;mzW-u$@a%&@|5QrWDCH~f%p_@6i`l%Uy1I1`9RHmm5<3*56JAhd zGDuHUV>c+a`P=4$$A{-{te;B4iP@$~ba*I2%C${=gllzOJ;j6=GQTU3<@Xp*st~{I z+U7%U?@W>T6wA&G4wRFL?g@SOpRF)#K819Lze{zU33r z((aMc{PDoBscPm`4F`Wv!5KZQ{+1iB?#IC<2R5jcbzZ4~_dzTC#|CRptRwU9q@*%@X zOzE#+_{i|Ut-#bpZw{5>JA7PT{hBDc5K(x8qfVXE_|~=e4em_t!3}xSD(JRb>H=-E}3_4ySN1EJ>WPzJB*djPcN%cFW z^CTolw%ZlDdSiG5MS!XAIGQE9o@}?x z3xnX&zad?FDKetslsbfzU-$$_MzK_r!nX8WWTao z{UN+HQW-a08wDkG%;Noce-RdX2 z1a2ICuZ^VNS%O-W#Kf14g<+H)`R}0$Q$0P%@7^t*o}u!t^z{62LZ0p+{cg>B$OMk^B`{H@h?O>IL zgYQ~dor`$%kYp`*PcVq^oW|5^emcyg~ssC8qF$SKJ zFNY+eT<%efqSYws$#jXJa5Kyu(agpKbnZklnztEf<4 zVaC*FJ6Dru92jxtA>q%`tuA3Zf+WG?9#GM=^{7&>lW-vK6|wq}B_aG3r4K+W&> z51k5T-0A@dK;ypuWaDiHWl7SmwZwe-^iDhZ87RIiLl5cVC6MHQW$bAc4qO@4_BS4& zvx1nCtO#6Ucr&(}`wj9`N;i>SYNV32^KJ7CBYXiv{?)P0-;`qgGla*Xqp$Oo#~gJliq~WDNrx{;zK`J|6b*wsRC| ziacD6J_o8wOMk6DGW>ph;aPx3B zj;#!tEynE{r7u#l_aMNi+N#=!LKc1f4`#8W2}eVmg%*^ufOQbp4v@tXrKF__6c}i4 z+FxI_SAkB}-Wt{oScXF)CR}Cd@Ooyb6gCKQ7_=Ef5q&JWs6#bTi*Cf^q;zB!Vk|Yk z|d#m4iC`@qE( zkBHyzm$%l{mCeTU=%dakCG69N7vPoDGjlPy!KpCf9a_mJ6aTd`F{;4vn=Rdsx1Yw= z9L3%6?*)C~+fT%+&KMpjhG7TOtl4TxS*U&)Id_hQu{$pX1@gmATKqn5T(~t5HDE?X zt6`OH`$y6b#ah6xpL@*?8G00B^*{Uo?^pj#_u>42?>QSoDJOBU%Ofq0?IB68wT>71 zqCdPbX!xghC1x^yT2*bIaewdc?c+^CPHOJv7CdMgVN)-cZ&+l_edJ3y`VsXr$EVM~ zYJw!NXa9!K8$!7i#QPNrITb$Z^Q3H-*31r6C&`*wJ^@G19ekG0^j#)YkKHLB`t(Nmcm8O-(dPS*W^LoD0TqW&c#6u@JE)dVrj<{p zG0iY*+6>@EY1;J-x$7S5oFDAK46wFS;eFcGbe%u4!|{&ue^5RVi9Cw{sEWe(Q1d4` zg$q_Lb2U6mZsSL8ZX>3x+J!hF)_Td%swo7X2V4yi9csy4{v9+Ga+AhS)rrF)sjN!J zfSbbDj);>hqMLCp;E<3Kdqqi^qNl4n+0uT_y^)^Mq3?ft)SuMeZpfT7D(`IUGSMmj z-SfzlkWD+BPJYtX{Utfy0N9`iW-opJMD=2v`wfX!gcS?3=$q|kW~bgv_&a6jmLh1|l`@_Hxb z2m=P!wZl;mu8Z$(mK&XZs%c>_K4a)FJZ1r9zh_?--@ytydh*jEBH?M$)I|`0!$LBt209T!$rQbih1oe2}Yqjov%7pCpS_y%eoqpBVYi zFaxtVEu23`t-G5!mb1?59mSWI-A5GoGNdT<6V<(zpZHGoR zz;Oa)e(@?Xda^#%a}%bdA&Vwkj}+gF#pOh{_H7!kyX!NxYHhkKCFvbhu4WisC{3W> z->wi4R9v|c22Bf!89dI*eizk_%l_cZ)=b>WCp3R18OMQvx5&YPiPt@u@ZF-DgVrC4 z0>}4#Z7`GHD#twWUb5%RYJ-W?-6(wGGjoCjv7!?Fx>Zm*`QL56=W)63<)$O^3d}>^ z3~_y;)F7W}%KbX(SEX46a6X}NUG4@z_dw3}16@{f?B>Hi722q5HZg9V7X$qtSfujv z!6*C9T0LDhWmEe$?e~lZv<<(<+;(duOQ_Kc{rSs(AAIeifZ*Mop6-M!8i*e%8}3p& zTL370z`~T6-HsHa+ZH((!6|(C6Dz_qGf|c;W9_)iD3s=PVt*JaeaPvtx(vHMEnB)= zfw{`MOa|VV8q=7_Y{A9gvWtTJ=b})tiJ_RSU^C6UU}1Y^f^LDzWI;;j5kUNTF-yYSnl8M8yIE0{cv6e6Bq5q?vs+<*+UdoRi(tm0r8K4Ir-Nl znR|LNy{EV#hAKupxrl5!E)n|2oFE6Q?Q|u9EQYM%uhIISnp&+Y!Hc!Ee226&kAC{h zlM5T!zb-i~UE`VPe`>@Lf6SrP5ONbF=#RJ?H{uX=upL9|0g^1&^yXY7*ht~+6}oB@{_ zm%4q+WM1(fOz{^)+hektFLz`+xxZxJFWy~CUwZ0HC2#7(icjFclq&_Ji=DvbryPm@ z&M=fGlHu@_XU zoy7p~Kxc~dVawEEOMcHozL56Ft6L{{wvVA#-ze-{Z?nAH-Wty!s+(2O0Mu3 z{$y00?~aC0y_|`Z6qzJ}5v5ePj*0J4{!}$PEL${{PeGint5ZHN5f-ZEtWJMO=|bL2 zuGnPiqlsLrJ5hT^!Rc*tkiOIYy zX)`ELLMJEB?m2xkHo=tJjf4InpM-&1uwbb;|Jksj0qit+ zYq#V>EFzHGo{fLj@`7kt0zuZH^l-?>NdA#E!1tdsSV%{T`)S`x*E=iNCrn-=DPeu!wsz-&NQH4mpu*vrXZQ3U{AgTS;n%?OD%?k2x6^tZF)H_4uT)7 zBa*nHuEY^@g_p~c<+)Tf-ThoCKS-XMPD*WGEmeTBoRNM?Z(!tQl;CwEpO@paB6`5o zQdG~_w~OSLZxPzZNb*{=SB7+5gu`IC^vr&ZL1yy4ZE0oY{%K~bjc|_F z1(|lUIga=m{cgQL!(zdbRgZevcSA>+m_-HHu;M(-3TW(F;^@>)mDoX@(FgdG%Ef*?7EGF=CW~nsj6GRn){SuZus5 zH(5Ih&BQ<0N>zKSYmuoz9oPB6@~GbO^|ZL(U~0)jm<_B+Kmy82$caHa4s;_)fh?&R zce{D7vPxT{cskjqkKW$3KE;1aZ5g?Lslj5S1d4!=x|8=S{TJ^XQQaB^D+3J<<~jfg z<8;(ZG`3OngdQB_oywthPN$Dwx0 z)=OfyZMJqq&D9FA{8pXQBxgV6ZugN$C5Vn7T6Ywywi-LyVhLWytj~1Z(*w*c3FwmM z1KkK69zaO^mt`*cBEKp#HW|*?c8jk?lD$B4X z-ZI$qU`nEN{g?LNvio5=p;9f*JI_gHJM{U|zk+NacUzq+y5!$2a#Tg>DHxeI&I=KP z*W@h-a8H}B z#FkxF$n+i~s=?|#T3_kB=DbyWv*}Fj91H*ghjPBVRdWzCI~t zf}u$p0%sEs3Na%IweYhjnrwmmjH)y)nW700Fjp(V|3dg?^$|T%f;nnjpitR*%hi6` z%YJ%7MI;nh0s0;M;XXf z)@B#0m6K8M0w_Twa$7vH{ArqZx_Yg6Y58&2)@eZ=sEXRr%#)p zbTk`qgFmzE^v(>AUP`(jY_Eqc6QsnEX};VFqnFKg+GuNQs{6()_EcvTHyt|}JYT+$ zY{)sllfWdDNiD%g%sfQgxBE}*{DwRchGZyqajZ`av8{=8oV~&5Hr}etA`VS^?@O;E zCI;$yb#-;O|7~}IM&B<9%+2dzP zTZPCyiawdIu!Uk5lXz1Ut9?$I)4aRn@FvSZNTXLqfV6 zH(dhKB`J+`cS+PQSQSM5xoZzn4o9)28=I3_J>=SEs}(6wf8JkMZ$n@Z-5(iL<$rQ8O)%A z5o!=8X~*i|;83KL3|j}Kf%qS_;#K=w;$nU5#{t-gh{0>V$Jo{YD2d(O9S;=FQK=QL zC|=2=5fr(<7DS^uLGzFQG4i}`hH=b^u)$J`F?n*1*Vpqg2s!%Ux=i-*>d4se98tSj zM?~MKciE7dvEw(bebH9kgM7F01+>H z`(OItC)-yxMnw5C4JMd?5{Ze8#UsMgceNyt>Z-Mi$Vb)^7k%XOHe&x8$>cMeJnl0! z+*#Jz486tBAA=Bit2%R`&Zl9xUdcR*tFbdQsIZ|0B@dDq%aW z?UMfdiXL2iU-s8v#iu+J+iB5Y5So}k|>dAUcla(nx7Qw=x?%B0b`3(_@I%!j`;RmN0*MOGjrDEWOJnVy-z zg}JWWlnFzfA(XCour|>mh-&wHZ*ZkfYm`&KnWKu(>ARbo8|HMyB~Scu+o8|z4Hm)E zmhW(8wp7l=+)}LwZ>r4#952GS0lC6m)Ph=!;Ahj9r-*rG@w&2|3=xkY-(;HxF5>Ll zM{5GE6*q3XE>BZA12aMBjhkyG-h{+-n*OCmg>Hn_5{)*@Ep-T<~#pi6!^Kd)VHv zO=-D`kVDe=o{bG|en(Z6gSngFTp0nhJVC*NDOEwF-Gx@RMik0x7r&iX)13?YK6#S) z$crA{d#uKjbNy*tVnVN#hay7Cfp?EVg;z^$By#BIg9l^w-8Wgvj^pnI#fq(0ebKFt z&EorCEp)?t#`topitOf5tER8Ls2#p&D>A9hy zVRqmHxK3~G-us3f5CP~rwV%%1tT>E1uChWU$CC~>H=7(#P*8vc%f#6^;j|VVtRDc} zhHC~Vxc>a*c$ z`>Oug0u4b248+1ngS$}zHzCYaX4%hW|LT4B$@SW~3w1E2IN;oA6^mlQzj|F>zAf;Q z*!V8}tm47xXRWeu%VTZH^@y;MYT0b|yKnm8<1b+xYHW+%j+@W2F0i=;jC$=-Y~s$< ze=f_L6;M_{!jz~A93h135H-k~(aPijV}fDaBRzChq4AmsU z5$YZH6jv4in-%3nyyP!*@&LtIZsYeI@p!+V@{a2s@gDr9AclER1l(}15GiLyP5B( z@RDK^gaX3n6V&QV^zd?Kf8&f6Wa_)VA*)>fWA3AG%i8ebVk(U)WRcqmlsG`8B+mA9 zgBfLm)7^cn-3`lE6Mnf@%)NO$0}7L89r}dQty)QR$N+y8uRQHwdc4v3G?!x|VkV4+ zK#Agh)A7qn>=4Dh*3wWT)HmmE`)c zob7XdKdoG=J>6nP;|WCb_sdCJ9oQ}ufS0dEB1N5w~_83jgQ!LS}d914Tu%*#JqX0 zg|+Cxg&E70;#~Nvs|S0j{qmXFPQP5z02cpRk9g;KRi$Bl*q=XtvcPctlKJ01w3h=#F~<_QC@0HNze~ytcneM{AKlN zhir3XDo5Cb992sTCZI0y`S%h?m3FkcsSzNr5_NN?D?U|J)LSL>?Vi6$mEm_+T94Vd zG{quOu`9i!@kkI*XZ^H-XKT(28ysuz^4jr22}8!H!%B3x(Ov+csX< z^W73^Y1JURxUJV)VS}fysH7ykc9t6~Qkr(WP;LChXwr(e@6@Q|0VO$K`gu7_o)5Tb zre{~?6!PEyS6rN`#6VGNH6YF1#IBg+EhO^w@!2i*ul=>NDcY>5laSn#7T2C z^UM!jH(KCwJ3aC=vWPoc(wiGIIBsg{rXci%)6FiU`1LuNQ%7PdtM*r~%>W_c{lCAD zyYg0@{6Bv>dvH;y2ZGF4{*Emyk$Mxvl58KAGQZrF0VG;8GmykRWrjnDb6v+G&$oIb zM~y{KvW9$}eE4I1a;VS}EFz_&iOz~S10s(eufvupuSb4UX7N^>wUNZ)EG}IM_=|Re zyvQ3Np}v7Dy1_ZRMxPuXb}~SSrk!N%F}Vs>QjXaHmg< z``!N_D5&A3nk+hv7>$4Finr5_jcvs+mGYMqJI+(fkNDWn7Nr zj1ZUW(M7X-0AZ|PWadC%rx;_>@(ucYoSBX5vWWk^zy0!^!8Of(X?%6MwL*BbejY4AG%ni_fj7C+Q|rR7NJzeevI_MH;#0rojevk0UzW5QZ*|*W z3?fcl$ub?h3{)+8;18~-H`|XQtk`&}V%8Y@&)cd9Ja`9yK%`qAIwP86oQ*3$4uZKv z;(Tu~>Qjz2cwK73P$c~R_7c84`#dU$W&8-#dCmr(MD9mm^T4pODtsflNtT`<>$kZ| zi6r4wZ4{soKDR#LXZ`5z9upbKJyy)q=wm3* zPmanDH4VYtpb8+vU{8LgVOt)S{{pYc25MgSsxFfaq@WB`S`gr6kTA!BSGGLLI2z9i zQeoC#5ybVzamOO#X_yt+1ac8nHK5On&;>wxjwaCdcI-3FrTGT^%L0Q*qq zy+sa!u9+mSfnF}lb=}grPNn~VYJnSDRhiZXCCahD7A2}Y(vq40{=?gmu;!p>M)suv z=BVr`lxcx_cZj4h(j@G*O>jwk;^c}hfNnRA)`Dl5yxr@MIf#T?LmxUu<46AcCwN=T zxo79KE^TGS*zS2Oqd_1kc}F$iC2Fua+?3VO*fcjg3pOs`dTQgPK& zf$5to+i66b$N5oL8MFZe0sQ*$&;Ewe7PJ zLCe>v$Lr9!#Kfk+hG?nPj!{agpCB4I5-=KVd3)KezRZM&Q73*0p7|9O$@DB9FuBpcEPx8IlO@ca}WnuYBgg7gy%C(0m@+)?{SYs?kD}L zB5NI+%a$~;>%d=HXYz1&hW?IEX91p5ipH+}@d05r$D?i~r+tsB$1-4xX|{&5X03*#C5Ya4?c?Ir(!;6pTbWj_;2Pi)Vry zNzkjQBKnf{r!t2<77d5d8FNoMjyFLQ=Zkq8#Aq6Ew)5#h4HlI2g zOqx!uUrSLGIwqJ%smbzCwoxj1-p$Jz#gaGTl?%4OELUA|^@S3*_P)D}?BsFt^cMwm zpvj(y<4<409`+wnyMVi&A374RZ4*Bj`M-+FGy!v#*;?*eJts8LWUi1FfhNVy*&a7T z%jrX)ryY!m!K}Ahbi|-AtQ5IH(xe3wQ6xr+_9QzFVPb=q21VqnccfY?AT}Z$q+gBN%iws2By`zy5EnKDH}| zY`NBs->g`uR7eI=Het?V@ApGDEDUwlT{KfcG3i~s4I;Hu=Yx;f+2QniHkG-}&G_;| zq%KA%;4``z*e{xBTa|Ei6={ILDlIEdr>H*&2)~>6{It?ak95gBDUP`#(nF;yd@C^^ z^P(h9_s%Px@(&$V3QR2S6yseW_OzFH-H*N(PMddGn|Mflf@C4jVfk=th}A!>H|N;; zW5y5cmKXz}I~S`?Pr*$#-LE8C3nPSXI$_d$ITn}I>w5aWt5zP$k12HWwj^Qy+%Hdd z;i|PBM?_)avKb_lB|6zLJ^xKI$4WxZ=Kz;#fs1BHi6cF~syMdkf)Bhgz=A=YH*E%G zhG@lep~C}Z@V-sBGsfp1H8c>M_{RgAI}oPzArl*nfF?CqAVYu>69g^P2tqB!U%p6Z z)BXF!uKLrpFo3WOtc($|dN2BJ^b2oX@V)lkMu%wa(Q|%62O9|4m*>>-V=m;+^j1L+ z!JIqUEIEUnVKCUDcqa9+!$LRD?_xQ2sP~T}5L99+?BN0KQ+@*HJ8d^YEe&)jE~Q}L zuf({P#Ea8sNfmHDp%Pt3Xyg(RnE>T?X)!aQoGvGf{|gBvrhmySS6OjxkMu*oq{ptt*J zuEDG%B@5SV7|Fm1!_|{YRHJ((rNPY`+EAS^Yf%RcVUV^HW{;f}i~rTP;QqQPt@s7e ze}aTVvZ%H8#!5x>8NyB+AVL6Pe<7VI=>!}L`>kLsom{G?bXmvB#U9f?v(VJxB$4``w#Wrg$}# zhaB(kFM>YKcm#jguPduLci4Z1{@sCZ!rw_YNG*{au9yny@M=$Du0Vr^S?`(8Tc0v7mF=EU43$hAzVOtY^pi-u0y zJR&msYh}~{o|d!*??lSTKU*6I(0Qi3Uyv1$jZNLBj?ZO25gi%uBZIkc zgh#nVzE-Et#a_G0Ae0hmEnwB*=`My)w)*4X7_IE$YyV&3;#WP#fj3}(F#aT5?DF@` z%yMDc0q*9T>As@@uz9uS7a36U1Kygo%Tr3N+o3d;5@NnmLVSa8fL=-zC{m+ zx0x9kA6@I@YITZ?Dol0xn&1O&B0)>&BxHCXhmb}yT+C8;1PM*a98!w>)ube(ES3lI zXvvdBzzM)DvA_$_l@ChVF(Vz0y5sMV#9^?5E~OIg*AC`SoHjhe+1{eM`m?ljAPfr9 z<0f(;?$1^)xG-~EKW!hg7(AW<+uf$fDS+C2Nw3tKyWq^b`WqtR^I7%oNY?vrSqa!5 znb!e^S++U&0Y$f!QWY)iS9_ISkq0c9WP7gI{90~KKlZgUyfy`HcaM*vxF01zA{Xmfgpk--TCR=v+>iDyJw5%E`^p<=)Q3u zjFM((%b?Z?TJn+_7V2RV998*0QGCP3TC{_!n-G5I!SMxrL*E_ryXSc0(T(zef78Z^Bpv(R3Rmj229@xOB%^)DzY9Kw+w&zRWbiw^ z28dRGjTC$a3RJFN+sRfP3r3>2K7~A2XWEj*wpMTWlXc@OV|PfUq&-K&V8cR96+mIS zpd~W-!tarJ^Th@M&YuJe5Es9G=H$P#jDDpJZ;;|)&ne5i$(vUK+8ph*(vC-|_D{#{ z`(~sV+HjhjsgEQ=%EMy%iw#aANgYW4X|jODS{ul>8QjT|gJuk?G`~`W_gvD>e-VHL z4YB_^Z>wf3_>q=Iw4$d!+DrfvOGOi!=Dq3oRefi)Dt+%#C|)Sh%d0r{)zM_zg8Lj{ zzNQ89jiBp;wkdFf$4b8X=`QEkZ(qOrs+jYaj@K_CBe3~B15N!Hd{E6oM1AQz^vddP zq5u7K`_D%5Put78mYjWZB?6Td$h;?|ybk7C^zV8-MWJymf+0yt5i?Fmv!NRRxv5{b z=B@DMs|9!RAWij=(aa|Q$wE`yH~Mz)$bagR=!aM@M35KHi*sq5$Hrin_|s`(M^OswZCNOFuT6f z|3K)z{tm9C4seR8@&iAY0fd`Rkt3@=rr`s$oSN0OVJ!OWd1hTRxF(k~M%K6rJ@`S_ zvN(H+?YDgj8*%JEyZ_$bYVbqj{HgQ?#Oa@57S8J{;z*}Lm{N|nb6y!tY1dhu>C>g-$}5+ zeccD=l~-0z!`Kwy>XX^f%pjpKcXNtFci;^7Ut&nCi3`d3{+je+%r@y3!OzbW*J%u3d04DxUfF zMf7X5Rlo%=Uv(f!jELJl`$uc*&y0)WU#f>S>}D(9;R+f67WWE^N8nA zb2JsW;h-g{e3S>9G;qP3W2-+sk!LripS}=v429C|gEziY%q!v^--~mJ8z4{0o>R zRY9PHa`(rzi+tpQOxrdfV}~gByR7SDDnGW+$qV%WjRqON=y>&d`>R*4E$Wy)CY{S5 zt`gm#QDq86Y9&Thzwp=M%c9QXj2J4fiZu{ZVSFc! zRgXN8npP(Vi#|8)<5n4N8FY%&z&XRIN%kw*wwRP zayJn~M8rT|37f6bXlAE-teVb47E@ulDQTv{tAn;LnLNnNEXjs7UU@25Fq4Fj+oBos ze41AJp=YCry^*4?^dkQHud+a*MCPScHhWDO-R5cG*IB3`-pzJ z@9$CVYv0kyIy5M!%EoX?qZ7=`RY+ocPo0ROiF+YGeD*7=zvs#|-$J|Sl^svu6wePL zPuK0p5-=SMytg0AgqC${J)JEjTC1H;c}e*~CDUZqCHcXW#a59o>#?BPrUv!x6=aeS?aAC;oV-J zXM6D|SJ-R+1f~DwEMd12b3U}&H0?UdIi9gq)~)xGsuE6fw0vR9M5ZuV=RW;H6aIcT zQbFTps{g2ehp5rIf{6T{v+KAUrd~F)F)Q)?_G!+TyU#5qCc%zTeLv70kllLr!*$sr zJyNG2QEeh6lHiLdqIk~?78sOA(=j7;4bR=EH#u%7J@yE+RY%L~xu4;3sMdNW)0zd9 z+XA+hiFJ_%O&vq>WYW0h=>8d4P;leyprufTK4>u$K9`F*dXo3rTU7L~+&$PZhz>VD z)3xq)qy!rW(NR`7RCzxZmVbGpoL+rh|B8Y%-+&`orKEK?N%7_R>hJD_sJ-#GX@?KL zwTf-w_hwbvVs8?!-_>|v9vigUBA@-3+&Sq_t2Z6Q09>o-daq5fuKS$hq|sgA#zv*G zD9x~Z>xKK8a+=F`!+uV0BuN*!O=x9FkZZIFu@mAzET0%Uqn|cQQwl3DEsctSjiCGS z&pJhW>Cf#ljO)siQ!*ndCyo?p*st>{O;yxB^loyOQoK{so5hNagiiL^za6Vlt6^pn z-S=qV)Ezwj(~^@P>?>gVn>$5;{^r(a^oQ%SNW>X8L*T9t+@UYY8M7(L89F)n`Ygtl zH124o0UGpDb!6#^Nmcxw&T{Pg2yGl4zJ(4SDVCr37&0d8@AEw-UBSp!T;jB{?hXPP z#ce&>16x;fXaZWWbMsNF(}Kqt?zG3@F9-=){pg+>CMM=r@6l^u8~iEd-!?g~bRYke z5~+uZ#on9(N2gQZrG6W>C;TfL=K5RsJl(L}cpCc?K%hunC~bi*M_#Q$*Uq)|4%BaS zQTwEuo_0L;8oVG%1hk}A5ma292aS>7B?A!UyA;zsF%ijc2@ z;Wki`uvdvKJ9(npWb_7^2d4sP5^4Bpc<=}Dm@e%!I<{f|BK3+c?!0LVcYDgk%U5Kt z%$7~Yb=p0#0O;)n$et29`L3?E?C1LGH2$plijp1ju*~&1e$vMI;c8>L9LZz^ya0%D zN$%5^0RqM!h$|^7mP6ydDarAQ{HRUb9wXa0tL=NgppafAvtqjvc7$xx&Etqd?L*+r z&JR^C^RiAN<1`!&EvbCzKb;yTE1OA@2kJMvwXXD+n~%?=q=Jzom@>>~C$|tOubxrl z{Lc3Lc}Onc{MoiK%7k=wm-(9j@&t5U`g`;N6dVj@7x~}z*M&r5C-g0qF-y}qV@aza zr_9dC7fV~}^U*SBf$Y~nocUZv7&Aj;5<%;g90O9Vq`-p!+MTrmVHBZ;h*pH7xl68o zL*?_{O6fGopwH9FD!+VH?N)gzbFCOd~|Hjq?Qb;e5kiM4DB2*6> ztF(_R@nN|$af;Pa+~;op__fn11}p25+e!s>4;Ef+qcKe1mt6{t!j*nGcpP;|_g5f{ z$z+0lF%vBomp3#3NAjTFTjhoS@9|G<#+H37E?4Ec4SPyImBWJ(3mb^*%-=9)&v9jj zR(LOmcMsir1%&i=>I+^2zSehaUfTuILnXaCW)nGmeKHV5=r}UuKLa96*C#0lh`5rh z;$}wX9-%*^n}H+<5J!q!9GF>0G06QXgFvhCAz8EKSxgzr#BqRv#+p#z-6Llfac4zC zkjSy+v*ARleczUnNO~bkED!zY-hi)#p@iiF@X;tSMgzg$MEv&yY9M?B zaKxnwkVu>ltr^cm30ufEl?tO?)0mZfxYPNKD%N!r_(|3HksVZiY{JA!ZLo&xW;J8M z48+dv#o7L}mA7{WZM;a*;q|9LwPot9tnTQ4?eI*I_a(gDNy6P{(Q)-EdgozH)ys=w z9VIQhy|K3|qV1z)6~t;~{2*kGJX=jB`Wxi4&gn-q<7Au_J&=ZBf>!*n1 zA}r851Bgz_bQDU@ZZCfCR2bh!{Z}u{5y#q-1d^|nMx9XMKOMmuDq^V=!k*u61Kzd9 zOONt^`)bfCo-18kzFV^la6Y~S#cKXA8;pJJ`55$xprC3pHF!22{IgP;5+AMHQ7h(h z!-zB7oqg^D^Jp70pWw5|YPL8cbaeC%D&0rq(E%2QnsC4o%uPag8NzQ3^=jU+zUm4t zu%3Q_^dPH;_|U8|>@vfPHC`u|`QwAEtn6bexS_5+MGp%@0cUaZ-XLVaH=A2t?p3Q; zJo)#A>}tYFY%<4dO`b2^%G{e|5j#OL{#(OXeD1HUQ$%_d!^Vh8j{4T-ks?;Nk8lPC znJ|HyqMgI+1?HfN=UR(g5G?6jA(`zpIf(sel$g=*@GCzA4_wL;Z)Mi^uN2eSJ`O*a zfU}^i;>KHk^B?Y>2|QTPreM19hQ?iM&fNju*%5G}#@_H?rETXcFxR{O?Gz9SL$5?l zROCjJ1c6fT)zyuubWr#PZjQd=<3~i8B^wh%V%d4O)V<;3By1mnM9pLnm(vF1o>Nu+7&;=W!r!smTnr-Sbah9aK_dN8qUt zo#oh(Xtr2|pJugrTUuU9NwoO_a7~vR4s|{4H%CuOTgnz$BoBW1Y|Q(-d?lYat0i3- z;k0MGD(X{i9ywbN=Hdfy#XZ!rp(eu=lnroNQ=6z;JdF; zr<&89qL^{Zs;wTCB9bz(E)k#8Dz^9XILBjF#}9DV>#G^toL2td$PBck-RgVF@|mT- z#+wP+fU|!_f39~thZv67I1Z4O$PXwGHtGKvM)ZYhDNAc$K@2+rl2cJ!zq`R%r?>vr z$CnsYaS4b>)@l|A=mPt+jNLK@EOVQ<`wAJvvn0CS_jrU_Y}Pt}>^h*w@_B81Vg%nr zv+3MUYv|`@g}Q8k^tLw3!g35y8C<(uy}jD236SqJVoc>xqxqIWs!Ze2Pi67${Y>@< z;>7;nUDr=@HpwZOGVn&EI~GL^{sS(QAR5Pa0bHreMD^i#+d^E((K&5pjDTshv}V8J z#I5WmMWTSl5;`4}+cN z2E`-+wEO@+`?Bj&)abnY!|6C!QNXV@%w32blid@48232Xr%D9}g}l*+_vl-dlp3#X zV|j$*-#a>%NC8LrC>@*GPmGE@@(*=%u;$!jRe|cu=~ja+*;tuS9CUVtg!cr}&Rh1k z32kamG1xg!BZj5Q)i%qQz#(kW{n+|Ls)2vuisC0**c4SPKQlts%y`L)XA`%!0O95G zN4>6vz3H}qZkm&p*16xaVVC7rJJe~hGd8gJMSuGoWJqZI74LH{W>k4T3k#G3Mhe=u z_8d}*`ENlepsF#)Kung!qTon|E>0Oi318xHzMLsYiXmgBEb8~aS*xwvt#2}&52|JE zKjo+KR|vG=r~Y}G9I_s+f1P~3ypTd&On#e)W|-I0lxDNMW@dK&aSA4Szjk}ecu+Hn zdAv6DOB2y-%GBAAXBiV_lcZvGl1Ouz6SC9deu-6gaT4lxqMSaHJDW*DY36OtW?MRz z5+xl~jJKc=s!*%|ueIUJTDuLV1eq!86bb8r%RZwU5gH{15zrpn%iFf=`qFpyn6s2WbU8)+?YOM*1c=4GNq z9#@LsDX&Wg&Q!(~mY zk}=r=otcMKpi5P6@zCChK6MU#9sYa!Y4(XkP!o@mp9+{Ubq+k0gK{FqZ;3U_g zJLM@f`je@o?&@K3;F`(AOgHz?wbM;YeR@^I!!z z7m&epWME(@)nogWR7S@Qu|1P+n??Cxtj zCtVJ}rSG{s^`OvL6j!&sapU{*>f`={k?lE(V*3wQ&0#$u9%_@WXqolCGXs_dp;(_# zm<5RMCFA3}Q;LjOl+^5eTg;JClqqg*Rz)&SA1EpZ4ol|rGR<<(_OxvzZS=uXUI3I< zEKnFBIdm5?39^C49qX^%_WJ_A4m!A{khQiu{!f!FpIK4^XmhbDz8Eb4n=PABM@D+b zE`18Cg^%w|0-c~O6cBTmf%^$?&HOlI8Pe&~M@?byAY(#gm*I;$s(j<{kN|=tGS$iq zj1H_vwq|y*Z*a3Xny`d@1WZ)R zqb&0thAYA=%)2iD;|^S>FWaa29^XHQmb-wb*hCj=t3ZQb#fq?H|5E>IFAT9`pLgGF z=@-Jf8E?SVO#M75kyY0&L7dmr|p>7(9rv{gwj+swaqEqt-WU#dV zeNKMYBZqs)OduE-K(c*HoeOBtcu>%f1U&m-Nrb%^n#%!SVYG<-jW!ziSBJ16h67tC z`sB2e1cAfGW2^i1W|v znng~>Y zgRtyHq)>O0nHy=@=4+iYst_xf^Se@aZZHVhtqhe#6x<}o#DK_*Qkj5!BShZ9K0;JK z*TQ+)t>gISgWGC*wN#?iOV3LXV(7iP%J}R{#K@ek0G`b91&jsTR3GI^O4|h%aGB#; zJOOgx<>d^?RPsqDBJqapUb73lS%6m~A+p?VMDrRw7-!tJ;HV8vU8T6dtt{e5$o$PK zYVB!DfTW6Qo>8YFmR=!g`$B|#JH|b6HZ7G#dp|a>#|8e>SNV@t8j8%LJ+XuTLbj|) z!fFyN_Q-Y?l4kBA8o9#q;j6;EgT#;bXU`v#Zcf6Tq!TUtHl@_&70VaKTtM$2Ey%hO zBNQPgCkKQn-Vl>AFnkdku^j7OCH^oM}9}iqMZf~LmESK%uWGnoRx=PCC zf8stc>RK`2l)786b-cn<~a*=biF2a=>;EVn;C%RTy! z%tvx(de8OOa(y^hGmQc!dCliu0Uj#ltR|K?L1uKRX zYz=|msBw$gG{1Du{WksMDX)$dZOUN8DAq|qM>my*ZU|CR{su0Cn=(FJ8gD#Ge@ZtK z-Ib``6Xyl2(yyJ?Gqzl%q_Sl#et}hZQ)~WwiJyvs&l}xai-$kRVpVN8QCE!+W-|w0 z?Jo$8Hu`1_>AC^WzdIkPhtX-&2iN_@uAw-J)zN)DG(<{qTWjqay;0B=NHCAA(r@|- z#C9mCD9j(mbz)KCX!|tG2(2*V33|t&Bd8F}zpWzd4(ts?de$}$^u)_2$e8cZN_P$k zA{O2&iRHdF!{^R4Gy90ZO~A(bYSl$Xbg{K-X6|pjZE?_!07;wt_iMSj3BnKe{+!NT z`&7Jk2^>_o*`Y-bCT_;k6r5@DWEh?O$s(=yRH!$y&Z5}OM!mV@1MKl1KQMk}kX>pt zd*Rk*c^X@@J}RAV2;NTZpOUq;<%#8V5rQMIG8#rrQxNJ`&j~8e5 zgjF&VehC$#|K%x)-Iq}Kt#U7}CLk3s+e346H%goFZt$ir6X+rZ>#e|Q791RGzi~$n z-g<~99A>9Y+!{nxweR`~{OMpe;1$5>9H)!x;mWT>MS30?#)1iRbT=I%c}`j=BXr^q z3pN<+{1C)tK#4R(rp4PSoXjn7y{iGvV1cYKthxzl&Y8$BI|5+b4)QCISm7{~@Mi&)Zon#33p3LnbGtO7@aCPZDzF_6HJQ`jfSUQ#- za3L`0nrblib{2y0U&3_#$6h~hUuINOh$FMY82K!LhUUTDQ^yq(Eg4!HmX2SFQXIc|uU89x4<%{~4Bbm)&^yTB4Wc%jsc zH%mj+Z+7MFKz2mU0-)S;$yvP#vLmpm0BxiZ%Qr;@BxJg{dNh)mIF#a;_*K$LN2vz? zA)_VPz$-{v{u{xlJ`$NNo!>~Bvhvg%Cp4IrSo8>*8OAc0v%EPDoRQ3YKPl5$l7udi z1J50-`?+@cPlfN#pZ>BBUx$5cFn`mR#_sTrSx1G~t^Na<1&ef}i5#zuQ7{NUCA0W7 zCjhm|M}8Sbo-jw(*AVv0mZ|#7uI+pUefa`QH7gDVKvl}Xx&F_x4sgWJ-KYP>MGrjz zY3EGUht-m+ZDO(MpieJAFG50%U_geWXtn`_`OT-Ym%&cbbpc(2<>I}{b#|4EC@3Ys_++kY365AwDnx>h zK`)Xn3-WEK?AClPrv-LeXj}iL^k6x(J%Wk^6DDFeqaTHG^= zXKEf%sV*cPhA&xcp2|3y*pijN^-s+_l?$_!pPfLLA%_Q9kRFW|m1~qcu0%7^J^<>e zo)S`B260F~HI3Az`0c&tVp%1SsBp|NCrT!GPS3fO7*1)bZDoZ}z>68I#L%w{PO@Nh z`M0ULJBLEpiwh#6B=#YqFH<_1lNF?NlM!z(-hl3~rN;yfri2=T$ld;4##j)lSND$h zq77*$3&xoc(Twm)tZiv2wRip-xX$E!bdwQeQj5dv?>cs87!14Saisacew=!tBBo4m ztdXH`kOc&Q@rz0E_ejAKr|Wiw0IiOvldtdN>KM1x`|!j%wO?sTeE1T;Cw@tucel&< zX%f(pK_C$SZ`=PfwIm@iF>$6OLIET^d_qYlA=`vGq=Mt~BUq(}LNMyO=VzaA0jppX zzA`5xgvWaX<;ZitHg@*tG zg#6V>DR=IVTSKt}|KVTtOa%v%lV^V{HC6LM5D}-NlOlm7q&%zgc@QJhN+3(lnsw|VIrc?k8R5dWL8|S-BP1#KPmB>{OqTe6!hhWvfpPS%QV_^=+ zA8@onbcX81L}4Z(TIzWL(*yA1zt|G~Gi{F0;|na1}&i9t;RfGPV!!RA74vp&!! za)D{|&T!F#t_Pw~1m8B<0`a0Pj~f3RZ^7Vax@l^>v6NyBk?Q?>Zx(aEAl$j$dtRK! zs*fDt98weN%4lfSWkRB8qGudnFwMvf7NU2`WW=h6REXwp)d^0oXZsV%Bj}!2*c2X- zw!xG`DWaWeQX*_Q+|y166tZbu=hs51B?AflbE`)+kN99}g$dIpsf;?_L*vUAojKVJ zf2;wRLGY^+C+PDbtm7ep(c>)87V87{TBUJ!u2;uB2$^*r12C1Qa&Po@*4w-DFqyC? z7e-?vZ<62$lL=%p`tU0Ekup{9RJ7GTnpkx+Ofk6QUq`+7UsYANKcV}tf5NR`mOq{J zIHP{BV1fs9_!EC%Y<$NxLbc#NlGxpiTM?`0`INC(vxBsijDABAYdS^E6c5T!luX&| zyk`IV+?8du&kg>C41?*xa;62fj z{){G7#AG9;_d;57{;CYT(<9p=7H34U3z|(Iaju%y?KkFE=3It@`t!A`X2iOK|9T?} zvKK;9yR*7}c2m@I6&+reMoAWL&8BIe`7)5dUSAoe?Y|g^X{g^{4P&co`Tetn+ornn?>Kb@QNKi`WHknlBIxq1g>2vh(tYU`e`<%0>K z&1zz!kuwZ16_E&q*&WAZDH@?EHgn=L@#STs(;JF9)|AyRG3nlS_V_< znFP;-z5XD5zrv3r=4?cQ!qlpD{f?Sd&t}Q0X&C#%5Y0sXt{KgRWn7e%a~O0$WyT=y zY1X9H?4zAz`jX8^2?H=Zsl~L-BcHu0P?D8TlSr~|; z6gpC4Zc~07N7hdAf*hq_I5|O0D}!xu1f~R`A2?P1k?X@79C#&^Zsdv%2nqaUi*^97 z97NS~Ch}u4XLu-f8Z6D5J&WBJ9@Q;>F@W0YwdEv~7a0{R)N{G{1izii#9@Z$3NBQhnrFJjxM2N_KOZW}575eql#Vanl~bJddp zd{vyV=jD}=jH75MHY6x88wSU>+_kpUdE>Gf$Q06QC9gULlzBbB48p(CjiEe`NC{ci zjab}!2dFwexAqmM+S2gXELsd-bMV5J70PNtHgOaFsJJcba|#y?Phj;R8QttLF8|Ag zb3E(}t@}MH=9!b>AB*mbxGK?ftHr zm6R}(Z4P(8?y-71?x1k5YtYhUvcatG{ry3TZqo$(jmX`8)!J`%(b`sT|F`?Ox0m|I zM5eOJlqm_yc)UOm6(%!LbPzwo`0O<=uLmYghzv>Z$DKyk?BvURi8b|xCOTJh>HXnj zkzIbWHnCkHzI-w~TWWQxt#48s9Vf-%|1utV6{8rG3aBGt%27cu4CWrr!1D^aCdQaJ z%AOAaH-Nz6LBh!PyXa@H)3@WEI{P{s!(DL}o+yx+0S9)xfvs;YeG)>_M-}8nih5U0n<=h8m``sfy>^4->tq^VY$zI2F9?9udndt)eXPE?|HcQd4=(0 z{j^wr^}4UMlbz!0B|2S6xF!hPAN)SdZ!D(I90+}mDl+U(IHG#}h4bC51ZI0E*T2@Q zI^r}NQ?MKd>T_Z=fB)UQ8AqyCA1~_nC&^5k&0k$(k1)`CTX&~o^R}_UW%V^csbH;I z8c$P&Dn-S2pDS<(eL}vy_+@_7l;eKs>GtvQIp8H_W@qpAd_hDX0?yhu0$e?x_Vb3f z2cw-0WCiXaSn>$#T-HubjA$lDY3!goYC|g7P#q0pNgq$-+_gEjE-5Sw{?^3z9A&Zy zZ|laLPtET+vCiiMh8O6uWD(gGeVMef{PyVRt4)E1RcSRU7IpgOA3y#F`oppA3Vp+S zd+A+Cly^6%;ddFYqLdmBPp00aW&b;fdkF0QeSf^u$Z6Q`!kGKE%<{<|&}p!nkvcAL zSWHYy>B;c3&rGM@Rra>-C>CMq6gSfFO0YF)oT!?6+W$ z|B|cgJLD8hRT7$9x_YT*WGJ8yD+r*AU-Tc}ujm`%5`yoJ`DbnDxpR`p(HH68rWKOVa65d{1ZIm$257ly zh73<+%uAM}0t{kj$eud5$Fv0w3LKZh2vUDo00V9!WWkTMPO0!PVUD+sIk*i!!6t9` z`w*&bgE=!4R_}kSJ$I<-t`LeF)VmiS=oj*WvnvC{LchpTenMJp;>LU$qK?fNf; z9s9edZW2Zz{!UBv@Sasp4{}MBnaT%L|NCI_WRpm%08Ix?Ok0oP{hHpbI0}o{vV6y0avgG$GHJI|5LC zF?hN^-^^lgrH{{j18(jQ#5oi>pl6gcy)UhuUM{V=nJB<_Elh1{lf)eMb!#|q@v49_ zkUW@%V)%aIH)ZGjUjq*DgB3mnmchI07m4pr{BkO)efILj44%0#z3_V2H5nq?ngv1< ze(!#1Mz`7GbhTJNwDAr=!JuYPa=Rzc6#n?4DK z{)PWy(@0nsNjSBbzmcYtW3llAL}hkW_Z5f4rOZ%nXMCbUuz$bBjf~zR=j8ghRbVxdOK)=U zPVkvL!%1kDLZWm_{f>`LlQN6Ne@8zxcgSV7&*j!Qx@7Qfgyj1m;KG~2e`7w6a+qpx zD0NAKv?j|!{{8f@f|fgS!+(+AY7^3m?MM!m$IC#og!My}sjDl`OTm_3JWQos|A=c0d`g8*Y9HhsD z{7ukF2t4xX<^KR6kVJ3AHuX1)4ns?`nIGdnY98*n5v-c1TDFA$uGnTV(G|$ok#BfBamRza8g# zzwi4sp3lc~IlEr*qW@~)fl90#l>rJ+L}q~2@9O;CXq9*Lv1GyKSB9{2?pqAy+J?J7 zPZq(td>?od-r15Toauftx2tDGIwB4I`WOJwB9R(xoR@ZT*g;6xnya!X32e~aE+3Vc z%3iY`)v;!qNe*ty5pVv$#kjEz+qY4F7^#Ylr~d?X!bl$5J)krmfZA(Vp!{X`N>i(= zN)tmQuCl6Wn`)a@r%tBxxRE0$2^DlhiI~7{ynX5X*5{Laqo&!+ycc`pKP?BGRIYWh zd7myJ6=T7?Md#@O{-AR<)q`Ec?B^nk^l9{}e0x?~DY`Vik(BtqscbWodb@j+h_-2q zg^o)fYQH3cD^oWV7!3)WJjBOx3U0V>Qx5pmZ)3i!q2 zWPs{-@o%baIJd=LFknVK07ar5jOuZJ9N-FM13;(A$;XE-4=hKV9!9)FT&4ZEi9{ZF zue4ham>zAU_fn~HB>gc_=s3SAHR=(6rqINn1Um^2z7kQ#J05s)P>Oi-=eV-kk1}_u zOY^8-Au2*3oVQ;J;nk_+VY z8>r19yKrAgS6*=zF7PNvFg%Bu{eGb+G4{X!M7*4FKKoBbTUwx&H~a;jkU~L0wBSa^ zXZ-wf*31&qS9|o5Rzh{WWP#!BC-~T%oUhd^*yai}ks6#@ke&j^HCymq!ODLU=@SjEugXe6jf+WB_#X>)vhCdrwQNpUgVg$51KFPwtrw`)9Y96-n^_`2K zIEncVcmntCVQ=1Kt^WZffH=vis^Us@O5GFZklHqUj=<}9DVYmS;d=OgQsQ4RDT&6zSN;g5UxI(1q zm5BdQEXLh!F_^7SPtc7BmGT*MVz}El5!d;@mZuv(DN8*p`(44c`tzPxo7m9_R_l>o09z_Je z=&UQsE|dr>cef}kT?%6g9@M*LI`tk^`;l-oUz+IEx;6fw4htDsmB)_)Y?M+Tx0}3+ zZvK776j-grk=ar5!R)sxiknLskk@ig%LiTn?hI^j-0Gzsc2etMMtu-Uw`($c$E;Bm zv`k^YOqkNT*Sqigh1D7B=AAuz(}zXz<0rX#Z6TLAwHFiBL7ru}CyRCOA3&_P&s}kC z^@x=#??>~w=a+4PX2No88J+LHV)K2z`SBn{U+RJ3nvETTRYAZT-;ELh#iNSgBu?(x zthg{=+DyT#`pJo5JI(inHc25vJ~51{C3sC&k71xNQYE`>`Ht4$Y0w`KUlB$Fpn^ie zi3@fW&TulH8re9DSW)AOg1-DG%E^CafYYNuMDYD5=6lP)MQ+5NKw-OdfKkCn2T9xE zW6FR-3E^MKp>l&+-C){t>E7<=v94!7cS9M+w$%>Yl z%2}`Mr|u7Wus-DG-ooC4LJ3RwwJYA^uQ_(10l7LPto1c}m;`Shz8{6{za$=d@i_Cj zML@R}M{%lWwe$v-GLv_iJ=fBj`RYiaV-k2)Af|bTlpRo>4H+L6Bk3A+GVr>1ZVEOL z64tq=?`PUrC1KxJT=4ee*?Ebx>bNI99r7bF^6v^Oq?@lAanM|Hx_f0_%_9 zLiO@^7(#~A-NNKtl&c(OvpXtCf-dPSNByX&D^@Iw+9Q>ly?*(Whb-RGG^M_>`RKK%hvFVnrk+s~Y*$ZHH@Aek&Ogo*bL{@Abpfj<7A=t+< zGCfH(G#V3)u2UW^eEOntfph2n*Z4Ptc*p^I$yE%t9bd6$108PwT$_Xx!c@NH!2wJMH$NhnCo*j+Bz5dR7~K$f5RcuR z{$3QlJQi*{rTWz%`lE}fdijOPKam_P9P^(2z?c*}fgpN`Gw61gE2CTlb1Dqf+*MS6 z{KZW1mi;KVJkS;JYj8OyMzFDQKvU_{XIpAIhx64@PM;#p4haCegBd&#fTN*aIW_7T zsw5Oz0=V&dJJP$f;^~jz0M*4SW^pV*iY&I!lT8JAQf^twJAqK>$s$3R7Y{~&dO07Y zG=#n!q{3T$ltY{RtUy_B|HNvjO=mfXJl6?2u7diE^e<~povwJlAi-BX!v=hDR z`?j4n#FzdG7h+)+z+KqNe;_bo4D418wnI~o>y^)Y)G=p9^k$wG64P;$ zoliPBzw=>t9v~j&=p(uTZM!$SYUY!W-K%Q<696<*4fZI*Jy=BCt95{HcE*8t5tm(! za82Odp0L-*=)!P+%8Mk_@881x&bhN)%2U}PwCx(r=ssoxl#=uwMzN$G9q$sk2W_3( z%74hRWN<4|%k0cvd<%OBJN2J)brp@%?8giEWa9|^;7UT@DvJ}k>8}E{XURxb=<{F$ zIe}5{C+fmpi(k%P_&>oE5fE%h64%LIgNCyqKE&Et*+S;SaHqd^M$yHAuJ;|_6N9)e z!WOg)j}L&C4$N!5ojZ#ccjgBzE4xko{s#y8&DmmFJVgn>_-mnczTnvS*4!cVp?QUr zd*Q6BzJH!8d*eY1 zzpLz*jmvkhzQnCV_Uf&xt#5KoXrd%@gKq`hF5lM__N@WnH4pd+R%0f#YQ5;v7`O_|Ir^`^{UaNrV~dh3xth;>yu6L5+MxZ4tSZre+BcHO(| zIofKwqZPk;5{%+G!@s-k#o1pZIhB$P+?R9>QY|DO?))qHza)&eNECBzmS!d1k z%vzR0&$D#gbmo{S`32F*dg{)boUD}>CXJB*R2q?+8x;vAy6*ap^<;VJfU;W)LPCax z&qZKe_>xgdQ90;)tUE>sd|}G|FOO2f&-bdQKXKcVe`1E8^JWcIMsS zlJ(6OWc==7H00-J$t>#u4+vz6*W*xQf|0Kc>|p(R_l^^NbVEH^LjARH=u@#je}&btBj#xQ1_jI10Q zc;Xn|XJS_wYt0h^?4vp;C4%)Rn?gTj&8_Rx#|?@75hhSEF+kfLyb^ zVn0TRKir^H1QD*^ zwzn%mnsJ@J@>Sqq#Jw~MtW>7%>-g?^=O7-S2`f>n&e~aP5*V`$H|1q2UR}7_M@^d7 z5bx9*%MrTOn>%DHiv4>Qv>wYeicJtUDN^elHOdg^;JadJP#oV@x7Oj_a$@35RPjBG ze41?!MCanoXrG|r5-xwBX+M2j~^HFS`~nS zj*^N}esYIvOog>uKdDS^(7!F9l&z>2QotwZ;Q~}z*&>M=-9MWtFCsfWHrkz8TIgz$ z)N>2EvQ)DM+LV~Tw#DBxTG@ok^mz**hwB>+_amt{KLe57>>i&f>B^OubHGa0#q1Q0 z^Qxr%5dVR1Ogk)O?LW(XKR1$r)KinwE0flZ!ph;9A4fadM@%NoQ+Tcek5^1qn+T76 zSrLzN&6P+zi3!XSpoCkk@8q*s67-0qBQg7whjeJph+qmU4<5;380L@e$1}?WH_Cff zwU0gPsj)iKr~I~NAEuVwH;qUJ+g1<*jaewL6!n7L`mIZRPtYML`NyPm&KOYnSrsWD z^?S~gz80%BV1^nGH&FDfJ7Q%xr3TlXQQ)>%A5M?jHL6=p^lJfP(>+u;R2|anH6+Oa z>;Zwh=2UbF_#lZ7=9y4A=hPBQpehs@5)!gof9EqGmF?Xx#0PoR>x1k(&+`fCv-@xH z>@a|25v9k`l)a>bnD53GgsmXhRAIKl=)BSw0`M&~n%0Aala{pbveI0gS;p$pigBlL ztDmI#k(z#=xeu_6i1H`NQCxf&3W?K4h!y~zM4$VFX&Y>fajXUz*I@^j>lqm9?3MD= zlkn^0k7LH18wXPvj=KH1HG;?C5aIKf zmuCS7s>mNJqs^7h*3u)=|Z3G-9((>S-Grl&2Z&>(sZY3|v$hz<^V zcX0dX(mT&>_lw5DWfRZEcovn#-6~t)8ZG=;BRk#+e(wM>nP zJd17Je-Py14aD|JXmLqoV4Q*BKgCSsgRuP4j=S=^|otTF>^1+120EcLeI7j2RNW%Bnge%Gj0)lM$D z%awO)=jBG8>dY)>-TU!C5>94MtWC(eve{tNq~B5@rYd z9?bLK-s0}=?*D%=bD6iBwXb#E5Evf9<$MEr=*Nb*cywA$=QSpO3x6p-_z$%QMcwT+ zP%a;|`HB;~?3&((66Ur>^5j5yOPSt`(O~>%weu23No$5*&9Z4hb|)-~qgUpY(3$OI zwx^)@QK`wwHGfN5KA+UI)95zZC;j>lmIHB;46;TwfqketS(x}A#lBy9N0j=48hYi734b_cmf39JU1e(OpEGrDlK`>|b%`GBuMH zWYc}MGVWOso9gN5?KoT{@d1%+l$-KMeOC^a{2)cz>k|_mzEBPht3p|F^fx%~a_C@m zOpHnRq!n+v<&$kTqXMEZ>6*fLe)wTkat2Eo?`ty2S@+L;CB-0~L&L@Q`E&KLombMvVW$-saKKzAj8&2LGJN=A0S0x<8k7wl>zW1jJN6?nyeHeI?N0?o`RgVV^zRz(VQ{(xMiR=b`UKO&-f%| z=l46{Ll_?)zy76qL%%|hWO!9#4`T7Gt^6k8L5|o_?;;~v*4HcOT`e$%Cxv?h&|7K4 z{Bq)#pC~|1W>7&N7O#WDxUVfMJZvUo z(V<)z>6w)TU0iV9otrY5eWKk)Yw=9o56sxSPj9m>F5QKTZON#WqAB1OCh@ zF^>*a#m`t;Pjc=#-~_;Qp`?n!s}o*dqG!MrxuC`sKW2v0^{oXK$CHV_$e7~9FwOoQ z9xsokMjGVn-itq%;{L4PEVb~b^bQrg0zjh3UI11*?8hFxOUA* z*DN#LS@akTi#nY>-horDl{Du{GjQc@&_YP2PRf#_eBkDS>?eZ+8eV=v{o_xILy6hT z&@>(5(F|-q$+K^Ote{v~9*ygVMq>ig3935W&Pw`p>vo=Qxl*-4GW%sihW}Ej%*SUZ zl!gW^j+kLAALL{&mdwRhrKql{yVOJYjoqI`PJ)+lC9k+{$Vd^$C{gp@Xrh1L&LQJ& z525g^EJ}bsw6XbESsg@IL0&U%0(A~KtHu=F4`HLqjmMKA!!pC6uE%3Er z7JA$oanP8GYd6xM#A35Y_yZmj?kihN_^8J-9xhdCZnW)bSH{YwZm>F{8S04pJFa2R z;CgVT^E3tP*S4p0YfKtP!q1wUE3)@DySr>Jv_GxJ@C@f`SCXL(x#Ime?ByKi84p+w z4*JmEE^%LR?WtIwZ*Fo^`tNdqb&2F6PISF)gfjH`kXF2ncI@eM+x8ko|Ekx1cPIAV z;_dwV{)w%*_@Os}t609Uu16_mAxB4(s*$vvstaFq{xGXlnfB+o(RJVr_ zzDI~XhsI6G{;o$!;~HoZJz|`%!2T3>`rqj|GlGQ}>q1bx){OI6ir^4zidtJ@`Z6{^ z?5+xiu;x?1H-vZ?(OkWrSTn6gzgC-gllhVfX}Zx)W<2fw5p}bD7K42n@Tb3)-}R2i zf5z7((QLsb4QPkcQI@$1F7&g$O-P%_JqWO0-9Ek_YCG| zCyV#5PnyGwBp#ZyS~jv_)1Ik=IJ>Zd38hpm**@wx{?va7h}7yo-*3*~xcO>Vy>59#T0 z&+$DEk%<{0OY2J*4rr%V&+JUt@crgAW!LV~Kfame`*2P&f9p1;VfLXyHmOX(N+Nyt z45Ud!62S}5JsZA77mD~P1vXpf!}57Q*Al zAeSx0Y~e!@YqKlgk9cKF1Pz8= zGW^%vu^E^pCEYU~^G6QTbs4fq^m{i8(0u_A_?<1-=jgQFK1F*|If2pHduW3uax+-_ z{bJdxP=GNH1ysUF*iiATa20*zN+?qMWHzAn(0|Kk)Dy!L@PqMo5* zz-c&hzfe&>bVOEyHJrYtY$-tJ%IUVIP?r_p-%TC(R$>NHgl?0Z)Yoe%4)Vhq^>f@7 z5WmZoIEZ)be0`CkyQ)MN*50)IQ+k6QM)o{L<`>>O*x(IJ=SZJz zJ+g2bj*F}ndE@+5x7iHy1zbFYB-{LQ3W{m2p|y>C$N6x}=P#v>QEvLXd~-7d`|Ovl z07hiY6J2&y6B7=_RP3W(x;T)ElF0-DVAvN=d=J~72zu?!hPN^h+t=V^2{~j{daQh^ ze{`yG7i$o7Nc*GIx#^^4=_)rMGNE1UIGh&b)wq@0C}e;`T%IMe=p%E~t^_JxI^0wC zAoD-{0~W-HJ~cvW)H@>+$*p6*jFB$(Eskg5RE*Eq2vBy;e5{0L`MI zSN!my@oK;MG9&L&Ph@f9thz0mdJ}xW$d&2hS^FU@j_znc}z%yZ&7NGl&!GB-E; zcFNlUDW2dgP!U+755v=}1Pu6f(CaOO#ph2+j-fmE--jP~e4M68+iv5$UAnu8VsLQ3 zpVWEE^;w^*xVrekvk%De+w8w-!(Z@hY)(Ea%ga z4qf|Xm`ng_B`s)+#CJJDd^J|bWN3RrZrp*?vy{f78FaAQXXr^u1ZR!2yP@@du{RN3 zJbZjZ9M>Hj8tmt6r(@96H4F)rr)K^fVFgPZ^_j}EdtYV3@+WseF4F_|Gh#LTtbD7U zA;y7|n@=&%n*~oX&|D#O7E@al6da)vU)Z)+rwt_%8mFIrKG!DfsuO^qhNA z2O&t6CyD8kyM!ApCnTE`Vo@29Qa@b>cdEaQq32}|xq;yph;@s;{_7l^2vS}_?l;NU zR^3(@4U9zurTbuat}SnC%XVdZR|p&n5E<_wN=O@P9_m0_;eC8!X~{G`_vrR-^Pch!8>g<>aR9*ve#1 z$W^aKO||7V&dkJo&!)!|4HN|o_ys_VCwH)SN= zXgx)l>%abZSa9Q1=I3^>#+a*102L7v2DV!Y3P{$&GBU^#r(-@oiyJoV>1z~Ha|qg( zwu*awu9x4;SoL@G9k)}#x7@U~bU%2VtHAp~AEUQwJPGC6P`NQoy7!!gn!HxuV4l9I zj1^X`_-`zwxe;}-!wMtJVOnTUV=mg~2i8$SaEU;JJsew#O?ibPB2Iqcp2S>{fhYZ+ zjAm6;X(B?O{Iw24EMwC=KC{XJoR09NB~ua9y~YL1rQO>fZ?t*b%vH7RW|ZdL zi~)GJ;8K{mi%~mp?0g$(_z5mRQ;i5m_p=&z9d0fAq7akoO6Qv3rlTGH#Tx;^#RjWj z8CbZXw+9dE;fx5imKUv~w`3O8`Us|^CS?39bMTj*M@Ud?G7e5=Q*{5gWj#{H|51vr0kz>y zjb^@LJ~%v7Ku|=A{r-ZJ7Tht7jG#lLab zqL%WLpK}YS&z30ZqK#AQg-hbFpvC%i`Vh|WDb1-lZ6`ZA5xW%UPdY5gyLc)k?;tkH zJe45RoxT9CTV9&m{cBb8gR#vsDJiMl`TC^1o0+_VWDb|E9b@nhg2}XQN~Q$6QBTeo znD{md4f#a_uwwysyU`~qHFa8%DdvSAW#}ObxyBvT^ii}U&*6j~h3ruXO*842t#Spr zoMqgTvvi8hT=R@8JWLMw?I2|UN=e2FC>BpMww$0)&^JUEdd~RXX)qc+6%`L^kp`X}k z!NHfa^1y%{0|Jq=Um93}a$sEr<@40#)6usl&-pk<85r_=#XaEGe9H0r$`g+7L5r(w zEh*fsc||sBm$v;PoCnE^Yp;LmqfzkQSt68~Rvrw1q*r4r_BH(6+-yIx3F2@Q? zV-EG$WI}16hF%fCaj)e8w-{*J=i1JY&ik1e8H`H!LLp?f7p->{w4AuOr-u>Zfed@p z(zY$WotZ>kTe4Y^8LVSmZa!07RTmjqEu2}H#9d=!4{2Q9ph?&W@b0~1=DPkqE&C+p zg{XWFU%7VSJ}gwkv*RNtJkm^tkSTe9VZa&FxVwETlgmz6pI2Urv4|14 zR0=mT5YhuNaudk>hxcJw)v1hFoEwSHw7zt z^9^1+X+u*d84m4`uK9b-zqFY?%{WkP&=xYl-kdF4q%wjD{CP4D0P-5;zJqLVTiY=~ zv6SX2HIK{A97(dL^>~WDr+#baXLltYc-j5;_P-|?nVHMbsg~G=wwpae_n`y@!@Ki} z^mCs-U7_ZD{WNtG+Lzh}DzF5K{s9!e)H=&-fmpjJB2|6;_opq&;AQ z!-^2;%9dM@jUzl31NP+<8EPm=0fD~6>&o9>vx*zfI;9C-+&|bw26mCFT5jww?UtB;I$vmbRqe%6e`X8;WE$@7_Cb@}j6 z@n8SoBt@O@bBzgff}yYtZ_4G=tkw?i)?*^d?^l$WL$axl%RKm3R8ju5gc6DBiOl9} z`N@n=rHYd(M2Q}S6UGm$9g3nXOiD_Hk=U%P(9h>?g}iEsq_gkUr6U>PNrS=_x@;cd zHImb1kheinR(TPT+yNcD0ea&%mkAxmO~pTn$dNJ6LXSq=c(e+4H!QVGy01N=5#MU+$$V)=?JcAgJ*cF~^8voyUC%>QJ-3G%=d6wOE`&6)F1bO>sj zddCl`EXb5VV^6s#xcT5Ca0z#PSFPkzMsYE5dHmuE+Y^dZS5j7X0Z6|uYs=B)6ZT;e z@^?R|^opV}?0+D-l8mjgC!?Qx16p1YdSN@a%e}W1*=~eK>jtAPlkEGoZ zmCyKPF`0<`P;8i2EPtaLxHv9+x$TI{-Et%77bVsOi(^>n_jRT8!u}{-i8jTh2DRBl zChy5g%5pQxP^fR%nF_Gi>*vs`lqJImqaQ<94xtjm%02IJ!X@E;MG0%Yhzu7py%&~e zwlYi@LnR0z725|5Z)A7U{aWA~P2bO&cHXcSjBk+!#Z3C-q7oStF9sKHpm|pj!EevD zCq5bZv*o_(P{MyjEb~0??wW+zz;n**=E{;VNLQUtpGBr+^6goL`E-jrN$bvYG#WZl zU&f70G&LoLgHaqw^5(B&;#Z_};piwa5AkM`S-84F$%3+$H_H*sAeVr2wbxU0nZCe~ z6~DU#(+!%jrVHzFDZ;Nb-tXqhIH=x}=ZZ1!#7x=}wQdXr(IQVTvwc;gIc*W#o%5Q% zXu_z!5@R9EXs)umDJAEcwXNkVb_Bq_=U0VwK=tXth5(3@(O@G4>+p}}03gzLf)c+2 z!h?YA9jfa;5dt8T!FM$wLhvfv-Ika99;(hU;9~fxOP@_6!pJ=(_mB?>F}rHFeaB-w z&(Bv_-+dBz-0Dn;Lq75dF;NCnq{ehLeGDvn~|M|Seh0HLRl^e$~AlA&!EvgnJmdkm^oPP#22bdEO9 z52T+s8gk0!>LzPee(L*Bh0&4x2pJELmeuGb*+io;CG=im-=Sbo4>gGX&Pu_zfcXe7 z{v=R@#bNcCz+|Km%rxuRNt)mvW}eg>anWf2SpqVPq^y{>DApG>=I;S*;H%*L=G{a9$uZ6l0hzJ4^q7wGW+| zRV^bfK|7Mm5bgDnz?QDmpXNm7r+_5|;8HLIe$AQ*4Vr6VdBg0_8np-^(iahu1@F|O ztZHL-1d1*GB^PH4x!NNm@x#p*eSe4}SFwaUPC>0U-9N#Z!gNCiU z61i)K-r2o)The53OGz{2Jv+(Bf=FqO^3Nu)nf!2hd7K*{ObRCuZ5ID6fz zY@+v)?ADpt)Prs;8vXBy`JT$L1n7*})w>qc=M7jc8rbH%Qkz7NjS*%=Qy1VXp2u5* z?kr6@H9XhXU?+YU`o}(HR%R2sK26dpB;T!1f;>_NrYz?KQWIi5^Iis>srX z$!&}3Z39*F3S79tI>(Dx*!y7h{R#UY;I2h`yVh@s)pB}2%Jyu;x_KC+IRpmtTQ85U zt3n}}`tJW6kjho@o#J+(8=)L;}X)E&Tqjjj;ayI-Ge+gMIJKr@n>aCm?E%48z;Jm(mWS{O>Usz7S%ON+N8V$ADWQ%C*Hr_9Tmzsr} zENNgZK!`AwK^Ju?j-)A{*g5@sI-L+BYpVd}7YjCj!r5~-$b0s9{}l^MF{ znI9th(vHz3l#Al($QCoOl^j!|%eV2=)xxD$FfuSX12|$)HC4yuf?1bzshibDqECA8 zX9MN9y=_SJ&D}|%Zb9&cRx#~Qx;5uN2~;j-f-ffr}yKP)KGu6#+wJ2nx!?b232f*CS_-F{_+NUjX_W ze#qMvRb)r%Aygv@65uat2QrlE%EfHD*I1)8z{vFqyPh zW9Mrn2NJU|NZ@e`3->$*l1{;mT)D~#S`5kiSS>xFjt%iUU$I+zstrV%aiJmm_~K&l z++l^*;xI|Hh#%^=Pj1iR&F{sR_vgw44xQDu^6lmMU6vOllc3h1M>FvG>9cF7Gy%Ih7R*; z-=)}|*FX$h%gkIA4Ph4IS8GWj5>Z7VLN*(3GoJ4Ymlnvi{W1g&AE2pfoY4c5*l-{t z99Yl4Qa z$p77+82h??X94jXld%C;2 z0<~@Z3oq7$6cT%50yLUR4*XU{rr>8k2PmG$V#cW82G4xgvtVrKK9(S0a<#gPU+{-> zVrb%pp_$6lD}~w^9CN4;6|>TT6Cil*S1!k2~n%NCv_^!YCQpRCdeG?q}XD z8@~_4ymux`og4pdS6-%pDiTCsTMu*@03=j2d+SHAn|)r{rT^(JNr)}0(u+wlOT);r zWO5L*4pT2h#cJ7FR`!u*j5Z@$qi(MOniPId6m`tUWJwwu-fd}#*9i6Q1{fR55D?W= z;W1&F5~fGQ%Se2t)F&snfXFbiED({SPVg>ae3EZiY2b8tc(OD+h(R0MBBbU#ac8%fw;#0ZqF_IzQ?nw{d7}@v0h9QWm2&G{oIFbMp+?Xw= zijc&&ujBjh3G-3TPkH2*Y<|v5kF8#=n^K@mdlh7G<~J^2WiTW1y0IZ{AwHGBGsu#mZM#>VZaE6r`UrU&G`fq7Ug1)p0VL)!cm2xLCJCNY`4JyYap z2^-4dbGydualhJYU_Vud`Z8!*Q9{CLl9DulI;OjuiJ8O=BCKu-o{zdo@T|o1^$JIt zzaNRYt{*o@+&{ z>2k&_pN9Mz-wvzVX#573vI>gf>fxCW`&kz7=>ntFias!>9vY^ZH6}kgm9C+U zqB;^gKUMkFa`rZwwfG@;T2+ z2M3GC-TdLIn`DDhF8xeWeG0%br*VPH4dRy@Agvo4_oeAwNGKszH~+?je$@^+f!0R? zgmtOivt;#ELsKmi7OHQR*Jy(mGV*3Gs%JW|!!@^{l27_(g7-75gLr1%$n%y*zuCa7rPueAV9 zCo?{B7s2gE-1&j0J3aAt^Z93hXS)}6!cE#z$KlYm{f#^ehp+8wihe9a0d_<1p_tvw zUzrd^mzU=Xy~*a*-+Z;DX3r!PPhjCoR;#z9?V!9`l%YA4a#nN+*}Px4S0UX4o8s;3_AJa<%F@38MpVRRFVV# z#6?EizpS>)#DgnCpQUg>Xpx#fG#BrFx!4+>Fsh~^xRo4kybMkUx+3I&O=A9PFkgq%pC9pWC{;yQ|R&0k)jeVoE{=yxe{8p>PGU#rhM+Cl!Jkm zanvE~iNYv*WVUxFAF1X_@ma88$NL?X` zpUn>*E57?mQ9(yP#+7AWuDLv>$l-V?ct;X+NfLC#GnQa@2lxJi(GJfMHYrh33=JXK zS>#|r#3pfxmoo~hFJtr>7D*trnVw2|?TP>B>xp?Y*ep_Oov5g)KjdPP;rD`fD2~u3 zB|ll30Y8P_rl&8Apk!U}47C%S5~~MGB<*oke&e2sLsLs)pJiR1Ok1zaOAjlQ z8S1~kI-Q-^9r2vlEV{Qg5GK8o$sD0=rwfl%ZPOsBL6b%{5__)hLUV zzYtj{aNxggTFA@F^%Er!`7DtEY7e&-wKOx2nc7AJV>DQ}NMrVrrR`Sy&&VT2H)vSk zG!34Ig)DJFGho6z$qYUAX>ivGlPdG{?K7DRx$zSJdZ|b%nNghkw z6_9II^DgRH`?NqCMF*$)n2mmwp(+E#`9)RF?kb_we?*g?^t;DeMFdg&S+2iiv6!S5 z>iA}yx?{LhO@hUX22u}N*0=eMPp(hq#7?Y(FE_q##ZDd8R|m%4!>G6f69R|XXKQrt zf-TXn%D<~v$AY|9h>%D8LaTAE?_a^ET@VAl*yBGZ{-YRhBQXo3nXTcAU6emWj^5Rw zsD4nj^@9H(^Qh`mOGxBmWPFvq8g16Abo38%qlJ;HHTzqzqVczfyaOX*8|tV^?Nak^ z#o>?CF%mUjW)*xl5=;N8{mkgspe~zyR*^n4VR_sh0`*Mr_NRuk-_@D3@J@mpmH*-C zIOgV2a8$ zn)lr>nm=keP-9C0r7ndr(PhY8^RZEc{qTaBND%&|G=2{uR;!j(hP@r+OLKR0xgDpY zu3>@N7>#yR_J%qOQRH&ESC2)BOeEQkJTGm%D&8ZSf*FVBUP7mTQ~TBemg%|VL(ilL zgdQTxr^sy(n>%|oD`erX)vI*`ua=`pIhxz1G!@%8uk;Pt+E z9X{VN?Xm5|U{m^xj-l%O7reiJoEe6#6xRP>Xt#ye`ktxf-RGCK-263gMgn_L#`n`P z6&2wQu>|BzJ5;lfIE|7t{;x}KdDPQS z{VYxW5szsdW>f}5cLmvj8=+$P zgSrA*oPJB1{Jl$rC9n78s1h(?`ZF=+VlA(}32v0`f2O9*Vo6@kp7|=vh9VFifOk->7;meo+N_lLLcLx~D(rWg+NA8qsx!jTJ zUQ#@H1rrXVPW%@~xOdn(Z8uPm9{*q}<)`WEU)fRuPF4;8(^f+cg{}cC(DlvzK!0l9 z9VPk%EP4%xMNY5*M@Z?qu*W}mxrKwL((u#WN&ly(iD^_$5AahSBsSU+O?h6X88}&c zD1_He#<}$n%#{<0Oma|h->P=FmF+TXm;aQ-FL(Hv=EY$orM3$80MHO zPp(zNk=p9XV>gAR7!ZST06SdRQ&6 zTK`ipG?+XvI&1kodNA+40R@no6p_366Oa%tTQQ-hB69St>&gXmk>cgx;;%4d9X06Z znbwe|-b4}xZ8ldyNgjHQEA@y+PRepIL#_>RP$xVMtJ7j0#cu?v=wr;bV?Wf`Fi$7@ znQHRpcqM69DmNN-oCj7y#ssR0$EM^|ojF=JEK9X$7{ZjZ^lYd+w1Z+lgxm(Hh@NSJ z`{vupu&@Gt%2k^4btTD%=VyL7KxPtucPTD@lIfQoUQ$6?FRVw?uL73nB-c zw^8KGmgHL=Khy9(Y&d4CQ+RNXa!b{RdBnp*dB?z}iT_w)4?8@KK#o+U zHZoKAGC67Swjub$yY05+AP_{%OlSf75_oY{f_C_Wqm$x$ zHn=KWrj=Vt{j1G8ZqPKtdqb0x_IyzbVr}f$?`NCQ-N*Y+5<@8G9di^j@l%1Zj5I}? zT<=+R>MtK<O5kUB+Bmv8jfJ;u{J%MqxL{#oH}wQ70Os4Agl#%22N%kj{yHN+@vm(_F8mE-$w**j{X7HX??bF)5YKbZiBIIaeQ2 zR<-e_S0&=9X~DTyr4$}I*jDa5D|#~~e<_S)bj^Olo;KLYqA;Sb(d%oo<$iv?zmZXD zLa#Jf!cnjGx!fyBse=OzKN2r-)Uqhsb20;5fggK80wtQ-gm5Ztw^g7vh4d~jf|t&dY85jg_h@2KTOwn<;Ekt@hVN*;`94V z?-1!Gbj$-`N!QfD5tvpUa5^K{$Lbxf6$s7yB()VMijc_NYblKqdBuAn! zYbzH1WIPhCz-rGA9#@Qe`1c86%X8Ue1!60L&zvhlo5Tpo>EX z%6uuAB;H?F)F2zN#C=XpuQR(K|4mhWp4}`)-A{o}gM9n5wLgm$qE7Fn9i1|pF~8X5 zN@oztnA}tj^s~X}SZ`kqEh{3IrXUfiWriiy+9MuZ;Qj6EnH?t&b`9rB62#GrEUs^D zIC3FUUB86|>z+Je|I42c@!fp^5%IqeXW0V1T-m=e9x$J(YAXjw{BP|cczZjM8?k;3 zY6D|rDAU=LRYdLSbH%i336k?UZ#D!dUfJ)@>N~_)Di!K+S6eWNW_;@a60q{I>D67M)HCwC z7Y*qOmrtH3{%fJ{JKtrShRa4UdH74=$0>);w(gLuH+@f3kPUM~SX_+UwIO(Pa zqIUte?S1bN>GeOvue>$qDVx!iR0W&qS2FzRfhtB4Np{Lcb@uCO-rn?Ie!Sx=EpraQ zqg$9~L$G=X6O@@el)9eGa=-P3L3f9PkmcB0CDjwm%;3Gh^I`*6e!WxwPF46`7UA}y2j+oD3FL%32Vx6>$}#q%u5(*#M&h2is+p+#lGrm?cX z1}6mQLZ_x&5H!ImrfGcWw3M#@-R5~8E3XvuM~?s{YrCBEtgOQ2W0heX%h!mj4SP{~ zZEdk9LLAcN?;Zc%sXDh=c&fR7ue8NXrrr2mfq{vO`dOT?N6-|rDdjEf)ysvFNhd;u zgxKabZFw>(Nh3)@8mve!y|KFdk!f@+(b0?cYQEr~Q}Qv^o!&iiMhP?pCU;7lt*>Hf z<(?{vr!S7QdRr zBER@BH8*aV4VY!x((2JlnPFID<8r|}UatJ15+4~;6g#SCEsbQyvfQJTiUvEih}K2MVOlCYj#ywi7cS;#2o&Qccru+VT- zEVhuqSsxc2^6jrSB+i|3H;z`R^L=d{CBDyB`N9D(o06?Ds9b%Rsr38vD01b$0!S_A zYu#uUn7o1tr}3GDiD;Cv9pVJdfY_3RnBSGTbpb19HRhs;@=vy zn)CjjA(a7p2ZE3D8qQuOrKy8iA8D?724D(>K6YLS<_(x)(c4_CA-UXD^61hQ?jEt_=kO{s zUQ4<4eyK=x2Zy_ z! zYjWa4s^|V}fbn66m|$jA@;ONXr;0CGwuG!$0i#ZwB+#lAY)pQH<+xpoQ3nt7{U?gO zl5y>~c=V-3J^FHUcLWiiKTM=KQNu5#P$AW2d(Xmgt>eXU+r53@K#ti=qjeD}95Ri# zc$+$R@y6{FcV%ZrhK-8NtLT}<-+wzk+OGQSdc104`)&AI5t1R#I7g+rD``e^X)D3z zMd41=DK??YOkRb$)HTm&X;w{|&zq~`u-+VMXr@x-Rp1=IjWQ}T_8)v3nE&g%#VDj} z%FsEiE+Q14-tNn61E`NBEq2ZxRR#!o_EPE5EB#2;lGP6F{Huz(*b8RYIUos)eX90xE1{=2#mjD_NSROy;t$%#l^o-_BcgH zn)u`#AnDZFC8%98Y?xVvphx-&^Pu6qpMAhJcwJ{EtB#MKWOASaZm7sk^Ko~Ul|9X<^z9_sdRw7@l`H%*s2bFoW_|t-aZ#y~K|m+n2QHm6i+cvM zU#|iT3^G31Yhx)4XV01K!lmRJN1W0!xbfsR^_h2~hYnGh)S&Bn`Tv9?zw%OSC$(wO z8|#gi#*Md(VR>)B{Gro@?`D9>cl*MyXu`7E)DitFsWQ3I`5Gkw4|CqjN>e_F1am4! zV_e=)GG?fwY5BVXsuqId#DfMPLaOpO5k`9Kp1u}VIA34>T~pTC*@#W>+As8up7$qS zrbB-&$NSujR0&I{5P8i}ZFc7q*>Z^Z#9}y=nh28+nqP*;(1cr`JcX?!c1(U;vV|B+WTeqTD-BL-ev)(L~?JjrI@Hy=|IuL(!>M1CD8>&T7U zI&N7p*tETTOs*a=SA4I6DEH0uSNY*?wzIyipd1b&79|W@!3KYX+lg?>!VY`g)Zjmd zNQ{=@1zighy*Vd4142q2irT#P-FLUGf<8mfn*;#JZTvx`wNfOtrmxuE|vm64>Tx+e{GZ7+aH}Cb9ufwFSEpq2s=;WwGy=I zjpm?FijgY@24ih+(ocq^7sZWP!0&OAs0<~w*z)Moof6KS=GwX>(Q+8z{-T=Bdf}ac zdFb=tbC~(f#M(R5yrwfUnE{CRD3H3Ni{qQ3Y?zuXqeRiZ<4#XR)zl{UO}eMd^ToUn({F?){$2jCGtX8tBxKKc+fe z;J4%lf9>sXxJY_%=BpWVUa-GtwSUP-8KH)}$th<8N4-l9wf3#Rl%HGFQgk z&mpKVT)3uu4?B)GViukIZ6{NE@E~6!amdG&xH*~Z^G?%SJQQl} zgttz242q+5vg!#=r-Xp`9-@R1rN`D++!N-(unMil@u51csH+TEH?i<-O+Z6D#_7x(!>%*mr$a-M^5^}`5ACiC2~e6( z-(2(6)NPgHBK*X)onc-%I@8_Gl-sJg$OXquo=^)$%mPUYl|@q|joooa`koQ`F~0)` z&-HY>!=(W9TJxzsrD)_>)87a+xuu6b3JY7W5a|X4+6L*9$cJ!!m{MoagAv;fFhX~! z_>?Nz!i9 zjA32tPt$BH!q*h5X?oJ;O=GL9c%?Sn*~2l)DHv~0l&)l}g4JB9pwAQuD+l0&JEqMH zg#k<&*qfol($l4mda%`tFuN$BHnPtZl%$)XY7J^mzxTv}9%Eh|%SJz?BhO=atEkbt}MXg_X< zU!cgnuJmqPahaxojqH8VAe35Y{ZnYdUknFoZohMYOkm7YUxIAY{-w!9mI4xff#|PUj>YXCKGOU^X%kzK zYmePfE907P@#ngQ8XViyYB%~OCBIU#=tuK+><~CZlP{MuhpcoVU2(DyeKXxtiMW2g zguQK52X|3rBR{$Oe`N5w*NQcHV;g(=Cg1Uox3Wq2Rqjs-#@eh$RJQ7UkPIk;Rh|9&mQjDZQztd*0dx+z23FUDp`zq0^!L zg5SVTXkJ)jtf!)QU(7~jN}v{r>}qHuBMme8nS@wIqLH#IOn`@qHPF$9WvC_QCU|~`x9;_n5hBfIADi1A{3dGhfS|01FEj{Yl zJPJq+8P~3v%*GP0&wDHavIeVyIPYfJg@mG@3o;8+NeWU0u4j6w(lkXvLZf>O#-SH4 zmY|D$^SMq#&6C=T68m%9*&MWz^)Im8e;>`W)umY^Eyc|534a9XH~q{q=x_iEl z|L(HCZ_ws{f_6nT7UOsR-Q;eR_-JVLn6JxI$LeLVMWd_iy^jF7=r9E|bB?|ckS7B7 z<5-f=x5$dJZ-ssAZ{K?R$bVmOh4X7|l~h$Mo+4Am2=cTt8hPD}@pMVXe3bUbaZC?0*=4-snG~+@0tAFgqcrx-cd@{^>;|=l2Efm57KLdNd-b zR{jx_?0a~DlSh7UN3N0I=q_(OFcnXVzqypC%PXquerw!<^M6=&=q*D|V8CKGdB$S+ zpuh6byIEOgBHc_9r&nzcp6&hCe2=3Q8e)~7z5^IG8Gn^P^9yQz+D}biY>zsh%+G2? z`z=;cPeN4JaCS_$=|aPD2?t)1R`Y`&ByWq7?KLp(h(mWbLjJz+zrAhWCSkcDf(olV z{+Vs9n==g9j`SeOu=01$3tH{0&-6h41)qaY95k%>Mk>Rw7^`hZ?RbxBoSEZ|JNw@O z9@z1!wAmoLb24#PPRv1r?A}^K5t~{>HRVjw{gl+ea9U*QV3iNU`y*b|NhgDgVD}%p z#`w`T??gGC9BEObe|RiW{B8=s*=gG<)~ffW3Zte@x2vsoQ>?6E4`!4XYOT#6%A+l) zZx3_NH)`OflN8mwVJ<%kOmc=2{Isf;BX_PK9R-$Qi#H=AzA-;$BvW3?c6I#L#Li9X zip~nAh=*WRoG@`~JWIU~eU~hc788nS?yeuJCmgnO>j`zhw~D8iYd+(Q$XE?tP<1x; zt2&H27kb%a6ozwhhqN&!)Ri%`(mkGmX{kh%==y0N@(b{?>>Q@Kmqdtst zaLQL`Ny~rL93U%*ienb>*gAXLD){g8+T&k$zcF$m(+P+$YmAw#m7UQSXx+cMm;r zTQ`i(Lj(;PV{?|N&xHiX`q5qnvQo+=*ls5FIH^_g00Et(YQuQy^(Vt-_oMX{pOY;B zJ2wUch;p6szRT$(#J!X_hRwmSR|)f{1qBCdyu|jK2_ zw$7v>Mf%xWFqUWG?t>3zy$f?Hc-ji{84^k-W>&d9(J9Di*ELSv_~#)QMz|D2iE?yA zG#_8>D=w5Cz4$P!klK;)Mcg zOwgAf%VfK*VDtK~$i8sv;nJk5M_lQ?_ln%mxcu?GexSOO_)A-gvx_Pg+usMYw3h3o z0pF0{9cm9yBj;9$hFf;X2D;1(r!p}c_vpUO7mFY7BLv(8+eKjk!M?e{2N{BVAiQ_S zmvD|2iKt(Xo6K3G6MKUfuAfVugXL012UCiSJ|e;d6c2+SZn9LPj5Cu-&%=okHK$I!1n_KR$vHMfuKX|`sX#EK-dM#6Y>YWeMg z9aXxF?iB>)St-wi!t7#2dP-6HzjA(EO@Ei~%6_4e3<-1 z=>sZGH2a;#%%?A3XEOQrlZJM+tH5?sdlpvny#{AJ~d=4-jlCn%u7V`Y%4L`Xp@$HFEm$!DdSD*5)ZcUVUjam$mWbnTP@& z{@gzo4aAdq%3XcNHzDNyZIZbG@MA+{g`^O1!gvWeDU5zeh?CEU|0KhKRx%nP5cSAC zOu1Mhe*s9Z0N2rSIuod~)_DssgKf3yR~D*Fnvny)0JJ6tkMEHNVLzpuB9>H-6Jr;v z>ESr;QoX}YM{bb%&USbnZcIdnmB^#u>h0_ZkjZ2G)Vn9vu;Yzyd-6|U%^`aAU1$sW zwfPWd5e+TM-$Yj(kbu13OG4wc?Y1QVx9UWz@hgd5NS#3Gr^toG@k4RDvF}noFZ9Fu zHlPS>4pJfh<2FXHRU~zBuMh)0{7Reu-JK5@FUj;)2nir`OI@xdR{$Hbw6wJ6X1t76 zwQ0mgBlF|qfw=RF<)VJMCasqpVPbN`@tB{Wu`_JxATS44(+=OZn)w%4V+7f=;AowWY5 znvd@8PKLDkzBTyudc7z(px+5d7J8k(er*$mH$6zDM1-DTz9NDK+$jJ1kd9p#h``Ys z+}}_(*=pL*;^UX(^hT5`>s^#iR-2F_8(*}w?~32lOVwkJO&pTIsPXAn5PTkCx!AmZ zN`J{>+dH%~pc#GIF~h$!Fns6!$T1vh!^1x|hT&5?t0Ql<^%!*}pQ89FLp+XBN5)C9 z8Jt`2ypW)idn^U2;G`SARA0*sufin6!@fweTBo_WSzJz4L?@c3_&21PZ@#3UmRAKu z$3Aj=@IT2OO!d}kGpCSo5KjK{i9oB`ma11RJutHv#5tc59iTg`ClP95$h^DSXB2aR zWa*Op8LzO5KJrXi9upMvv&RVT7{l2!WDlPp-iu~PTk!}H|Eks)xO3YSVEIKYSGHMQ zXSYxr3~)#0-Yx4DCdcQ!h~ur0sM5+?=HC5E(ogv-w9?$!H<70(c{GD5jV4ApYub!o zIu7BFmNRF%X3Wn84|yx~gn4Xb3-*B3>odXFT0R&3i}A6ohmbbgw+8w$b}I6PgN~u~ z(sS_aSKlYa*S5|*{h_=_e6<%|s7JoUd%Vb%THR}t`C2|*c#OKu>AtYApgKZvevOri z@E}yDabtU1ma&I5vA*jTSwCNzBk3?_hltKC1}FWol@IhBcuKP2m@Z?q<%jTcq=nGb zzQhbse(mW&&|19@&Am$hXjyLhD=cZ2ao+J3`TYC#^Fy&a9eyx{EJnmZxZ>G;{w0Dw zOX=~6R0eW68RVtAtzR&aE{WKGuU0!*F4t0h=&n)Mz4;`F94U>kzD9;GG2ze96+~Li zl?CT^v24>OdGC_oaSDEG9C z1RHg1LUHhx9?8dqeQ`dkps;8Tu#}*8d8V%=ce4(|bfajeojJtSu+w!NA7Zpw{52&BSx$oXDAh4<;m8<_kyf?%* zCW8lcoO7e%s;EeaF-Q*b)A9)9Udfy3V=%x3Jjs|Cz+xy?E1&5BEIja;<~67~0}NRw7mrNY^;8s)6UPH#0Yd36;3r7I~F?2T=8UjgGzYA;;Rh*5j z(CkG;??+6;Ol)a5lH#`i-P14fCTfUXDC5=_P8EZt@S@sAikkO>(YAHsT9H8qUY@`$ktrdT ztMYkp9322|**OJ!5<00E4gHgzPbp%->RrBUX1yrWe*NyC(r}mR-}Y=|wk)p^Lk*+v zUGv|g8Jjtxval57T#S$t@8RL$aohUv4N8eiBD#3UFsU0E6@-;S^a6bd=*M@D4oq^| zv(*|E8`atSf-8bLaKl4YCCiqJbjsPe_y#vGv0}Wl#)ZEpQW|-C^P`w2d&^_~lvtUEzl^l9=pcHCHy>iiUEW?y}1%5iesbW*4%(4M4OD>AMwaFD$UuK zO)Ewf`b^DeF+|&<*b;MayXi~8yt}uTTVF2@+;Gl~;>_7YaGCmZZ2nq5Rc+k%iH|H)0cqR`7+CN@DiD%W@Bs&i}We2gFQJlMbb__JznLq&0k_C9Y7K zzHm8O_&FIFA0Hpm=K9tkMD1%qF0KK4G*%Y_Hd1W{lTJA`W+Gsue*eTeMi`Ai(8UFGh&?yRi$!hMG@|)PP%pJEMgq z18*eSJX54m$sr)neQ2Ak+$@FLdm;W6h26ZLvkf4u^xS~yitjpRr>m0j@{_;YY{2u$ z^GjBQtuq3ii|LvV*QjVH6#A*8$R!#!K4ashXZsq*sCU^JIQBq4Nbm z4TAI|-TysdN^|d4^@OeuUA}oQ!h(%t100?wC*li}mC;pr9pl`KM{aH?%gv_-$~JmV zNrQVXT8GtDYK_6O8S;&a%-Q+H_2Mvf>Ye)qn3|0eZYb#gI5QUZ3B}L> zjz^)~fC32^jme|ox@RUXi5$@wfv5cEgr%e9A^M!Y2a)0Z;vDuJ2D9wZd{vMh8Csjd zswl~1;-gS9abSmSbf^rE1a2tEu}a`2L!cP{rQ@jO;T!L)O*xsopw;IjNJxWX?moEX z+~XvR(Q8>KilkQWYnbUa_w!66#b-;l9|@0eJb@Pin;}TyBt#Eki-?rVOJj{xk#D|L zt7uoXJI!M857SZE0^Bk9f5FQ*ch2qm`gDT3m~O)uCfKvYiO)TC3_VT1sT`#UtuEouI}>zU^&u(1y8! zwu|#x|C^+w6Fd@_M(I^tw(n$}?6>}N{?@NJGo1Kd3*3en-n@D`90L-P)PIgnE^QfC zmrn#`6Y)f$p`p93{3ZT=;05x)%)|sv0gNw-n{2Hn96U{vr{Zk&;)Q^x?Vc|cHZ1P4tywJMe_c`2TWoD39OdO|@c z83}MTZME9Xb6Ng$mFt)Hu}Mg53T6Xvx5&BwUaG&5&}YPTst4cEZ@)}Ne(S~Plq(l6 z7h%>$V47itrjrkoB22oWFGhb1b{*Ino~O!YP+@+*w|69g%74k*iiPwF2=>5}=_>-* zptAi{kxXWBWu&6=VeZ8ed00p8ZwfI`V@Sv&j2FwXjVv=PQF>IvcbaI1KiOQj9t)*b znJg){Id5nJg=jnd!I47%k4(8%=gmB?MYfOX8Nsvf)Sgu~d2o&jV~(phy6eEs1$8nR z8;W1fUrH8O=OeueFOAIJgeJ4vTN2N=l1I`EREi|ZPsedRxzA2+md+va6h zIJk2GlyhXOtz*uOEqoo?ZAB)gLtnf?CFB1DxakmyPFZrIAZeCy2yrQuYXBt~dPwdk zm^+gtHBFIp`_olsY<5;w<1>?k&)a_;HIqZ5eN`j40CjTs^D-HByu#M;q`)M+wY4?a z$Q4gCkI5A(nt)rUSv*6oyna|vQp;_BD8AOzN4DT;+6dk^ps(+a1A^+@ak$z)yjtf$ z8X2reR&_c+PSRZyX_7}vDR0dGH`h+k8pw9U_(x|-6Mt*H49w|<5WV@oCviF8`4KRd zCqBZ)-Sz#CcZ7dTUi?m+dOqew1w<|M&>Oy3fcX4-xU7KD&zYf=M@kBz2zIqiT>A96 zu_DTq2-KU`dXa@lV#4A!HEh^#y#gWHhJ_djJz8||++#}f@%dsz6pLBhS&)VC#d7L? zl6pKcN;JV!^fsD3_^)*y<0*4A6_E9{N>n03nn-g0LqCzeo##InZ~X=h-RfNT5c{mXlr?jm=*W3MK4!j#GqIU586Al2g_K=vM-#Ql3l_N1G& zK&Ko?(9OT2hhUWlue#|G&TURnIR!@4ARgVzjYslEhGR;7!$qvq=)3vA;HKJG@8Csa zOYFJ5Aj5Z2s{pD7X4z%mi@BSa)f=Y2M@#*Y?-{~3ZrI5r%^8@2JFW;(iFv_xlaUCo z(@lt+0V_N)m^Ctd!+oxH#@pNril~t?+3BWllbr*5%g8=6;t@rjXt#R{vt1cf|64?d zW?3iTx=56yQ7d2QyWM`U=j$1a7GgP#|JJY3 z(Cunr%r9kS1u5XVK48er!G|Dgv=nXgBIJ3?O*&`I+-MElWKplsF$!3%S0z1|c=Bk) z3smLgcs7@uzVBp3M=wWmH|Djm0K?FaDKV{!&yv>awrvnh4sK@G^BX?Q%H-GW#RH#a zH^az|+@rknrOOs55#Xj=VZp4spbk<^p-9WK($KFqxtzT&)tJ9dOEbptq zzT42?T;z!fy9js+;@WDzy^+hUKlPU3_tUY-7)%s3 z5>YUV3JqNvxBXc%YYmuR_%Wdovp=lKFTQYW$n4<`wjJR2^j`ZB_M>kb{?(g`erGTJ3P`^JUqRad@TLE?ofvXFw=2-`{doTG{+dLTAN5Llgm?EXq7G&m z<;6?+iO>q1IH5t^`eRz8k%q#lT!S*ztV}a+@6fXwQ2siiORVf%nCq-A@dS+rJo6zH2#6zY^K6+iP8Gcx^_H8B#7`x#S>05Is zY$UxhKlX8HH+(4K(XRvaAjkWoRWis%Zy&h!Y`*S?+f@jTp-X@$AjL2CqtA$}sJrDF znXo-8>$;}19}$=W{OtKJtomPCaU1QAqDrG|@-stChDBZ4WJa&g9=^qYYL@mh_l=LX zU37wnrgmQlCQX8^k`HkO4;o!nXmEu53O5^{5wEeFVxgY)uEMRMK{7xTGKXz65b`>H zt~+Qd9$ke8Mhgq5S05=vuB)eqQU`CV@U=-MnZAT^eP&+VbD#DqzA!%LFU~RO0V&Z~ zMOH0^5l(+{Lq*k}ILMzraxW@OW|!Rbo!cDZ2ZBK_4D6O-!iKB_p62SNEj6Gab`x+v zT03&^c~d2CDRUIkwpp3sy?VdWKbc$D^1LI`Q52JTyCHIaVH4GBJQnM1N0>h0U%X7M z8VPy?>OPwJS}V*}urZs@$)KhaC6~f!RXo8fFLx@&`W&$RvEOy02uf~H^=CDNObmU} zavC;UsyL>|!3WxNZoFRc!OO`__byY5LSWsEu-Ql+UfP`HM_=shd*Lgo#L0mR-EwXKjTvF<9|!NYNO9zZ&^W+z z-^rtj(Ma?z6B`{lBWOP(ccYp2K7#Vt4sb!@t5 zsdwRnjU;PSEmqt7sB`eds?;eF_ifC zn8r74KD3HBS_?0OoOO3 z(z`XKarEsHWvJ0*QKm!NLK&C!Z#UqYba@tf+iLo6B{;}Wp2;xBgH{T#3jhlZ`r(G2 z_)*r5*<$E=ybQ58e}a2)j6A1&Az#p6f&$r>i`)H(wbO=?JuaiSlL7KyY`gHM($ISXC2;)J8ltF6wKJGGHySgFn7Gu z+sO_Pt~hYqw<=!jlh&J#p<=6ZJNO8cpC`9{C3RE3#J_#Y8%MHr%y0Y-6Exu8Ca{d+ zr_HhpCRKV#=~{%ITv1z1Tv|2G@3Ts}qsH37*6-<)DnM+0*Yn~Wl9st$2Jn$&@PC}AlDS?v;~9?^;_`nF zmt+!X^~OxBodc!w?FWzGl6wj$T{tW`+O0Vu=m?0vRst3!BXyGo72gzY%%7UZQ*jI) zif(CrRJBpId9q3Ius&uvs}2V~#Zg`WOTep0p#aZXL&Z>?LtBb+|7jKcGD#S31mqr; zeY@a=`6#$LPMQhGu?lKk(qZ3dcCSZ(~pdbir)oWJKB>tf(W!l?d$+x zuXOeIb^Fm$QmNQ#RkcXTLNtzGNdmPHFH7qfidI__WeWX5A_n=6Yr+kQsbj!*9V!~h z9KeaDT=HaExE}B8B8v_zBlcQj%NsYH9T}OyzDsyYod&)AJP5-qR7-b;4NqTQ{zw}A zbYb|hlE?FSVTTqwl2kG1x4j$k96f}ox@1CUO*TH=Geh=Wl!kVY3}&D0v|(43br%-d z59hmM+7g1$OlNI){hkS@Z->HgB|P|qb;hrTQdlUW$upfwMjrFIA|R_&U%<2Tt;hFj zTdMx=v*ohuloEhrtXx%iOw7%V0T06SN?ThS2^gnBs?#!c+#vgU@5inkgF%Gcl)bK` z0Aym(@iw8M3`?DV@EFFJ7s@Q2LAK0ox^R>4M&LK)xX^3~6<5)@P;psxNAtpyAZuMM zh&sUSnf4F@d?=_5`uyOaoCb*tGH916km2s%jQHfgQWa=&-?P(XL|QBMzD#;P2i{k?s>)3UP2kYBFzl1=DWyU2f@TNIo( zZOUC#S|a_3D$eg7ylGkz+5tge6wjML*vqNSS+HF5BF-Z1xEA96Zs_osMk+LlWTnWE zsO8YOd9J`iSC|gXD4N&X31DZ>FHQ@Yv4 z*4`Q7RsT^oK$bqqScUWUv|o>zWkmNOj&CmyfXWia`ci-3igdL-Jn3vbeKVuAA4nP z(HZdKWlYC(;+;y7Z?yq3<`8kl7LF#%mAu!NxG-8uBGi))RXkF!c&edAqtfZH>54Y1 zg<7vAmBmmwSIgAXGgy*AzIRgh`N)Pi;9O2{wH_t8(Ofm@^#OhWo6-9WbEV;Jiw3nW z#~)bw_WF6UJgol}sD{fMWo!;F3rVoq)kxFN@t|z@n)S=^v?q)GL-%@?`L4>1U&_-WsEYkv3oj`!eujaHTME5p`3 zhT^NsOTz1XgR(n=ZmSc$*~}m3YPeJ^^$~xVcsN0#lZF3C%=j3(ev% zN{S`|hG6)Zn2G8)EPH9&dZc!VTlmUY`n3!~(`EyWoU{#!{eh5MXhns^9dgJ#yz8vBKx!mOnFwheyxbu3KZ# z{C9)i`gs{n{Mxx_fI8LrpP$iq6V36tw8=Z(|2;Zftcy~svdp9nqvdYX=!>osNS#X2 z`_6@z5xmPiwn(ly>7+E3SW)BX$id@oYm)42&=j76wbrLV&t3aq}+Gy z=D(rxTQUrG8@yzZ*tX>}j5O{cMnXYI?a0($k(BJvkXTq-4uX9IKWg^{$qQ zoLV@f3n3~P`;2o{Ep?`{Ko{})4|DdhJcvi6g*HNpL_S=3KQe7#-t&2`{a3e7xMbk@IXCs6!JF%ojJk^(FqXW2^9H6) z4}7LY)HHKV6+Va^cJ<2;*Jx8>JHnrdywq}Pll*w!S%Qc0nc|&DM6HrvpPEZqKu>gOkc`dmZmrm$P$=iLL9B}m73`5to5?)%ELBhH|bj5 z1tVe9X3z|h1Xlf;&DIczc+i&L{td(L=6;*DE~1>H%c<*0r~{vN#`Q)iL1 z*jjPPa^Zw5nC-8tZK!D|w|siJ&#!)Yx&HAhQ3XCdxFszGimBK%PCyNNqV+bKNp4W&_^|X?tGJb7YF0-(YKC^mL_eSBK7QcJx4d1k+zg! z$|va+xNwSJ8pMW)C?R$^O*$K#!{fg>U{oc;D^qU6MqrVo&6%iL&^0{FX#sVk?xvuC z&-!_`E04jM!HQhbu=_9+8<7`>1N95lX#T}9CRj5*)bM|@ZHm&yb3utiLK2dHOK@6j zmQ=N0L;~*T05dQ#w`Ah7!l|?Cr5Bt!bj2RPFo6DDk)i#fwb2BhNq&?|u=9jjqvsfuaqu@qzh!RtlD?pAGx%9r zOpIpUaVpiG-^koM^yK#w5jAxmjyE1;;I1pR?F)KfqOxFwTJC_zs_z9s*z45G$C5ef z2y$c!y}7O1oqE->8OLDCNTu#%B#JIlaWZz{?01x|-7U##+@Cr@t|Tv-T5QYlA6sZK z?c|xG{+KVW(V{y|Yc}O_e66hE>U%ZWd*OnvOwLao+&9#si~crb2>e8mAs9G@zKC@? z%Y7{AB4tUXha^iLe=dhP9sG8D!Z*GEL$Lt>2jU!59KvFcJjhu?n^I6MDaAG0DJpU@{jt= zp-Bm_bSq|`WwU=ZDsbp3!!^YiV9BJep8oOJ+Mq1Lbd}9B&1E@ZP&2&g!r?t`*Z@w5 zLUnql=f~?Eztwi*CmUkVQ!;+Be)Rstf!7=afsK>DqCLuuEVz*h%DVR5)kD91ua*8P zv__uRv{tZy(q)Y+Nlo~z#c4OK#Lu)X|q8otvz>11NBWX zu7XE!H5MG0Txm8aTX4$#aUBAar1}{#d67YKI6wB_!2$iLLE=qZ_}QR_x{xg|c~WfN zLSEj{Lk(Ww>eCQZ${3mptL;2zuHZD#gbJNn#SjU}7ZnvZ?4xM1v9gLbFT+uaXUZ1w zBKWW0uRaTJn3#ZhL?VGhOFWD3pSN#Yzx}&~BKVCn%4o75P-m>)k8u=tf%kQ#hrY)J zm{t6vo$VbE{GiUIW+z90ld$|C$C*xq}=ia-Z()$}fo@@%kv)w3Tq(@5WbcD5>N*(u|HM)B4U z_B?eEN?;Evl+%Zce_1@*_4dnFYQIdTo`nSjhCb@nPfjf6!Q^l-`u11UP`4G{co&g1GA4>Y4@}eOf-;Ho(5PV`S?eL2zBaY?`%;`lq zp6V=Xl-ZwByr|RWXt~g&>h^IZXdK1xokBPhx{#~js)GV=Glp9@P5hAhf44(=E(8fR z@#}KryhZaZxihg8q$(P>@wd%)1~SC=#;xl|Z)OZ1=eJ=nI&g;z-2Ooe7?8rzuN@z1 z{C5PFP!u)l{5(Vk+wTv8XYhq;5fc*=^)HX@>Q|w!s*7w*L%Lj+qwkI5Xv|*fnx#g) zTzJW}QG#Ul$#j-RE^63{XgA{x+^sJJpyu|ksG$do(Uo3orLukf{d|B*z;`vB2=?`L zqhm$yWY>dPkyg2d*+zHTPrbm;r^Vi|`Fz|(_~HuuSwTE`p&H%e70U2ilz`noVX(P< zaA`)dM1Gj=i#ye^Vrp^fUoZ&Nf@MEjV#Hb`}!~YB?;B0fDQ5!#oA9})a=}f44 zHB;%I-1#Kd=58it``l9U&IdnHjOGtyn(A|QzHR@em(rrcw&l6c7re((TYt*_0iL%IIG zrtW|HpB~Yx>!$kLP41`=sTCF?+;Y-t zKC2PDYKW|&ckCEpWoexIYtw7}%9+@Lf-;;py0J)l9F75{shp+E-OZZREUYGkQPgnK zr{`o@ZS|`gyG_c+#Kvco0`hGi0aLCYb^~KH*&l~00LVJve5F`7{g@B)03ds?rcw~Y!CC(DPOK}>o-T`j4q)8F9J74yXEu_vTo z$ADr;qFugQ$@&J``^M?8GuLNHu90XKv+Ky3dm5jMXL~bbT-=up-uQ(srBP6+q7U$o zrVtn@4WCXeF8r8v08$6e~3m_cwDR{%%V78@F)`Qxg+;N|cyppa zwoI9AT;utkFwSnl zxd(ix;p5jQ1yefoQI-N|%4+^oKg9^-&CF=Eh;7y1=*LzbTCmIiXhUnmX%S&w8yZig%Cb~SsBCwgYjj;!vC{UrN6|<%B_F4~ zg5Ny(O!cH4Axf}3Yju$)p;2Kw1%WbsI>4aW>c=r|u*TBSnNH0<#7EhP47_=6ye{cZ zrMdL)JeC+!>uW z(0VwWM`agNX6vXV`*Xf0);jJ@qGpa1{TpulV z4AC&aT&TjkOHD*W9dN$jWWwj2wE+C2U*z7Yp}bM=GR+0ZpYE*UB|dQnoJKGF{@qh1 zaarMQ@JVEJk74>1k}(dNNtgwoWrL%_4Ek~Zbbq3VufR?cDQG-iueQu#U4&rXmRYhB{7-d|Zu)p!Z2SwHN@C*n;{DU?{hH^Z3s0B%gkn`=Sdn79>Aq8- zmYvv(qS^iRK>`x`?*u|8>|_21w9f>O0eD9qRNe@y7_ibbwtXVQC?8~umm1r3eOCybp=F}W@UzQ=X`c4-FtMOpUwZ-L37Nf%R8VZJdd}xKSxC?> zwRi4;MrmQs2eN1Bz=;2xr;s>dT`2aM{qf?LfA33(Z+@OUO8A668Nb#E14!}zrVlFt?(l2HBtz`n8aT5z7aKOb)X1By0Xt@82-p)AF?MPomu%Dx&evK zVWw#{NnIa|5w}K53m?N`FA)1Os;eA69Yaj0?Lt!-TrRg+JUEumWGqjo^>!{=o85F3 z3-smVz_AKCSxzZNv1a0;*l>eT15$J{VRcPjH}{WQGM59#W(&Bl&h{EM>-Y9m(dU17 z&*rxychKXulkwAko*n#n!#rgoChvUYgQ{j{kt3*hGe=*7uCT@dB2lA;#3_>=w-M(S zrZRoPF2&0vwnU~rFM;lYSGWZ$PL*9gK1AVfd}S^bjOEO^^}D7@%(5h+8NM8hEec2R zQpCFKj8K#;ZSAkxXR_B6iYaC?4~B1Y&GvJ;-i=T^93Gg(H+LL4E-Wn}HE^aAZ+2BA zm96nmHBsMA=!v{aOx>MaU-ikvE$o15dUejaZ z*-n;~l~poSJAc%^)p38^yXJT6+~pmI7kJZ~=3{4iHDf2>vi!B#V(rQQrmFMqV4jjBb8I?=-MZgd)K%N6F6dbT66o71)Nv~XHE*D-LZ^BG4K#&Re2OJ5Km#m8nI6uyPJ_Sc#Ha7+25V(`x{)9AP|SR zvYfOoKyG`Vf_U>Klx7{(F#_A1<)lcrQm*vK2?7(f#YZ8JS1^#QkDK%gJAD`9)Eq6K zURzrmIU1`@-MSB9Wi8~91FF(#)1s5-60@FAJc+P9wu+ng$FJ}i@bv=_S{feU;6qx-(X zsaD1|#UYdqA@}KN2pf-3NMfU2>M5k4}#LfdFumLaB*0bZRH0~Bo9AWh0KL*f-2GDMm zFat4?5_j_88m#m)7UEhTtXCh-r0xoI6gNWwZ|RPI;gX8fuj#-J4h}zdxjQdP#!Wnr z8kI_Q#7<|3(tNyj1oh$) zW&bzC`$!)f}8wM}H`r1e?D#c@P2_*v~ny zn7%&d7zIY)pD~BSk$<^i%0O1H=9)LhC7x~9MbM|;V55=~PFOB5P8! zP#QO1akV6j{vwRhUvgBh_+7Xr?9e!6wm%383FWptKhvps+w;W9%}s_} zzcb|@mz>UhOG``RsKLIiDv2n7(fojQRhmWHd|&?jK>rS!LNCF~q*~l~DPRS-p3Shi zHMb4c5$}$D-P&EfcwhjuMfxMFYN?M)G* z4G`$6kB!8==07-pube-)bP8NK@|qW2y_ESrikjfJeaP3eob8reh4i*opx z_Cu}9|HyrQ(^KM%fP<6sm2yPWviBC%TG){j*{+b_x7ON7qOvzd^UM8SVhX9H<}tt| zNTsf%bP%IHZTHaG5NGq_#ZlmGTjzb77l3zO5KRo_a!A!q|K>SCl0tihFq zw`Hb4!Xukgib;)g1K~99?&#zM9Ker*b=Yf9SH0}HDakj0jCj0rz&RMjB52YjA|Nn` zW0*i5tf!|(@QFTb-N4k)sex>{#*)hI5vcR}?pL2XurlS~nbX<(lfy5J!CfoQ+fKjF zbeh*UKGSwQj)|UxB_Oq%;tj;p4s69ghiugQk zOGn!5S_{gWG6jxH1e!D}MlSdeO$LI`V1RrJP$fyBG!09fa#|5|kZ&#DBC2X6Lg*l> zR(oQ@yy`E>FVM+j73h-p1~=Iy7i7v}-$CVbcR|EL)cpj|uY#$mX|8|v87JQfyst(e zmb!*kfA2f#arr{YH0$gY@hYw8dN?!q4lbqu^WazE_-F1lZT`cy|kEClN}z_Ey2Fs|4gTOVeXm z7M50JY9zY^)FWvBy>uN-!$AxZlmw5oX32yEVGL9J2oaJ zf`kwmsUU*V?Ojn5z2beOpbeKWpi%Y)5G$wo>+UP;zC$c58KE%K)jtRDW4eHdQ$H(H zwTNVa9el-u9SU+~>`(cOw{?~>Z0g?ReN`}B7QgXD@u^~`0a$fAZuA#2U9+ab+ViEx zRi-Lz$G0cf3GvSZ@zF^v8XmbmcWfyg463y&D|%9B#9uwov*B_U)xQy_1DibzVOQij z)H}FjZxwV(Q8*x7c0s~%6A>~3TWE#CGDVY`pDzAec35@-mOv>NglZiX$@elY&WNOs z_vN%)S#<_AAmFp8kWhSAMg?klU?4b051nCGyWC4W?3_VRW0A$>qFHqa zr3Gv_OFkpgG<-PMlBODN(BHPUw3H~c<|lBwG~b~zH#bL4hNPZD^)ZuOw2>(zwZB89 zZm^47nmQcX^IDpmEp(M*Sj+2zq(UKz^*)FaS%xhnhyk0tFepR|Lxrg)fguV>fQlD- zL<&H2q-3PPOf!BMeF(!7#pLN{$mA4voYE)ukA8!b?;CkusN`p} zd!wna6|yRjqXOpY!1Eq1H`7w>j!%2Eg)TdH(tOp6jv2686Fvs87xR&leRrDr6UA7c z!;jc)_N2ni(%+rAlm~c0U4X1N%i6<^5Q|yc^M^l&t#GA8lvlt()w~?Ru)UpTP4UUf z8mnw(&|kR^_PcZz*!r5=DzIir*sY z6)v)1a!KRo)b^QdSyQLvhNV4fJVyZKpZ-h%IR+J~{X_GEE2A8`ck|eez7Fji0lXewVqfdGU8Bvq73PyBZTWXy-=bVn~fQW&V$=&X1SU@e|C2C z_G({KV-xi8>T#R(^;n|YCst&K*hj_eu6vile2KH+eE}cZ*oTs#6%mDMY+6Aqalj-t zfsmzC<)|Mt1C*dthgL|3f)zrTPr`L$m}&u4=gD}(OA-G?jm10$uqCAf?7rqqP*`zn zF_@RW8U?AwIg4H3J9S>_X{vm&&Zv){wJK49Tg;Y_J&1ds0BW+P{WKYk| z&KA$UPt1l-om}b?+vo7Rh-py)G+`tzM!VNp25(K}64kzxvQ5c_x2zk}jZbO69zHiN znd1EMBWw(vEmEZkD+rY!Bnap(1Jv&ZBThLB6eSXC6PGx#;RN7L-Hrzs^avs_YYPUN z7m81A{d}-_!)2n3EeIXNGKHJzvCgNQzj${jnksx3s1A+&v-+R z0E8)VIYWa!0(nMU0!4b@RDpgaT{!`uo`g?7oUN?kagI(F0<$<-4kGQ;e$@2G`T5ux!|FZ3rZH81X!(zT z?9fJX%29}6zjQGQwyZ8@N?_dH!$%oH9+ieP@>wv54T&^aJ4Qg2_b*;T3B@L>_CPPF z)PnO%P*4;rqGd#`&u$3r@->kVs?st;PeI%zQ=wO!m@@TxOvF#w{zFXoV^-m6sTz-O zy$9I(Jaade2EM?J>umRN1!cZ+8NIp(?t#_om&$hGpsX` zu?v4)R|!e5rbygFQBJf^(fC63Mh0`cJ>3--f=kJRk6`G5lT^@%jDJxh;^_}Vo9J>1 zvbe52@vlN|G46`;LDbZ>)gKgjNu(p~f2HXBjbY|{!Ael5^hr&++($z< zw~N?5(;}1ANSF;Ewg4v=cIl2*D4*>Z2>hNVE?Ms^xP)!ups(lrp7F z!`Z;3C!U3wpJg3ok^QEO9QQMM>;MST!_(8VNtij>r1IDoewJu0CvVH5vZ+vx`)!2v z%nkDwCEX%q%Yyd5?1<~d5scH0`_s;+{pI{BK^MNQ7vUFC#{QQCN*FyN`ulX+#p#;S z)yWftuTmt{TvEQl?0RkAGHuRACN;7Nuv)Xfeg)eN!^clBkJ-mDCTD-;_yaTfG=+%? z!UAH(mqW$p_=wIP|GH5AVQKK~z}OeU!82;IAUl^p&+o?~K>StUGOAz{O>y*dV(UU-)KD7}$DU@Q0Ea zWxnhWn%jVa@IM71C5HtuEzNNu?Xpiv?k-Uo9D89C;Y0pSiO48vmHyIh(o^9ySqMOl zktWQi7)S_8t&)aQljL#cX&*;6A<$sN`qIkav8T*R)X@hCY`A)VI zSu^L`m}swFs(!uuYyRQYdNxt_EE;no3vHMtTWG$Z5TZMBrV$fyZyecrVNjKBCBODc znil-|H^xkPdu<3Eh!H7FE@4UG6S|s^X|hyW2q_PiToxCWVGIRtS6!lJRQ5qKlyxAJ zw9?eEhOyB?G>C6)`)Wr};weue&Z+qzNsnZ$2fFK{ALjm>W0#*!X!v^&&U%1QNmAZ4%fR2)-!dC9{hL$xo4`(1Y|4Gc!AbOD*EswS zC?Yd3%nl7AN~oC;%0rUn#A41Fif*udJa?Z|yLkZ+- zO(pqwNTpQV0~I_I`G{nsFhYw7MF!%cL{x_#GR1b4&VQ&OquSZhRFwEa57koPZcFrM z0%eAoo518G@{es!=iY1}SBO@GB~}?$vd|9Lt3ZvTSu1Xw=N!3yVuOUoDR$Wv$;Vqf zGFaA)_b>S0_YS*{aaNQVX)BFJR5k!6qCv9a&VZmgv)UWK!_=eBh{1*BHr9!#wpZe2Fg!cO|Q+#%>59zWh?%5Dr z86?yl6e;^}(=XU`O=M6RN#q*Ehv7Mj+ERp4f8+_YrO*l6dv3|nWA$ba_q7He_3u_`6`X?fU zq`;m+V1<&g!&;J>?D9`LCeNAziIlDkMWDz$c@Gt;e?@MAA}xYq?W3be(Wzj!7mef< z4t9$YQwM;BvzUViPiUp^pEx%;$UFN_v8VlTv&SL*!T*}2C{oB$m~`{B2+5usm!gxf zQzPizj2Pa4>%7A5(!X+8Q%ml~ZGMo{qA@Rs7svipOpizXEXUEisNa4nCB3sZ+wXe^ zUq^5`SYoDR^~2tCV4yM*w+_-_OnUG@E$W-#Ll|09V0;v{3X6IUSz?6}lu&K33~EF^ zUD&HFOU_CBLXe)Z>Kw|MTJT>>+&@dxF}sB${7U8f#6!s@>WRfb-v2Hd3#$r*tI9?s z{waeucZZzJY7c2)r-fv@3S_9&@242NLWeomtO4E66!K`@^aJ;l7gak>I3o$Z_oG~1 zrph3;{O!>6)|FaXW_wQcvaLTQnzlvrmNw;k4C}ZgTZ(#OGNzO)zqrVn*6n*2jS7w< z26`~pM=4Py)-3MJW6atuDFUAD2Rgn;I`ae$)}$z`f+a-?<$9Vp`bj)2H3%?41in)kCD3b63&6==V?DrYh&CJ9Dn~G;59B_#|WG zpbS&^bsAcQ-Oqi2|FJ8wgY#bvY&t%P;3wQm=Tb@3 z@}?5Crnky^F|oIjpKZUq408b;qQ^h1Kd1|>xba05rtrkz%DIkE# zh9_VeDBCYgu##AC3DXsybrIdh?dA!7+>t4#4uiUsdpxi=dsLR-%I7O?b5{P|VAia> zj$(a6)lFVvE6_9}T{YHbXM2Z_2IQgA=e&10BsLnTAz*2?tCpG@( zRBJaEwN?WPKDe3i>YEj}k-kCJd4VC)^Qmm#9cqE+tn+c>&ruq@<0ET=jJ8z?0EUqE z+9c+e%GJL$>!fWyAh4w;e*}T_&HRtL{qMOtcZRAEKVHTaGKMA0(m`s>!JZ$m5yZq{CnE1xe#8i`*_Ac*wot%B)6SUc@OH0%ap1$oHb_>g^tH-(G z^&PFXwY)E|(O34~eFx{)>UUrfJ84)+Y*j?*R_n{(l~acT_+J65-I0iC)C>9jyIgC#1PPTS$1fc3o_& z?uR-AGM-Wdo^5hw_d1BniPYx*Sn_^WkUv=)guc%AnFC+Ozh7>AIWa7IE@CPJTdsT=YQCYS&p-RGZl{Yj z{yuyY681g3sjWZQ9RpxN$2^pY*{wFrM&89l1+7!ZxQv7BgXXVGyuoU`O-&b*Vx~%2 zeu5@DV&9Hh92)C@j!(%)!P&GC;rS%(H{kWC$9p_u&t9DQ7vetWmw-G^i<7nWo>E)A zOA@iASz<9Ky_|2R8d)7jk#b`4dX_4#oo_LRdSf!?P?bK5{3k(vO|VR(ZEe$$c9Q{n zL31)n^1f6dlN5esi${=(9zp^K5EJ^TRc&e3$J?XX*JK4o#Udw%@z$_1LOHM(zhr`; zOrb~-%GzEpUa~vsCz@xfC0PH^#QR9^Wd`B>bynTh-uU=<^mSA*E)SsV_u>VfXsyIo z#a*vvTm8NpoqRP_#+Tn9jbE<3??%WS3<} zEMJ;Ar=x&qFFrr~j3n~9TBtWLGaG2Fx0R;oZCkx`qJI1}Pb#STQeVD6q{5?$1VtJj zU7DB>6qcC4henTr(?bU;eiw5}2f?)R=2frvn>eyf+7s@@)#NP^2;awDXje+7HtcRB z$+paY5e<=|Fxa@IGJ&nN$Xzu3{6@DSVjIdckM!O-6V^m=WohJ8ojlc38jGB+#I_AI zK$n&%Uj#n5{@DKNEL}B;LSGCr8qp&arZti^Y9m9ZGv?h7 z=V}?8{v|-MYbdcJHk>4&s!%k^q&j^HsFwU4*_)oW8i>a$m}v@s-+QK3HB%^|= zv4%My;#*WFohn|+^*Z(|CZg`^siWG}j{b=F^2_1eteqbfOAYVj#YIU78Q4m~;HJq` z%53~n7%aZ+FH+Oeq#%(XHxS21en3Kt9Ay|jyA*8*5&kAYr*REA?B z=ry^uI!HAv|Chl;J_^AugDzMiW6Xhh*e^MmFG!Q8H1iFGEIAK~nle|BCMuoN`}I|) z=F8`oA#`%YiV$}_5X8`@fE2`~0Uz^D-Sw7GpL!=osWGrMX`ars=OsWH&$9LFoiN2! z;@-vYTllVT=##m>ScVf0+T*C=i`yqd5D_RcH!a9=H8p>ZCJ!*2)-Z;Tptc;g?pfZ1 z?dD!R8lQyK{5V+VP!*d`kCTSEw>Xe*l+Wir*KIy$2dMomA+App&xI>XLaeZpwPlj! zUxwj_JK_~H8gw#5!ja)$tzc+~ERkw(-S7ASo?w)hX zG*R|*=qs^D@lhY6;<<2Z%eU|FW44e%rGk|!Ld)MLF&p~9tqvXB>t?Jg1s!ytvf(nYmZ40%MEdy9bZygpMg-LgL<+tErS6>Ofw zRzLeKhHq$TRF4{%ku}5z_6MIzISPXe1Q3_eBK`y_7*${_3zJK(Ra0U^>JO_!9=6Vf za}|$FF%g9Za3A5JFA8V??*-+Zy{)02HfusM<+y%KV0S}Cr7#?qAEZWAv-=MjjSQc6 z{GR-^nKx}vb8z}Exux@8Hiv$R>{N8%ClP1W zl>AzNXN9ZlkQ_e$yh)+%p0-lj&NVXyU*$T0bJY&~M3X@9!X3M=++AkusRptf&o9aT zJqWffX{SzOk0Q4E4KT&yeu5`PJ$uoy{oai$pSKHuf568qnsdJ3{5!(yJ)g(mUw7#a zNz0drPP1<=lp6g@tZjgVD zNpltFl$IIE=w{bZ9U`{ZlY66lc;GA10i_v5o_g-1n0zN0cJP6zM_{W%w;vVd;~or_Y;M`=T2WfeGiJ%DBMFn zgb}{<8fx81I-sogOJRCHcOC8OKw7`)LmRa3`D4G++mDN;4dtQ;7qKtV*)F{l%~=h< zLNavEG3+;8aO9fXF;{<`s+y?B%v>?7wKU*JB2~M$XuN33tS4A@fMnVcK9~9_-O46@ ztJ+zAZ859TUk&=CUqV`$sP`RF8{b-tVbginzj92b?=Ruhf(dHv?{74`8RQz?2-G*8 z0=K=WcQ)4MrCp>BJbjqaX;!Vcc&I~bZ0Vg&IHSShMk1qJeZs-`W$cU zOVXO>G0%cMYOu;#PmqXUiLf;vdhyN;yUgV}#U;fA*>O{O~OC>{|T+hz_;To5{qBP-CU#mgO=mlSJS@s7D_sB#O>Qc_h%*Nn5 zQ-`icq;bBG<`YL%dbM7cG`F9rrLCl#X<>b6%3S{rm#FsXs0*xZ>r9Y?NmsO9G@;$!{KJCEh6p?icYXST#K?mzB9#OP;(`PLw~bVmbs z#~N&X8KyD2@SRBl(cvP_!aj6Q>X&3}ZL2(LJOBg~TE#~(U-7DHw#G{^)_nlXe=G4! z6NvA-iC#;)M;|J7O%bh1nw<3T#$_Q}W3^9@*;ih-Op#nX`skYDNXH1@MQh%z8xH%i z>b0xyI*q1Fj-FqgVb@jD`mk*i>~y?$JvtuTbd~R80;}zD5nQ;lE9UC|P{h_mzY5!M z2cV`MZF2ZC*-|$Py{sQ~C*w$K7-E(_cYTAntNI~nl0RA|@hxxmu-UMG9&yV5%Uaku z&3%zbYv380$Z>8wOZ|^CzfUB|su|V^i*9Ley(zXtxK_T6upQN!cQ$*pF>K>(YWQ_Y zEup!?po3)j)O2uxYWa1z8pi8dD%Ys8zmw?J+TVxTvR=MMjc&F!!ftid8vUjGZRp5{ zqx+jV6!?fA-Pl0-&CDk*wp3@whP>WcF0Zk+rN6$I%~1E z=DEsDUzazDo@nEkAYqSA{cJKt&^Fp}4r@s3n`YrW2iHTpD)+tDE9!A~PpIwNc4A+(P7a^CmA*=t}D~-W@|6^?v8w&=535%pRqJg zU{RWv*)aE3L3OXV+q)%{Ycgor6(6mQvf92X{pddgLm zEk7&I$z(iC5Kr)w40+fT4y~Oln80jB;xy32-T)SuJ|%ijy^f{@^FOF8!o8``aVFVy zPRnyQ$?+K3pNDEI&3iBJ)Np~4^k}&9-!)am35<1gyziLX!}CITu4s4-Wo11_*8;LB zJ4rpW7MLdETS?zW6PJ#{gR`0YQhYgd(t;6|cKg{?KD1_kGfks+*7vt%5jY=fwzifZ z{HXIzp!G4Ynr6aXR^6H9-SgTIOvNfa&H4nF93-+U9{QXp?sxWcXve;$X0)^ZpP=J* zD$=%`4lv_gj-VfDBHO;C^?o^hEyq6sdH>3sXkD7#2PNY)`JIoV|6Z?Xt`z4YLY{Br z+A|>O-A+nuxdT)WjTmg2CkM)Jg0xM{H=r-y&$!ZeInSN96O61#J>yxy=XJMWu zoeAy_;WIkQaF@%oVklK0iS3gNSPJHA8nc_(NBVo zxJXA64;LNFmu>3>arCKdRy=F+d$M)hcYb0q=M~Q%Q?=2W`0F!w|5l|nhTQJd)Hv>l z=u#)Tr%qj%^T_a zRxUvgDEtrdqia6~PkyHxmakueU5a&F-Amn|wui!9UYB7NK(#{+wK2|rb6iqaADCQ! zg|BwluIyH0DRAjt7?Y*9Gi@HGfnmyT{VfB#Bo*9?vpPgR(!=|lRADskJI^KL=j>hj zyNmwj!!W$l8SCZ(mBO7wm!sD{oz5eE*Pb*ry%URSrT*2Gjvc;BRy#$8@A=p2b(PEa ztEVL@<~T5XaxUiwK&GrW?w5Pj0sb$5y_U^|cI0lAsUx0wy*nIjI_UL7d+iJRueT`z zKHPL=bVS9i$46~VhIwt2W2Y2?iKmJ3&!)^3Tg|-Ew4MIJ|w<}?M+_W%r;l~2hkeeE!}=Bh9>s0ryPWX6i;4b|92bzF&#!R{;8T=?Jw>ut(!$~ zX4d$-59x~-=`Jdo{B1u_S@iSQLJt~4%7uNpgToX5|L3wzH{`Bd;?_6cClAJ0q5OwL u&1{M8R^d%LbM6%XeMYX){Ha&}=a38pe3a$i$RT9RL;eRc+#U7+ literal 0 HcmV?d00001 From ad6fb3badd02e871c7598de31d45ef4e0d2d1019 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Fri, 21 Jun 2019 12:14:24 +0000 Subject: [PATCH 03/13] Added issue template --- .gitlab/issue_templates/default.md | 45 ++++++++++++++++++++++++++++++ 1 file changed, 45 insertions(+) create mode 100644 .gitlab/issue_templates/default.md diff --git a/.gitlab/issue_templates/default.md b/.gitlab/issue_templates/default.md new file mode 100644 index 0000000..1799c49 --- /dev/null +++ b/.gitlab/issue_templates/default.md @@ -0,0 +1,45 @@ +# Summary +*Introduction to the issue* + +# Versions + - ROS Driver version: + - Affected Robot Software Version(s): + - Affected Robot Hardware Version(s): + - Robot Serial Number: + - UR+ product(s) installed: + - URCaps Software version(s): + +# Impact +*What is the impact of the issue. Try to describe it well enough, in order for us to prioritise the issues.* + + +# Issue details +*This part is important in order to clarify the severity of the issue.* + + +## Use Case and Setup +*What does the setup look like and what are the objectives?* + + +## Project status at point of discovered +*When did you first observe the issue?* + - *Before I started?* + - *In first couple of tries?* + - *In normal use?* + - *etc...* + + +## Steps to Reproduce +*Make simple example to reproduce the issue. Try to remove dependencies to other hardware and software components, if it is possible.* + + +## Expected Behavior +*What did you expect and why?* + + +## Actual Behavior +*What did you observe? If possible please attach relevant information.* + + +## Workaround Suggestion +*If a workaround has been found, you are welcome to share.* \ No newline at end of file From 2883aa1b43601e143df5c60ece37fdedcd515058 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 24 Jun 2019 11:13:04 +0200 Subject: [PATCH 04/13] added socat as exec_dependency socat was missing as an execution dependency, although is is needed by the tool_communication script. This solves #2 --- ur_rtde_driver/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/ur_rtde_driver/package.xml b/ur_rtde_driver/package.xml index 4d47acb..f9ae0b2 100644 --- a/ur_rtde_driver/package.xml +++ b/ur_rtde_driver/package.xml @@ -39,6 +39,7 @@ joint_state_controller joint_trajectory_controller robot_state_publisher + socat ur_description velocity_controllers From dc0a9dd44de2128dfaab3e08f168fe79c5404cf2 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 24 Jun 2019 12:10:26 +0200 Subject: [PATCH 05/13] correct installation location of tool_comm script --- ur_rtde_driver/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ur_rtde_driver/CMakeLists.txt b/ur_rtde_driver/CMakeLists.txt index c832a47..6032624 100644 --- a/ur_rtde_driver/CMakeLists.txt +++ b/ur_rtde_driver/CMakeLists.txt @@ -119,7 +119,7 @@ install(TARGETS ur_rtde_driver ur_rtde_driver_node ) install(PROGRAMS scripts/tool_communication - DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY config launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) From 0bcbc25bf9405477ee8dae836f32e604446d8ab7 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 24 Jun 2019 10:21:32 +0000 Subject: [PATCH 06/13] use industrial-ci pipeline --- .gitlab-ci.yml | 50 +++++++++++++++----------------------------------- 1 file changed, 15 insertions(+), 35 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index b88217a..1d5ae67 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,38 +1,18 @@ -image: ros:kinetic-robot - -cache: - paths: - - ccache/ - +image: docker:git +services: + - docker:dind before_script: - - git clone https://gitlab.com/VictorLamoine/ros_gitlab_ci.git - - source ros_gitlab_ci/gitlab-ci.bash >/dev/null + - apk add --update bash coreutils tar + - git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci .industrial_ci -# catkin_lint -catkin lint: - tags: - - docker - stage: build - image: ros:kinetic-ros-core - before_script: - - apt update >/dev/null 2>&1 - - apt install -y python-catkin-lint >/dev/null 2>&1 - script: - - catkin_lint -W3 . - -# catkin_make -catkin_make: - tags: - - docker - stage: build - script: - - catkin_make - -catkin_make tests: - tags: - - docker - stage: test - script: - - catkin_make run_tests - - catkin_test_results # Check if one of the tests failed! +clang-format: + variables: + CLANG_FORMAT_CHECK: "file" + CLANG_FORMAT_VERSION: "6.0" + ROS_DISTRO: "kinetic" + script: .industrial_ci/gitlab.sh +build_kinetic: + variables: + ROS_DISTRO: "kinetic" + script: .industrial_ci/gitlab.sh From 7d49801812b596c6a62ed87fc2a7f8d1a8b6fc8e Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 24 Jun 2019 12:54:50 +0200 Subject: [PATCH 07/13] activate catkin_lint in the build_kinetic job --- .gitlab-ci.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 1d5ae67..4937b63 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -15,4 +15,5 @@ clang-format: build_kinetic: variables: ROS_DISTRO: "kinetic" + CATKIN_LINT: "true" script: .industrial_ci/gitlab.sh From d42fbb241bc3afdbedbd545e42e6a5b0442dd3a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rune=20S=C3=B8e-Knudsen?= Date: Mon, 24 Jun 2019 12:04:17 +0200 Subject: [PATCH 08/13] Adjust critical sections Optimised the used of the the enter_critical and exit_critical sections --- ur_rtde_driver/resources/servoj.urscript | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/ur_rtde_driver/resources/servoj.urscript b/ur_rtde_driver/resources/servoj.urscript index d44268f..de285a0 100644 --- a/ur_rtde_driver/resources/servoj.urscript +++ b/ur_rtde_driver/resources/servoj.urscript @@ -12,19 +12,15 @@ global cmd_servo_state = SERVO_UNINITIALIZED global cmd_servo_q = get_actual_joint_positions() global cmd_servo_q_last = get_actual_joint_positions() def set_servo_setpoint(q): - enter_critical cmd_servo_state = SERVO_RUNNING cmd_servo_q_last = cmd_servo_q cmd_servo_q = q - exit_critical end def extrapolate(): - enter_critical diff = [cmd_servo_q[0] - cmd_servo_q_last[0], cmd_servo_q[1] - cmd_servo_q_last[1], cmd_servo_q[2] - cmd_servo_q_last[2], cmd_servo_q[3] - cmd_servo_q_last[3], cmd_servo_q[4] - cmd_servo_q_last[4], cmd_servo_q[5] - cmd_servo_q_last[5]] cmd_servo_q_last = cmd_servo_q cmd_servo_q = [cmd_servo_q[0] + diff[0], cmd_servo_q[1] + diff[1], cmd_servo_q[2] + diff[2], cmd_servo_q[3] + diff[3], cmd_servo_q[4] + diff[4], cmd_servo_q[5] + diff[5]] - exit_critical return cmd_servo_q end @@ -42,7 +38,6 @@ thread servoThread(): if cmd_servo_state > SERVO_UNINITIALIZED: cmd_servo_state = SERVO_IDLE end - exit_critical if do_extrapolate: textmsg("No new setpoint received. Extrapolating.") q = extrapolate() @@ -52,6 +47,7 @@ thread servoThread(): else: sync() end + exit_critical end textmsg("servo thread ended") stopj(0.1) @@ -63,6 +59,7 @@ keepalive = -2 params_mult = socket_read_binary_integer(6+1, "reverse_socket") keepalive = params_mult[7] while keepalive > 0: + enter_critical socket_send_line(1, "reverse_socket") params_mult = socket_read_binary_integer(6+1, "reverse_socket", 0.02) # steptime could work as well, but does not work in simulation if params_mult[0] > 0: @@ -72,11 +69,10 @@ while keepalive > 0: else: keepalive = keepalive - 1 end + exit_critical end textmsg("Stopping communication and servoing") -enter_critical - cmd_servo_state = SERVO_STOPPED -exit_critical +cmd_servo_state = SERVO_STOPPED sleep(.1) socket_close() kill thread_servo From 0b4da2dab56b2fa11df4aeb6401ad9922bed5022 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rune=20S=C3=B8e-Knudsen?= Date: Mon, 24 Jun 2019 12:09:23 +0200 Subject: [PATCH 09/13] Change extrapolation log messages strategy Change the log strategy regarding extrapolation from make a message every time, to show the maximum number of extrapolation steps observed in a row and the current count In this way the log will not be filled up with identical messages, hiding other messages. Valuable when running on an unstable network like WIFI --- ur_rtde_driver/resources/servoj.urscript | 30 ++++++++++++++++++------ 1 file changed, 23 insertions(+), 7 deletions(-) diff --git a/ur_rtde_driver/resources/servoj.urscript b/ur_rtde_driver/resources/servoj.urscript index de285a0..0811219 100644 --- a/ur_rtde_driver/resources/servoj.urscript +++ b/ur_rtde_driver/resources/servoj.urscript @@ -1,16 +1,22 @@ {{BEGIN_REPLACE}} -global steptime = get_steptime() +steptime = get_steptime() textmsg("steptime=", steptime) -global MULT_jointstate = {{JOINT_STATE_REPLACE}} +MULT_jointstate = {{JOINT_STATE_REPLACE}} -global SERVO_STOPPED = -2 -global SERVO_UNINITIALIZED = -1 -global SERVO_IDLE = 0 -global SERVO_RUNNING = 1 +#Constants +SERVO_STOPPED = -2 +SERVO_UNINITIALIZED = -1 +SERVO_IDLE = 0 +SERVO_RUNNING = 1 + +#Global variables are also showed in the Teach pendants variable list global cmd_servo_state = SERVO_UNINITIALIZED global cmd_servo_q = get_actual_joint_positions() global cmd_servo_q_last = get_actual_joint_positions() +global extrapolate_count = 0 +global extrapolate_max_count = 0 + def set_servo_setpoint(q): cmd_servo_state = SERVO_RUNNING cmd_servo_q_last = cmd_servo_q @@ -38,13 +44,22 @@ thread servoThread(): if cmd_servo_state > SERVO_UNINITIALIZED: cmd_servo_state = SERVO_IDLE end + if do_extrapolate: - textmsg("No new setpoint received. Extrapolating.") + extrapolate_count = extrapolate_count + 1 + if extrapolate_count > extrapolate_max_count: + extrapolate_max_count = extrapolate_count + end + q = extrapolate() servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + elif state == SERVO_RUNNING: + extrapolate_count = 0 servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + else: + extrapolate_count = 0 sync() end exit_critical @@ -71,6 +86,7 @@ while keepalive > 0: end exit_critical end + textmsg("Stopping communication and servoing") cmd_servo_state = SERVO_STOPPED sleep(.1) From ca2e2f1ed82bf81a918f701c0fc4d5ef8c37bd73 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Thu, 27 Jun 2019 11:16:17 +0200 Subject: [PATCH 10/13] Added notes about minimal polyscope versions --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index febd98a..e5ef98f 100644 --- a/README.md +++ b/README.md @@ -14,7 +14,7 @@ This driver is forked from the [ur_modern_driver](https://github.com/ros-industr Create an issue on the [Issue Board](https://gitlab.com/ur_ros_beta/universal_robots_ros_driver/issues) and use [Issue #1 as a template](https://gitlab.com/ur_ros_beta/universal_robots_ros_driver/issues/1). ## Features - * Works for all **CB3 and eSeries** robots and uses the RTDE interface for communication, whenever possible. + * Works for all **CB3 (with software version >= 3.6) and eSeries** robots and uses the RTDE interface for communication, whenever possible. * **Factory calibration** of the robot inside ROS to reach Cartesian targets precisely. * **Realtime-enabled** communication structure to robustly cope with the 2ms cycle time of the eSeries. To use this, compile and run it on a kernel with the `PREEMPT_RT` patch enabled. (TODO: Write tutorial on how to compile a realtime kernel for Ubuntu) @@ -68,6 +68,9 @@ $ source devel/setup.bash For using the *ur_rtde_driver* with a real robot you need to install the **externalcontrol-1.0.urcap** which can be found inside the **resources** folder of this driver. +**Note**: For installing this URCap a minimal PolyScope version of 3.6 or 5.0 (in case of eSeries) is +necessary. + To install it you first have to copy it to the robot's **programs** folder which can be done either via scp or using a USB stick. The installation process is similar for CB3 and eSeries robots and will be shown side-to-side in this guide. From 513ff9143df53bc973442e785ce58fc3279bdebe Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Sun, 14 Jul 2019 15:05:21 +0200 Subject: [PATCH 11/13] rtde_driver: don't unnecessarily repeat joint names. Use an anchor for the list and aliases where needed. --- ur_rtde_driver/config/ur10_controllers.yaml | 18 +++--------------- ur_rtde_driver/config/ur10e_controllers.yaml | 18 +++--------------- ur_rtde_driver/config/ur3_controllers.yaml | 18 +++--------------- ur_rtde_driver/config/ur3e_controllers.yaml | 18 +++--------------- ur_rtde_driver/config/ur5_controllers.yaml | 18 +++--------------- ur_rtde_driver/config/ur5e_controllers.yaml | 18 +++--------------- 6 files changed, 18 insertions(+), 90 deletions(-) diff --git a/ur_rtde_driver/config/ur10_controllers.yaml b/ur_rtde_driver/config/ur10_controllers.yaml index ebbd6be..a294913 100644 --- a/ur_rtde_driver/config/ur10_controllers.yaml +++ b/ur_rtde_driver/config/ur10_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 diff --git a/ur_rtde_driver/config/ur10e_controllers.yaml b/ur_rtde_driver/config/ur10e_controllers.yaml index c100dfc..0608e0d 100644 --- a/ur_rtde_driver/config/ur10e_controllers.yaml +++ b/ur_rtde_driver/config/ur10e_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 diff --git a/ur_rtde_driver/config/ur3_controllers.yaml b/ur_rtde_driver/config/ur3_controllers.yaml index ebbd6be..a294913 100644 --- a/ur_rtde_driver/config/ur3_controllers.yaml +++ b/ur_rtde_driver/config/ur3_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 diff --git a/ur_rtde_driver/config/ur3e_controllers.yaml b/ur_rtde_driver/config/ur3e_controllers.yaml index c100dfc..0608e0d 100644 --- a/ur_rtde_driver/config/ur3e_controllers.yaml +++ b/ur_rtde_driver/config/ur3e_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 diff --git a/ur_rtde_driver/config/ur5_controllers.yaml b/ur_rtde_driver/config/ur5_controllers.yaml index ebbd6be..a294913 100644 --- a/ur_rtde_driver/config/ur5_controllers.yaml +++ b/ur_rtde_driver/config/ur5_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 diff --git a/ur_rtde_driver/config/ur5e_controllers.yaml b/ur_rtde_driver/config/ur5e_controllers.yaml index c100dfc..0608e0d 100644 --- a/ur_rtde_driver/config/ur5e_controllers.yaml +++ b/ur_rtde_driver/config/ur5e_controllers.yaml @@ -4,7 +4,7 @@ hardware_control_loop: # Settings for ros_control hardware interface hardware_interface: - joints: + joints: &robot_joints - shoulder_pan_joint - shoulder_lift_joint - elbow_joint @@ -31,13 +31,7 @@ speed_scaling_state_controller: # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller scaled_pos_traj_controller: type: position_controllers/ScaledJointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 @@ -53,13 +47,7 @@ scaled_pos_traj_controller: pos_traj_controller: type: position_controllers/JointTrajectoryController - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint + joints: *robot_joints constraints: goal_time: 0.6 stopped_velocity_tolerance: 0.05 From 3993466f24e5060b2660c5cb82aa532e3d63d426 Mon Sep 17 00:00:00 2001 From: Felix Mauch Date: Mon, 15 Jul 2019 08:44:43 +0200 Subject: [PATCH 12/13] set controller publish rates to 125 Hz for CB3 robots. --- ur_rtde_driver/config/ur10_controllers.yaml | 4 ++-- ur_rtde_driver/config/ur3_controllers.yaml | 4 ++-- ur_rtde_driver/config/ur5_controllers.yaml | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ur_rtde_driver/config/ur10_controllers.yaml b/ur_rtde_driver/config/ur10_controllers.yaml index a294913..333dac8 100644 --- a/ur_rtde_driver/config/ur10_controllers.yaml +++ b/ur_rtde_driver/config/ur10_controllers.yaml @@ -42,7 +42,7 @@ scaled_pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 pos_traj_controller: @@ -58,5 +58,5 @@ pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 diff --git a/ur_rtde_driver/config/ur3_controllers.yaml b/ur_rtde_driver/config/ur3_controllers.yaml index a294913..333dac8 100644 --- a/ur_rtde_driver/config/ur3_controllers.yaml +++ b/ur_rtde_driver/config/ur3_controllers.yaml @@ -42,7 +42,7 @@ scaled_pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 pos_traj_controller: @@ -58,5 +58,5 @@ pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 diff --git a/ur_rtde_driver/config/ur5_controllers.yaml b/ur_rtde_driver/config/ur5_controllers.yaml index a294913..333dac8 100644 --- a/ur_rtde_driver/config/ur5_controllers.yaml +++ b/ur_rtde_driver/config/ur5_controllers.yaml @@ -42,7 +42,7 @@ scaled_pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 pos_traj_controller: @@ -58,5 +58,5 @@ pos_traj_controller: wrist_2_joint: {trajectory: 0.2, goal: 0.1} wrist_3_joint: {trajectory: 0.2, goal: 0.1} stop_trajectory_duration: 0.5 - state_publish_rate: 500 + state_publish_rate: 125 action_monitor_rate: 10 From 03e7030872c72f916b4fff1eba48d190e7f35fe6 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Sun, 14 Jul 2019 15:53:14 +0000 Subject: [PATCH 13/13] rtde_client: fix typos. --- ur_rtde_driver/src/rtde/rtde_client.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ur_rtde_driver/src/rtde/rtde_client.cpp b/ur_rtde_driver/src/rtde/rtde_client.cpp index d0a3a71..d9e512b 100644 --- a/ur_rtde_driver/src/rtde/rtde_client.cpp +++ b/ur_rtde_driver/src/rtde/rtde_client.cpp @@ -67,7 +67,7 @@ bool RTDEClient::init() tmp_version = dynamic_cast(package.get()); if (!tmp_version->accepted_) { - throw UrException("Neither protocol version 1 nor 2 were accepted by the robot. This should not happen!"); + throw UrException("Neither protocol version 1 nor 2 was accepted by the robot. This should not happen!"); } } @@ -110,7 +110,7 @@ bool RTDEClient::start() std::unique_ptr> package; stream_.write(buffer, size, written); if (!pipeline_.getLatestProduct(package, std::chrono::milliseconds(1000))) - throw UrException("Could not get respone to rtde communication start request from robot. This should not happen!"); + throw UrException("Could not get response to RTDE communication start request from robot. This should not happen!"); rtde_interface::ControlPackageStart* tmp = dynamic_cast(package.get()); return tmp->accepted_; }