From c9b1963f0c3b4466589c9eaa47e98fd24ab2d821 Mon Sep 17 00:00:00 2001 From: Cristian Beltran Date: Wed, 5 Oct 2022 14:22:29 +0900 Subject: [PATCH 1/3] Add callback to sendTrajectory --- .../src/moveit_controller_manager_example.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/controller_configuration/src/moveit_controller_manager_example.cpp b/doc/controller_configuration/src/moveit_controller_manager_example.cpp index 9f3c2fb9d..0941368a9 100644 --- a/doc/controller_configuration/src/moveit_controller_manager_example.cpp +++ b/doc/controller_configuration/src/moveit_controller_manager_example.cpp @@ -49,7 +49,7 @@ class ExampleControllerHandle : public moveit_controller_manager::MoveItControll { } - bool sendTrajectory(const moveit_msgs::RobotTrajectory& /*t*/) override + bool sendTrajectory(const moveit_msgs::RobotTrajectory& /*t*/, const ExecutionCompleteCallback& /*cb*/) override { // do whatever is needed to actually execute this trajectory return true; From 378045d5afb5f0d22461b23dd9be9433ac3e877a Mon Sep 17 00:00:00 2001 From: Cristian Beltran Date: Tue, 18 Oct 2022 10:29:03 +0900 Subject: [PATCH 2/3] Add tutorial for simultaneous trajectory execution --- CMakeLists.txt | 1 + .../CMakeLists.txt | 5 + ...neous_trajectory_execution_tutorial.launch | 10 ++ .../simultaneous-execution-rviz.gif | Bin 0 -> 418753 bytes ...ltaneous_trajectory_execution_tutorial.rst | 47 ++++++++++ ...ltaneous_trajectory_execution_tutorial.cpp | 87 ++++++++++++++++++ 6 files changed, 150 insertions(+) create mode 100644 doc/simultaneous_trajectory_execution/CMakeLists.txt create mode 100644 doc/simultaneous_trajectory_execution/launch/simultaneous_trajectory_execution_tutorial.launch create mode 100644 doc/simultaneous_trajectory_execution/simultaneous-execution-rviz.gif create mode 100644 doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial.rst create mode 100644 doc/simultaneous_trajectory_execution/src/simultaneous_trajectory_execution_tutorial.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index c394c7c46..a64b09bc8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,3 +74,4 @@ add_subdirectory(doc/collision_environments) add_subdirectory(doc/visualizing_collisions) add_subdirectory(doc/bullet_collision_checker) add_subdirectory(doc/mesh_filter) +add_subdirectory(doc/simultaneous_trajectory_execution) diff --git a/doc/simultaneous_trajectory_execution/CMakeLists.txt b/doc/simultaneous_trajectory_execution/CMakeLists.txt new file mode 100644 index 000000000..a64a8e7b7 --- /dev/null +++ b/doc/simultaneous_trajectory_execution/CMakeLists.txt @@ -0,0 +1,5 @@ +add_executable(simultaneous_trajectory_execution_tutorial src/simultaneous_trajectory_execution_tutorial.cpp) +target_link_libraries(simultaneous_trajectory_execution_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS simultaneous_trajectory_execution_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/simultaneous_trajectory_execution/launch/simultaneous_trajectory_execution_tutorial.launch b/doc/simultaneous_trajectory_execution/launch/simultaneous_trajectory_execution_tutorial.launch new file mode 100644 index 000000000..2b72a4ce4 --- /dev/null +++ b/doc/simultaneous_trajectory_execution/launch/simultaneous_trajectory_execution_tutorial.launch @@ -0,0 +1,10 @@ + + + + + + diff --git a/doc/simultaneous_trajectory_execution/simultaneous-execution-rviz.gif b/doc/simultaneous_trajectory_execution/simultaneous-execution-rviz.gif new file mode 100644 index 0000000000000000000000000000000000000000..396ef716b3c9ace3434d027e255bf37e4b077951 GIT binary patch literal 418753 zcmW(+byU>P*Z#1Cgmg#?xO9q$gdiZ`(z!@?yOe~KN_Q;X9m2wrOLsQ{A}lE_El7yC zu2N0#GObjRG+LGY>`s5HtWo18_8e zLIY?tfcc+KUCR5UV4yGz6pn$SFi*QV5MUGnfO!-8R02n-8@Vc{?=3Wi0)uoxH?fMdaMECh~)!Le{S76r$m;aChD3!t!I6c&QQ z!cbT^3X4Kv(I_kig$2-9Fd7R%V_|449F0Yxv1l|FgT?|FEEt1@V6ZR@7LLK9FjzDO zi@{*ou_T&G`g*VBwUtDLL~wEbdr<6u@$iU&$AG|pbKw7B0uW*WYA_{_c7HFJfP_^& z%Dw1yI0cikE#$mtFqW3vcrwbP1y zX#cI)tg2aXrNwo-KaamfXsyHNVr#9cMc6dt0S*b7x^LZPe-t^t=A>`^_AvahT7tS? z!|r&d@Vn_rzs8@_g|A}CH2hHqa}`=unp6Hw@8;EP`19iReO#7R+>WNFR(#x6yF+mw zcboWnZ1p7aYfZ2EUcf2EyYtuErLK+^8f|{mbV>jDwLTDveJtGl^6!NT4Nq3#j>wNc zpSA}IgnMM~{#~EE`P2SN<#R1Dj_>!+q`dGT`B~1WA0dCA?puaZ$VzF9`+=F*QB{29As*o zY75ex2kqo45;$?^DXmw|(?P6_lJRJLEo}v!KL=n zHVsDb)HHLyQoJ-(d4h62;)QA9YcvN!2Glf{Kywm=HRhDhsUUVx(8Q`FV*vW4^{jxxjIS@)c5H( z+o>9kTszK&UsTJqpnhxd6D%b=(;(p-!7?WEhh&dBRA*HY2ki0@GS?8R37XY}S+bUj zWGgpbDsbUJ>NQ+czEKyWS0-Z$u}Y-7jmhn;>q^*46toe=Ol03*g;!L^4|>eUv=nfxp*59!LsBQOq7ax@#svohnQ+RseEW@ z#b}h8U=~L{D=Sv2F@h$mqWBD_m?{^+CROY?Nj)j4wDpM>EV?`)dzOSGoSwv5K$OnDBIb zH)-+q`jh~MpR++Ck!Eybc@f-555hDu6m1p4$n{?Tx zU%<~@f=zgc0JM;0#EZBS5;{4iVrP7bQ`sB|2&AFdt)`gsCG*Q&bw<1Iw?SI2Z^ z6&nQP#lpLHHq_m9Bd2r&0-}nWkA^#jUU5-`txnal=+P5OF9SpRm6{};(xZJ~ZQ_r! z=a$HgFu`Sy*x5B3P}9ZQTmniyXbSmuXQPmkJ9~3N|09e8H|_qq33G ztni`tV#wp6iLaTcG;JPO#nQw!gsWndV#=1!Ds8QE^QbPm6pRz6@kgypN^5M|dz}+U zYkAq=x-m#7>?EI#hgqLz46CJf+gJc}Wq~aROZV|E3$g0^&hvV~B+y_`F*uIIq_scV z7*$LkZsk6gHJe=ejgRFjQTes%TvB#wG56Kj9ogk`Q60P@5om?Fjq10oWmLJuR6;pn zqh4@pW1ieyrFN*QeuMe}uWp_3=ZI){3E5SpQaqo2{2|R3#zDCkQ_h+#i0?J;ud2*R zk1V%{z9Q4S-`Q$Z8GVmgXlidly316VE=eu6EO@gy4^^35EgN*Ff3MX73CREUU+ky4 zt_ye$v!+~mJ0zZ7|JfU6%g$stW{}8#bU zJl}BLR1=T1ba-d9gk4B)&Kz=a^o})NZ(eAr!>@6{RbF*rXlWglsd=9=vAQeO(l+z4 z#;Zha?ZCLD9o<#q(>Sqq;@{G-aaZFzptgRV-O{-)Q|te2V*RSUrR(ftZQ!<=#Rb_( zH@5fJ%ze_2`@_W^;J!8pSA7GAskIlwDe@WHVF|pT?;%${`$Vg5Mer8g_b9?Wf-~2W zB!GV4@q&BQKc-FGjMf1*&H5;)`WC6yO)r0fN9-GnHQl1&@QeKVc%3*K)}z)DZrSso z&|~YzKW|2rH5=fu>b8vhS!2uuqN#bSJD&>=$FFaOLayvc_#OUE7%sez9C)}Vd=xur zJ6)STYicjv(T1IJ|J0bft^QMTrES``yD|S_@~6zdwy#0=jfJ=x`|?cfGf}drV(O`V zCF%BA_$O59lc}HBWDd(_N2Q};^%tUWj&Vt~tl-(qAEBJ|dLjhgh_}c?gT~wMH3`qF z9R!bzzuhi0Pd~5ufIKq4xLxcf6R(RDJhrC(haNutmDbf6?ju3^{Z6Ve<9jt%fSAzo ztJf(kEAU3x%DbhC@n3Y+$1l_+1E?KQ=}|sD*w3B2j1GR|8nT{Q9j3b?pZ%sh6E5xG8nwwItN@OO2F}hiB!NrH^WFhM(P^CnUby z;THZou6O@C{p-uU7qxz>SZ1gfwLkKhbECNAmk;|BsoCdiUe@92y$Gt7wFiE(p&n`{ ztqvWho?rj1{p`eYiz+z*-U$8|5(NB{Aj!V`s!0&V-M!!*WZ7O1^0hfdhTyNe7@i9`FweV#bO== z-9HM#lL#W9|NMaPGcn{d&Vp3wnNzK}7dgFakGR)z2p15+t7acKv>42M6U<5I zVHg7T4M9c(PSZIiY)ix}hSa>b&l~X*lL!?z43+Q=mC6i#*%~T~4wbtJ4T}hAQ4YSh z3;Pou=FDZOdSi#P5T-pErh5~nS7D(82{&{Mhx&$@WQLiwh8c~9TkVJ25JngqMris* zIP*ljgG9JEM!@JJU3ntiB_e$cBYiU?yec9;j7IwThP&-Yh7d*tK%zc6Mt!~s53Pub zYK?NlqN94)>| zIL06eV{0p78VqAmzOnUDv5lFrovpFmjYaXl5W{f2RazHxm~aRZrgldW;nj&W0j z@n0+AiXmZKzVQp0@#xn0Wpw=NP5e52LUyLbkDstT!-Rd`gu~2)}<@huD_;ZQ) z--d~ozKL_0i5C@#*Q1Fyt%<-=BF^7LkP#fu4}PBs$E}1{j#`>t+lg)~R!}90LXs$) z>>m;NQ!Ejy8rtb9+vzpiu>Q3HN83JeN@o9?#F3TE`PY{1Z!$ko3ZG<(pkJ~OLy81e zC54AK<@s2$bXJPYSjwx)lou+g;(n>x1Tp+KaP; zX$Dzorfq5F4C!W)>6R+#7Jlj0M(Ov20XmXNnu8*@pp1tX>0S&O-jW$Ue@RY&1m<+h zPg%B(i$8UgCXe#3?B!#BytWiOxo;A zA#RzK=_N+lPEOhOe%Xku>}r+ls)KB#UmBUDn5P~;18>_&NB38y?HmPD3)naDJtX zd;&gXIAvXbm>m&(Z&XGyZV_6VHCSBWJqZ5O5a!;NfjV${@C>q3;biSxuE|?os7&1B zPU1G6J6S3GH-+yyB-j}tOkVNsUWB+>gzRMF3rx!LxR>~o6j?P8%sfn1iY+9vyUl|y z=Or^%rb<<|5oEvH%dgQb|HP{ZTM=e2=&j^^%jWs29)Nv8*sPA!pu` zD1}!bdxRVm#!;l&3ZmiC;;8Qn3@tIzC792CUDT8J{(uuHE9>8^A{sYK1RNHfxc}=nY1;pxVM;iw3&3Yu5`2?b#(sg=x6F2?C2OK z=^T;n95d-0UFjS@>YV)7ImgsB-_f~1(zPhvwPe!ui>sk@#cB#mP^L))dFuFO@b?Ql zf00L787I9WcV$jNxYnPaJaba@cNn*Owi0yx?u!P*QjerXK^F7Y0y!}cT55p|WWGu)4r9?^OeJS$ zJKt}9eb?TRT8Zd; zAD6RYGJ+=QB61j6mUe0E=-PPGX&g}%@N#rjZPed%G%9d31{*jMF*zE2JQ}+?nv5Au zVIE5j97`9lrB%sr&C2l2$|+z@GB`~4Kj?;;W|prGf2kg??i{ZPtXz6D((rOb-^g9~ zrCZBte=G9@&9Q3-W}=;W(rS2OFwTBx)qW`V<4Eqrz{AN&*u>27C{H`)aL5cHfCxoaC#?hdM|hSxO4i{bo%V!B*8)|qe>dw=&J?nD|yy< z?dn$~=IcH44Dc}%^>Tv1Y=-dT3~}Df!>$>!wHb=L87h`p8kt!-vswC&vy6GO%w4mr zYqM;3vkjev+J`Vld9k%`5SeevUGpka-=1mA5lmW@x_?y3F4Z^tt{4BE-1j?l>bn8*yAkrc zdDnMKnFXu(@Ai2Mc3lhBQwxqK3udH?7HbP$cMIMuiyvebeYzHXrxyL!7K82V*2NjyR4GCjn#1rhx2-a3Z7KI|DF>OABeR@sww$lA z{KaLt5V>4&w^Tf}T!$>H%3DUstTeAJx3a9XAXnO0J|;1B%>E3A5f}^#8VsAQrg)+1 zA3l#Tf_v3XMAfdN}>}4%1#y4iePd<}tT3hK@ z+vsH3q>$YtH{T@tv`OW<$&j!~Grd{JUsSd?kv_o}CjXM(nli|0i!XtmUzT3bd`p0J zTS#bIM0Q);d|M)aORQ%5#q_ph!j>E>rL63Z{HHAi^BrN$oj2V(%IiBS2|LncyD~z% zucmjnLtKd$iJJ=XOzZGn>WEPk&5qJ#5YgB3q-9H@{*JOg8rJq)@AuqUf4-Of>1F=Y z=hIK${Ga|pD>25oilIMl?MRH?)2eXNhRf1MViWYky7wcd_oGhtW7hYR@Ap$!4^lrJ zq~{-mnjhpO9OTs;5G3sv$Q~Av9hBzd6`LRC)*R+f9~LGYmY*Je$v>>?K5SY)Y`H%~ zbsyE|t8?%1QTGzrY7=|a5tqu5x&8Fd=fXK@Q=iIfappi31~^qYELFuXEod&IKP{DY zoh;-pt+Spk%APK3p02r`ZX}#8eLCG;KRv!bJ?LJdZjPSPm2`_(9m)H3)BS6)cy)A< zSWTP2bcWbclME@cHwcm~?gy*CcOvVRaasKGnIV1UR zX6*Sg5_M0qf6uuObpO6z`z?U|E%fR!E|$!4P!y+3M7l|iq$c^ePU`8()>+B;2WMSQ z>L=$J!-A~&mrUK4EYp{a>zCTtOWoSb9KV9Je;>eawzOP#b*8WMPOqS+J7&Vy7FyR< zJy-U%J5E}=&WYEquddxJu01|qyIcHu@Ak*bjoxtDJ$rc9bcUdsVoyT>r6DS%E#_VH zM4`a{wN1Z-UaV69>)+&8e^V{~rhopMeNe8BZlo&z-8y~LOmSD}?YA)Zcekwf8^0LekT^UK@Xb_Qe@E7{@oio1 zK@Ypu@AJo4SpNFeE9{d*EJqLacL5fdRV@_M#Wh)y;(@0M24ERwz4m7esEB9;4F-L6 zY?Kq2WPI@c>exb(pJ=2j`sv!Krt_OMhyB&HSI>UtvM}hU=P(^(%celX<32H?VM5$Y z5~E)@XP}-(;G$&jq>Io)iX&sL4!;24kqJmK>-5JG3E)59Up1J_hEMn=-Sdl^jpVJnu@Ziayd;dfJ)iVXsS34An8YJkPfh8g!3#~9 ziycp`SO4%Xwd8R*y|iDGC|zQ;m8k8!blwoH4YI#Dadr?^6CM)N(|ECq($ji{|6E_^ z#m7;h059g}Q0QB`H0bueO_Z$Bht*1heAv*Hftly7_gjkq{Oh+?p`6X&0{goWI<@oh zR3r7gE*fJEn<+Itr$6uMmRU^JE{!$2rmi(QEASVMJ#%FKEP0ifeOU6Tm-$oEwUdTo z?~XaDYT59`)qL^s?&QylANEf&e*}}R|FH;;3TYT6^xj?H2_IE5X z5nwzhu~5%GD6@ev9)59%%f=p7YE?5HRXOcQ9o4j4w;$O2e4X`Et*kC1t^mt!M-pJ{ z7r>sh#`QYJBI4apg@r-FIBUVBc@|A%GkuL+${p8`N&bNuokQc}Nap#7-|K^4REEBv zH!8pQjPjg*_2;G6%$rADUUOP6WUgkP3}Ng>R}#FagGVJ)5zXI~{W{Z5ill%2_c2wr z^=DKINIgM&D{VQ%3qou{-tGjleknS0`GcDZ?l4K@i)#)JW z(O!H5_Yk_U47_KMK9XsEtO;vshQ}p{J1*_anma6WSU>YAUA9QLpkmRG`Mv_fLY?)C zRYS73kk`zo?$22V7CZCbQY?)*1U3AN)G=nqS6g}wB2*7)aQsPKFj)N&FNt`QfL?-s znAG)aqY*XjBN@@X$v0Oq(5vH%=VeW^POhnp%t)>`$l0WLw?P}`3yBe#h5Ez~^EPaM zc_6Q-lHcuyj{aqJi1p#&k6KCAZ*UbCQY)i0fB3if_>fyz`MO$YMo%|sTtc<6(&-JX zJvT?YMfH1Aa$2pIoq(03n$bdXIvkOaWBO)XSBN~Mw3<~oT%}PgVJ2DJxa1~PvfEBP zCF`q~y;zatR3@7!haHwbgW$<%FS)a4T+uk!gBMYKE}uMeb{=v|{qUY9OK8kH_HrQ5 z@EZ;|A7U4uXMgBGKfroOT_C&aAcsBp`suew0RjHL9Hr_^=v=uCM{0(2grtt>y=@rH zkRxJR0&HvaHNgtk1oDb+?p26aDYqc63aQgvYOz-t9}D;~(yt_L;nJfBlceFTiV(Is zeV^TEr|rh8UrhGBLP_aRCryfb!OS(IjCs6XdACKdmozw=BfM+9IebIX-ETHD>cU6L zAd~%BCMwz9xU$WlsW}bl=Kap}xu~9szh~Ywf^VhN`Vk(8!ed0$bRvB*28_b-=y7~- z0WOXO0A&q7TBE%(b!UM{%&Wj=|L;43D+nGl3{ z5z_9&nfA~)qT8UkF3$z#5=+mv{ETDL#=4<(8IqD!jWDsyQMgVv9RBTUK0?A~BiJ-p zogipGy_>Vb@kp6G`FjUb+Njau=v+p-Sb6wMVYY8->sS3WUB95hflK@re})&kFS=^q z>?0tJPA~YBVNATs6lu0dWO72h{#a>bZHv%0RIV=5LSncezsO}2zj|NN*@ zIMpY^*hM_W`cIzu=ySM-H<*?&+wo~FjYFG9KS`1pt9K#YbyN+W96;e}>~`jseAC=4 zzlU6c+fv*@H|(~JrnR|_Z1PEwxk^*I>a>G&ev#qtJ#^EKXhW4 zZ!zbtaak?{mx+3E5?n`zv%sv$SI|RyE<)ZYYctPw{WqVWjgezJxyiTVi^HPLO?fV^ zZqnS%)6eq1kL{|)AinN=vecUGa`14ITs`VuCr+t_G>-(9TiN?-x%}K&If!F1}8M{i&4kPl#2@F&oKbMt2Bui_G6^^3X zq9mHI?k~B2>8xksxPI!hMcLy!^kN;kA^X8`mP-y`vJ1jb zN9ZdUK-2%q^iOxqd!#gpb_`AbKFRlNMejX&v(B(y;qd3k4*T+*pqYSQ_o@WdMgVz}w?eoE}d(wZ5YC_#yN zvfO1KiQYWx8?H&H?C-0R+&h8KJrmotpKdyS+@FlRn&|5?YdR_89akU(Qd`Aav&!i+ zwB9$WI+u1@ridx9DQCA0>9qW2;xr%NwZP@8`PN&r(o43}OP*U+Ya%YvU#EG_LhQvF zOZAdQET^AZcqCMQIHixiw2uKJo)y|PYEtOx-@?lL;&I>?*RekKR2jB7Zodm8C8&Gt zLT1aRf0Md367lmidSo6=C0rn0}!{jXdVCPAiU z#IQL>bF!TZ1Sq;@F}Gjz+^-Cbdh|V2FK47tVqzZB1rND|zT_CB=?Qqc{xoaQIlRkA z$_|H37Y>yAGD$abs8!~4B>}<%l4t0gsjAeqrB1(KrY3f|<-T&SdXkp&j{MEMTG4)V zl`@N0i$_V9zivP8rLur&zdNSO!%M+K;LZDL1y5V#b`|$-DD&`p0S-nf!?c2rr9&>dP!Nq1R7BZrEklCQ7>7Zn*P zuf@Cu65?LRbu8Qyox_)1(EOTtdSx*EFMq&j!DNXLALwNoCLC;; z#hFYJvM-vM8rv4DsN*3tl_TU_4GBNuMf_`02vdC>H(r^lN~Wk7U@4y0HnQ!gR7o$j z+3>iFDJnp*nmgukuzQ_m`VdN_QTYO3O+7{!jRFbvYjj~ zl(-&vQcqxVKy1=ZLFFArUgTSBPH4LbZf~eW0=}XEOn$eK1U228!uhgmHt#kp60Kyh{65Fv|S%8s38%?x?9%u{T)3LABmN9$~O% z-ho71plI?#l?1VDusdaw2tVP)5$DZFIB|L|CB0tzpGU* z^}ot@j#uMpY0uGo_SM=E$gs0YV&s(IA03nrE?e5+;pWw>@~qz4%?qi>nPT0)p}@Q$JD__SHk~z;T!zjSaC` zDwz>_qz1!@MvT=PxW~u{Z`O8HZ*4@K z=aJ(emQ}%{JXHL2fxX(6hS>xL#@SY4Q(*pdnbYmxx_^!@*c+@ogu?;^cg?&^(HWO6 zlg@r9Q29Qmxe7uuNJTc$dkHH86Nb@f%w8!%bu^&V@4m7ZOM|V!jW3 zrk!!!U2rf~$NQenJFbVvkzbyI&~l(YPnS>5eBtKN{oGmQ{7xo>VmrZco_Op59D0@@CyXg8HL zcTw(kJM^O6BrJ6epLSMG8ks=4#5->Q%q-vmAndGmP$I2SVxHmV8hUleZ2N+KXF_K@ zTJsmtrjhAI5c=gduB`7y$79=x}nD_XFK(O zkgG;InxYTaj@uRx$mJN8HS%do3WI2Os8UaW@~~>Ps?&ouk%?_cZcAIi0H{+=iOqf~ z49_uYvu^1|GT+l~5FNheVb#uNzQ!TDcGi$AuF@aKzW#`_0#l8KY-q*anaNn`a1U>B zEm-e7U*B0XOpf1x66H3oQvRsq3pN$P_RCjGA(u>*iu)wA z5JYSkqCf|*qj&Ln_BheI8$-Je1RIWfDL9|ABI4Y2Nl z9-}cVN1s!voom*@C5cr&MF>895IzOqZyrR54kDZZIA?a>kOBA=4j{)Mc1wUW6QKO` z^H-mFZ-wJBaczI$}GK0+RK?H0d3s-v~ zq4h7*Tg#~cFWa&pJY<~Bm{zjj2O?viW7BrJAyZJl776B@pa$ zEhe}d}KHUfr=LrX1=JRR;A#{!$jzNA2KOuX@O$IP^0yv(d3ZpD*w>)7# zakQ%aF|N*!23CeY-(mUwRA0oToTlwcukFeVoc#;{O-o#Z%upjsT;rSYfKf{22HiPL zXO7+j1#{pNoeS1cnT4oMlGTYVq?i21CmQEdSa>7NU-eTRr=O@#`$>fR1Z+Vq<){5Z z`=XZkQrft(hN0%Z&0_|(Ej6yK%|HJOHa;W-6L)$&OgmyfT$fB+I^!HxLrW!lkiD7y zK8Y^8smcN!LX-(2%M2lnk{ERE!d(||dMRgrFq30+mLYEKk*x6_CI!o#deAOw=Adug zE@k;ax`m-oM;ED}laAI0%dRvXpi*=D+-@h%R_lia2TZ@5tB0eiSYP2#H@fm| z3+`{RzZDZ9c=A(C6qWk6mRWavkZ-wg8){Pw}+SYz&jJhX+cfbr{0elI!HLhPR;wQZBp++07vWDTttq*KC!gbLgA_{=m zG339&X9==yb_nr#w_d(8l)j_#mZGZpvUuhYla#m@oTdReet|8S%x74Z7w8Q7t-$$= z^+}XT={}fhIYXtLg}qTDZ}+ociA81z^$lS50*5##YZDF{aGogPVbauqtp8VSq|0Yd zkTMx&HYGE+n?A8l_(`U9xUvpVT7*g#;)_?{cV@bL@O{c_2=G+|@k#t4zS*_ra#^+C zTaWmlJm%FuTTJ`KXp=0%F#f|^1=mKRm#x7y-b3H3s3wrfgsMm(LuOXiH0IY5x<(3bDnQgiVyD^$`DS2k+s z>|T~vJ4C1sBs}_;uOh@sXzzEkt3tEepL_CR!Qy?B>Kh>=_83U<&$K94CpV&+2TaVm zT#a!ND*U9xE&Ock7n4NWOzHAQi#7*Dd^AS3*HJys(Ls^As|W=TCHEH zP&S^7k4sNsS?Asx0wzv|KsdrVhGQP_zeiEw~4%ZCOOS8_C}R)O*Uz#z1)KRi`YhLC^9s=(hIh z%4qQ8uihQ>r@Jj#yZ6bWR>a{%1%hvzGyFVF%hI%3?C$2TUZERIzI`$?@tj@l@ya>v z`q$DGLzMhbSQFEFzB8J^?>3ETyVxIj#ADSPhC_M0+(>Rzrx;ANZK6DtHB|m%%i@nK zt@mOK4FfM#P{VsYgql3xI@0a&jML68~J`O5a#>sr5;s%!qz2elu;hUXb4S7?A4@8U^QT?6rN#|M>gwmx5qW_N*qI%Xxk_EvRsoE2=!a#5kUG zVO;4sk^ezqrgJuxv9tVlRhgm%DrcFJ7*#}NS#kSeB@%JyjHqw8PfzUcae;H_AdUK@lJ{F`vrd@JvLamPu+K{ z=TAKM{QrS{F?Ju!UN3e@&!!9nzX16)&ToEov!;7)#cQknv_SW`-XVhO-&pJ#0D1_Y z$=g@OxU|!1G1m;ySiE!{rgt-S9bx_)DCDIJXD`w<0pLM_SgsP7v5QiZ^;-*epPl+) z$?eX@QK>(Z&qkkwc8s~zOFoa`$pUww<}{w&p}y(7mT8)Y>V0hbZe-Kdv|toDceQ95 zyLN@POZj-ckX<)tQu-mdSuL-jc%EUYXx8iFNuiaFl0YUr>=NX*|*Or@q zv4UY94fxrxoZ&G%B5HX%+@joWo8D8Ii1F!5 z^O1i@I(Cv>Hqc8JQsP}T8Cv@uN5RYWn(X zEQjVFw5RZ=>u+w4Ki%wBY03UO>i8jx`8DzQ)!oI4+r1R_*eDk1c30rY0jP*k9#V*~ zuc;7%@}5x!B7^CgH!?C8zUBWhlb`X%$82fiKT4sC5f&GuQKP{ZZ0Ava&h-?g705xC;X5cHo|NDg zSIna*PyS@jBT-Xq`|&Q1vb;SA?j~kSL%F1^!1o>=9Js?y6#YhHCPWyENMG^KsMK&J z)(bG{-BVyliUzBYywk>gtnNwPgeg{+&r$^$*NDol?vy!wunP)QwKQEa8xGQh7tHheMdll>!U*rI&G1!!{T25Lp%Y)#KnaclR6Z2> z;)LJwO*&BQL}G8H$Yh+%@o%uBJ|j*Vuzgm+k8DANO#o^1`rj4J#t*Gp1Y&T^WHu5Y8y4 z>u=3R7CU_{-NS-H?@6FFbRapOQo@J4$xD=uKBKI!8%Fql{U+zNeFi3L{uS^``p5S8 zqbEPq)h_1zdahW+5|1s1tRG2{QPk?uV&8Of+YS(YHJ*Q#e+ks{osP}ONTt&{cT{ju zjVJh5zYf^DtiPJ$*72BmLVa{;E;H1&dHd9FOw;xEm1Zmhhwf6Od}o7KFSWui*xxUk zR&YXtdIE#XU1L#P^}yVic?(oAx30HmKShPei3q!#VfO|3MVtfWQ*;(3$3Pe=g!!RS z@@G{d;=%$@TfPV*(*M(CzD{ZJ{W)cly>wOjcKpKuYG1X% zR)POkQtA3rz%Pkb?oao6uw5y5gzenA8?{=N^puiHm`Qlh;Q6cAh!&y>bvm#+LvdHJ7%}0o289cy5*Tohh|s&hJW+IBzt0~O9RQ?Muy@%r-!B; z&RS?g>gDm#1D4i&_$2`qctq$GDLh9)N*a)UG~V^$M{L!1oL_%>L!mQlM=GK?0Nzqw z+`|a+SuLLVxi#$>$0tiwE!aBEg&qg9i@+{=tFrsVmvjwrWmsdLhTz+8Rri$5)dOXUNY{wF4E>wq99(6~TO`}3yyKku3(6wJU;9tEv!+7du0}`{L=njTSULN#RMckPpuVLN$IC?%T{XfvJ@f(R#CQ9Q2?uQ**3>T&q7#Q0@pW&N;eoD zyghmI8jPnH_y8ySJNmo4V8y1tB3zd}I}oM7gom%IK*qbY>2)*ZZJ72UC^FBF75aXC zk8&M4Zu?VaL@CooiFtesroH8a{~1TlRIs?2Uc&}h4lrcEH|A8I-Z8M|^q^Q!6IAA} zu{L#lYjs9u3|G+EAT;Jdn_hB;;5=gJ#Sf&|vvJQbA0N_P4aK7g!qMJKO?|9K8*yA0 z4yE6Fr;o+|Z~)tgQtYL#1_{=I z>gGe-8gSh~-28E%9iG*IxN=b8MmMM2f323eB67F_!LN_sfLNp7*>k_^wtwgP#fNdV zTM|tNiD6Rh9ZxM2ogy2Au7rsZ2S%wI5PtoDVEeG}Gw}3@UGAPq?xglHfiVQ%7Nf~T zVGwy~CynakbPZ8%9uQ`(a4L?l#1HJZD4&SmriD*6;<7Y zYS|WCv?{U-&PsuE@8hZRHx5BG+rAoobcM45BJ%>({Q?yV7ZnOzw(>NJ!CC-+o$in) zR}kpsPtWEVUmb^lJ|b#uIZ@{|iHItsd9D_G+H6$)JqSNYgAD+$4jAc%B8arLvG~y3 zpS^isTKB46v}ri46TEg-HnokQk-#Tv=k~k*5`s8-)k*Pzw<63L93)t+Q*l^YKB`xW zh+M@t1PR#VRgc`ij{Jm(8dffOX-7Wm(zJ%qoK-031D!Yfv;B6^x!vV^nCZ0LG5XIqA+9f9g>^Zex?|ufK7;v+gtUZ~@K)u~Xa`Zs?vBIL9KF`4jh z?J6F@uph^Vdu+nE0sy``&Le=IacV%QVxXS2iciFe#x|JFF?dWLzsq=|iK~~UZV7!q z2NIFT|4-bS6@DhfcJ9NCH|$38dk`ANt<00TvI^D1Llfu><%+8ooe%NXSK(~`!t~dI zCWJq3IrI$gPp&EziaT~@N94HfgwKUTO@}87C(WMjn_t4EX&4ol0{C7MQ1QS?%* zt_@(S-hp?behZOyK#bSR;;#uZuZz;XBY)gztP9GgpXd{wk9dnhg1GkP?iSd>GHrF3UlxTd_@oGIuf-iB8~ zIvY_C4-S5X8?~W4b#?7)uW1@b9DeOuzR8fQ^xu?r!Sr$cd~qQD)&W5=GJ%#n&NUFu zHPkd~H%IRnbS|(9dY-v5ip4GS$s$jigz% z>a}=X4ci){up(NQ3zrg`MgJf&rT?tA*RK2s`)6= zta)dPOH^m^jQ!Db-HRx_Qu`<0`0l!Yd8puk6y<2-fMZCXzl+I6U>;r}o00&|BW?Ld z6~ac1i-b?*g!yq8CUJ!gYXvObcq(wX!sP9p`sw2w_-z-pTS4ttP5i0-H2WH<8%(&i zL_PBI1d6@F+#d}3Ac?)}_!Q9M@7arlT|zUiZa_{Vkb9*&07 z_XKgdKDugPT5W}QdN|x?2^J!vPqv3s&6F*5SDg8;TpB&xcRZqP<>+hy5E!6(IFf7j zK=|W>kcVDM{uI=K+EAT0M+!&*b)?jMdbC}isg?(wV-Q`Oyl*1NGPUJNx&nijS3hbI z#G@Dx`T$Dufxr?6np6J~w(jqo^FR;pZ%GtYA9`# zJ}pTuFZBD@?WxEIDm+JkAWRPWT8@CQ%~1sVALChjVXs2LgF^w9rvT%yf#p+P zv{4BB9{^oIqQ60v|1beaaxMwZ7KDN-q=Jcsxfx*scV__u~O-IIrv<0PLl8GusqD{yR zZ~8hvg%TVCuOCAp6oPG#sDhp7g{G*+R>*z|g~M*RrpI%$Yx6hHtV-@IOcCTunsiE| zOMDMEeM0~S{CF7Hc_#Cy0ti78Bm$J5ySfXN66m3S`2PnO8!=Exf+|FD6nl9%guxWg z^|EF{vuZ&kL_s6~yc9@6!591%D8g`nw+3W@1`Kxwgg_RA02WaEd|NyeaFv~5yW9Ts z;d;DZ0f93ehwPO69M9=qt?9_$jwCQ1!@dV#IQkYCyiW|G8l!Z_y zO2vW!D2n6NnM#U#R%l&F9MEq;X9T^Xg=FJZh=%~$PdsL1PJuD>dLcLhCoa2+Hin`) zg$_wUtTF|uQxHu1e2ve=Qp@W31+Qp3wge!71n_wX{5S+ez>i}=2AJ0pFhRm7ft4>n zlP7@^pbk%D>jdPIwst9XOaKy)0(Qf7Du6*4VE;iHl(N+}P%qFzFK|>6BtalZdAb8Z z6l8!1s6Okjz6gLo2!H_y;Qfyyb^-)CXy^XiFK}qf^>9YKB+8It5kj}ek&$P!{DmJnegKnVdR3zQ{G7A#SqWak1Q8Wng98dT#L zR%Ezr*g}B{1tt`hOi&^<3cFqMX3d+WPX85Ftg_^&QX`gD9a?jE^`aF4K>`2(fW$?R zh^2^?E5p3hi-Bd|yje0tL0OWp$-;*XCq}$jabw0BC5V(DWs8)^9HrQLi11e{Qlwh7 z(>%JJ=g|}YT}-|CU%SVSVZW9g+wi7;7Av-ExO?FyTfTj7v9;wNso$*%CLwMMbaT&S zT9GkM>R<5T!;2&T*J_Js?$O(Uh7NrTYu*bV-kW0VSo=ba{B4)Asg*r4Tk4bALdL%K ze_OVoj<|sU^es9m>LUZe^B8QO~4Iq>y5x1SCKpf(%5+AOtqy6aj<~KmdWo5bop) zuq90_(a$~s{Zr6D2_4kXLQSO1Gzy6%NHp(kX(dw6J_{{UTS^1XJcKrD1<^x6{Z!OY zOXTlD3vGdrvsDj@$e{9=L#{sLMl&w8?R2B?AL%l*rxi(eEsa9Zw)>~TfubXYA~JN# z6}r}3Eht)5TcuVBA_&2Dh(#n4NVVG{((Tp@Q*|{}a0xnhT!W^Ch*fsql{Q{#QF9lg zZdbbvGLtTojNgAl>bIlFBL9d&r3_rc0^ykKoJoQRq}r(`A(BWW;3OhoMJ+P4m~1jK zIaDG7O=O8hmXlLaC1rU|J~^y4#7e7|KE$Yn7U{^?q_Q#-h=L`Re$GOKyuiQ{;h=xU zqTqcmZrWd`2L|}*siTJ4BZ04$x@xLD3eeJaDx)=1oJqks(_g$&9~X_E+76KK;17ivWczzHwhaD!O0=N5bJc__ZaA&*>g#2q3R!^<;FRPzwc z7q#y?=Hn9mwNFfnPKm-j{q5&<)@n9H0*d0xWgc$CTHhlDBANwc;=~yZwwxQ4= zPm@SQE>e-FssB$wY_UH;{*jWCRE!~8D6SNe@Nb)RP~r&kxPOS!lcgLX-z;~k%V~&I zqjF`4*b;%!MF9e88XcNkw}1sufB_5$0KqEQC0g`>7Q9f!98@8tSuD?Z#*>AWpajil zPKlbTa31u;$cr&;0*$1Y#3m-O1s+9UhYu?!IY(#5(X9yyu@uqyUK!6;&QqTC{L>cb zBPj|2067uD+&@(r&{bBh74$TyJrVk+4xZ|R)Y^>*A?i>Q&dXiZvM9VRDzA(>RHGR6 zXh%WHQIS^kqa$5cNJ)y)dgaR^`C=*FUYIw#(d}+iLkR>7h6Duc6bTAQKu#Dy1O_mH z0R-3yQ2$Pngf;XciF}|1%*JxEIK(0jEz?C7ui7$sghfkS^kQ0g(Fb0TX>qo2M=MG} z22N}s2|ZCjPIS4Gofb@%OVeXgVXC#7&Qzv*^(##Q+tX(<;dPp!?#W*WVEfIk9~H7DTb`=R|e7Kc1CMTg~V32 zwH@JRRteAmR&awF^eu0HdqL2ZublvJO9T|4fB_V>0Yqp30T{p&6GdPZzMw_)W&yKh zmP`(*h~|}^30^2AkD6Uv!*#*h3o_Z_7Oof|8KxkCMx=2mH^{;S) zoBzT83K+lxt{;IBd|(CNFMjy+pM4S_PzmdH!iZZi1~1%O12dSzAzCPg8oCfu9V9cG z$XRP1S(;phrdKT94zO+`0qRi3SjuXL1RkYYUp4EIw%w?Yfjqg*xT=Lk&WI%|$rz$+ zQJA|grk~-4)v%-EyUW3Rg6UrV4>>Cu$a}BwM-Q+6U!{T6h<$N0STvZMJvj{ z2`(rB%0v|^5ptrD!62E>N$&HXlWby5{YC;V_2e%k>1Ra)+A)~K&1)H=vrX9pKRBx~ zfACWt>44@}UNa7T1~(8va>qEr0rf8=%^&G7=UG8+psQgmIaCIa!W2sAtwD8H3I7OT z0rrKieV6;zcWy{y*F|qHwv^0Nba%YrJ(-nGmZf7}GkWP|MFLv!3tPN*3KQ@(bD=AM z1$Za|?ZoxD51MXtBg(=0EYqnf7jMeRyOW@#^t#oZZ&!X8RVH;+fJlmHX8mS63L^M) zG&9HquKGU?2~dEf^YG{dt2(9~$ZtlRQh!tQq!Qiuk2|h$k%ye*5e2!)OIp#DdP{+Q zd#PYy?%B>}7Un2%vYm&zfFVqI$vvY(Er6tEraG_8%N}zUT^1!-a8WFx;6pFe3`Snm z0s*c-WGmW03MwoC%0gv=&UsFAne%n*e~r1=(au@2k7Pf;5{+_hMP!c$eE;t2ipVC^ zZuYWkcIJ8iEZh6|kf1b29YovUvHmMd;vKahRK_R{TnK?hN+V%f`!(v(g{O=&kz z6=I-6daaEBQrtpPrN}xNs4#)$#(n|f4nj~c%=!Rlc>CJlaQ4A3B8@oMIIf`%=p}b= z)pP&*s9$~fyB`^TKP1Es%64kn@r&j}sx_FR$k+aFJM_aLw8K{f5IM5$k&vT5Fb@4T zX`)0g0@0&YaKp%AYS9)gD7sGP;7TW`4C=rt%Xk5*QXvhDuFG7e%>Tq<1-mFrz$%Qy zit6~otlq2)NTCXrU;u^yu69r-lmG)64G4ws&m=(5Lc>$qfaFjJ?}D%ihma&34I?1! zwss>~B=B$?@CvVR)_TSC@a+rzWcnCD+{A4F#tr*EWU0gm_q>D-!axnufUA;8_^4?O zoX7Z(j}2J?0XQK;TEP`ap$u?>`p9tHfJxsF5eyYk-MmIpZj3tUO+q9w5-HI_NN)=k zF%$J|{)~m=P!6R^&RFvA<5DgZPtFrj@f20D6hDy^L9rD@ZsjIKH2`ly{O;^-aqp6V z2jPm>a6)8+A|AL9nqAu!qfflxapZ^Z&&02vIpn?~FvFG$I z?fUK;*De>mF&zD+2%)1sSZT=WPVVS#qdbN0$T1$fQ5>NLv{+8wv@jnVBn$O1^l&Sc zbnEokZ~eTFAXAS<%#hd0Fo?ztp3)?W#y|@qaty?P4aQ&%o(BuUAPdBRBR#SsJ5md> zfQ;B+6-v?~DUu?^0071yvi`6XxBw>#u@K#FAm6Vh3-Tu84=3S|w=`mq^r;m9z|;Ka zQ8;fj9Fa6Gr5%nEkxBz?&<0R!aw>C@Dlv!?>(9p^upb#>E4eZP)v;SD5I3IC2~DCW zcCZJZ%mWXjot|ipv>*eZfQiO{mJB8e=n@JbAc~$yXa7baXUIr8+JLemr3|J3Dh9v| zaiRyyvN6rlF$2a356QG}#>Ad7XYdIVXGLdpCJE4yGc&U@A@eaw^RpI63RNf}7KID| z2NJWx^K_%NzH$<0lPkIKki0Mvb(2uerx4BX+mHlf2n8|_KmtZb40wSRw7|I9A`57N z7BT<<#6U1SVhT9n4;N>FZh^i2unVeysKn5|cuf<@b2rU%IF*CbD#YF<#WK!Bv0@Ae z5@0^tMgrt>KC|XL^^-iYk`zab$PmQDY(rRXQxQWsR726lURsV8Z4np2aUM$)ZvTS9CwLIbjOqvDX2}9W1$bc$pr9in zU=(_Rmck$dnrzfg;}-5=amuO{yr2pypb5HesHO}aO;jG4^hrt7Nu#t$H^ju;&aosy zGdu$mI|5S_q$6f<9H|sab+Jsv^zViYHL?&u{-)B(W?1+GK`^aseg*OP4%AbE0D6?G#H>%j{3SKRY5d_(*OXAAbl zDrq%QiB(o>HFWxuHv*(x1S$Xa=0FaP^8f5Z&~ipI2IL=POjbxi3Q)^4sv|2U&?^Pi z)mCUMTj&BylQesR>u~Ptr0X#Z1~9Uq7qXxuYKAQ^APXd*r)(8EtWGn46i7AW3_8II zj1)<|jse&*T}QKFNz)vE<+1u^GWBC5>_a3l#bGtp38OGK&ciheZ$iccY$i@TIxm4t z15X_e(S}3+s3YV0F;K_Vlx}l93$;8mQMrnWxu{PF&~Q*900dMZ3m{+>sP24LVGRJ_ zbUbxQ^2w|g=OTjC3cP@7Q}x#vK$nDbKe-lXyOw`|(q>nw(?Db>)sKU~#%tB~Jd?FU zAp{cjuQ;TmGqyv346s^vg;)yoR{tE&R}gDEF4RNacH}0sa5q$N5!V$JHx}8krD{=M zPIOAi6zw#yT^XPUcS09mLIg&K7VJUj)rxdETNGky6@N5Yt zmmVY6Olen2&9n$fL0GVKHMF#1nFa_v12Woy4D!ZyYxhhgcX`Lo9$iXiXO>)}Hy^RI zvI4SLbrO4pl|y#W*I;i97ht()WWYEC1H@oQk)RgDz%JBaEf7Eo>}YE@WD5L8RMX=Y zO2IpevWWK<+4128s#`jMY00KHPI>*3!qCf*ifh{y(PdEoZS|MspL5NM2fBARo z79aqAc5MxrjMGg%Z#CQg2~#|SfgRX0clD4d`Jmd?a5HpqDKv2j_i)$IlRG(+LwRsF z*`z|~DeL22T+W|nH+gS2selU4d{O71Y+;wIUm^f7a5y9iCInohrXaSxyr2_?S%|%p zDWF2nloxq%cbT2}mHz=tk-bJV(o}&32b!7pnO%9CK?1b!rHj3|l)yQhBPUfN3E;x` zW@B}N*?D^vKmzc~H=hi;9<@)9Knq4keme&NL^1;qECQ5(3#z~iyxu-UfD1UmOkCQEnHmG-Gd)w; zcQd7>o4Tr>5R2_Wi%mM#KxwOG>sSc2kt=x-pifu_zo3f= z2>J{Px}d2x5dX_$tPz>7>&Y$LLJAUyTy(Xs4V#ij+N(p4gB4rI8dpRm0&<%fo0(Z8 z6u=kjEU2`R8&TqhSRy3q0s@xI=1}-@pR5VIfT)G~6S}|@p2Iznin6tNvblLov$<)2 zz-wsDOB18ATbZ_j+qMP9dHIHs8;2q|54kHMxjApSom;t~ySbyAxvBfPrTe<8d%CSV zyRmz_y?a!MTw+f`2fwRt!R5LEn&1lx+7r%Tj}1scI=a3;nxaD*!z(xefB-ty z(~%>2zW+6x!%h4u0jjJRX~p5Y#aaBtT|CBNe8y$G#%cVK_0hYi_DnEDN9LpEl6;xa^tdSJNykCs{+-F<3)1B`;Waji%c7iD?;8dyh>#No~1DOg2Dby8*kt%!>sM^fg9?2*}&=L?T<=*k4gFdKvvj0S! zOP#*$VF;_;LFoZM@C_oPR|(bk^L%)1(ZhG)zqb%Ce&Qqk;*+4E#eSf<{PMqmYK52! ztWi?H{p>+q)FZ_eoUbwr|Mc~ZC|7HRLvU+dhC^H2UXTA1st!?ergjhOp3^c@6 z>LC2@KRnOG9txC8d6YT%_>~`%NtyXM*>TfUvejL-v3bvG#LA;gvvK0#ufF>!UIC`S zn29;UA-t$P!3^HP72NCWh4kzbN#!kk`jOq<<^SIM%GGWC?yVQ^NnzCiB1r;)NhA;) zIM5(Mf(j27beIt0!-WwkPITCCVMc}$H&(=WaMLe)zy6K<_sIy?&lH?b+yPgZ|udymxZJ+j(=>4*t7%@8p3GCR1IiEtGyu z+Os9aAnl&$6Fg1QoaN9~@i(;skU(wmxr9IAvVwNdt$>o+_b_wP|QjkGPYEG3@5=v>B zPHqNMO&PP}u^6Ev=9N0D>E?%4(~wzG~HU>Alz2V7AtZ>#e%x%ImJa z3b8%Q9aTGtD!*({eLCH%C#^jkn!(7p-^ReE(h0CSDee>g)*B$lFv&do)TW_sM5>rf3 z%GlRRh3&LS!uF*3)~ydGZDee6+w;=PpWXD)*H3@-_anCjDa}RKmG@L-c|nm>Pxf~` z1ln(Y)>|O{8koO*rDr|J;|ixLh`|hM5LSKi&`6Y~rx4<4gm&6qAd&!xBuJuvZfjBt z-DWl>z0id;9EqpmCc+$&aECfX(V@uD3c|T;D{k_coQC*1$MukhOk84}_~fApjU_$r zs!%Iv_Z6dLNQ+$I;s(FCL0M5}E%_?rz0PRHiT?lrg^2(}8zmu$QgrY+Cm{)H<_ISb zxeq&OM57=32uN?C%Rdt$;1~^Ao%sZEk$-F?z9bkO3O1@tL*&^%ZpRb<%}jZ!y4e+1 z<|&<_ZYNoxibyPpGn9})iff_@O3D<(s!&ptsjMX}Z;47=8c~;(++{9*>C0gD@=QY; zno#zJxnxf6ZkJmoGMyQsBqRcb(v;>D5M>Y3FlkC`dy*|&@sn&SPn+Td3Q*pMC1q+Z zbIfGtGuNrkcE(d6k{F!w!igrt#VK}qG^T6J$*|kN6PnE&s6pjPP@E{ZV|+6#%4A{{iZEugPI^-={5;?AWR_$)u&2zrcQn77Jz6@_EqO3 zLDd!=o%5cI@=>N$Evrk-O4hT+1(Il?AWGi~*SN~{B_8aP6Pt+FyCz|;DLi2c6Cs5a zP9i_|Ea!XNamAx5b~dwVg)7?O3ddft6m-g~W$%jF9j0qxSu%V_E{ zi`vUx7K(j>=v-e5+t|KJjEQ8VZ5`RjHLmfdNm!#_#uUV$x<)ppqRkauQHtXx*Rjb> zuK!3;1}Vhvw$#OKb#a9*{{=U8wEr!xc1@MoD+X7*&vle_&wE|;(uJ++(NN873Cv!~ z_r1KNZ+z`5O#IHbXZ!sbeDllSngxxaK~ZQy5qi*fA~lSFdssv>@$pZgp<>Bf1^Z$_(}3q5G+ zv3Dj+ZnUExJ;1uU2860jt^cL>x>vtSb0JgE@D(ws%_?nT0!lELspErc36#3htiH6X zQmsaF_R*~2=ulWX@yizhw)zF0Ad7`1W+Xy!h+Gnu^ zwXY3;6}^ScZuWW8;s5+}o+COu--hK`1{M*gA6n}@hx*nTxafY_eC%X5-W)yDYhJ5; zA(#dPiTcMJGg%zvYp;9Sd#w`}U(qS1qWj(L4tOs8+D~OKyx~`6Y?ij0-N?prZ+~+j z?V1Lt{JAwp7LR$xXC5ytPOMr4y?M=x-dtgKYrpLcVASjT->kp4>Q4{w*9ScHv9G-- z2R!hCv;5_|=eUaXw%3njr1KRvRq1wIZjbZ+_r6zt^H+YfA3oGf=uAHJoiB3cXCM0@ zEVANC;*P_MfBa;@`K+M)b*XcG>glK6Uh}dSoox7_cS3jJuy;)_F zXSH)BW)^?^$Nzr)w}1Y}fE2?o@J4^!8U<0D1nK`JfUZUqxTS8Knjs%Cg4?G$ajN5h=aMM6D8MG zBymOlBRJ(IgiVNpr8j%4=X$m`g{?<>Rw#v6ScO}tgw3D28oimh?E$KkhqACsELz^iH*33N*+%7>lVWi*-?puGot3#~laAi+3Rf++u=8@g7&SW4(xszqpIb=!?vljLxWx z%_xn}IE@CODiail**Ja`IBC@ddQ1q8ZxN0KF^;-sj^$X6Zh>mjC64V#j_!Dl;#hJO zW-Z!eT4XQpVkN@b80SS-;DUbnaYXpgq1(}cw8IbH)Zv8_Fn1nWpgM#p* zkQd32w&swhwvp@DkRQp99ceHkiE9=)k|5cSB*~60Xb&)`jW0=aG)ODTW_eC%E`fm? z>P8ni`4(H?c^<+V;B}0`cV!L4lb5HHN!bwIb}r{)eM?!COevLm1C>Ncl#thXM;INq zUJWak)tZCv(SCmD~4Q&*yT_ zCtZB0H(QWg#m9Gtg=6_RPi^5&dC8bm>6lh|5sFD-+ShxL8JM*}hej4w76+M?*$|TH znUv`?ps9TeWn}*lelV$;G&hK~rHoRhW(c@`3S^cE2tlC}M51^mu@OYcwPQ>-J-1Sg z&`6xaxf`JOEwd?`R~C%Zw=PN*o6V?ybP=1=nSa+ALGQMj+c|99=oA;|L)N#4B=VQ6 zwjy0dkK&|FNr;bGl810OLf{FX6!D(lCXvJ>W1Jayf;OHhqH7_@N$!RxPNn7KlNH>_FWa%5oiAHEi zg>Wf*ExMv}>7r{%moeIwa*1E~sZV3rmkjZgqRD-uDNv!AG|oAS=2Rs*2AP1fhe{)v zKIEg&w-IybS#45``njVjN18vXrE?>mKh}p0MWA7tWUYB@3K*Ts*?{2@i`ID;N zs++^rSdEiT%9*C=$Dww*fZMT(org(vloGEqqPDqy)rp;iI#Y)FRM!|uV(O@{<((s8 zC;vI0BUGN5rF5JST9a2!86{>Y*QNa#BJ#PU@7ZPd*-BwmS$D^umD(kgD*t#s^@5K| zt8rzZ_)?P{DlVkCc!MLM!xd(&zzG-1KqlHN9BQn)IuRf`E8})UI9Q^(ii`B3qBc6C zFKVqc%A(kMtum^uFp7J3iEx*?d|Uc) zS+LyKr5W+1F!6_EOTQXow$1pm#Yv6(8;!lVxR1-YkSo9e%>TFom~-rT8vv}pi95gx z{J#uLzz*!V5G=ulOTicXz!~hgY6g)dJ1Z!Qd=ZSn6Rg1&{J#-$y2`p6KtM_pBw8;# zS}_d6Gc3b3Ov5*9!#Rw@JFLS!%)>wI!$AzhLoCEaTv(D8Dh;_pJR6cI$&pTMyieT3 zxps&rNyUa}#n*eqg?K0?C?}$ID)3X59=XM3ti@+syk?xnXiUazoW*Ml$88+PZ`{V& zHH>Kj# z%WTV22aIF!kpQ|Z%%i)@xlGK%Y|P1A%*(9HQUC;bCxC#e7RHFo%zVt(?1`Oti`vZ1 z+w9HVjEQZViD5@@VpvS&e9k$V&gP8H?X1r3%+BvD&+$yp>uk^Pe9!Zo&-IMY{jAUa z%+K;Hu8|p}I(s+j`@QL_(8rrDZE&Cc>Vt8!&cx4JMGgwJw|-NvWJSl zB^hesNXb<N_y&>aEDf2_uGEZKByFkSX(Xp>I>C0-r~*>2p&j}6+9P1&C<+NAB-ogK#{r(Ji9 zwcr)Tqm9~=ZQ2Rl*kFQcfig#A`qR68NP)`RzYWyDE!@FP+{10tEP=KutQ*#>%+(CK zRwrD<$RT{|+6~g&*v#D7?cCVC-PfJV!Sh_3y}XH(QRAiE+>PFKTg&&-7UaA*MwB=% z6W{MO-?@}~@Qq6KjoF(2mVWhbKk~9sVUvNOPSFo zz0ubzYcsaIAU$K^6;KpT(i0Bi74G39j?eg6+GT9{Nm$D-s2~u7ES)+LN4V;KIBvW<3R)D zP|oB@9_3lSZJ?Cp}x`3Tz5nWSY}yWe;(sdNo4MiU3)`(O+p&G?rLF6;o$I(x z*Dq1iL`w!6;iybkQOjVFjKNnh^e??NaOaz($BLdz<-w=!u-+iSwoET zofZ7iAN0lU{L=sAr@kI^jZe|P{dnAi;?MmqUzjnh^HVzh;(x>yNUCp0$GuMfz<$Q7 zMC>Rt*R@`G%MK7y1pi79Sa6`hf&>vtQHZdi!G{SKGMpIk;6jTOF;?Vwa0{tcA=|ZT zXUm?+e<@Y|IyutimW~c%LYygaBgP~Na_-dGljl#LL4ghxT9oLffA&}|wRiGfQmFQ# zPL*0UX)CEELz22m%2rCNVX0C@c~b1zq-B$`Tzi)7S+!`ZHccyc>{+^QtG<1E*Kbq1 zfs^L_8?~=s#A%aASlpQLW54pgD&oJ=(PA(x^FuY-Ovp zRj^TAyAIik)I!m!b?4@ty7%edyL}G_PF#3#s=fa1 zBhWts6>M-p0NV?Y!TJ(RZ$1bST+qVxCgiXxp%@EsC=q`u(Weu4N>Qg032Nv?n>3OU z#*1c*kwzN@VvZz|OnUD;uuOWcwvlc$vPK+}JTgZnl|*t$C!2&4N{~is4LbecORFR+ zVT$t0DW4RRNft>ob3`;vJX6h{Hd$&wvkFUWPC3b{Dy}-|)bp;l@Z9syJlhf!P(lNp z)0WIClR{BODO=RhMjay!CeSFIR5(jV%M`UuEv=MOkXTboCE2vH&9*HzAp=uZKXvue zS2b-FR{vUMjg`|`ZLPH+GPWQi)Y)ExDz-bD+eBAnalO^kU71Z5QfMQ4RN6=(o7URO z$RHLfmV`9RTX4S>H(YYZHMd+Jl{$A_blG*cU2mC!_g#ADwO8GH^R0K^c-3W!DWd`= zYG8p2UQDK&5LTF`gc(+t3{`83msAN`stqJnN$IRchdYkZV~#%-Ib@P$1li<~Q7$>v zk4|;TM~VTor?ysDR{7?Pa;~Z5oC)^XV4#1_2`L2Cy%W0UghYC2rJHWa>7<{QI%=x* zYN}hK@y!}*maaCdYpucN8nCgc68mei(e^sswYOF~?6lK0J8rkxhP&;v?H(KNL%;Jo zJpaJG(@Z>c>ph4+2<-;=-n!vyUqGffoN zj2?OwRg`i}FtHEQ##Ddh@xUK1Oi5|mel>rS?5|fpefGC+Uwil|O0|tp+jtG;@PB-| zogFoH|Nr>CPYTatQvs)E!0J)2P3w72p&V!^2tH7P5v1S*Em%Pe$^}u;!WIV;#y7?hj&qcw?$#JIJPJ)<5z$%0Qr5?X{ZS$xVGg+#$GV;2ERldb86yShN1iQG zlB+plmd1C;M+P#IkW?fm^Y}?U5)3I{ykIFacuG^I5|yh|r2`SQC|FW4mb0|tv}{>R zTn=t^szco_lY^`g_EMOg<0UbDIm}`j2bP@Lf)0;qOk^I@b<>2MWfCAev7}3zaNFkC zx{0=LhLfA)^d>pMX-;vLQ=R8rXFA#WPItx=o%3ubJ=JxecC-O3Fmln9`u};5e^Ml% z{S;t90l2<{8Z>|jW#~d3iqMBD6rvNAXhj=JQ6mwQ6y5R)dmtAQSF|FewE1XBNqSO= zrPMhpH7QF`x>A_7G^Q_=X-#QLQkvydr#t0oPks7RpaxZ_L)|HBK=;DFwBsX+31Kxw z*iZrIbE-MxyzN9rKF>Ap$=24NzL%+GMf8^W`C3U%>VK?!2Shrfdy<}0t*wr z_hm3PNnsTtv7#QV7{_9bYShJ*Z?qxt9t}ww*d2Yiu^T3_XiY5Q5~KLUBVKWeS*&6h zzgWgD9&H=sLm#X#Fts3Ri~@U%Kmr;iq8GL3kd2JdBNrLTOIC7|iTvav2RVU2{_z2= z%o8_t@gFo}1uHTUic!!arwNdPYNfChTWq3bUb!%blK_)do&Tyip*kwCB1cp_=ULBt z=5wF@%xA8MMZSKLO%>bP!7C;@gk{xgTE}WuM>CqMk_IcJAKmCnPukLyMr)=kjcMgX zRn&^ED_RCCig2i69ex$aZO-f&RV_zVYCiMne)SOvsM&wN$~CTa?ZRHyj3GwsY>SN@ zV;UcO#>!4MvYGwt7?0#YKuU^@)#zH~=25o9<@RvBja=jQR@~txcW}pT?s5ZH-Ni+B zyVt#tY%^DsZDEQ^*)a-wOxU_1*-SHiRWmiW0%9(#VRgvx=1pj<6>9cXnP2_fhc`UU zg)HxSEnabqk2mAz-T1{d{_)npcPt(K%LW;|U~3In<^Kp?`GH-YV3@Z&<}9cA%U6DK zoQDUSQ)w(KR1pqQsN=7zC3>nRx2iP5WZ})cwVFqwW`=*ng;KbUQg2iBR7pXpn;25F zm+fq@e_iZeCp)yqZuZg2Zb3N)pM9K1W!J`iO-Y6_lk4tey64^QddK_T{oeQVNm=k! zp7NE0oMj7rw9DZLg($>)v5!zk>Qo1~`4Z(V`<}~hqFMQ+^Klg@qEA0e0*@rRxTK3t}J{J7q5C1=BwLgCIbAS8mN55v>fBy1E_FOJe zW4uAxZE(Ar-S7VPx%r>}|MS278$kRMzyeISM6y45YZH1?7wM8Skn=c>122s+q6xe} z3CzHb+rS9qKnyIei>b30D!H7)xtX)Mnma)ilsOhm!4^b87+k>uD?yZNjGcq9yFG!6N*td(x1%7(BW2u@d3CyNg07oWj48!YZUfz_Y?E91|v# zp2GXW1*(ui;fuW}!!b0&drCtxJVQ2ALo{4NH*7;VoWnP)Lpij=ILt#jyhA?JLpN|NMuAwghWd$zF1+tr!vInYpWaN7CH*W zIub=v9K|$hqqZ}}QiLN^R7F=@#Zknz1q2EL>^}rNK>fqT0K7$8%*9^ZMPCHKS`1?4c2q|li$`~q$9Gi1GQ>xIyhneuM}QQ=fP}|={KtYENPQ$o z{(z9TGd#lULNdcbEu2V+tjH_8$SuT3iqyy`dq|ILLIXlPIDtlzjK-2YNs~-TRx-Iw zY)QXaluP8jO2kB(lu1gw$w|z~nEzZvovcZoBqGz$M4^nGZ7D}Ex`#0G2XtIYE$b7e znVP4hny8G*RHVnIyvlRLN~_FDuG~tmG{>*3O0XPDu`Elhffu9+MPsBzT^vRO{6)9q zMPh`@wyaCKyvw=F%eOq4wJaE9EX=2|%+8#Sqe;xk-85O7yojjRFaeRz# zyiIKcM{dN;-ONqi)J@<#j@o=3a@-JpIZkjf4~hvNQejRlSx(3d5^*`pbLy9Hq0Vix z&gnE4?9>|V{LbnO&+K%U?*A;$I1wMPu%rv|kPS&kh=jYG*vO2WPx-7*i=@x{v`>y) zviEdIY|FBRBptn&8v+fB!$^zAOi%@-7{W+H!x&HljT1C{&;q4U#5hm~y%PwvP!4q^ z7*dd7$xK6`%}(URw^FO0^vOq5(V4W#o^;WjTu~ThQJjp?79C1b^F*{TqjZs%IqFfk zaZHqWO!QFD?etME0@AUe&LsUJB}E$~<)SB@QYdAkD7{jxl%x1MiRXM$Gm^zms?UMa zPyEEoy*yL7MAKkYQ($bEufB8NYL{P(ImPL zJIxBLkd46b6Y7Ay!v7G7e;~P#K#M)S3qJ{o$aGYz0Ew!w4NWDBqJ+)78qwj@6=peA zL`+pw^-Wd{re%6nSB=$zkX3=8Ral)>T&>kyy;WW9RbKs7TMgD-6;@v*R)la>gFx0@ zP1cD}R$pb-g>cqaO%463R%$Jr;lzyMe3Ne4ven|cnF$+TnHsZ@fVAuu{=BjEz~S zlv$~yS(p{SA^$&0% z%%!}9%TT$I3WZ|{h~Y2`q`L9oSkc)6^PnMyYmU+F+oP))Jna)R)Z2e(CV^|FyAs@9 znK;`W*Dd>7)=fGKgc#Nc66Gw5REbSeEm4b+j>)n4q~ z-l9ZF@&A?H@hx9v4BwO_g#;i(=v$8PZ3N4XTs60B!}2BBVf@;dlkyI1AJu`C$qU)Fr*6SzMqC z$)6*J5B1CvBwk|hQDXFDVkmCnC{AJ^Sz;?rVk*v`RMf}*_+l>(V{;VaF1}mci4P}E z<0yXOh2&y2cH=6>VmXduI^NDjlH{N47X3kBJQwAg@MV*Sybq&b9wVB!B zGyk*U+i(*puvG0eBKcZ4OYSJ|x!uUsmX4J=A8t;uaNO}AB+7Lm$bAmHD&z>2I;mjS zQdYP`y(NuN60l_YbIZ8zGiLCW^UeQzX;&!p++0rQT7NYsFS<|j!b@gx>2rJ{`pgIN>`N_ zQk1|FR6N5pyI1|m*Q5)%MrE_6lc%KHsH+=j>L_4D2G@yQt%?mePYt-FE0U$#D0otr zUO8pPg;-2p;eiWOduRjCC}Gu&=tA-eT?>iZnUDxE<9B?!76C(|D6`|4Y2r~Hn*X-x znnoU-zUiILX`cRRpAKrA9_pSZYM?f1p>~jxO%afE$mY_qL+#K4#ZX3FP^(Ufg%i0X zGSC&qP^s3MuLeXi%nQ1}TDkCQ4Xx0?fWxvtYrKtWtEkk#h+jB`Qyb!pZq93O)@#1r zYrpPm#Ndp%iYr{w(Jc}qFJ)o)Et{*hYUjM(et|A2wI?Q>>~&J3bdl`DZc-rK?03S_ z#Rj8v43MJnY%c=S0(xm7R>C8GVlZZ6*Jkb4Zfz+(m>Mm~RRxN_?5*ry)@c$mR2J9L| z9cwrAnzlf1w`q$824DC7Uiik3J5=wpNpA_Q@Ab}a{NC@hv2VV>k}{<4{?_jS=kK<8 zYo43t8cYD!1MI(ka0icY2%m6eYz5og#0A^d1F6}W?QjnN@Ee0pYOCTAM`CL8aF|7L z#8hz>|L_!dahr|t7Ju=yY}xkQkA{S4kYp{S?(w4j@uLRvqz-Z-A95r2@ghg^BNuWd zN9rx(35I}A=n+Zu;M2ywaxBksE#Go3?{Y8yazXuz|DNXOB{eA+B??b-314$HZ*w-c zi$Io?SYqGkdtWXBb3D&;J>PRa?{hylZ7xzkm}FztZeu?_bVE<{LjPa%GgkCQXLLe; zbV-kNO7CMwuXH}n^gl*)NVoJ(*K|&wbWay`P`~t1$Mj7%b@V*Apont&qf?`i4e#yV z_onsuo^@QW^<2MoUGH^X|8-jr_FWftUnh28A9iGi3Xh&mYK~7gfA%+rc4?3HZr*~I zRtRwbT0o`0)bQ~MaT6zTZ|`<+f6j0(ad9tqazFQPH}`Z$_ip{#>LlmJ;rS@qbd66%9l9!WTNHko=O!vOjyUUwdP3d$a%0Wk(DWeVt8=W|P1BlgE3#&-+&Rn_8u& zmfx`vr;fsPY;{+==9G7JPYM9O@_B!E#a9WUm}fs$ftMB&-^M@X?tHnDW{?! zqv(V${e?Gugg<@NPkq*Bc-Ke$*Uz0+@XsiJ=_$WkE1%~wlN@>VRElm?lrG>9p47~& z8Flu0Eth50icAExjjL!4te$zSR$Z*!vVBd0eRbEa=!(ademwu@cnxY_5t{SJsOG&t z|GZCs^mp(lFLP{ne;c%OmnRjFPzm#q-O=Sb5N75}HXnenx22Voc3axn`loOq!-ftW z+S;U$45=;uT45yBiWHem5r1iXC~_ppk_r$06IjupKzkcEQtY@fqAhzSZ{p0UlVr_b z_Iv{UDKuz;Bt?%JO^Q^4(xwTdDEze$=s&4Ze^#A})oRtPTBUNO8rJJouwS#5McdVE z+Ocfcsug?IZCtW&>EfNMx9#4$edY2E>{l@0!G;SXwww6v;<}6#Lw?M56Vl2~r7*Ru z*{H;!LT!Rhm~tYig-}~{w6*ac8Pu%p*&-Eti^f*}Hm(2m$kDb!o4ptM9{qdxKZ6QM zk&>u!OGo4hVFr&5d^&OI)u{{rCq=ZB+z~If>P)dF8GEU(qt9+#J@)nP+r$5D8}w-U z_H89$sy{#f%t@s57a&tx*jJx{1tNH$f(bIXpo0xU_@IOlQaGW76=Hayh8c3Wp@$uU z_@Rg#k|Cgp`bh!cek%r8o`OCpR8v&F9b}6^sG;UkX&!CzOOL4G#*sz>wNsu12(@C- zj7!Efm6K5o#8P>*&17CXDM?Yv-tJ3jhEQJ8OX87G)> zepx4+QY9poZ+fOwlz&Sl1)!f!8MU2OS0UO}qA>p|+9;!s?iuN#k~&H$q?2M=X{MKI z+9{`>S{mx6qIyaysH37Qf&5TQW9X+l&weg7^zhEIfNQ1_Lx^% zD?U93+dnm_78^!3UIZQ~APu`yNg!oeoO3RD)Q)e4W@oLq5aD*wCLv+eN=>UF1e-m` zaW$^I^WtPqNlw#fySS2ml4b5=U%e6wFX@9cBU zKNCH)(Ly7gbJ0ofytL9sKh1Q{QB&PC)K>pX9dy-GW4*Q3U4zZF*k6wgwAoqVx0%}c z<+^qPow*DwdkzK1P~F(s{m|XSpT70?222ut1oU_|W=bg3Fe!K3r^PYR} zxC6ht@52ZG`;2+|s;NDe`6noU%-@;>8Hc(mYxS#I4=eWDU*Em<-e(^^_urE*KKSFC zUw)>o#0)+2ZOh!N&A)}_cj@<^o^Wq4;@`ji3)$;JmXjF2C}yGrSj2w{%-;eV$iN3W zFoF#uMNuS%F#}>OR~D2W{YK+5hs6JDCn01KLq@2U5{{%}C)^SWLHH08!tjN0av=>H z62ls{(1tR^Aq#srqY$#pWkOsYpt3uR0kCaLK1?Kj3gx|X-WTWVNk1EU5YaII{Gk5cEux}@J9Ki zJ(;qUs_Y#qS4m3a!Sa=|T-IHZ$G<^UFnaDQV)}ZCzF(d%nCcUzFNq1vVIs4b$vmbq zWhId3wJ(}Wp_Nm5l@__>Z9V^iJ0v&Z6QK@Dhd$t(jyM%G&T)p5oa`xQfzD~pceWFr z26AUS6U2}JQpj=_%-jYgCZkFM^pXM%C_x8mQ2MlPp8@J8>lFG)4|;}&dg58j;yBTv zSad5D4Ix!{NJ1a3@S`GK;haW#LmhfFq$)L`$2i)MAhs-~fI6bv=Hs=qU9D_R3me&b ziqow9^rk!2X-<7QRHGI(s616FQGt3?rXtm;NquT>jMzpt;;J%m^Nifw!z_e=^{X}- zD{R8ruCa!-tY{T$TFHvYZW>aMZE>Mje?0$Gt(8C@y zv4~x)Vnwtp!a~+xt$Y8dO=8zdwTK3#n$00+K?*{wEXrxRMvy7b5|juZD8)MG@8PXj5txcY%bZJJjr>8kG`@ z(55`8Dc1Dbz!8_A=_f+MlcC5Xo0X{MA1|f|vYg~4818L^pxx|3t_#w!98V`$vC)N5 z2*j8U(I>gRDoy{TV8%3Z5sgot@)xOG#wug^%379kmbtuTHGVnDVD>VZwMaoGquGsc zjN2U3bEUhUuM<^7{RiRHLYj; zz%_2t)ejzUC@;&E%*s+X9k~dNN9~bV!evr5GEcG0#F`?Z3EI&4j=4VU8aLraBH|sH zoLU*Aj{E}Jzre_vbc8H(BN}Q0tw(;63DTQ=!7mdWt!o7FhE$9MBtgc32yA=N#zQ-D8HFEF`Q?Nl^aj z()<4+IrvtkDWPb#RH{xj`BGiJP?g_&<{#hr(T9FhpKtx?U%&d;-@f+E@@L|MznZ+~ zYMb%M_6uoD#1+ZWYCweFzqU7=d0x38Uw2oO5NRO#M|4PnG$fw?S$)izpDCJZXawx_ zMtLM1y+zBL*$9mx1kV9qM1)t3;Spfni>^Ud0&I@l#oY&bUKsnXla* z_w-fo*;4p0UWcs~TI`r=vC@(tgno^ibJ#{$U4*-=3!)K-RghP^*~VAN7)n%yY@D2o z`NR?Gmz%gmy7kTcRmGdpj>1*fEg@XSdExX#T*ZZ<#gX9{n&HHiAsU|HF)f&L!OZ^~ z?iR097sz!Gt7%9@2p#CG+C!B?1@%iC`vz;3jIKt&xJ=fg*#|9e?EA#!Ofa!BmoIR0$zjM&S%bS=J9Np2~bo z;+<4yeH4-9#4S3BkCg<51&xutRPYT^_z@rLjaf2^*)pDyGBzVKLfJD)V>D8um6aJZ zTB9>oW0z?oU6hD1rkPS~RZw(Qdo&A@G>f{R<2s&WJF25Qj@3KLqg%blXS~)uo?AX* z*gmq%f)I;@z*$`_BAt1aTA9^av7bK51a)JO%%BA}3PhL|UZ(Y=Zv@YNUyv zV2r5X4BB8wMoM3iBoLZpNuuOQs$@#`#3_MfYQf}7mXg3#%KQ+KZtW6uNq|s@p&I&R zPXc8c2IU$GWl@^p>Kz=%X09+grM2c4Fstw%SH|r%?!4g2ZB+09#BV+ndzj3%XW5 zE{kilWK^V1Z0Qax?vG1`R1Ka|;>o1#3}$1-NM?Q{+SH`-K;!`#=!#gAQU0WY4&{Op z<%2qCgf{4+v_mH~C$3m%hGNEra;Syk%7=Q~z|o)lsX}Fpc%I^xR2YW=qcDD!g;CGI@!tQkXj>~3N$JU0;Yr)5 zsf7~WSY4b)RA3?EF@&)7NReDgx)g_rAxk^V1fpdZepmz<^-1M1H-6N2;RB#3qx4T{m(gHm>S4W+SVHnX9(yHpVKgUZbqm>Z{_a zqMR9QUS>57Q91VER+3#`6-Q6tld+62nsT#^_Ea+JrUEr)>&1c&?+aQ;zv zg_y}r36413w*|@IIhjo?2bl=OvBcb;5nhlS#MP<9y4cxm*j{Tisb~R`ax#cRerM)X zX_gA?l@e^*mB_zpU`I+Nc>>S5aVxjBqZ^*Lop!eO&ovQ{~XdvGC)4 zVA%OJ$T`W#$!M#(Jd9e#*Xn_W{@uunl0qBU#y}v)u?QML#7K9nAAwMWK#Y~lsYbLq z8l<9JyZzIj)kMwu2D5-yXKd?y%2VfAMR=5zZ2E+-602f$43QpIa1!T`E`*R=VEoOge=aOfAPD^t&gU-hLq=8yj_w49 zZUskDg+lOm-sQs1NyMrrFgj%jzo2bZ?D6asSmxDNrZ5Vh@CuhHkew%a1}O39Ck@_W zMa`C%XyGa<%1v^u7sBD;W$h4KEfHgF5hL*tD{-T+4^DPr({jcfiY-^#8hqWRdI@k> zrl@?)6|;^lI>locAEZ2{*WG091D~$xQX>B*Qg9nv@Eb4CCtBiM(y^4LF89{OU+QsR z@-a%5>|!D&W2!0N{oNq*SYjIT6*mp=m8xf)>JdSOs^;pf>Z+|u@~v7jtYUH{b224+ z@+5UWWv_K$slbhEuS!L96qtGB=OaHvk`xDH-qyy zo6i<(v(tJl*k02VgOeD;V?w&~Ji_xlH;WcSj)~UURuW=Xb}>N86I2qZyx5o6xmTz` z=^UqVfE2~$_Hsl2@^a)9fw9I za`5s5N`;I{i3Fasv1pOr^NxLAqs#z34}cMRU@ZHKU2ME|;SIPr$o zi5lL}>q7tuOL;_g*$*8JTW^dBYlt-?kKE=k@ZC7Db?NdZ0fAvTbYesFVguyn3iAnG zGzXI@UJ37=w33}2a|w&`sI`Rl2H?(`3}>4daOy_8nF(YXGb*u3OH|49Br2r++0gwU zmH^?QoyUt7i)~CBXh_A?X-WThe8l!_pN7c}Q!{9wGZ4q&nu+ssFEKesH*|;d zbYn_8cr6qw<#WkTql{?Tei(ScTiLxFs1d}DQZa(q-&7a0o_(6oxkmemiRvK-->M7C zs-+k6vv2fmpwR@6yc}>_Dvo@|7Qo1;l}5H+L;wO{=^5@>%WlgF#BuDc&TU!(*zFZ}(72>i*C@#b`z7?2?C9TLU+19NLA|Yyy6wm2@m? zTpMpd3*Ay1z8d(c73u%v*@Q`tYUJg#P&~EUq-rMb>LuH`Cf|9T z4xC2nv#tx*#WEg|oSQbw-wK+I9H6lj!~mb%xu^>P`pAE;p1Fqlama+beCtN+p7WAi zuLSmV4EB8#_F%!9h(kMxGd61g!DA1znC5E-ySkfBnw*A&$`*uF6y9;{B;jEM9KoJ= zjhaYn_A{$=4A0JGjd_(wDxS!OyC`6fh)GE7ICvZ(5Yo~DZmWL%dvVZAs0xm_Z?AD% z^A@gRHZQk!C&m8`TX%I^ymVhYbz{78Vcd30d^#s6Rebko%ty}oHsQX@d}JD?LOOFS z-I2mSlB;>0>nKZVTe$+1A)tVL0OfvSR+&E^^o*H~De0eGF-~xDcac zdhg4SGVzJ8Qpayn^Ziomz5D(>`~rU8@4ep>{@_=|blrWSM|J*|-+G*}h*Sj04NQ@) z_2sWJ=EJh)+cGV`V_3;E{6T$aH2dmspwy%O)K9RrCv0RFbGAR+n#Rg|q87KpZrHD< z*z11ozkdJi!}~Jx&e_9B4(afKUWyNAw>Co;7;1d;SNz61f5tz*GCfxEN4)ZPH=~Sv zXwb7fzw`HdfB3(jIPp(S5KI2L%lQ*a`rD)VxBvR1zx$)VTGwOFbMY4Q{C#wPJo7(0 z0))MP0{;y(Sg>F_g8~^YTxctagd|cTR+LClV#bLUD`K=L#bHB{AxVxjSrX+*l_^=S zblDQ-OPMig&a_z*=S`hCdG7RSkW>PW7l&@tNc5;tj$}^$vggz(LWIAh{-auuYSyV% zxnkvd^=sF#V6~Fn8nxils%zP{b^DerL9Jfff|Y7_>sq{YtKzlw6fjh)fz?6{JosNb zvuOXl`Xy`_GGL*TlTfx?8S`b$5erZ4jP>*2xuV4iCL7wc=h3M_uSWgab?nlxXUjfq zTXk*Sw|D2}{o8l&*1d-VFD{(4@#M%^FF*eLUz^O+H&>^AJ;A1dkww}{i;&=36-9(0hz5jA3pB((4|3$(vnwCBYbVVqIM8fm=IMi*xT zjjy`$Dh;6nf#i!twTP69Ef%{na>yN-R8q(R1(Zv!0F|W5JJYDliXovSy6ns8!leIf zOw1$zj7P-OM2k%-(`@riH`kOC&N<_})6P8W+>_2e@#OPQKlKz8&_M$|)X+o=U6jy9 z5oOe?Ev_rm%SkQOY?C&r>Ta!(r2G`rxXf$lpZCH`u+#**drF}h?-NLh7jrt0RENIX z1l3NZ+CtTWY}tg20M{a;l>*z!bqg}2YGn&j1|mZ{xZWeBl>kk(6`@vRT96};H1f8i zqCC3x!*W417u|E!O_$wu-ECKjO2I{{TXF4`2*r^i(~GMpL;Y7u#z@;PtyX}w$KYU< z4R(u7Y>`4?QWz#>3wxv>#TJS&{_!7X4^ETFPNk57sx}<9hYXC{A@(0!rNaMJEog07 z*;#7a$vEX_sfDprgbcpQo{B3DwiRdJ0!&sWdo1;_rVXPMyQr;8!06PtENi)|$LdV$ zvbfF~Y^%fmTI{mPJ{xPZ(?)yiwcTzTZm-{#JMOR8rWdP-C^6At3}f1%mUf`$tEoim zbN?U~=upTphP>z(R-#|eG-W4yfay|V%3*dOr6@=F@KHbP;Shyb#2_9Kh)E# z^VeEjw1tMfYE)HmT}!w%FQt6zUL2{I`B+IlSGE$CuasphLjwO1Q{FO_s7y-x46?7j z1gS~$t6yYv1i#hL4@rzU%$4@XCgCjeEISHIV}e8w7Zs~xt#C@UprV+9c{5|%R19GV zR!E)+36TlP5;haF$xeC4Ue=&?!XEe;NewC|XMcP=s3PWV#FPJk#t1!g^zqS9W)hgo@>szhLrQ&p{B3RU+ zUN0lRCpHnVe-&&L2@6HT2DY$>J?vl?o7lf@Vlz;atQE6Z!!CwWLQxTkW-&y@@z|nR zHw!IjXGU7lmUgtMMeS-&+gj3|#Iv5o<7_coTiK3^wWigrYF*1)(4s^tK1~Vw!j%+U z8aJ=KGU{@P+Fa&7*SQsvlrHOqTV;Cev^R;k=_BH_rT>{@Osl*xui_$!W(o`Qa@bO5r_E1Pr^|lGkhu9 z_0?0QeB=kNmE+s&_>%|oKY29F{x9XmjLP4mp=|u4SM1 z9O&KE(p?8qDLflp&qlY>oa0Pqr#BtyaF#mLr~dS+Cy@+!O}f_aymdYg=d!n@t;Yrl z@RF?3NH8)pqhV_c(D@H#2}&f2I+m>3-R@z(0<8dDHR;;ovC@7Iyrcs;)++C#nS{%Ab^EpXogo(CIJbekVeSu@=jtL>5m4<;8N^#2=L(K4+8~`#JukuDv1WPcMexZsk?#4P#EsQM7Iwo4yh?1CPW<<}BGN@&OC1d``b6(Jy5`zMR zaGZdqT4D!AZsz3v;*WkX=pg^-D%t@6s)px$a0;vN=jO+%hz`t-j_dZ!3l%5os7?&6 zZVbba4A0OE)9~t+$R5gMvbgXKD?^LEEbJgnJv?T3PzGgSrVT`A5B)ELSSDH4&hQM) z?Bvbt7R}KjP0(xs001Dz3egTFQSc6r5(zK37H{)3Ph1iJ?MM(5O;8j=aa~F&mmKeu zP>}@<1KF4lXtb&?=p-+`rWG6GypFFHT~YajZ83uD5g{=bago@HZ~25V`JAuW45R(n zjbzTPqQni|objTbvD~838mUnluMHZp@fxSm8?~_-xp81PY8lHhGu}_c;;#ZVkR8|2 z9W(G9OXU%hpmpHU9ykB69s48URO$o!QQAmx6ax|<2XZGm1_)HJAMr)wnC1$tunDJZ z=NeKXgYK!ONJJhIBdKsAuWY<(NVAZx>q7DiwJrOrf~}Au*0>vJxwA(>4JTArW#F z8L~;_$00RR%Jj#eg3~zZ;^Wq2FlrPm&Ox=<$1lk4VCO>mMXT(f%Wt&9W$kwE1&aqWc^@z4NHvsCjSGR9a+Q#_2u zEf6MG(4*{{a?uh(6HoCgkIU0=6GC${LVwKEP;nD2v?#<%a%lI z-b76ZM(@PvRbX*ul26tGYT4-NKYJ!IJm++r>}Gr><}e0fUMO_#6L@-NX0QaOR0voy zB}bv<7hwN}7-Mwfl94bv)5FfB8^JLfyGL*PzF)juWnS$mThF5;YcG{EBekEsAbTvg~ z-x5Q2YK9avh@S{aVuFTR`s;Wauw^nyJ1)j_6bO+7DT4%vb#mn$t5PLwY&J(kD2h@- zUv)xZb*M;TH)oRtHx8|6MM&!MtAJ*h(jrKUiD{}zC()~hPKSe9hFO$#WhSTxgOea+ zhD6WGZa66+ltu4g##4>vALFVOB;iIqr+;vd2RmkxWN$t@24ZfmVdfJ__pdoSvYGJe zI??|#4kcim#IrlYb6@rKJN=bk|5Z;^XeP_EUgglT;?IjlLb+TuC||`X>_Lo%aKS82WaVJ)^sQ~9_?-Xg3Jm->%MPhlSbMmf{ z3W9=^6^?ihMsh4EEiGhALRBxcL5m^;Wi?ipR%uzO!@3eIqjvK&^fa}?s@k&2xCAYg zOh~i#Lx5f0pjns9A8vVg4=nPA_5fPytb< zV*(^y8}N{RCwW}7Z3Pqh2-BmaureWYG9R~bGt)95S8XYGawC^9D;IMw^KzZTVif;3 zO+$)J^P|L0DlH-psQ8m|O6v$O*3zO!G+*oxS!#A?ERry-QZyoWSG6LDjA?(jX@Pe` zq@Y$Wt~XtG$gr?+{R*LnHGu9A}p_ar)n(|fy@hUS$=+At!B z*L*YLe2KSw(U*PK*L@{GivU)B`;~qL)_wyPf60*j){Q3B6D`=&Cj;$JO~PRdn1ByB zBt{lL9gTDmFK8baK_j?U6cp1a!XqqLDKL0sGl*o@P6WYD;b*I11= z*p1hi`rz+AThor~^B(UwkMY<&`#2v_m1ucasZ6+p3z?900;!63eUR=}ee-)avU?-4 zIUyP3Y_Tmn4mv4$lABOoi7w0z7L=#MujcoDNjZP(_moQ+mHz~?3KkB_^Xo_hfG5!@ zX&Hi7!jJhFxM+DMCh)g{q*ogF9cgPRacyW#qG%aZY8~Wu4B43v`I&8H3xL3Aml0ucArIc^;Sla`0r$zB|!w~2wO)1D;57_4_ba^^ym?sw_-Z4 z7q4p4Jj;5r^i7r1I+fSjl-qih>DSH-R<8NVf4N9uQ4_E8TCYj-DFN=X328@MdBqRuIr{5fxRkRauodzML3J z^SPtWV!I+w}&A$k(Lr!dcxWItttG%nJ(+dI+VFEmIb2@SzE+M9Ish(DR24FDx19*5%De?(=r>z z>xBaI8^3GZD!0;_Njt}N>9n(XEJ+;5gFL+e(=UtMxQ+ijsFw!05f`5ux;Fn=p$%Hf z6Pk0UJj$sY%Bvj9{h7-jOj5erq16v+7&+sxq`&C5K^&AUEgQ{fa@eO{Qx=iJ6c z@M-xwsrz9IQtaPQr}CANru(Wl26Fsrc>73RjFPUR}v@@c| z_x#5}-PeCTMqm4a-04$lCwYP;c3e*?cGg!CBu9<R$h zrDzUbj_9r_UEI}SU9;__HYGmd>wdY&fGbI)n)f~;b{&SbIqCyH$Q{F4<;bcf2X<8T#D!>$^j9&D)*bYahlQc2({}kJesQ-XpT#W2WM-kA7cO1md+`%WN4EMmB~W z-JBmQUV9XW?yKMKfvn*f?&2NdeI$9~3BBVD{Ya3rE`fyZije0F_b!c`3d7oZiw?qn zzU#8n=<9#z@4x8rKb0-oIyxL6k|YqAL;}Hq0}UeF^vm9_e+~crvo~>~Er}R2YTU@N zqsNaRLy8}UWja*~(W^4EV%@5>E7$+8Uc-VNE4D1zvu4wxU8}Y&+qYiZL3KL!=~Sss zspiG26bKou4FkV4Nw~1#!-xq#e7KRZM#mW;W0WkBGDMD+Gh^P|_;N;D4nqqb9U9@m z)236SUadNzL(dRjI}Qw+_H5acaaYzIdvR{xyMgzv&D-{G;=+vwN6!3q^5W2+OK*PM zIrZh%vsd4ao%?X@-NS$Pu6(@2R;<&vR?mLnMA9xV#+-Sx{(SpB@zcN0KY#!I{sjo& zfch2qpMe4*NZ^4CCiq_~WEr*Bgm+PB;ZXyD2G@peb;#j|9)<|wh$5Cq;)x=Xa^Z>< zwrF7je+?DUKN{9H*^QOqXk-75Jnrb@Y&rtjqmVxaY2=Vc5;vr1ED`Bsl20NjWsy@x zdD%s_H7OfP39Y8kXNJk2AVyk z@&r^yHf^=iPeTFa6REIjm61?sNf=dKdhL1_uY5s>;;<$bOYE`6CX4K{%9^-ImlOgk z?XT2I;1^&_imL6l+!`iXji0qd1}QPNB;QEwkZ~osgLUTaW1PVonMRe9o4}V5JaGTO;~88q!p14=aKaEb95KTb4?MBO5@%d-!54F^F~%Do4D!ex zhrBS!BA1Nv$ttUC&ldddD|5`7yvJmx4KC>5&N}z3;LkY&&2zi;*&>B4LP6M0D^j#l zDuhql(u&jnkm9s0HA~cVE1*q1(bT_?a*-`!PtCK?`<)k|i)^!aVT{c(D|g&<&uw?z zc;8)-6mGZe_lt1jL|ctk77pd%RU%I1;)W+)Ws@`#jpfTr+cPd1?QCIBE1R@p_0gM* z>#yg3sryeWrbkL{x}mrJixgzQ-nrt9+c-IPYT8pNrI_ySyFi*cs%WFcKU)0o#wU;b z^1?TNyz|OK&;0-M)JI=vzGU()ruNw{l%=fab}Rn)wuldjm7<6q_?)sFnJs#XZ3Rl9Hn7F|tiFAwz9UNon-yjie<7`&hc zGsrBXM364klAs8eaxEEUt9&R-A*h4{E{w?MWvL=V=wL_+0CH}AmP1|U($$hJ6fj+= zTV4J(kw3Aet5iCg*SqHREhgPdFf)r{%now2>zLYFOt#=s4_l7p{| zB`jwt%dDVhmAL#HjIbpU!o^F8umNW6hDp0(I*xHrf?PvPm8#?zQ(it2<}-=M9YgC`$;wu< zn#`>$gKJpZnpV25Rjz7%YhCebSBN~zj)1+R9^uo+qSfqZ^N6C0vd2!7}3juS(T9 zHx*t@%qnTR%4aVfl#OJ3BcRnNXgR{M&~Z#Oq8A5y%;;-(&7%KU2l>}O z4mPldy%l-#`q(S#ZA?}D-SJNI+2JKGv>B&N$;C!{Jpon^Ud%5`WxT>CX}S+Y0r17cizBD6Q>G` z=7u|*p{ed=61HF!nv$!hk=5*mBPG9_{zY@7OK<{N{Nj?E&&e{bv5}Kp`)D#)g!+YL7tZg8& zNADEV(R}8pKfUVhCIx7bp7hFQ@^721ZfHs~+Ud?c?jbd6W@5=mn7cidN;SLM8=uVz z?~}XZeemWR+~8Jm_U@%m{o_yHNwm-YlD0pn+;IOk-|siT$G`7I*<(xqZZE>qPvGwz z_*E$RMTrY&3#8ef{`a>(*XCdU{Ntbh^#_3d*M9<7fcY1I2RMKTSYiw4Yb@p!CRaeH z=3>3nITY9`7&vkj6=SWHb04L0(;{V-q+uiISsZ49D0qS@n1cT-c!E;%f};e3G8lt2 zIDfxrkOy&)0+|2|>5w<)jor8uvBz`FHYEsleY#hD8`(I227Vl=ks=wAw!?1h z=5Fk_eg!v<&XsL#Tlh)s6ia=sh5G-m)s~7YWbIS=}}Wi5mk62 zzh!0Y<2hl|28|aZM>LYwN0Nn;Dukm5l0b_wLi<)P*MOpv?3Hj6^$q1M~Me&*N7F_D3L9aV}&`9>gk^F`JVD=A$U2T z_8Fh}d7s|cp8A;=6-kA!0bFWkWo^KD*_K$=6+6=vB-*DW4hoVG>U|F?p%Ka^lIa;A zNuhEQE+2Lo#Pu@lLR^tzflx;yhh=VKR#X2@BLS5)W{Nan;}SMxHahSFA;)K4?zdw? z*^}v~lSG-6Klze7ij+JWq(54uLg}M6Iix}gq)d9GL>i?{ilpqNq(-`=3AZKS1AnJu zWnz;A9JZV3+O!FfhwG)!Y%SaUV*V>Bl*i5FI85JGN9<8fn(Q_qQ0 z?1Efi`IRWwfq-e3E|nCCDVT^#mx%eOgL$Zq8mWtlh?Od-j5?`}nyH*hn2@@uo=T~E zxtL)1E?6RgmK8P-QZGUQLPV}JXFi8?!s#W!`J3Llt>F5tfaRm%TCU=1 zuDsc;=$c2w$wyboAGJnuRB1utiE8loWtwwwlr=wAgFo4sKNRs~kXJfWM>c#4KORRw zrL#$%!+F$ro?Vfi`5CDb+n*L&u^8JT-I=i*d$Atdv1kdhO7WkJd67QSnE@w$0uvgy<7z$|r<#d;yZSvSd8OQQlv66DP@1$%yR=S= zrBoWV1VOG!3$;~iv`=caO{=x?#GWxsHpun>)FS%ej@S7o^&ly=oDhdAeGex~RLls@uA(`?{_hyRbXEzUP=y zwT7x0hqybMZU_>+TZc)fn|COi=UTk$dc5K)yvDn{$lJW>LA=c?c$`Lft3?vhSf1ER zjoEv>+S|RMhe{vYogX{CB3r)dxv}J%zUI5W$Ht!=OR~cupqV+p9a+E8Mtk-fw3vA~ zI6Aak;-mm<8dSTrSR24so3#ZjwFI1#2W-F#?7&Z(zzwXx&o{skyrTssCt?e6+gptu z+`(w$A0XVl+}lt=k#hf_YZrBq!i^ickn6cE{JAhJzMAX8Ed0VXEWU+oRo5x5|pL*QKc>Kpj2D0!wBl4TS z^t-=^yg0&l$okvJKw?dGa!o~xz!!``eH+;;-oQK6c z%*f2l$?VL~yet2FOw58A#Dc-g*qqJUtW>Q@bYYyE>Pp6AJkH`AkK}yL;!MV7%)Dq^ zoD8SS+Z@mGJkKH_$0MenIp)Xu49NV9zWe;o{LH>~jGu!Xpju{srE<^;O=1k4&<%~y z5WUb2J<$>U&=OtI6n)VeZP6T^(H)J^AidEZJ<=il(IQ>aB)!m)tbC{}kLdi;>AbBL zoXMmt$~4{5oZPgjthAN9lm^xnI~LUOH`F#$)IKZJMvc@*P1H-B)J(0^Q2o?W?bKA= z)K(qURgKkGJ=I&C)m*LAqQ}E4SD4M*xzW7LW}Vh994*hR);jFgVqMl~J=aHJxByy) zOYFpYoy7l5%-4IJ*M1$?fIZlKP1t{3*oEzyy}8aX-Pkeho8Ro%l3j4-%Gl@H&hGlg zY`od2N5}3t&;cFV0R7q1Jldjt+W86E?rGO0i%lk(qyB4Pur1rMz0%2d+f0euu07kf zo!h>>+qJFRuN~aKJ>0Z?#O;>T?}oIceAA6a?-U5N%3Q4Z&-QMT@-suhB3OV2I9pCm%-|}7G_uHFaH;253&01#oa=bA|O;T|61AU@(E zUgG~Ge&Qyc;wVlUtJvbL_~I@e<1jwsGG5~}e&aTt<2b(KI^N?v{^LF#e7pL$QnO5_R6oMv7BliGD&FcV z?&`4q>arf|v_9*$UhBAi>$;xnyuRzc-s`~r>%v~*276r+a3=qhZAi3CUeN2%)?V${?n+oA1r!llFVi$MMQ+F?7N>a`GUP*vQ(co$Z+G7AgzoN*4(XIW z@9-|^l|Je9F7Nq{@9*C4@y_r6e(wTL@BVJ@1RwARZ}9s*@C%>ti2gMU!9T*HsxQNF zCCb~Iz6qP8E)eE4kOUeZzX>!|o!MUU*M9OQpYkZb@?e4Pngo?}YJqPm7V_sC6nE@x zx(RK7KdQqy>b|qX9`wOJ^g>_sM1S-~pY%w-^h)3KO#k#w4|Li#X24iQr{gqIFhk6} zg%3Td zt-bcz_r34?c%I{Z{)zMYTxWcL9}*n-`o+dE^&bV^i(w4QGihY=KIV9NY}#^cZnJ$+ zwE3Ap^2o5_BbL)1MoqjA`>S)^UH7QnYp4?s!d+aNQ~Zag1h-E;#ZJ9!P7y7qk>#hz zm!~mNr*Y3tqi$2GjjeTEx2Vse{mO8Uq*5@?UVe1w`0DZQ{FmniE$54K++A(OMwmxc zG)L9XE^53lYF}Q|w_G&NUo^iw9DE}y8Nk-nFy1LP-dX;j0HFXkK{sF(8Et+b61Jy36`37DV0!s9SY=jM*gw0bs#$R{ERTww z_EzQgCvqG1rO8$24WY<}pi&L4g$?uUC*zNTO_8y3r^(^peCmam*G|3dy%(feY} zYV*0iSH+X%dL5xR6>3YSt4+s>boy&cXX|X2`d%p1mCZH54>sre>&oX_5Eyv36n~he zB<#8a^_5HANP2~I#fGYt{-nDW9|sz$*M>7B!)_@x)@+P%_h#r0Hon@LtT60PS8A%= zzPcm6^>MJN?#q0uA0Ewv=K8&*o>=y0L(L5bYa`hTFCV;aJldM7wwND!-E{J0p(7vl ziuq0R*}?i)@w4GKuP;t^m-=5mYItg#uu)EFgg7rVBnGrh)}ue7^Ms zKd=nTCx23P(@z1E#s!}OZ#b`i3W5Z(ECw?qm@bB}SyDDrJA$12OPuEeRSo2|ra8W*l4Jayh!Nz@Bu zT}?7dFk{kfNh@4Uv8>%#O|^Z?x|ZfRVYc=HzFN4J?s2@a_7Z``ww~c!Yl!5;E0ie+ zDkU8c%_O)_WtI($e)k|HOz8As9rX`FL}yycLW6b44e)#plW%rsB_41AJSbt4Czmw`<1LEw*1x85dudA0&67)L-$WU9}J6Qa~_UJQCJ<0!k9}B-zoBMAC4)@avqJVX;>Y-*EA_T znt1B6eKe^T#CberlxTH4ZJJ+tJY!k6eLQR1&3W>{ankB!4!%};^3mf2wS6*=z}CIp zk3qzR{6qlZB6B66-GR$TQIontL-BST`cP_IuFA0_If5(LPP*{*9Gj2ujf~Xv^UVZQ z^M*)rl$XFtrF%MDBb=E*NFtf!S~^f=;9@X*x|}J$5({sa+t{VYt8H@TwS)}a_Q~Y zJuZs22j<-llDj%&dXUtkn8%aYJ76qykUSEe$D1!VXs&gTGBuFLSJyje?RJp5fS-?1 z19}@oX-@LIGmX({RO)b ze^FKy^p*cWS%dGO{m!FudSn0pS5`$Ayennh{)YQQSqmN&|Esdzy0FQ3J@=m}YZ!{= z;r|=T`aIT1@o$xNHQ6-pyRw?Ue~^0kN@BzmeR@AS&33i$s)DrhTUq_d&DS%7nTpo4 z!udAWvyn1v8#!_6<{P<5#zh->Y0g(~23^Hb|ADeLX4Agun}Get%DS9jvD1*|>i>UI zS$kRXOZNLX{%6YSIV+-bWQ=@&Or#cC%f=0=4ZJ9!>z29Ae-3^Fggn&?SZs^lS2bM7FxK5 zHWEse73Oa?O-q2f#u5PB9SJ(4mlUq82*LQ)ajO(2F5EoX;*D%4rx{qNDJbaTa@z~j z!_TJdhTmq0xl-1gr0ZinGBG#Hy=j|!sAgf^LNj}j@BzcB)p{|==3W#6KL>&>2V2-x zq4(m*p`+;SkrCRDM&iFCAvukDRzv80d>X_=_(ViWeLrT>J&Rc|x%Q#&J2%?KE7X#5p`}RNhEeEksWHd_S=jKaczGl$DVy`%lU$$G~M@t)Ig&%iAJ1WS?@7 zwyu~jRK7Ck)Ohe>H$4A-*!$4E!QaZtI_!0R@DgyXKpb0s#Fy$Y1Ef?SLD4r7D0G+! zjwr}~>nav18j(1O2l|6caR4{~+y9k>Pe@V^?#8|H^tl|{ymo#pfdke zJwIL}trFL6{*Smc40XHM?f-2q{jHvV;!?p(8)v?$2NLe9SL#_DkG-Dp7xjE*U5WEs zJ#iOhQm)if1K&gI1_?hWEt}o75r)>nD=saHv~K>+rQt)8|7$M&p`QN*m(CW0F^Cqv zm`LJZap~bckh>lKp`grPxs>p0`=7YRMo6CeB{M6DK#@|#P4V|hQSsu71f4g9w6v!Tk2fsjhR(Mty16bs*GyVpY}c=q zUF$JBA&(2GQrGHR{qmRq884l4%8($ZMMKsY?@K5@JJ*n*iDY6TMh6}z;zd0}|2 zE0sOtyG;BHFaqqV4)h;fN+*w+VeX_W>vFgT&3ei(8jEj^2bWQk1Gy(ru*vL&Y7SiO zF?;?{&!1d6d*>$AWY0gi6neMA^}StW^&TbZUQf5^`FHhPCOe^|l)!!Ge_YXpMJR{N zd$Na=QCOzCenwd$LX1SUYK>7oL3YC;VlNG63^}mneQG4lTWk$j|AtG$mu?5wOXC#8 z&;>F);l5@sCqQsF@jI82wD(JrJ0y=R>;Ds%jt^M<hT)%oJrij>>xYjONubOgutb^Irmk*nyXaKz!n}qzNaA#(u}5> zD8IE_U@}*vn#%URu9l2W@mi+tO5fxg`^U8Ym+Zk>b`8Erbeo(42y2gV7{inSUh$(r z{YM22?YKE)G#taX`z#Iw`tSC2fC#(6xd33;JI-tE&Rq!lq1!f9VQT=nKq6T!l~| zOagZs>H7&wW2wiA(!$6>+YqgSxu21^sqr4qSTHpde3011@qoj~{B!D2tpUm;e0Jr` zQeUe*l(H!e;{Yg4ZOA(E1pR&K9q>RZ025EDrTC^+gwh$Gur_$udG&e{PFhb->63Qm z^B|u(p&3pAJ{+7W3G^7SpmwvXZ8EU+Q%@~lds(Tq>bJpVuTRq-?TLt{vipXySHZe$bzV z;;J4{0OGZ^7r8GNfr|3?&gcAZPa4m?f}T~Dn$D6lWXyRoqfHrR-|()a-X`RGQXjV@ zH;Yv&P_}YD-;9M2VPV$Bowzn1==aoyIdO~V&9qgq4&2cF#wO?PPzA&(4J*NhIPWHMd@ACFXidJ~D*`TCX$N3edz^ zSg#>6HEgP!e4iUX<;r*9$JV(MFQ)_-h>|vmj&-;%iQ?TM= zoeNEEv?m$|&xsx!fqk5aPJ4)=oNnjU>g1qBLx}(Ey5ayZ0k6?l{}XRO1^w^50mj_c zfA6}gTdpArI~e4Dxvp8YAen}l7}8&^tGd2A_7MY#8=K zV2Sz5bv0feMH>&`>E-z8x(YJu|HXB^@&=s2`g#^VaauuEV2i-WV(7ndT^S5m34XY)IFEuD?iBvluIt~> z?Z3LNzvUC;8Jfl-vkd;5@W z34iD~C)EFIwPo#cg7!lF>Mz%o%Piu}pIq1S`1PIdt}9Kacx#yI9ugh+ML?=Og|D@u zoiI#rS2k7ZFRts2&sucd?=^dkRP{zIS?WIX7!$NuGLrE8a$WB}pRJWY7-B0!uZi9Q z&mLqN8s$um+{68f6jo%$aT*u)R=9FqX~=9Q)a2S z?mz$Ty5__vo`g6P0=wpT(oq90exCR>NAvy^)&dAunliYnWlPHGBIH;i8obwVvud8- zd5dA0E!vKEEhFfb$^Zd`<9wqa|64{!POxO*+fHXdxx40tr<~8 zXwy7^Gv(FnOD}+gl4=7+KJNo-8N0-^87ki|jbj)1*J}gNRLJJWT%5s^el${N=R_4F zCnpFRz{S^whst2$PVXpAMVyByPbtbC04T z*^AieLHakOO!wkh!3GKMl4kD{at1WWn*=@*F63b1c;@CY_5cSYgmpT30hesk9f9DPSq}w>2h^7LW`Q`SAs{@(0{_MK`qT9nOZph{ z`Ul-&9LYzaZzL+a%a4;>dk?wJS)@uhUYvJDtO_siZskwJ`7K04G;YGwv)L$aJC93a zpRsAoEskf19+enI^lNlcP1HIYJD5dm$q!6tH}Ik?N$rN2$y{vH!!W&`HBc zgmoG>``qU7MB~(8nR6X`6@_O{-3QMQ(#QNGyE6>=tC*v3=~?7aULxIsXSv6k!uez8;Wg%?Q^>egu&z#% zb{*ujono3hSXOb7I8_s}BT^ZvF|bI!WP*q3Tq#+#{|QglUV=_W$K&}2y+fha_Kxj* zRiS|;I_k3?*aM!cJ4?$Cf1X@({1 zGQ#Jh$jC#V5ta>k?elj@Lp6E)gBuUr&&M(dUKPleu5-tpj~6_6RirVvsor${zJl*s zEJ-Sn-PgqsoHI-#F`zV$@B08QQi|)3;ud|uvyeKz+F67W*xhk_x#3DfId)vMR^kn@_54>ZplG73`)M%<*Ec7r+siy0ecUm2Ws#GW^ za*;xA_vuvU5uxgo)yJ$&mo7dPE0t3BN*2DYH)Ixsp2Fhu>(=I>ZjbE@=$og>U&6a? zi|%_G3e(b~x&_+DZra7*y;|B;I;(tsYyYj=2f9P+hF&LKj`C3;Xxh+#eRrG8-Kd;w zyCQ&1J9Ep8SsYipA_&O0*Zr)<4}aUV%h3N@6nR?`_cx|+a8No~mGA|P6a&6~#;Gie zJem&yq=RI3FRDZ#lT3#OHZvO8>Rq$=g<#!DxM1!mg5=vot*G##Sk7tan$Bd{v)U!X zFQ=Yc=amV!n+@)Lp)-}$-5U(NTow^?>j`>uKyhLnX1Trn&LVv;>-Ohq1wJPnN)en= z00IL5{*up}K}HPlH9AcMxJISnA6s{6!7@FPDd$cJ;KKSJcVtwNzMHAa=Tw=RUs~!6 z@aF5fP;(gGC+hG>{MC8j0rt1drmI_V3&Y>$Du=}eojq1gTUx#y45Pkg3!vyGy)Rwt zAZzv)Yu*@k-dHRM#ySLcy*=~@K`elvB@wkyv3Yeuh%;iNs)q;A!%KzOOiN;+F>|R> z_$s^Dd0_(p3#7`2bYCY3RMr4r11a?b5CWiHHT-ILCSRok*o3Y!jb5 z(n#RiV0)>Y$SR@vj$v7k%LJ%v257E(IDG zfdb8Y0(9#G)G2vXM+m6vFV3dW1N(P5^Gl19Fj_JjcCb=Pp^lhsNWQoN_KISWCh5X{I^LY`=+FH9t|Q$AmgJ$;z{7AXABk8So>Win6kZo)#8gKbDC z!|+)UeAqr!>)uo+I>eL+MwhV0Q=Nzv1dT~p^?Df4lr>O>Jdw=h7~x@|;^brEh?=nL zVRl)^j#$9<<=mHryIAy0Vp$&sV>7s5%1YI?!XYfzXDQSkjB~E8d2-s5>m)i>)H`en zxJdbXNyWh{HQnTB4<=bvi|V18CxZZ-6g zzo{wQkJbCvn!>fLUp0l&6uqA{g?sCjW^=FqR8#Q2QS_&p!t`U9BH-uZc9xe;gh{v%8?Q14mK7L!BU$PtV7A!3dD9;S)t|D~polAc@i zpVt)FDZxX3swud~=g?O6#nsLDvgp+>?{usGswoi5ntrb-lym2osFEvb2Nh3a>3tEZ3BVxo>*j7=D094{0Oa@3e#K&Juk-I$_b4gTZckf{bh>4uNS$Dh1b}ayJp9%- z9Od=mB_{7NtHI}?sB40%OXO;2p8L)IUCYE+LuYGhlX&O(V52*3LFg~b&P@_eQtqX( zo1~s^{=*^T^n@ytm`3509Fks4!VyMqY_1)0!2OJL^l(+6Cq&m zXnl6Lyykv=4)B=K)V>XTeYw2NmU+VG38aa!*79RMXl zshslAm_A2tv<5+U-!r0fevm>BmIY$p;0T<>L6bmL?cR^F%)D~GecAIMjWM~`fuuRUMivR2 zkfg=QKyEaRdS4Pe@Y0Po`d~(&1kQbGTnx8*z}+|lbfw*P@qz^e+odgXq9L1U&lJg} z))tFVh|bjH&?A9`79DF8%pjXAC)}vYo=zRid}BAnXFMi;x-FZSfYo0}RTW|k4rYF{ z05BlF%Ma;blp$!4lg=r@12yFGR6D@1S)ib24glUJy}$>G)x!4`{4sd1*g2(*)Y`U- zzx(dh8*3@@k;r7&c;f`T9bVf zwT(xmwh_fo*W@P~XO6BOH!apB%4&UmepKF*LZ^qVFx9S_ZyzkuBhz6%^)@C*IqY$X z(M|2rs-gaL^tO@}rl#pUse~%rLZU=BDXr^!{t6*vFmtGIhEMq6EAbE==t1vH0IKI0 zQWt@%WuX9`66&lIn&z|#qE5u(E3Khbu!bU=o{q6mu=m!O_vg8TH>o-sG26K8>iXvb z9bYvm5^=%16+Z5#oHVa1mAg&$e>|>IYu<^ttqj1uzQm{TMsttFtDmPTSBsB+ey$vW zt+;?recB3oP~l6F#(Q|@7cjq{$I(7*M-^5`z6t$A;C|ZC^XV5bpLQ0J?1@u`Eye-` znm8jX!%Y;IsAf;!3Jg_7x(qDcx;X6?e*o+D#i#gGCBSyhXdnLgJ1{3p?t1mC9v<9rZn~J;jjU^4Q~KgI)|t@~thvQ^4iO(rFjzHw6hOJDWhaby zIayjJPL-k~PE=t0>{jqunZj-eNsebE)u|-l-d+fQnL%x^W{c0Y-OyKr3$IbngS#;I z%aHsZmIxLm#YA=Y{T0#-xZl76K=Nu1Do!byAC9#+XqnJq-BVL zT}XM^=TSUeRP!F`phZ7`UJE3}vXYM2&)0f+`^KZ~U?QLW$x!E!yQ@TGtN_qqMu-(H zj`{G*k7$ooRGZ->#HN|EI1*Q|-%c)9(M7I#1YxzLH3(u}XR=fg6qkeImaf-`i<;u8 zQeqweaqdfM`4p0$7m%rrTtcNDvW&TWqs=*m^cXyIOROGw10=eDa+P0Lb-yMHd3YcC z8GBy|2$vNe?h%8v>{5n|%cl25b1qs(b%?OwWKN7O-W11Ow0e0mO%sgT7~DbhU%ZBl zG5bxC+zwbaY%wUE`sQh8eUv@_VU^VIO%$DwYkRCd-jE3|VHJ)lfaRRoi$=}MNEt3V ziHoC5@Ba=LZyoS8kqCVHlr52bdlwNbi-j7&(&J~qe@>V~VULB0(B@{in#mGlGTh1PAEB0o<-AJ!MpeADWA+aMJU*M1ZO|)}t|kvtvS4B!IZa$BdtW*pyIv z#EaO3FlJE{M;w=AQsQ_73s8X&H1$0e_a~9W3ZZZ%F%^5w4BlSwK}g`@a0j*}N&!x7 zmnH+zqk&dPXAC=6QWms(FxOIU2cLDVW2DrVEXl}8T)>Ez8H(BGQK#=&958B46z>#o zdnDKh3@wWX;#A-SQUsOI`J~vv^E7FRx)3j9U41B26MWrSkr)PXh!@Fo)oohzTuv2*M)J zc^uwq`rEDpjFkOKxdVfkRjXh=c&G4UO|Lw7WCh5xfjP{8LUj%1(#Ya09picnrt$(i z7+8tP4+2^RvF5l$8c#W|BnEKF;zlI-cAvUgB{_$5N8RiS!V{p+VF|vYA$XV4;kdxP z6c&kpkHIX+bxGB?Y|YI;);7tM+{*;McM_UZg_Dd*bUhy@SXes zBUnICP~>Fr9aTSq3d}eYQH^?!xL_Be2Fa6kgcb_~XT(STEKafk)2-Y7m^*N-z+Y87 zL|zWbx*iJ15L+=xaKT0-GP`j&y5PIoijR1TBm>%#fMy|ZmpTOTLXc0Q6b4!-F({s; z08UEjot$W=YI}!=1spyVtGXKiETBi!MXq%7U;Xaz7X({Py7r9WitFJy)L{m&Cc(R7 z@9ul!1p6Mq+%~Zhf`Uc{{I1)w?s&nhn?bG#?;?Z7aEZb6dHeyGnUWa#{sO@+Gp5Or z*v<)Z{&x)glg;oV>o8v?C4Y=@71?0vMzMf1aS;4HFOry5KNQmI2)d|_q&#MICRS#s zs>5j+Ny;!u-Ai=tgxltHr@lBz&2vfJlZ_0Re9Wo|F2M;x_5=eP5K^azk7pi=Q$aNT zu2NGHQY@^&uC^lA>BF!QmEGPInm%utRgwEs#MrP&3EwsI zr_l&{c@+b>*bGfL@Rf&jy@wWMxG<$Z*7Lvv9Dph;Qm&P0Z9S2Lf?f;F`D_UuaT4NX zMv6kXr09zQxPz0XauIbnPS^k^9~*%Nzy0cXYTOr1ltHbsK6a*}#=&p`?!3uFKmQo1 zm!|Ieg_2sI;5<{o-INIb?(B+y16(GL`P zD;OSNMtXzAL#jT6_Jq*3-bc$!l-Smf2qQFgmpiHs5l-cv6qE1{zOT-q6N*O z{p>J`vk;dchtiY)FEddbNHK+M@fc+ZW}oMy9*?n&;*6<46f%SVJgK=Tc9^Qd59W=A z2Ndq~>`nrpY{OkcT^5Cs;-+l4HT~uEL<@TJ75N=5Si|vQ74upG@ku2tlqGHJ^wR6W zPCgODlof58uGlHXcThdPDkr4QJ)WSDyhK^wud)xfvE!pDymuTDR0RS;*3#$Ai?l$T z?#vMDe3xW1xO-9Bu_0l=w68iPbhYpW&0)w2MS`0~A&@M(pgWU*#bsq(v{u~zg8$`{ zqy$d2q)E1HT=NJ5s!CzMK4V+F&(!W-ndSm;+%flG!2LW z2e!phlbfGpcrp7_VkdXtB&$=GY)|60h~q9T z2ED9DJ}XFmfERt2xP*VoYj`S=PTv1O4p$~SeQzyPz??PCyehXh3scBd87CP?2Tky8 zOxEy<>aCAuZn=xoVB{0B*5kRe8D^B?e3!x5bDD5MGpY?iQM3n#_( zwK~mtfzk*x<9CG?hxKNBj-d{<<*gGl;;`$U{uu5BXk$mmvepVe|6fs>#kzmhiDj*F2A&@*d@$ zUbelY{>0B7$kd_zS=SP(3{`4+!q_OHSG`S?8JqRbt)lBgbHxlR6S6?Fzi<$xwTN(WsimNy3$#&!zFSVb zMTMh8ojYxV{HGBI4gdtGL;v*O$BB+3Y*}#;1o4Qg(>H%9%lX5KGSU5x6+fo^dBmZT zP=`C?wvJ1mA50hZj}eEwk~mLDD=VhA**``cT_EQyU^!78 zjQEcc$6~kq)rdoYB;b3T_`e%*Fh*ZhjTt>0b^bcy_#G$it36M(6-s!X=7=t9@B;pp zNh953QTmpG%hlzZ41ZB(^`4N{@2fZBmBow_a|sIqp!nlAHg2GomK?Oh<4YF1gcOqP zM<31k)npwNP?E{x34rhUti5CDd#7o#{ftG+#Zz0AagHNnSU1s%V~T7~0r|G;o#BrW zN8KBO;j0lxeC0Nx8-9X%!8{Ga{d6M1fPPc0hP75YdeM(Mq<(@~woiJAd2>5f_}ZxA z*(&qnQoc3tlW)sw8Ho>8$3){75u0B}E!>_MfDgyF2#oFG8EV$bgp-`=Txtwy(35;3 zxxZMeP`-`Agzpa+=K0KfbIo5K;PK?3sk%@E9NJ@BHA(~usFUs2pYK;B_Ls~Pj zm4vgx2N#kWhNHI)%ng#f5tw%;nH44?!cDtt_{w4&G_f7XQJ@`M}UwXws{ z-I&|Sp=f}BLTL~RlP+*rr6P#SR~#LX9dIYy7h*W&YdpiqEB(X$o(ZLc!!+fLt6@p<4d7UNa_s5 z^wQ1>W+a9)fY>t&5&5o)j^icDHwb+(eeekrZB!6|JSK!~LNGfR0s=NR02s#|(0Io_ ze9YTGJ-{E`OCjh%h~I?xpmFPg@VVE8E|O{ATw}nQ2tyagZUc5aJtTRdC)! z+y%XoAP@-_MPqoKttth^-tfg})Kkl^3YJiMRfH%@0`IG-6yH>(((IOhSrmO#Lh8!; z&+dpuy>s~wcjV-%EO+IOAg*yhtJtR6sg5gxrDL~9V|qG;jw_K?WIXg2FPl`4t2iq; zj3u+D2ZxyNU7f5pmEFo2i8-$MOPpAkH8G6}U5nXz^7$3WVs?91U0W2-+~#|n=(}1+ znp$Fab@Xn9PPTq1qRcTrOto6|G^DcS1UzVxbJl;KlxA-bftS73L2ji~^ zb-W#P9y&-|F8Se(yDDQjdPciQ9CN7Uz9w-{V9j z^R?jmannzCf5(YpSv(~sN?TflvURmXugY8ow{$PgCtC?>D}qWH6uM<6N_6d^YD(YT z5#AS8&R^0lKbvb`%uE>bUEOZl4xwzCT_C8d?^fEePrdlC{-CaLa&RYfL5M!x`lmZG zd-3sf=;S3)!56Q!fMU*xW5b8rUwjXQKCXVNEv?(N_7nEt%`&QQ`ElCf9S(QE6H`j%`|r*qO}?sq;L+eGX~*tbe}!mXza8r4*cDk* zsu1vb3hHi(j{Zj;0|1}_M$p&)d*V<`()-7;y}uC0zb`QTV>U{+&GIj^(JgMAU$fEU zl9<{bvr!GkWR}_-jv7X!&0LEeE8uE2Y9!)EOng40T0tt!gFY)brB?raHu{2&wg92W z?(0R(qz;NnBS^AW zeSwC(k@GP??rPk`7hw2%+?0}>o%M4ziklPrBaeY@qCi_Ej?rw$_!`OvG`=w=F{^efiYY}CF__Rq7?By{|%*{BKS%;R(Ql1hY+VSQt>&(JmXJ&Q7RR>Wc#4{r(8%$HjX7 z&XP8>sBQj-yr>tkZN7L(gHNC~j+K&+Sa`*UGc(RpLWzr0<=k~BzA>V4e=TuMh$6Ix ze0upX1-|jP&_^gIzucO1oIFO?VFB~8^=NZ$=whRyI{Tr0K-FE|vyRlpbMw{XH3` z3>%M5++K9_9fx{$=}JQUA^ex~UEjDI00tg`EF2&l&VnUIu?4&xT6~m2{A} z9uk9!5vWf|fkpcc7e$ooWjy;bt7a8(Jjx2h^wB@nWXT-70YpdpJ{zUvp*Cm4m`c%; zL_O{45W*~Vk>H5u5?2*t;?4+Gla~fz(&4cj%iSXA@!c#azzxlbqHC*O49}4X+bPTn zeJqvi5GPaYT|tNMO0x7)oi@rcSXaF&~a$y_u`Gy!W?P5!!u{nKvd?09O?LHYZ?MNRMN=pQZFwM*0 zM|DvQw0CgD0o42aVD${7P6h9T`_%(wcO2iLjhF@K%3SZ`z$8S&3~49Vs>EbvA&DCd zCwj~w5Us_PLsrUijaBPYfu8YQ>A)L3Q!-frcaRdeZqw*@9_6$<7yvPVpK_r*0F=)i zgafe}G(w~o*y)LzkHD}R1#_XxVS~D_TsMDRaEkIBT3$=Cqj%^x7Y4&?S;KF=ASQ=M zj3Uho=?8cVllV3f5=Ep+@*_h_0w=1xrDOD#C50)#!ZC1e4a2LAjW92^adyV60$(0x z)hCW)#J%=~%Fos2gU?IdWR8k72hG!iVWhd{N5xEbJD68wsfr=J!gQb3aaGb_ ziLtEI7ZP#Yh~r>6w^azKkh5k zJx+$$dR`HSXn661(R90i6qvZ485V0T%kx9WUtblNeiDa4;kFzY@8f=6X#T2_O?_4I z$K%FHr*4mbDlnmqzxuYi-h#gO#S6Qcg@Wo7GQoJ2$NVZV1=6|FE9y(I*8Q0{AOw{^ z3rv4Y9E1^dd_#Nw_Ed4eElv7$tFXvGb^{vr&K|+*5O?p-WUNnzTs`#D9$jp_*4qDbaHvYOrJz|bPOY8OwM1S82E~3|KI1Nto3a{G;~9^6>tA^i+go&fI2<~W zZ!Z1fb#XBd5R0?Lcwk#F(6j)0D4+}vw+Rrw`~;4w?__>pCw8y-H*pZpHZ4JZ6UXH; z%hp4|WXn?fnChoXG&DWMDxwDoiD`3~Q4NDG>C{dKzlp;UbE$cK`;&{LR_39$81;s- zMnjV{!40_V*GfHae{>!8vkt%(TmwNu9L>5 zxgCrAi@B3@m*%<`pAm%33)l}&+sn%~C|nz$x@D)KkT;O1hf2%k?@lunKeB$DXi(>~ z`^0(WR1y?4sN7gNK;3wupH+@$MD!FHc2IE0Qg!|;?@abI{5+eX>0ZWkPO=+jE?oE1ak1&* z^uoXsWzqkBYxu|63_BIfKw9DS`)WMD&t}{;V10y#N4nj>tMD%G@5bH#yFSVvXEWA< z)iX-Z{^e|jp1Z=$Kh9=oKK1>RxwSd{xt3`aPSfR zIqo)7i@tJPe)G>?9G72bGm0Y%218BJ<)%VS^@$lqElL|VpHPXMd>NE4%d2#| z^SgHE<307}k~S6CsLYH7w%5oz zIZN6u@>KYaYYUlVS@v5s7ktVEO$*M}2~4|B-0xsE?b7QJ*p@<(#wT1_>@8CV!y+_P z4AP_0>`Hx1MzBvFb4~pPl^;3tQ%}iD09>cHy9gPYfZH|ia2FQY=k6aJ$q;5QKm1Z$ zF0L9}Ub}@C?aRxYi;NLteFOtb^)j(vFCSma8n-KfEaBbwOr`o}KN{UmkDeUup+D7p zLkUD1{A{-|2q}T1=TSQ4JFS@jXi}<>8goeN-eCeieXi_|$J_Hx)byoKje#9O{|nrQ zFuLPCJoC3a>R6~dbyp*{&S3c-4PwvSDwjQOse-VDTGD+9OjRIvv-~14;b|xM{owN` zl2))y+bf@%Yjls0?ZCJ30<3^Gf1PFU`C%T?;PIXlww*jHsRY$qIq|TTnD&9iVA>3& z9i0I-7#$;b=f!wHIA(Gtpr;DS7*pmihEGp>-Kdq7&j>FE{8GG!vMPAIPsjJ^Cnk0y zsDOIR)hUhVkFaoKYd0MifYQ=Gq#DU}isuuY4M2CzQ$NifvSF+qokgGnpu-*Vp7!nmi*#Ohq> zf5?u$*RRXzp-&itHGE5hRC-Nh&X}#^+LrOdJ zsGT&fLI%?k>Ywmw<BRT!2JT9 zQL6PHNwti@4MRuwm4!7G3HMdJptN{TV4vC4?%=uFKCVDl4gin}BZsf6KwcSvwBr}v zaia8y)1b|k9_A@XM>!~oVZjS>-e@eR0fSplIYF9tX~BFTfGv10o7gs4K7W%>tW+(y zTr}u)OUP|4WiSSl+8sh&5P}Aq2!j+@HFnWsPkV(R(hX*HqPi3!nAa8ugeEwaqO6U{|ne<_a15adYtL>Jtc6yK&? z+fLSMfk}acU@H2flNKg*i-LGGJ3}S#2gq8fI#2lnky!?e7xPwPmUY$kl=smsGD%Cr z+E58u*B)92vBS{bVFb~VH6?X(0W%g{a}pq)Wa2BpjDX?i)sPL`*4~58l#Pl5AR7CGL=~j7E(68V z@q6Hy!TN+4-PY{s_WLp7&*iDbhA}UyCt+_9^MSZxmg;W^UpnF;w64aI#nkPD%|TQI(|)0;2ZjfB!q z${c*NX1!c8|73X9ucJHTX*ylgb8km|QpH+}JAEx%uWQ(+j8|Onxhp!6e*fm+nZ@<# zodL8n=)sI>Ty@z^3q6lPk~ilQ)n4RVnwXt~oO@-tY4|87S$269ELBU|2+LK@_2O#B zq@%LR2F9*=IW4^OV$rqB5!b`~XSy$h-|W?xNDCu&qH>XKH+#ltPzS1Jm-{A(kc6Ax zY*htLUMtmKLjlrmZ_-{Y30>9;y1<93(;P1DUVef;cHep{lI#nOsC{;5pnT}-)pW;k z(}gJcy({4uuJ;MyTsQ6{KjERW=QxGuh=%7OH{PU)b&fLLCYED4BY+4?%mKpyz0#$l z4N3?if;(wgIxC%IIB%)rQJOl7ve-6r+e%E?ikV)`c^+-P6_K1YPRnprHFCPka%;oE z3#-yo)5K>`7SB|}c|?|QjNg{Z)L%pvFQ*lk6z)66&zB~xbY#SFOdc@TW=6is`50Ra z(IFzAA5xG$#w$2 zzHUpv40z7(yW(tpmCch=I$p{sD4e)Pp58pmlgGScCvWNw?Z$Oq52~RI_DK@SN(!qT zQF#uLkw*#@2H#S79E6eS5#Qs9f{5N<^N0uv2@mpN00}g}!-F)#rI=wO*_LfAx11Rt z4$@)D!Gcj4_9D;2wBVjTAUmH^{)(x{whm1346^8PwaDs-K1T+#$;3<&krF@Z{DZlX3y2 z`C$xD4&bPw%(1A-%XuJ*Z-j?-tp5M;_MUM~?&;cghzW!M8ba>@k=}b%LJd_wM4Bi_ z6A)?A#e^Dq=!9NE@4Z(60TF4^RZs*(K|z$J^2D`f&6+hcd(YnQ^Zeeg_qY4w@juV& zI0Hj1?;NM}lRXF`&fKZlGRhih_dkU6a_+bSmW=7QrGzP zAq6rVDM|&B8IyAv?~uOF!t~cqk5Y)b9T~L*o<>PS(!P-#|LPb^2GLXWk|Q&cCPk9&AXLfCvd$GK zW4tnn?IW!jrLhgOy<>+1<20KT?VnMB`RerFUJ#}3*(`PxtpHV^Ia(f{zf>RH=a*-_ zC^SPWmsT&X#BeKFfd-~KZ_eQ{RWh&;l3*UBE~C*ZRkm+$W3Qqfw8XxX zPI!8DEba+0$90%wPm+G3Q;bqzw`0aw1w^lWO~_Uu&AxplUk94k0d|sv8TghLke4E~ z9Gkr4sc0)T8>Ip(Dn5E7b02DWwFJHiRYI&+j?ml&8dkOhR7R@h6_yiD$Ze`F=1+_% zyf@KFwWxYuQ11W4EyvC)JMLDYGZ+h%pDKMzKq>^j37_2`#nVY|NStd%FO* zpb3eWRQfh1{b3vS`lJT65wTNh==?7s+Wa~^fHryM(lpf6DB-M)IZQ;8=_5`%Vnq{s$}{)S7P?DI?Vk3zHWOI8EV zRvSdKI82H_OzY59M;LQfsM1#f4 zO)C+%xM72B&1BPeZ&PqGNVQNEiaW4yeoJY|9&9-ulK%63i>FH#y?m=rV5^@lTVM)N zrzZAI!Uo+*2u%zQvTS4B_Z4tzJDxHKFKPpFCB(C|Cj}xL<=fK&+oKy=GdkO|m)mns z+w)mE3KcsDmK`O!7ij`JDq@7oiJF0_U#{Unqqqjk&X&N=wye&M&d#po&YsiGK9;Tl z#jZiiuHnG0k*uz<&aUz0u8GsGo5;=!oVxsw?pn_7xvcJ`PNM&}`_*ap>KRMV8^xY= z%btzEo~QKnTb(`P)Y8$jM!PPipLJPKmNdvy26mE8F;5522AhvD94Du})cw7}HWwBI z`{s?hr9Ao|uCyd8eJ265+o#ktl>PKU{fycD%w7GgEB)->`w^@ITuKAnRs%di1DQtc zd|d-VD+40m2gFz(ODH{-vU)5N^jI$Yu|n5lrIp82`+b*%80mugX@P^c)_P@J2a%LC z7pewzzYiL+4jC&AnOF^(#!?>!4%PMd<<`?0R1Mu`Wxd5ZY-cs>5H#$RJ^V&$*m-66 zn1s=_3g+=~7@AFuQhZ`JK6D=QWc2A17NcG_J-PrT8iU9|PMeWJL2}HxE8~OCk$B?m zix96G>u8GAXqpvQa?ogI7jIbSXzusXeAcl-r7?olSV_=WS@u{(*I3ocSk3pbI@YHR zN>7`Fc!RB;wq-x<=z7|<^0eps(>~Vm0j2RltMTEW@saHDv99s)mGO!1t^o2Tpl}*0^`I|2^=^r0H{(~My>~s69SIL%(0X(2_*XNgnjy4{?68+Nr~#?+G@X4|t00 ztOI5qWdN5PO0oMRh=1z~bqw+}`A|jlg$n8x?dlLpDBk-g*7f}63$1~=5`CekeAkJG zIQP=z3O={vo6+1tFiC@}81UqH17O-C%!&@}z@G*N?Z;jzwowUsbdj zylVlHAB5NYJSYY|pL(+l?oZNP5J9gevAEq?R8q`o0XRzRdcI3$a1&63N2yLJkl7o* zn-A%Iz{YH3s7Lb!h|a%<-bf*HD426);e@EgxfdY!fmCsjvR~v+d_99^){(p7tAvI zSiGQ97P~Me(YZe;6s&5V36jI$u2NG3|G@X1#Pgybi(SA74kU(TlhsF&t3!3#G>}UO zG&u?xlFR}*72_+~<42NEHj&LCA|xX+3~$p`y#$-{ag|I}U3ug(0y@hm0nzG+0D#ns z=l$C_rxNcY%qp2S8C6w9P?(?_l=&+A-+H3&k-6$sMS-AROstEAcQh0sB)tWYQLhTPm8QHg%N zIN<;7Ga14X2{m=);)4U0=-b4?doJA$DixxHx4I7iWl9s_=3LwwZw4_!_Y!KHv_y)1 zMy)dwXzdn2AFayzFr0}G?a6^iLljK=nXwvIWh{5Ginf8y4*NIaExw;N^yfWJA4|mJ z>WSfShFo|Q_KpK<9)ID=i|EvA3l1_nMifjxB{JGO36OhhXHeaa$8>;u8Z1X&k+jx{ zIfy0o=3!OEg?pU#6U!w(zkeO&cD2c>Y10t2nu5x@Hs!HUl|wF}j915D1(xJGEHcbZ zA>8Ny(43!AG3Z>~Yv!DU+V@`mx}XKw)>3|*X$GCpq&-7CET zTAe9qg)v=5v6GstcEJnhR9mRK5>_xK8u18!9bkfasY_EArTf#iMEcSYqtx1@pz}^X za6z5vXyl3U!Bk=lw_t=i4@@`+mulQr*&BT0>YE=ESw?>4zy(>kyYvJ~%8xAH`{?AD zUl;?tKtO;d1sdeElbi+NxpYGjsuPc-fMW;f4Ovop&giD&N%2LuB|WDP!z7z~FP&pB zYbVn3>@7c;~7dWILaT>L4RbQ*4TMKNsug9A5Z1@ueF0 zzFIfx;!SdD7Y)XzJSMGU(8}ExblIzA!ULW9#z%)7)@o+x7dLR<;HGl;P*{tfXW#y~ z5HQDTh*4dflmv^UvFxi;wM33~*UXmm>1AMLH=EwOZAqZ8s`O6v(busdfk4<0v${AG znqXVc`LIfTNBpXOPio)!yQ1!|Tx_$H%!Z6$kChzi&+}BO0xHe4Vs3~>lQ-IAtx?rd zwhCRti!hqyuz4oZ@WJ@(NGNPzVC6Yv4A1k>GX|hJIHpu7+AV-78U9o<_jyyNxGo=1 zU_zBqwH_KUY0Dm&JER1Wcz3<7p!w_8zS7H%cda4|&zV#Q@Q-m(3}0;74*b3-9qnz% zwc>}G5E{ylx*U}^&8^f8jA|Eg z4FmD#Gtq>a4waSaZ#ySgAg~USf>^fO`y2j)PbVhF5&5A+t-u3lCxxUiH6f5oY~a=YD@={Q24Wp}rSWd(MqnOGPDQ<>1>X_gdd9%Q<3i z%({5~0Cdb{vwJtqJc~*5vU(X|(4pcQ>>6~1)suqU<@tx1kB=frXq*|3#vBWx&C5bR zSmzB1^u4m>OW>+Cyf+lYA5j#P7?Mwc2MCoK2lBi5y+C#Sn=obKY-fghh4z=Bc* zV139f!v@`|pX47T^lNViR1Z+ZsO{8dc0sY^~e*r5fAb`Wn=Gjq5We1Qwh&w~cZg`Q(1b<%Wkpa)mN z!1#XN`cRn7M#wo}5CxW;j=_6N7EPz+VRk#jNDRvO_MvJSrx5^bfe4j8a+P5ub!b65 zkb-ShV1(PENmAjAK&R^{k0wnQ&5;ONM~7ZAFj~_Dm~ZNU?r zm`|7?UppaE#XVI^;^{f<>JH;K69E}b;PFT`iZ!|-AnvG*<6@-P7YOwyE}?+wN9W`@ z-tgIeH=|y*gDDv&uFp$(PTwY|UL)4#Q>PL@NZPtmUakWe+1*Rb#8v_~&7r`QnFg{6H_H**; zn3TJPBB@?UDFZ1?8L;k|)T>2F(G98hxg>0puR`DHktH(m(WJs2%bfuvw$)M;@EmXz zqwx6@iZySyyOOSVVV>q}d2;ErYq#ufTV&5#zq*lJQzYkgQ7xpMqn{ClG*ZNS+&;W! z%|63ptZr97Vwe!c9$}twfip?T=ZeUTINT#S?=Cxb78a@|O}1yxzz<4WDMVd05KV`VW;V>Mn$Tf2 z0%<(&U>R1Zo(rg6$gE!Ks9q5;Q(3BBWv=m4Pkj@>8xm6WZi#7YyYxe54SQkbE_3a^ zLhXS?Z6Igqx6Im;j@s`_wLd!qU!2qe73)Bjb)UD*B#;khg&U)76diK-$1I|i>Vgt8j15aQBUsi)aXM>PS9(1`ujHOXRkz164S^aFP zrp}`NVwh?FUb*B4>Uz@JD_L|~Gxe&9O{k}=(pgPg7N@Kh=gt<_#S z<<{WSRy0dnh+d?kVf$Q${OAhYwGgS?j*c)r(bI@Qx{-&f$$+rQTnQ;>MxiU3+^`@8SrH_QeDp8d^t@jvbt*bQ9z z6SL)YaPYs(atP7@{{Nrl_WsZf``3QKKh1I!c<$&qt$9{k zmDzYOx&1cFv6Uta^yYjM)vJ$r6J3oT`RgnP-zv{PVYXd+=&xB0dG08KU$Y$Fo3-Ah zB2BTyLEl{8Uoz_rBK9kZvmF0TzaVJB_f{U-cIZxi*m?D2b;~gGU-I}4qjboN%|t@{ zHu+smHdCF_)L;7J-{tW+KeV^YqjQO~95O8hxHO3NnY&R*)xVqN(DAuToaM;ksj3tB z>nw+9fRn17oo-3FjP!?l39Aa~{Hjgyr^2eC6~AUVNCVuu9G-p1tvU#Ka6$cOV|fPj zGxz=TKqHV+i6L-uth{r_y1lxes(5?$@ykm%5VBY3qhZG!C#zMv5ymQKnD(YnbtS4C zk~d`Ogcl!$iH;U2i#>_uetNFk^-D^1Q}U}TPuyt3fO8RVG6((4l_H*=&8}4Pe5AB% zQmYu0dVst^lhSN`87Ifx%q54a<$?vd@bnS+x% zSABNPXck5iZ^09Uw=$e$ixMj4;S9eBcugs9FewLm5dvFj)FZSa-A{Q_fDxTSfN5Y{ z0dD1je^usM4Zhp-#pjz-s zMdyxpugt~^>mXi#vP(sS_y7vHVC>?LfCo2$F*9Q9@t{CCRtO_!5@)DQVI%6#)dL6LH#0md;B&H1K_6Oq!=m~vbjO*HECOs8E86SYIS=ChbAcLbD z3j;bi#%Gv>0D+8sVhV&P(!1yQ#}H`CmA6D0MYytSz0Qp`u4~yQg@(H=r5&7iqbM;i z&QnW-8zl|U@3w^tyRJcPUJcMaR^o{oc``0+ysw<8ZYv}`s$EzvWCKJbvRyQeFmj;5 zS0i}DZ)xjcnp7iM)!#_Ilhg`@d_p{lfpCtls#*fXv#b4z1$FAru9D1_20^Sg{Ux*w z4OEj5Rdo<1QaTL`u8^u2?Sv#uB1u4NSm4d)a1V1_M7I~>YId25VPqI){XUeyZI2Ae z?}@E(jL$N$<&hYNP7v1O1*D7INx7m3! zbz$ey^p$;M=(W`{XBB>Gi;c3F68qMr&mmDf#fi8Si{@DAWmDqNzKi+&lwGSdyI0ngY(njPQ)Ok7%A>FDm^p zVMd`75m=X$T5VSBnNVp(;!R#oX3ofDG4(8*^v2~twp#%0y@cixnA2)8-ml+9(NbWL zZvNp_9(!lQoit>7b-1YI4)v|;EveoxBV$3sH0!T&sl;AP9Z2A`_hsB+-`bDJE8~^0 z;=+=eAK~QOmvkq&#abW!y69lahF#K-y9}gvw|`P;lbPxl$Z;7aO#$t|vmSDYhI*XZ z>fJdn8P>~BpYVjXZyY4%HOO+_GeXgmuNMAv7?klt*J zCtN_XtCL3d*&x_Pj5io#?K=ELQnT38;5M@g|9Hw-G7YLYwp8}5!c6-kW^oCJ=_oaM^V{ia#b6e-rI66u>cfB@#F$`jIGf{21(&v|w`fC@+oh2yViL|<*FBIWPN$#9~9^}4{;)I%`18AEJ#jef=zT@Y(jYWzG@|%p* zlhymrG@cuVs3=pIkARk@axr`#S7ut=j@mgcUk*e+wX1k{w9x*=TUf{tzbH9yMD%04s1-+XRK|>I0GfP9QW#VpEFrUpo(XM%| zJAM)4b0WT#pp|)SIU*JvIlqL82GLr_`&Bva9g+lByo4M-3sv|2I$H4kokzm4q1fwv zmrp@d^*bBeUsg`~ia6BDgzsTi1`woLJ!c+Vs{splF4Gi1!WkzMju-Fz{AQjXFnjB# zCyCCQ@8OfPA0$6N1HfC)u$KM*yCL!bvoLz^{=a!}CePZ^*%h)X*AR;oyaEwYK2N)-c_L zFu)V9?J#O@KKmjM>;or0!@A%?;)VX5h43WCD7&&?kqmHfS(s?6u+&r(PrZIj8;hS@ z7&rs!k40~$`)VMU_n9TjOlz1r3HkOX&lZz;J zLffKaq1Z5^LvLb7on|YFb&50p=+fO14@yj&sIhUJTuh2nO!5&n9vdZwdXUu?p}`Z! zw)fDZ5KBvKC@2x_Zx&0Q5!+A}4W_|Xn>}PTikqN|?J5Y5my2jZMI|hR*dGP&^J023 z;;G*20ovJyXh@KWGhOel4-l6Iu17}jvp>Lt z^`r29<@mkLbo08D95N868GeKMo};-xrqsuR@qvSEqG*9Jfr(YG9H09h-`SdiGF0kg z%zB3b*Bvb9cv%Gg3`u=AI)z&Q(d|$XWB_XI|M`n{N#mvI6P3_fQ^qR9!<%Eq} zfiOQ+*kn&wUCYr?;6N=B*7pd8+w2Mo#j_szrkTYuGes`W_Vf0Ql;ZSWe;=JfI`)v zMb&UX)yQ^ber6Spq-y-6s*9g6sZcGaTBZ|FH2XVdFIB%fspdkJuZ}THDAa5O)NEze zYEH{Xp{=#hDtOkiwx~4OW zM!Bp;1znztosE}I8&z1Eh=8qb*`yiRgvx5t>1@(lZZbIih1s!~GGohT)4*o4K-PDe z%~s3J)|JfA(`NDh2HW2-+o7}Gsggm8xMY0V;)!f=w`8&jY+;&i@lgDQ*|FRCK}5{X zQV!M?_GD?ZpKgrEYKxI;Yo|7ju7p{hwk35|hb#Vu*&k?Qvwrmp*i}i9YR&o_0G%xreCnJ)-nDEW}EO-&jxlc{LwFP*X@L8 zll0h9x8GRn;!y2Lv*~fj62UHK?>wcJqi;wQsQeHclDtU6>;h-_SMWr`oU4%i|ZK0e>I8{6oL~$26P3tj-_fLjTm>U)ms){5PYQV{Can z|1x@6<)U?Yd0uPU)TP>+gjs#3`H#`d8Z>8|i(8U?iYjd#NFR}rvni5(udD8bC%zl{ z!i%BjV2*pNLB)0XQ{RR?7rGx94xH*eA1(nkgmR=&^-J2r>j4ZigYJ)+E;1Q6#rS-u z6;`WOom2?qtjbI#za+ge+`+>OyH0zD03Bu>IEBGL_gog**(Fn|P%(JM%B=H+gzEbBpiZ7~rv zX;Hhwn4=-JHu6XX$l->&LV2%$h$lpld+5pzWBlaHn1DriCnHbY z;bv~62;ep3E+_i^`F7jq!r=PLhJrV!2!8j4vZ`l3Qe6UkQ?*R7jS+4IhyYew0GG=J zTL!zcCYqPoXI>RO5&>*YQV_bXS1;Hm2<}1*qd$Z8A_d-`vk?(_`^DUPav4@oJ9)Tx zfl!02&L8XfvJ-C5{Zl(J!Kg_H3E^K-i5{T}b3E|OdkB$L9DjM0>!&34ri?fkWV?+~ znSOn6lnw%$T;*}50ICj0T-oi?fB5k+o7V1>97$PinCMzEC3w1J(cSP7`?!rh5CH%H z&~ zXBT`$W)N?y96eHQPoPwdNd}deksf3QDcs^g)qEOEpb9oQu4f4Eaf>;~VVxPzV9|xB zcl5!fO8xSQg~R+?@>I~IKnoK<94&-_)i(uw8Kf}I4Ph{}$O&XuC$W6YYM3g9DWHFG z6OK}yhQsnIDUcw_Wi(14Cs12f?fjZIE+=8fy` zA(VM&D~M5?vq_@N0 z1vx1590gPlRw4c#mYuLNXtf94+r zGA@Qw9`+3Fv3j0WtgvRLAyQL59aLa%AACFa!ZFo^wKhiv!9 zp-W#sX6Op2UiCh>iHg-8XZd+DKg?=Su_o2^w$qqmkZpJbLluH#ZX6z>C@GG<@2B-s z<0=<(^L^w3v*N|a8&6)Qs?t)H+AlfC4Kbgu&(I1oilbZ{tBtZfa7)7Q*{z*DbBiC) zuPIyQxtbiBqF#w3Ymg3YyXdA^oU}1<&_cLN0=;h_mE8#2dh_ z#tk$EJYZB6|AN1$PRTqkSKf>x$N9FelbqFW);yz5v$1vKoPHdfqGdvzzd(P?e zbLXsgq+fT<2aljNm$IO?P!4H?XEy|?*%&@+Z$<5EA^p{p60XDp9o zGMV=|UYb7MkQ9u6bSilNiK|QLqvQEdDPBKTMrX?i8kJJBa#;l#IX0>rA&@d?As`&g z2QADeXC(7PY^qu!z?O_5x=z<~Wt>MHLkbb3_I!S}x5G2h;WLLA-_n3ve*Q1hz^$f{ zYd(<-hYnk5E^!ecBQyw1A32?P-yBU|=zyIxb)KRJ8zKPcGd}Dq@yG_v$klHSSf8la z5^(Sl)*2Eui^O8(oVSOaVn>|fx1v_}Bs1Eg-*32Jc^nfM(PeUM5!57x01}ThSHs&e zvTN8MUyzMXSLb*fEpErW=Xn^8F-nv4?_Xde=E)F4#sqq0avbY(I=g3WY~=YGML0kL zmbQ1^`f)^@^xD-$GbRojiXR8s-ZT1>$tD3l@$-p*>dC8TDp38QTl;Nn+eZ}NK2vDl zfE6|-EFlw?8o_`*6R5{+nd{UIC|ouPo28hO${r3D#YB$70S&Ekj^JT$eHpZwjVGZb zOf(OQ?g8_4_?VJ%NkDd=bulAJbN%5&*L>C_sm<9CZ8cAF98z_(5v+m(5Qy4*Sh5lm zoAIPJ+z^#DnJCd8pw-SqFuY>Glsbn@GL>hyoRqoF#7EE1cMG3tE1zcfUP;hAZG0-# z$)C-zJuSjE-i;}J;#|6?JT2mw;hSlCnn!xTVtVj#I+`gXL_QmlyGu$2W4~)A0Drc20pt{1es0T&B!I`AmX&W{H1h89uY3J+o>tv*tLn zjw!1_KC8(*tHnR7&HR4*C{vI&b$5GKA5->#eDnIdjDik>>6k{%$C@Pe&D3S>%lFKY= z!W1Yh6}?9mU1lbTGpDIq5Hte_s7!)R2SKj_pRq_V-XpYV7le^y0@v~kGmGW>i!7XV zXx0kMF!?tXN@73+yMPiN&Jw4N5?38AtECe6F>0A1iLXq=7m0LfzfzaNk^l>Q05Qal zh6f1<`ZJeBEWyG9$~x9cqj43m>vLteZ5WWbJPco!GImLwS&+!s*#aE5i6Qn_$pZyU z7IOu`rUYwV@piAg#5p5&se(w?4GNV_ztQ!sctu-BWmgBMNky63eC3~Xomn;3Q8m6) zHE~ik$y`0HQ2kZoA42Tk=z7&zn3t|*-QpKr-^5hNGyh}L7);#A8U()npEQjV3qT|s zbl!hJT7}i<-y!WU5va=D7C1tpZ0c{ye||lF1J0xvPEDAjp_vANEaCd@Z_1b?aW+Yu+b@>YagYrL` zSMaM6PI`O3?#|QPf8EHM_`$pHjR3&@^^>8z;9RmudD-5h#kM{8t3}em%Ks@!UJ2Vn(|t#nj>NQafmq z#(#=H|4T^w|Gc05=SG&xM`8p@l-iBUDBc0a$_wr^{Y7fG)4CcVxZAc4+%#(sX^;4A zKfC7s&2HjG7EVLAHc@4zlBk%GAiLfRAQQ5HgWn1MQp|iW?&f2v5(_g^J^1vPMpO5* z+BM;lbQNj{8Vvw263B;u231DGKzW~d6-_Lfmq;C&t2JArWbf@(wK1t*I2XM*AMprK_={-6&(I9`D1*o}IOarL7ne4Va- zqm0@jJjk?*cHh<)$~AGDWcnBw?1q=s6m|xJ)bj zGxZ=_&|4#t$~#h@s0cpd{2G8Y8RUCZ?ZY`ii(PMH(g77iG+TE3-pLJQ#!->|J&*9? zH>s+dRia^JCab3(QvsKn1~FFdk%DItwpWFuff(xK+UuH6O-%&FIdP8|2JoUK zYNlkkj4hsjKHl4ta(?!SRv zhDynvc$X?tRXnw!x66P~IS3U*{C2j8UVSsU&qWgC9Aia z8Ay9xE+2?UYyDn+y-@&d8So;~n2$Ip&ip)5hEM_JuQb0kqZ!(EP-ONZ<^o;a3v!rg zWn_0DqkIK5Q06)!;Okp!$uBd#B7}z1Y!xf=_QkMxLoSR7YVbf|ao&)Q6aH?);=Iek zfb-YpS3;w65I*$yS!# zf*@=g+Sjq5jPjvscp2g?+W|~Mcf>k~CQ`OkS8KT1&@Ai6F)y@WD#dv$2}_ zrK@{XC5y`N-G2$S+>Gb8Hp_aAEX-UVnS?*y0qrGpmaV;hwg1Ff zx}-yFV60U?@eEP*ao-_r{0-fmFB40&>$2Uwmh`##r^fIYLqzl{- zvvP3)$S3|FSD`lCA`^GpO(K^>Z{sbO*%*_5BcMsB{tAcY!xtC5B5uUZCY5vq=&9#( zouf!b%Ph@4@~^!iebZ6bMS*;%(*Ye>{UMQ$YChYXg61L&OfGf0sQi;#xiqIQNhznZc_cB{)4lPZm))i#uZ z#!D}T*L2joVLC;_Ewx#cZ~`D)NJ@zURx8`a%kJit&a&`Q$fq;(++UmE40K!J7zPDXWTP!R6Y=>_`m$d+!hHq;le-dhUA+71jq4+ZttfxN$dCp-Q7c*J2Ko(HXC^Cc!4h%4KDuZYqRJSSHt&7s$-M(p zsmfBc=z^9qB#?nGPE>M`2Lir=oypfl?8O_Ga7V*}gDf-L|KJizdZ zwp)*VV%ssG^XXu-zBn6zkKBCRk+0V>BY49Py`K)t!p7xKdB7O%uRszoy!VOC=dV~# zV4sQ{QaWcO-h-NiYTn(yERJeE?m}zaSL`qDr1ZWfYjg9bAN?nX_{8)`e@5IZQd|Tt zfHEo!F-s$J4JOKv=um*;(}MoY$1&bbibw}QCdJQGug#m$+}CvGmZu*(iy(5_g%-5u zYIvc zCqG-ga5j0K@LBv?a)LpdJOwzde~;Sk_J!&`XjLOD>tc!_t?g@$PcIsqL(zG@^DmrJQ3{_YAz{ zBs54qbDRX9q>Zm2X8@JbY<$U_rnY*I%4)-Bb+l)7EfU+sS&#bd`~C^i!6ByOX86`PwEnprWQV16) zlul%*DKCWB6p4w`DmlYM#1nQp{hlB`}umz#l{N7CKkn}nb`&b z#TFgKR!ha!{}_S()-+yDEOuThaXTq-XD;<5HjOjWpX2EzPV&?&N*U`*gP=@2C#4|@ zWnmU&5dnWRjfeki8keX1H3H2&`CHRCCX;~QE>(VqBmCAhCgsYm`3FcNMxY%;NL#Ax zIjQXX#|ZRaAZ^y-4@k>Y^<&T|)A4?HhrO<&np;imwGLZJCN*5W=CrV4InO)H*uXo&*#V%f{DFY5{*VjUice(9XI{c-acgKcXE8@%?=mxcEETpav z9qm5M3YzhIf7yQd^hTL*X!8k_Xb-KkiKvD)$dCW>mAii+Unqo$PCvr^Lc2wY;aiF{ zUhMiEQaAOl@n>28;VX~NK{)O#{<4QY>umk>n)9VKty{9(=l=oPDUJAmHL`9!@A z(oCH4pKETv9gz|%`0xLV{LOj0yzIZp-~Jui{k7ftZ;nW}{x*M1Y_|^oIe&cW1V8!q zq1F`e{ZzC7$lyvuJBk?V0VdBO_qg*{#@A`#SDmahQ84diwe9O4_nxr448_Ht=O<|h z|F*&f7zLFFHDI_T?9$be7F6q=0foNrV^e;-^Ae0YwwfAJ6X<&lRo@ma}5$tbW24ix+ZaiV(rxkT04a0)ABjIDNYxntSR5nt0*h3a8Wf=8Tfl?#= zR1!GE2@UE91WeRd3Zt=tsX*KNqDEb9DEO7ITl78(z<|<6K*K%|B^*G)P2w-F2iQLY zA~4wZ?iBa`T=&C);e+uAJ=6)bP+=Rd7s<1%%7m&P?)_06w;cM`Rmn+1GvIR! zB{}Dg64?O9t~h6f_5e4Pt)>(l9mBkS5!tn+CbUt9C}S-E5eyYWo2H`Xh$iv-?U^9sf@yT*-ToGI(#bdw`K##4!=cBRNzMp=Q4=@7^o#|~WLOqWDR++ox1 z83~2$7{+uj<@>aqDm52t;nW_2R%%3;{u{$FI7Q5omFH-66m`d^Dd*#Qp(ahH28vxW ziT5UU(lbr+<>G!};M&rqMsu7imwN#@;|OrAWyXzby@0&GNNr3L<~5KalB`#;x$;JrK!kJGtXwJ~AmjP_#QXp|0kg`HnaBJorRnPSnkS<#GK@XT?^myr zF3QgfhIki@r3kESTNpQYOjkgS^fzLod4lK%>p;jV8nPj?Furf~aj76c(TXJ>r>?@rmoSD|w?2i{*Vr!W+ ziBGAClPcHf^L;@rvK}X%a?hG?^Tlk53FjbprOQ<2^0o8AT+Wt7o`;3cTiv8M+Xk- zE;uAp##bU^bqC1BBztLwb(LqHjzB;(%?!seKD;5f86v~w-n?80@?x}wZQdBh8h2rNB=PC(qbcyXZf?%f{O76`HXDgOhY$C$AI1&s z3PF;tIZ~D#*(P7c8ryxP7UP(@XE%SUPZ#pU7@R%5cG18Mh_>6$xm&nk)_bYEGD1*s zZLWQt)50Cb{^|19k00K;C;K!7@2t7Ty}vVk1EJz@v+-?VFQc#j!mC}5^1FJ;oVD%hkTHR_wHsl$-T5dvdzrI}a!CJcfhW&(GQT1S}TRsjP zq4sRe9IHB5L|g!9YAI!$Cv?fiYoQvs3!$~qy^XjiA-e(u&)HS~L6TRqIP1M&11g6R z`%n~&ih;04*O2W5`RKtn75F30Ru;gIzy0TV($o%=*Y?y^MJudbQlDI-kQ1Iv6Xz@ ze`3J`Kx9frRcg|wF{+d`96_V{)}Hx-mq}s{I|7#Pj!)M{Y`R1~{4D&)^UY)HO_%xa zb02=Xb#2X7pbj72ZG)5KIu?Gdd>+gP3n7=eZB89k;0~BL zPWfvWp_RO(U`8mIku-$YuU0k;2zyXwHEmOwC%ol`T4YdV8 zFE3yU5P*u+@KT1OJNhGf%uoE-=~&z#*F+e>b-d6t258~gXAG{4^rqaS#|$1GS|09R5r!jfXS{Oy z1@`hJ(VKP*)M?;M6}0zJ=*_lh&{Xgv+2Bkm8`>>{fv@m7nQ(PZn<%FTF-djgS!S~(XGsDcl%n(BjsSb#Qgd-is4Bb*nDj^brbc*QE z4MR854blzL0#YK9f*=SeAtkAD=F0oJ>)hu#>pbUu-?iTVVX;_?`0elh?7izEupL&a z;z472QPZnW<$@n4P>1b$1aD6V{MF7{1`Lk(7pM#}VX3-a258tlT+A({d$!#1RaqYT zuxkbm&kil!G8C_4ixSJC!G_yZ?Lsagt8ovMqywyz@}mJ-+f+XR*R)1G!zLs9avh_2 zk{x!ea3U!ouxqo`SBJU{S4mR{Y$@saSGBegM4u2q0GQC~P!(xF9TQ4nD87DbLlfyu zEN(e3Md~1RWz2>{D;0)?rdC|N;-Tu!B~Fxor9LU(I!yhd>x3sOu}#kq3okpXfLO%_ z&h@j{b@(pvK*}m$8K&;5pJ@j4QL5VRsiVU92Qt=m3|SWRagC7m>5O+UuAjlIdyN-h z$c!ae`exO0X=!MgM&`~jGoN@C+fHP-Pa3L;<#|6{DkhWVFa8@hoExQ2!<&+=yeof= zElWT$M_7`<#vdkqw%{RM zBRsG9afv04J6n<={Yy#Mmy%!T))~g0l;8cg0#GrLZWW;}9cQL-eq1(Vz%|kI3*AZ# zk$#l?-G3v}t)VrgPK$-oi{)SbnQkS9NQt_RrQ**J>2K1GeD)W*70FUbL!?^`D^Xs* zhe*ZVl(C*xqFJig{~<*B2i-a`Rw8IvEvoAEE8W^$oeO?(?eFPU!pBP1)G~pI0*W`# zG3E1`VKv{I@<~{%bk>VDexqAYYfV_{ehHB_^9UC6{v+Vo0~+~{-l1T4=Km3a`S6c= z<^-2Zb)|o_6m60S4ptx!J08(qPjyG5Pf|FI*! zf`+O3+VkEE)v^P)RI>ILgTF^WA{kwY0z~A8;bz^sEYmS!OKRmiJou{`I z30RxH@3KrBAt(?UV%B8=mmGtr?g9C)G+4h zIclrU*l=iiu-x^>F{Z9pS!w+^m6RV^IM=hBoB9GO`%$SyNTbc2C)ZLA#}36kX}tdt z?TOpCt%DxSZ=T&X=!aBwu~kLeO6@ zZElNv1*aJ}>gy+bQH5`{KFhlLGMvNs04YWo;}J+0;pp4vC^%D3oZ3#m{pP`WmZBbC z6BQ>QIECA*XfOu6%r+@XDW(j#W5Mgbx~*7Kajpy)15Y=xM~pmAVdAuj%uJ zC;%HA{qC;ob&{hbnv(Z|7UNb_IEuAOR59_LwC8up%x=AspiUTh&!uv2@@)+n9ozLM zMyeq*4aJXL(1^Jl6%V*(KxRdeE>ot4grrUjPe(?FFt65WQB07p2%o%g+SnjWF%c?+ zk3PMlb~E%guUWLQ?YR(<4`1jZH>$E$RrEd&pJ>+9?S{E}D}mXZL_0<0GCB558G2?q zRe#cRk=nj8=U0g@@e#0dKlf#IKJePaN@Xr4%ar%Bib2WQ5qUMni<7>UQ#YU~&Sw7F zDxYPxR3M?OP7Qa7&$)R5Y{g&MvBB+v&{AC1g4ToH@tt?HY2MI!)07sHXqVW0C%W9# zZ8$>FwWFEwNe3j1CRiGr!4weiNUc7-o9D!LqApW3t~IXXPD^%X05=&LP82TfPKmGGIab?^LXoaIS8}&y`@L5nXc%F4TK%Ff!-kV-ECxVz2)r>Wnt30Pu zuddv405=%jBMTF%aH3SD6MnOZ@nX+s@nul zq1<2bgO*G-Ybr~lCr2h4?rU^1_Hd#THO05gt(evK_Gx}iURgCCd&<0`?I@pIq%DFt_Lfw!bInMfhIXPPG6%c^;vBaI%pFfs_7#I@}&+FD) zLY-P%10;;q$GP!P7< zhO)6bu(ZjCXl1%@aQbi5L7wRP`MtqhNH9yigCI+QK^P%x^5!wI=3@o^HaI_OHi^&j z0WcKg%!G=jz+^4o?rJ{vd=gzwUci+O>If85OU^#X_ zx2c?i!PIy#o3QcsxLar0;x=bVw9m-+9`!N*cz}GlO_ew$b))ObUI2aUS|Iluec}|h zqPR*-j*SR3G|m)3G`Vcntl4uzqbjeIB>{;06ldF&z3aoSrchG#=cIF?`c80>?2J zrdUCVSYiEGQO{WMv*cLG#@K7qu{Vxmu}pE&5^=Knaq^yVipg=xjd7~eaq7o$8cgw8 z67f3v@pnAq^^)Ta8sm+oE_H8PARCHPSjNID4Q$I(Vsbawp- zVwy&`m~f2NiBJ9pcnU0w{~h2NG8P@llpG_G{IDt^&NDetKPjm(8C#i{cAR`;G5M}$ zV&*>sp8d>@On(5LfAJ3gE#Ue2V)n1zp|(WJL@T7LkZ@n)iHjTyxu>A^+G8%)m) zt&?|&-r;eqk67a2@802azySJyF%xW%$q!71UKUzO%p@lQp2~V#$C)&eS#&3tPn2l> zDl>q;mZ66JN15^WKGwf2Lw&n^B|wRNpH;c$cSP}FO*}wLHHYY9-Chj%H#ssX43Ow! z<-j9U>i;S;ROaAhpx+Qh-g|>d*$ce{>Jj=Q@!t`}{|=eaa=f?p|Cr496;agqrKLsZ zj`gQ_z26W;rT3_Nf&X`9#^0~tfs}B6B8tEISTxZa<4^%-ilnIv>$`jcc(u`k;)- zGY#S9rB|QLS*Sjey0Bi*u0orbmj3GUFHNUVrBOlexlX>(ez9Aay(i+ce0xJZZR1~u zyBi^UU9?kt?VOy^S4a6tVXFI&Zu0WCk6{ZfhYlQqRIsfDia(> zuv)4Z2oA>G;ZbQG_c0Vu-mv@nruD_2hP}2d*EN;{#hwbyE338(;*{3jL)+?*0@%gk z)q~ybIK;k$O!v#u_9?iz-M9B3f4k8uiKND?vr`xLlSblNTjZqjz}pA7M@aLLTkVFo zX8T=u1qdJGo(&(Y_jbK#0i=%b*PfEZvlDo?07(F?f*Zvms!mIWeLxDqrWsr$8}S$Z zE8L1Dxz^r3!z*LiwzrL3ok()<^?hV!$HGAcZWx=nAxd`wHK&Fjbb4|DsU=2xJ}`j( z^Yk))qP7m%?R_YfLEN+F3>Yyj3nYbQQC!&*f5ic|sHer7d=c&GV%oH`mtrD^;9nH* zJ6@%XC9az&QXfz_2H)w@r;(IT_D|Z0(0z^GnUR0RkCF{BE>)wuAb4~5ScBbTaLG7k z0V91UJY4tnB9@@2NF8Gyb%~C{B!y8pOheOazl7|=<&Ts~CzpVM8;slv){3l>x!%|5 z+RtB=7JFZ`8=qkm-sho* z{rM^%V3w--N$V=vw36}wRma_d+(I0tVOfAD`bcHcKsD_9BYBMkBqqmIsQ_u;tC3JveIIkz^4v{kZNH?kiw6xo$6!G1XUG^j zot#U#HM_=pmo~Kc{hH!+hOy|&)wyWRY#iyXw!iqJLY=EQ%3(928dcGLq(xb~pyCFZ z8S?@?HJ(Gk&x(0vw*it;?21Y=$U-}FtJ`Yp`gM;^239Y4i#YJL_O_6Rg zswu-32z|-3duqAPb2$Tcly7tISBU}=Exov2`?DTks zZy06i>Gi?<;vr*m6}XAK@u5qiQ^%2`Yp~6e528%EvJL8{b*J}p*lvd?evNb&D!u;V zX03-j=~zPDzF&GzLqFZ=JOkIKyF6QxQrAYACmWKwQl2PynoP3VKacX^pBLpboVhM) zL9ZUMEBg9o#TF)#hC6#z$M*fQzDx2IN=K{W#`^q~gz_Ill|k3P>#y}QiWpv+C-q4h zMKer$7yP(tZ8x|a9U7OU`}#b;NU+`|cX^OzFgBr@9Kz2fl#Ho;p5(4*E@(M1kk3?v z%|zq5%{$J9G(4P91Y`i1BevYDc|}m4S3>wXCtMSWML}Z%a119y_X4?Dy*CtZ2FU{z z(ZN};bO?U~)37EP9J%$R7B6`sV*6T}6U_bvhd|Q?$$!ggHL~Q;VB{tr2njqMay-V44!-)@~8I zzqywx!)96K=?muR)(14IAC^}WwtU`8A{--y(qWC(w@Rk@MMN>`>XKV&d|u;)fpv`F z8xM^WPsXU%s!IIE6i<{L+ZMLO?q_F0+;URq*3UOId8&PpHkN!#EHLKIOR#KJx+WxZ zX5rQW>9iqsfPNC7@+%{GYK65-CLpdXI~jXB4JrbcNTyvGg>UTNWw}nSPey`Tw%z0A zGqRBGcW3`r7OQvIa*6BIo#-s>C*-h9)+QWhUF_JGVhNkrf3(W};ye?F6_D1fU6v6; z9h!Xc?ver057kR>chhYeqbvAUQ4ed3ss16z6N%@nYjXuUw4#|O{pY`xL;AnYOg`c) zD=_AI(!#Lh9&*dRXHB7bLN^SB3$QZ-O$T_Vj6eNl3L z?h5JAiyX|@fz#8rTH`^-Jgj3*7#m$SrWNqm9{Ghq7BQS(i_O6#vo-uj#hh`Iwp4xI zN%yZlwD7pO#=ui|56t~gkjr_b-qmo;H%iPQoA~K*W*_SfwXJ-1>eXa|9c39UOA~GA zNp0219y53Z)+ylMy9ETG91L|m?;~Mm3=RnietrHy9#%o2)c&(Nwh#3jWzP!T?{8D( zA|WIUL3CUYN^Xc$VX#GTu#O^ro&IrBAtYWmGzBewA0LvU5&GWUh$xEz?jB#KH z9%}2mM`ga?hDXuC-h@;$GTq~ZG!}-{Yd`2nV(P7e_}`~8uYhIds`QgFV}xLJ6)=Fz z9lqK}Zxxw)5&*eaD8R(yBBSG6VYuo=J#z=uRYqnt4h(idcvjAJGni2@2V=NEr_mAl zjf~ls4U#(wpO%F$CV|_hq6m(%Z}!B%Zz%VJ3C|S>h9(G7Sab>-BTzpY)yPD&Z|>Ab zqo>*X66o*K#>iwvbHY$m$uXfm;cPxJd`wK2n0}WTVLv+I;*CtFyU|j|vCN=*Sc$lP zvRK)_$_$>%^2c%iS!N_BJZwy`oldYjPHA0P8Y*ZiI%>lTdl z)lVw#un+trM;3XUL}-kj@lCotofz$zoRplr6s?hE}HkwH%qJNnB&}Uljou00Xpvg8!2ufN(OcZDr<$qh2us`Mz25K#ReYBd1WE-l)zsl;jUC3X^HoM#CUlalC z^T)p#4=vk#MB^crS^ZbCjc`%rzhperDLy2UZS8)D3+hic@<0BE(2~N5{XZxIcfF@= zKR&($kGA|4S_+*|Cx({vXl_IQcSB3uMtY(v|HgRuLlHcPEK~iPBKZ72X_j!A_@C`! z|96mWwxPz?|6OS57vtgXx8FibM6#_(7a#BijyGvJV%N8C4KbQVC| zR_3{KQ`c#TQXMl+Cw|uJB+YiE8>0B?+mpKk0*zYF-}L-ot;R_fbXQ}yrm8Ny9s8WO zHw5{yF>0ob(77}*}A zFS#YDBOIJHLqmZHlIHH>)OFosA&OTa@t&WG>A@#>V}$28RB6%mQ=1a@7#GUo(uC#V z1vJSD|8NrdoJYlh`@;9(2H|zl+wzR}d{JAc4$ru1BtDWj&L3`d-Ku}Q*Ua`qXS-ip zM`S;W-Z*-j)Y|@3G4lRPhC`32EENH(5Ji^lghm}K)sy!V%p%((5j{*;IPk|#q*yI3h?ba>b`fo(2tn8 z@y{V!p4{XE*JZ_%Nmht+hx+7`Yg~jQeFsjAs_F?+u%X}$CTM_-jqJ>ajFs&&QP^;N zw9DP@@)M?JyQRbK_Jq4<@mkaaj{SS|x=Ygj7!7YjRyJAep`>2}U#O{0#1^A(Z@@-b zn6-`?T?FH+ndK2LOPn!oKoKeaP%-TN#~iHDtESO+jv_X;ee%pn-7=C~59IfAE=u`H z0MjsbF8i|xE*=FQVlsm?1WUt?24K(UK1&m(;DI0^Kyy>{3)@S(ziOf%RY_f&~+r%o_w&oIy6yqju%_Z5U$Fqu$Eaw^A$7J8aB zm=jEZ`Rr?sADImT4kO z0Cvd}L$=E$#t=E~1-LG-`&&g|-uj)qhf1z(aoh*%>*@~sLwgxWXIvE zRE~=QP_L=ZeCd*$9-euX1dAH~hXl=mEt!?r+HuQiZJZ21mJm{YuI( zS)WoFTaiv!t0Jv^d2)-)9t_&tQumF*~GH*Y`ZN8_q-$a}ud z@1|+hn0i!y_T20xU*@j2xO(UG6=#xSV&)s#GrhYRn!LGKxFCm*K%i2m-4Ho5KoLNu zg-w;`?6aI0mAfoR*N&PuvKn5N0BTkAaNcS9B!3?|MjWf)RjeGlZa5?4Qx`x-P!3(& z`gHF(N@)Nk6L^Qu0KSRtD%5UG!RlHg#PeOP&8H}3*H45)GMw{d@p1xmGueWt8-Evb2ncKdh z*g_%rHE=u?eRy86ZEoo6)3BhFYd{aha(Ojhs_q34uHh+E%OUW>`$f2BLpNKSgOBk0 zk5q^5a;&d*d|Zss7Z|X83R^ody#CARMX|=d+mXBRZ|y#S@QuBe>dtmqDVH|n5m=jh zF?}cI#@DD+7k$<44HqHLn@)&8JKO8=6JN@zXk6mn*pWDH=T0Sz29Q8{5+#y7@EOUK0 zu-E=coJVL`5gYMj6l~qgq-tGLxOFm?`g6bVR_hntk&}t$pWiB?S~n~&Xg+`Y^Ppj* zb<2I^bpG_`Vf%~M!+y8Ee`Gm3x_bP5o&*G7I|f7G#G+ZgUtT?_Aiw|g>Y;BM_?J9? z54XVmfi$H*quN4Qtr=K9`0s7i?h`7%zIrr%xr6@g)l)M0E6<;L75E2k@q1MJ@9&^^ z62vb&|6g#6|LUvfZ)?~;Xa5@2ei(7O2Wf5kwmwyD^I`bhY2nsF*Drlq86`Wr|Lu2B z=AXX*8n;m0npBVdr#tBX%~wy{&7p_uWerbxa5RkvUwCybeq7$D(1xfG@1TM`O2nx4 z-*|qN&wzh53iTV$A6d|jg>TPn1(Xe{r0DPT+I($$kwVY+Vt2qC@iI%vkN~aT98kh)w38#ySJg;l!kKzN*Gs#>S09vCS^%kBDl1=`=_pI*GIH$pl{j{cazY+e z1pvet;sghu^JtE~0^KH$?q;Ah=Nl%O+kNYKP1kK7CwG(eO_!FcBk~=HFg6f-D6Csm zDu+P3;?N5FBIAh9Q^FSabM9)i-!P^-z`p!`5r6&43-9SSv}9*$8ndL2ObDQ68l5XR zw{?nSup<>+{kYD^+|?N}ZJm;t&|4N8%`J96N8gfpd+!Z^g3~-!!j#UrEo~d{5oiKl zsuPyk&P6^pPp5Km!)cwiG;h45^*`R^OOK@A1l=u_oee)zL$1dnkYc+PGPm3(yD#4H zl*Tid^R12D0=Vp!^TzFALvAK}n+_S;wl1B7^1tjpKSJ5O{@{xL6I|Vk7fIg;e!(Lj zIdAyHZF>JyNe9g4Hy!hjcz-oZ0~Jr+_{{Hb0o61H;j(d+;45r2NB4GRt&rQ7mQgIM zs)vDEC3Kg2{b}?~Wi{5Mi;j4$5Pob52V%`WYYrTqC5zf;x$TviO#VR>(Y~wZV}d|} zsikzwK<6$5<9%r{NYR?)b2eE5J3BZ;`+mr#XlGC5_i`W5aTdAFScl-92VS&q=Wtk3 zg#cUo2yWcsEsfyD#l~n}T{=9Oy+@ZYe3!6ba~`C&i}1?C1V5ugpkyW`lTGZ=H?2)M zaxP}y{pY;Qo3@louS1< za@p*{IE<-BA`T`1P9ZZ*-<4cZS*?u4gk4ko+2DDG{P2jDZLDS0NYa|{_~#hfJ%;C6#>Y_h`~y}mc+oA{@yz>lebd!H{W z7}R|epw7)Sx!%;$IYwN*lr04xAL|AWh?En&ON|nFeCCfw^Ez!y?}pcw5J~UqjEGK4 z1(pGi_yeD?yS55F4|RsBdlj{fU!rHqhk*iONrF{VpQz3p>wt9Vhr$>&%UGULF zz4^J4*%(B^1^G<2270{9YpMAi12N!az`CBT@`v-1=3e7Nz9?{~F;H0iWg|U+u9O7` zI7$e%rB?|&lN?wP6sHA^$_6W>g@CVhvr#$RIstjNoV7I<_6(hLffxkanFJ)ke zm6zAuNl5Yl2|eDDMU}w8<#~qAB9lqW3VU$&^dR(sdJfO?PzwsK#k#wZjtSAMf&8Q= zuf^TAJ&UB~=kw#uShj?8&mUN-$-1M_D6*KwaC1%Kpw)9X0T(8U*t^M}%%F(n+jZQZ zL;BoCv&jOOrP=V}mJ+WG7-h<9(SbM?gFypD>7shW8>PaP?F+#*TW?Iglf@Rv&@Y`fq`kEW=O>)t&OWIy_Q>wfM^_wU^9yWM_ zz}2$1{74apxpGp4nBN(HL|KDY!}tOmL6@qQ-~C4;<{(&n(Fm>3ni{<%X?+Y zF1DRwWZ>X(0mLFqdU)kbz45ZvQ#;_%?C6Z)d9 zuTFN5gSOr>bJIlSmq=aqc~{wF$$qJN=7ZiN?B2DHH(!W!%w9j>qvDwI5Sy9r_pQj5 zJN)c;;b>M&jj+p1-c~M?RLm6cnk4z|Jo3z|`T493|DJnY^`|mOYqLlB`1fy!2=D$E zPt0j8*=Y0$bx$u`2$-UwsH=SDy-vz!U)|+~X!+?yr}qXv!)1)n!r$1hM?=1RAU_IX zeX2L{ureStp{eSf>={^oC(6y^V4yK#)7$j<#L<_#r@B1MUS-WDcfK!OC=CWgz59Nj zt?Nu6BVOcC_o>CA;n%}wwvNVH0C29uvjgG{(E;BRh`+BXd>AhhF%Ac83s1@UcxK6( zn_z;fuRF#gp(OXP(dreBlIe#$xKa3>x8e@(%+3chOw%csjmlcy@pGXT6`iCk%aqN} zb-5OdA_j8}9lT*;K5}{thB8p!T#+)gkJ=Qy=p~3b(jR0h~$qaZwEu&;Qqzg}>lM{sab zaA-qtIQNC|O%6cRQE-HKNZge0J-v`5ZhE_8lBSBU+#W$orrichj64|*Bw$ZM+xrfs?To= z%g)~@JZ8558URW;8+;aCj1v>B0$)V4{3oD3mTpp6raZtc@YL)Ov8*W7FF?g(DEb6z zI6`~@pBGg68k7ckawbNmzYwQn<7MjrlwNq02Xu?Bd|~&R4|`bu6{Jl96PbB$Vp_@~aJMJXJc6yHI&glPh^19m%E#S4nP3ifJowCY=fKp$ zScY;K_33#q=Kx&{*}0XqP(pcrx9NwSqP4svN>^^#0Pj~;(h!TwUkWdJUydot%`Yy- z*`dZC%KOlq33L0Tk?YJ9H=IaJmHU4?i3a_wl>LZfSb4ZnNedL?CBA^YkS|j6V7fG; z%KPaxg$Z$K)$c((g{7oQi&G^6zRjcgtmmdSo9<;xQCCnV9!8L=3XRjY6h&Zd+&6!{Yrj&?mRVJ2lncj=o7q~ znSPB+hr)K4LT*(uPby~d_Tp$zQ47wk};O}Vsa-nYlQGEO4fD`%5^3tIDnJBV4%q_PNO1-qUt74 zhx-{lhiWpX9w8%IgI~!i6AB@;t8Uo)Ks7%Ysd{w6j9%-R&gry z&K?Ajhniu2SD7i^Dk|iaLW4+P5GVufhCbfB_e9>)=H{6gRSvG_jpCS~pt#GY# zCEz=YBAv26uEF+mNC~-xMx9H$Mj?o<2q4FOT&Tn!+>t!ovJ84Lb#vpAlaK>#zGy6s z3T4$*I$!hqmtY_nCX{{ZnmPQ^Rcg3KjSxKuUvO=S2QLf|Onc0c2N+#FYjQcM<^)|0 zKL43#M2B%d6QmI!&H$Ie{M^fuj_xeMXezn)(k3&+7YI%>Dql$0i$hXaYv|}jBh22Q z+v$pwjbm>Nv#~)eI?Gk zcT8Wf`@Dvh7uow=I+Ha-_S~alGmI&ugEmi32y|B`#&@FZJY>|)L>&^xb4z9G(X;tx z6SeK$ih0<_Eo6GP0#7-LSV!WT!XONM^r{*-vv2Re1cHUq=>c5h59YSY&94FV$edbL z?h&|&g@ebBJSSOb&f^HJ+pc{!CrlqsZt%CFYhOGS8M{2Ob@=iaQh_H`T>xE_Z-uH? z_%aMGK&6g4kdYPsT&jz3!=uh$_FBXS7b(4ty3mxB!3wG$X;P26xz7(cX$^ivH6Qh0 zA}hl!RhO7&k9x(2D~aUr()rV)S6Ip_LXhe*JIisOqIy+K;@~o;)N#K?WK~>&>Zi+w z#{+u9RSETjp9H*)Uz<=?C%sZ#5llTEv{J85nH*dZZ9Z-qa)_)>TUA|^oIM`)7_QDZ z99+F|dOU)stjQ!*Ta#uv84Xsi$z~W@lb1SqLx`-&*Q@F zWo@B?+83?Vlkr0J+G5?IFL#}_mRhQ<8$2g8*A3T}yAQ43J3X0fr>v_8Qrj?N zIi2cLud7NN+OUv1ogR&>t0_?1d}w$&Gc{aSS3k6A=XE-}Kw1BnyI<4f(3V^C>D+c? z{l3GGbz-^OZwD>PUsle^iOBYaUk_U6$XNdu|DF4R|2Dt&+d)e$lG^Ue`~K>Jk>`Iq zXvO|n5dW_ZS}K3b5B;|vwA5P~{@>F*_#bS%zX$vNZyvNtYyQ>z+OI3;zjY7(?Vv>j z`==vQ7iFDm!*h&%ZB?pujOh-#{shyF#l&M?`JH?JwFerT#@a@D(P{f7Tgj96ty~wL zd>!KM=VN{SL;C$*ha>}oe+T{Klj>Fp((7scqEg7}F_q`Gl^s|PidwsiQiR%9KbpwN zWb}<&Q(DL_joKrX!7<&Vj0n0Oom>JtlF2MFz5=AomkFMyRXw}fG4Dm{bGV>ctL1JW z&5daXkzgtSkf@vG?O-?`8n8r8mURdYsu%T`SK-U_TvNfc6PwsID*Q>bzDIa|mQ7M` zz)HBzCxf9B9RMJ?(bg#__U4U%FLbJQ*H*y7geOZWhTd`fFQ+o-=ktY-QnU#2%61w! z-&G&*Y|b$L@TqP_{g$epz4t-&1^U)~U7ohnt$~r3N6QVj+Q7@-S#EZGiZHzQl}`a% zcIlJ%w%5QMwxDhQZWK^vjpY;FXcJFTBJ9 z0b4`i@OiX&caNt-@S5Lya9t)4W`#wtIAe*zPm#iWfzWP)r?XU)WmnYloQ(yv?dm1b zekpe}HcA7u)dR_c(O@=@R2&)&MdqT(+1lq|t9=0G%eNximpDud58Fu}z6eE+OOsXL ziR0-25;A>rGLsM>g{&!%vhX~0U;|zypUUgKGhoZ1K;`8q;b{x4$)}oLWwR7PA}eK% z(=byeH%Eh*Mi;;+4Hb-F=F?1n3$Y)aXDZewZ+$#y6`@HI8WiK@XoGMpogjX=K03k~ zk-19KIfduMv^(DJUb?XpBW4gt8$iy;HLVw-OcuP5`9OPFN(2qDqsetVRGpXm%-9{V z@+l}Yhn>1IycPfmpP^8X2f&LHTO8HrkE8Pwumlf`ceJC?G%u`An$?e_l3= zvAt99T&8*eH!it%5QM8!B8;6ym&a%u-L;x^iZUGEsV7$~#33_*WaRsmB-Wcajj<_m ze}HlHy9Jty1}Y<>cJ=m)nOEp(fG)+TWLQ6+4gJ8VKY=1ewq=!rHc(51Vi0$MqF`x1 z1R2ZBkWS-+#|fe5{n~dDMCkDHl{Tnny^&=3a(!5#1$Ay=|BB^!{=2YF37?Ic;EgZ= zpI2kEM|URiFl$R__UL>dQjFxH0NME+kw)>AJtvks2=J>{;;mQBle_qKq^EcTklVVi zNUcpGt|u)p#>!?S zB1K@HoDb6vu-fWL%Hay$ zBS*10+1rzc_}=Zs0LXVV^7`_WDX>O9?9tJHUs`_6b^h>ri`K z%pd69G)QwskVbVc;590)v8~@AlMz~2;K+T_)^w+mCRA}3zbgqULpAC=Rv8I~E}{V( z3(E#v0sN(`Y+q4|jE^@(`7hB>U`ddBxUhZCn?o|41xnuV_N$&lzDx7| zJXB4+9e`EZG=KCu_|EV~aimN4t4#RqU}*{i6A1rfT$sVQ895ma|KOYQDf#Gp{Ig+i zveC~EC$hYGXbHYLuw9uU3LgMfOaA(i_x8=` zNdoa_C|QTkd<%^6x|AejItUfLl$(f{v+G)RK0U8*KPtCkaotVQAP%sNcqwCm8kvwH zH1Z(<_R!(68<$~G1)?ewQH()Qdpxdge{6$>;l4Y;$g~# z{wZXv+h0v1vNHeS%n$)QqatosCz+3@@a9M5XJiVBp zJ`zmF;3_u;kyRo1xm!s-s}9xAgjWjh8P<(1l z_a@eG(^*W*A&E6J$*2NI>7b~j7*=(Jr%Fy(Ye*>04AbV0qd_M^eRQ%y;t?A0B}H_t zu9`22SSJ=b9+DJX1i3i+gqj;sjZH2lK;QSLQ=f@vRAs_#(9jxmTxt=7%p|S$lWfeg zcyW#xx+n$Gkv0UQ%c;H2ECMgpB`s}-mSRYp(WKVs=vr}q25#sa4??{#p`igP-H-Uv zkGQ{(49Sudb~98#1Bs=D@^1`{>Ga8nQ*4c4k1I%>+WpnJePqND+1p{cx*0SL@D&~? zO;a-0W$0#zhW5hsT%qTuu`vg*YrXv;yAF z6D=`=P@h5EJ4rBD$N=F&-Q*?Z2k1D3?_WkiYOx4!LWWaj_G1j`lM481BQz@$ZqN=T z$$}JcK_3!3bHw9H#o}Zdp~;qUlxKKFK|0OxTuJ(bd?ldl9e)$(j>98SjTipbmp%i` z&~O6`92^Y{>$88t10k1tTG5*bTa;u?F^mhPBj!X$Eu26d%H?s81y`E2BFOy(0nk;r zK?VH!fc-@YCBOP}>eCLxQ!iMihDX1@a); zCb&fZh{U*?M+bK1&rd07uW+Y-Z|O$2`uZHG7#d--{upSi4Zoo$0NDN6RJ7fezYwXL8_jYTYTfy}U^db4iiz!FOX z3w#*e>3yaB+-DTq;$PPQn_#PUMo4LelK~ofUqh-CU}FgI5(s#XWxjzkkVJYl%2GoF z;|!(fpX=)*nb6P|`^qumx|fu6UEV^mC4qDnhVd$rd^XM3I;?{a)G)njRjbP7%aJUe z$ehu;2As&?v+f6yjPlH1>gfQj@hP^sGL@G|t>@@Lvv4Rg@^L_c;(ato6Z5jes){G9 zs>OzIA+$}F?KW6P0mvx{uh5%Kxs9krZgYSRKZOwFYO?feP)5xlTe^p?McT^>^v$YF z3+^)|X4cS7Mw92cWOYBhstRK}RB-JdIFyrUr2@O_D4xV6xklYM(2Hc2#M5gomE6nu z4EUzhE%4pfHN>>?@pT>r9aEFCOM_3X3$s`aEL>12{7<^s@2d!2b95I5!Z1K442bQO zBUg{{MSSRp@_kRmyLnyDo|W_{S1L^AXy54u7q7{C%iW0UlBCI$Uuy1Dx!tpT@zpIh zU^R!V!

OsEa_B1$ob@n~!RMQA_1pGxaVgyu50B;P*}`QdI}B1|5QvP5sTHu2(>D zNb`ERa)47hA3e2$r^vyhbVH!svOL~M@`|v8;&RuLO-*i*`3oa@u2&r%;j(zz(ELH^ z$}caocx1Y+T~ABB7SlDjCwt8^$-K>|Bk#E24eL#n{oZr_V!5np1^02EW%?L|AtR?l zI$07mC@sEm$$VAd9lG2U*7mLU^jwo!lnatw7v-je>rRbO9o!ImS_|b&uu{e71%q73 zUDSD!t90pLO>1Ng{Tp-K8&oXW`3Nwo?2V17Gs^o4F&7Kd5K$rk1}=@6WhtSCgn!Vy zMJ1=#3!FpIroW{d8ryvG){qURMIZ|$ki}rfL(mW<{J7}mTN6{NN3#q_VE;#UC&6)=qL~o@_Joxt z+-B&Vi{GSm$2(_!v8NFzVq@*YR>(4D>LHFYtsNFxhC0B)?S4#Ivq{I@ohH!yX}%Dz zH5$ZgjU&kFzi_SDC^X6KkLA|>6S^KS=P}J6N)`Y2(DlE@kN*E_4U}h@Ad9kI{%y|h z59s>;E7uzJ%RZZR0twxl^<11+qZ<~8&~?p>t#s7y+*pSz$` zaNwwXWA`=YmF-ru;H2%|ka(D+-0-!-jlGfZXsywk3N)jDQAJCx*8-G%F*SFpWH)O_ zoUT2Jzg$%)7)D}fI7fGmv_Gqs?_pt8;G|{|TPR6(X;$dv>_Q*W+h!)zI6C(*HYA<% z&9h5zFhCYB3pT^g)oT+ML9rkui~y8BNQmACYk)>?b->@S9^a}(1F=gVCj^lzsU(ng zY-t4>5)_LNZUmDBQ~Q!=#%TIMEy@=63QHFoSBDFZOAYe8P<2LonCRx`{ z$_ORRBw7SKN)QjB_g{P}0VILS?@)Pt@48S5kUnDFE}t?*laRfKLHkUo49PapFT1de zWZcN12S`rS_I6Yqar{Xf>weaSCo!LDrkw|azNi3rm-D1x_`yIqHaXriG#=+eM;#2~ zPz2?+!|#~m?G?NGLF2axAC$7_4H!vyANJw74`hL5RuCS#Ot4^0HpT8P`>nW9h(L|B zVHvs$l|L#cGTiO2tpVVg8HEdAuSB@9hIBDH36k<*gJA?bjHHNGz`-|~_c%)?pR7Mq zBP%9pFqc!TzhC|FZfqub9=C$hfY$tqU%qPIW!?UPJ59Us72$b&mP)S;W_A-A2J-~m z`(NKX*-dOG&&LEQ4Vp3UCH1N13numtT1f6CkA~+97bp!qG}ud-8q621?;o;zyqCH_ zULgKTY1k=cFKtb=KytEw*sW=@7j-_e}&C9D07m^gy^5;Xbvy!& zvNNSC`ksBp^ANFh_{kfS^Jvze)c$BLh`HowK9qm^XaO$6dAt~N&;EER!J_1NIi-T( z(MsAg&Xd)wc>9yJyxfwL^`e^Xla102&eP4xQTx-a+Le;i?Z(6H)6XrKH_mq2NFSVi z>12L&w%g19`Rr@I%#HKCp?eR`_s1+=ogYj+`h0#k`|QTW(PI3Ai{qO%VHYQxHJ>j| zcRG+`L3^VQ5a&lv+gvYdBFpa}D#pHrjS7t-`U0_^d(p&bbbnrrJYUZONdr)21!k4JE!}X=Z3hM zWF4?~+(}>=Jc~0aJs~wP+T65#tK}WLJ{u1ubrMXv2-dqmmXSSJ?doBOi!gN)};1>IFDXZez!VDv?7AFHH#R6ThN( z46L?`+8Z)DOD*ga<`!3^)Om3%So#OfWx53{2s$M~rIM$r_c14(nJM;Y@Usj6OxcCq?;t_&$-OQ8zKb%rb*v z_cf~$UAy-guj{c%Mky zmdqGEFpECzyy1`83cKOoY-6;qbn6{RdNB;;_NTktZUxt8Od*t;CKqhAEd-p7AquKf*UdlrJ z0J=Up2uDef+9Z(q8qV~BK_YRMRx%(OYWC?#CE#Lc*MuE=LQ^lMG5{$L#|b9n%5ls@aepz~J8`mAR@xo~EAKoHt?4WREkPSp4e*}YyUkl0X%u_P z324dkhTTMMv2MA$)FK>ad5d4I-$}FhHSPES&^A32p|UlUmZGBDe>_i**jlA!U0+dJ zsV+lzdl=v)sAR(Vaha!2keeg)YwAi$JU{u9Fq_W(3XJ!E4oj1hPyd zu3J`JKDG3YZ+Asb#e(^6mh|g_>h~d@jc;_O>Z_krxV+!oKtzr{-cGerFyjWmZ_D8ziZU z=yybCu(%k}ZU(5SJ$ytEq>{`lYrd=ux$C&d2;Ml*Wje&U%BvF1t4(E&bGP~q!9IbV ziX+oKXtI>A|2=3)EN_a7BW50N_^|2)gDLV1>Q0Uciu8SSO=I;~IUYX6+$ zWA-YgTW0sKR2#^4nqJ2UAYXQtwlr0R8A@y3$F5c+l5)1N3?!2_QC;z$lJwVigRx?m z?4k#*@CF#w2B;m$bW}b&uQIfS89zM=;5d+nnFm~34OAq%PvmM;YRVIMEy$Fe#9uk{ znO~=o7mKmS>QzhLyAiS4G3ai@v|4k{;4CsP?Ykkfrt&#jgzXw3xvL?xW%mlkLJF~n zUyP~mn?ARzlF!eRy-oOh-qdc?F~pWcO=r$j3Asw1M`0IF^4kUUH{#gHs-zPVZ@YW>7~k!_Uh|E3UjN$5^X)Odf+U{b z9^+6}G>~l*|=R~y^{&fvqzus*X+2-?J>}Pj}{RE@Bn4Nng2knqLPg= z_K*5etoq?r?t8SzRRQvchJaths=;W@ivQ^Q`0u-w``>6$c7l1qT26}V`dV&UATlYO z75Cr2ePc?5o^JDP*7RS$k8ffX=Jm_(<8u4v_wVD+ViofHfIPdt+sW|X@qLI%+WqDC z!Erd{JZg71?Y2^U_#ZsX9&I15q`f_lK+TM&xqO%@#f!vOd>B|ot1~!e0*%u}iXb|b zz+3f&Px@~l0H1}W>Q=VBH(wJx1#h?Z;5Y1ot`c}jzDID2?AP9ZbuRtk!LJW977;}4 z@esjY;~KE+hRW{q%+IRq=-SN!XS;=Wz*`tqUjszl19HgBj>^s~o=FNNkIj;eDF;y&GjyjZxyQ{}p6g;^pesB{N6?Gkza* z{@#{&l@9;kNK)TczrJ;&{D+~+29XuSM9(EN@S14e{w_&%6_F8tdWu$lPflrp_;+TI z2WHj7W0?yeGtV=6Kmr<`3xou+{I>d)H~+gN_2Bb+%S`vJ#YYR_BVL^g5zv1t(}Syg zm*R4@+n3_gj zhOr5CoUYama_wS%xP--EW;p!wq08c&mF!$@y!r(1(!3%kGkMChZFrARdrjTy)Oc9E z1rdXh#zKWp)5&J#*NrT)qN3-w+4i@0DmG$Ve!(bASEe(QdI6sNy@>V z@+|Eqk`$Z{2Y1Ed>fw7hQ?dZo99NVCo4$ezK42aX@!(?v?WH8O2qTRCRg%ge&V?Z* zsYpBd#tahdinkoxQb7ixAOsZk9oL^FDSG%jB=W^|*gH2G5^Sx;i1=oQdWOoL^(S=P z!T16Bb|c}T{|5PTj>=+4%8Upw*StA1qUaD@RAQiGIsdb_G&Mzx(mO}bpZ2T81IuLC zv-;CD$1(z2vS7jhhy>=*?zPvw#@ysY@&K-nHnnGF+`2~ZZG>7J%2RSAZH*LJ$AIQd z#JQ3aNYw_=pE!|XPNbFpA*6CXW`7eGLY^_&BIqt3(gbGM4pzOd=s$RDYy-!FCuE7V(&8?B$%FL8TcXmHp)+QgTg zNQYi@AF~JAN_0>fq*!E3eG5_)zWV~%D}+jJtd{Zh5WAzkH6awKVrS(o5Fk7?th@NYgq2jlz;h){eWzQc-^4% zbmpxG;=$D+gAc0n-$bCISXPHIzU|G)kVEsi8mNUS9 zb?(_;VSOmih~+|VZGuHqzdPDe{k2Z9)5_qG!+v0-vx@IMlQF3HEQALLX(vt1fZzDhG zW+SJ$WVxuS3WR_%yU<;YVLpb99)X!#@b^3sXyqP6i=mm_qL}9pPf6?a{)boguU7^# zJSBbwh4#POb=l*vbFo%M)!iTd_6p43!aW$nF;hGkhdspRkt-2^?u}D4;XMkr>J!Nj znV)z)XT1$UFx1Q-?T6YZ0fHw+z2kMZZsI{VzS|FvRl}5(jELeaN(7}(?6(D{UdU&) ztxzEp>jTtMezzY=+^5S&n{vVUvlnWs{ERjphQKp>$QAQrPETL28{Ma0din2AUH#Cf z{djNaR)fp_7`>Fo!IZ_Y>u>hM6C<*eSBz!qg@3dkq5~gaykmWjaCq_clX%c!^8#+V zcRMZQSNkD?djeVtXa(`f;aZob1()Qu;$sxx(Zqb%6JO09iu~PvaECc^nud)TBkc!k zn?N<~WV}b6631&hw0Abse`Y@%1_O!NqnlWf_5-yEfTU)X9^L5=_Ji;g&2RQY8~m~1 zDmZ@p3*-?G7WF~`5!LRO2yfg)i%{l2vRowA7lCMf1}kCZX#R1|I9&n>UBP)@Zsu%c zeY0eLWVveICEqMr`8xqbu}_N3ytsB{^?$Ww^NU4@zFV>@#K`nhG}k*%rn?!eKUlK2 zt)0Fy&79@@YRN``n18fnJ7Rktn-j$itYwQFcJ=o?Ir;h$fR_iwlPE;>tDt2J0#I z^I-e9%+cLLIo8oxAnJ5=b$Z+>a z_0O^XWFINd7a3y8BfG6S{qGd7L)isCTF*U%L{FJR{{Zq-NJ8K9Cqhqimi-^k_%dwG z{lC1D!ml&?2U6eVjPIWay+hQ$fc)X-@3lWo|4{1tOOXG2sqg;+$cK-~rGA(CFxXbV zNqy--C&%&@!J=Jx@GPFo8DHsp@|RMEl^(9$FH%N$WoS}7N6sH+eA$!wE^B{$L_zvl zEF*GoG<-DgjZ)4Gxy&2*Wb&H|h@DZZv_2u?tw0Y0(3R4jZWgI(X1Z289}kRzBK=0= z+_oBOoIdbgh|=gwf1hK? zB};G(nY*!_miW?+l=^N;eiQfdJs90We`LXPYHI^_WXOjQH_xJ_adhesIYENFLJ%hErIeut!4~*M%J>^Xul6Iz|CYPyQ7QYLyRoW}tj~Yi zSVYI=C)-&NpE(sv!kgH0!Grt|gLaN}j}Mv>R7BKam2!>=I!YwpJS zOEM8Q*6)HY0Kf<60hav<1^;f$T-@W&x1xWUJ|t!(k5T-s{0vk4eRtI_8WO z|H|pMD|JKVkzG$UybD;V4z!Sa2wR&VB8$&Ykr(7=0j4jn(-f1zP>$2 zpdzX6w_8zs2Ah(`gI~wYJMEOc$M0Knm$HUOE^v3m=9N5% z#qrnlA&#Kr4}z{i)!Uz>5C2xsRoo8wli|UWsZLewoFaSUo8jR_iK_NjhDQ_AYxM7i z$93KLqS)n9Q|Z<%1gdp*YpRf`_rV2XDvR#E8=u_gz@I~L4y6+1DiWHUPH4K z9=!JcaR1e7XenvEA5_|(bUFTSnEFzs^l+a)G_@-ILly`Dk!R6UoR|uhhRg(nG!mz zxb{+|RejubIh|Q;UHV<6O1~Uj`nR#ErtpvGVv6t~RMq!;!+1Jd-XnS@UTY-y zmUH`;Dy^#=m!H>f{_Ukdb;C|s?@?iv%k`at$X$~ndi4k$ULl$WLA{bg`f`txN z|E)R1N*}5zlxQ5M;Lgw=r}sZFrDc5a<|m82$i@wpaiHD9`pD&t%AYoFJ~n(KVAf3(G8&U^k1i?TeI*zJ2WPwGuQ*YsD^SHIO)C3EF%|dv<@n$8d;}&oe%0U*?w9MyT2y!_EL8J`_k-ce zZI`>vmGl9``0#S{0pR{r_yDIcq@Co!p+d+M{t$HyswfU(ad)8DcHma8UW8)R)Sysl z@VwO|_u*jml*lde=aV11nc|t1_U5zT10fvA@HqhaR?!x8I8esLg`L%&u(tcLe0uU? zM)Y9!nw2~Ro%|r^iN{1pa+BMd&tyfw8h-9YjJ@SXwJc?(JYnrCyUNf5CL+)6#zE}L zhr;ApQ`CpkIS8lQtiwnGt8Rv)!FQy4-N5rmv~UX$>MC4{es=PiJ%A(o3T$?y`bKY9 zIPsS5r`@cpw=(iWec&Gz=Zu$MV?MzHASzN&m6?kRmx_Hrw%x<2ftA^@JC;nuolMo< z)tW~jKRbFO5DJ-iuK!k`PPFzXDu6e`BHWzUx%=~)s9No5m2nWrM;|;qe~Y#9Exnp9 zj5t1zBswt^S3S$vfa+0kfV1jzn=ZP)eoOwESN;?1e6z(Fp0?#7ZSnu)E$Jj4>iOSz z!!fO3Py_t6KpSa|g8|_H4dBkV`oMqRH?#`D{t5cUbD4B2u$cY(3pNEt=q2g88>dDM zsr}^*Ng>JIpE*`>IUBO^@%rU#NcW2k?;^1p=dbJEtnrt{7odM%plv+zAx+|E*BTth z*FL&dKHQku8sz&IC9Ur3%Af6$pDAe{-9CM@#?8?We!bSR7e7RMNiBhWtDfWMZn^%M*Y2TtqXcBBz@VO!_L;O4vWEZN@Fw3eAb$ z+7@0|h=`~l)~Vq>KZ;&RX*hf>a#DQ`V}8(las27d?TZ6cDDbG}4q`gu35QtfB3n%h z2Dge^Ii(&D0J(}O$N3b?v|14HK)>DPn#W^VS$qD!HPSjNcrN zJ{HdlMJ|*qxDlRyr+DrnGRF@S|1wDCR7E4YbWJy}t2b02nihnnszL=Leu-4lh}vjg zvLXYyoo$@%H}8a%W0N+IwJF;A5Lb83Nr%9s;SB6_Sr9)v7%d8qy$^0dLnZ|y_d7mo z2S_!S3H#ttgkog|wXS752~{af^yDUkQD`SQy1$GrgVUAJO%n;8V_00J@fFjSELuWA zIc)Fp=v$9XB-NO~n)rh#FBcb?RI#t9*&AK)vVF!zST5<;85KtqoTV^^)f?jA7=qst z#$BACU{3cnvG@A-3pU>ZrV%u`9}NQ{fG^-4@cbXZ+;>;_jy<+)`JWDT|0VnQUwT_o z>&|^o0NvdOB4KW4?EV3o92eCg=`Yz}0hAvTKoTDr8GnA1CU|AxXC&{eCT6)`mpNGJ zwYzi&s*CQWD}4Bw$%hzWhk3QZb?2Y&1l)FPo%M4QT!o04LM`VE;`H<8bXHXN`T`;5 zv2zk1uQDWvTno&b*M45SnxQMl;@tC`Cy6&*7ZBH1qk{u2-0#UW+ z$yQ!m7kQ?_u0^yM&hCa`O~jgoEjht7es0ot!xgk{DP7#y1-Ca7wPuyJVcKJQ{QL>4 zigA4%-CA}Q-H?%3HILj1R0lM~l9BxmAqO`J0aY#(r;e;!xk71%GKwN*B$i4KiDNQM znu#|6u{E`~*h>4iPx6aVy~a#SP_I&Olp?amwh9z4{9e?yM>TBKy(=%+tiovxDS0Y= zvX>ri7MHvUUHV|%SMj;~B;v)0F(p^kIWP|zDltB&R47Q7W!>7sWR8=EI_~tm4Lwpu zE&x9!kGU;kJ!dB=vHn&$bgQxJX6H&AH@pWQ>)nkW9?D9m_s4juF%7rr_ojjbblIeW z#V(K1fGA=AnhlQ6S?bk(v{e;I?{&_?Y}}D=JMOmK$u(hNP0loFmy^IcbtnaW*@@dDYWpF0v-KKZ7KS9@ie%O_+QrA$KnM_0N6TX@y4X<8g_R$a1 z?Z0-E_SW^`Pmj`mW*8i;yh2=@9sX_@{44?V)1$Qen017If0PEkp?5l`UBKrfK%0St zIe_;{Xi%IYG9WHxN~axlB*~4d6k=#iaWyn!>8eM=J}43$=9R$P=K3 zQ5-2cRpnB=g_koY;xXdpA4yo%7z7O&;YA#nh#@3PBi)Eo%z{b9%4yCPySkmS8T4wc ze9VJq$5rVb%#OTExMg#|vh-lG#rX3Gb#mmw^2a>hJ0!jC*7_dRVEV?C`f9sLTNKPV zAy=n{HyE5o1;u^dWrUDn7?zPJT@r0#0x%alIo z_UKog>|2Lt1E~Us$PMeOfGfNJl2~P#J>9C-wbh8N%@mUjVlfVXaaR_sjB50FF%Gw>sy)K=j0tReu%`t_ zGmI*4PZB5UT1uvVvy^D>6S+k7h?z-KCB|92JtrQ^i;+IXpJ+4|&DMvNGU5Qr40ni- zCW%EQf3w5{28w8{=CpTV4+ps5qd@}D-^+qD@ZIv$Q4@&v)}E)lLnKjTfU9>Wi|Hsd zh{;PXr1A@bl12(pbtK!-y~>$9bS%z>S!cDj1lYhnY$aM8q2d!V8ip#x1)DX`S-+UM z6U|6jha^71Lf-8$48)=WTF74d%=p^8GB}M?3$#bUUj-N6ZE{N_o{%%*gwNDJ{`}@H zEn9m)qd7>G$WG*F-SfUQsqS+u_THTiMJe2+=fwiK{U%RJWZ%71Bi@flP}eNr=;UFS zqV-TK9f8-Ai)v+uN_CCKb?}l-YXGrJtE3WG=<*9vUNA;hpq97m-E2U|v)&uw8*u5j z*5J46hs##lxQ@T6GTHFBS98ia>adbUmkhjHG+C)OY?27giAB7>+jF7BI`;Bbhn<_k zGlP^Ats-(O%jb8lpcOcF6r)_5jKL++4{83jOd1%E;}1jf)qKL+r7y* zEDroHxo9P2Fx+tlgkWz2oXyxl(4;}lII8^843d6|yWR*L;*2t`4|)1U zn$WHnMTv+`Vz>PD6(t)f{MtE6OhLG$6qC@vu@v>NW(l_xmH_f>+xY`8_)$9I7}1R&*8CR2@N0{xswl2iL$#WLk->H+>)L z7b8w7&?-)y7|PZuY04d+uOOSGCWq~axx|O1fFHgg19S}M<49;OKl4pS9e9}sqy6BU z*6*ZTv<#?G0U38YUNM8>-s;fkb|3tjiq0B+#NvV=JI0m<6>H?4G)3ibL)v_gonZz~ zBIN?J)YH}`#VMWrq*ysrgK!(o4mj%vu0*o(CFlk1Okk;wOXc96$mM4N-*$3DEtAp{ z&*_s<^l=ot=OC!ll*OzKR`ZsTyow&7EXAXtcEpp4zw?ZPp|;w?`39HP9%~VXZ~xNm z0%9(m8KsZ$EHUn}ye#@wTIv%aPkT2)?uBZyW^j)LE2Twz5X-cj%KTU?&6DSLp0B!3 zF?7EYm1kC!L8H}Ain9}zVs^72B+%^MGWAX&OZ&WBJ4GW(Y&tPZRl7(jmbRB&t4R(6 z7L>AQxRdBWy?t{HEs-rQd#&(liD7|?wv6H+B1c&a%aKEO97~sQV!fuu!;X?HKeH+r z-K|3>8r8w0yMMyfTi=NDxD(o&E#)95H*0kDZB)UBvA6Pt$r(^<-46z$@sB}R8t%ug z>1YgnDAv~KGIU_{y(LXHI%?YT55k?XcC-LgRp0A`Z}d)KP`xY%DGBf*fMF=EnUL|V z2Xz{NH3q4mNWlV{dGzkfm205Vvih6xqbRM$7^kFlCQbAwtB2PH4pL)@QO`El3~C`+ z*j3LWA@G%^+Q(P;uzXKeymvTj=+MmiRL^*4t`RuA1{!7F(~7SQw!~>=qLZV2p&&7G zRZWV(wKG&I+mKU66{OC>5Xk$6yFOYe#+_F{MTg4nJ=4&H3V@Uxyu!2Rp zZ97Sf)7Fn6MxVYlfl)-$7Fz7UGfd(&!_CYfdO@W4_@R`QqMUj>{!!(a5Z*w;b@B+* zx&V&;pm)$KZPam0yu=a41e(GvBQ<$ds>EJa{5|f-J@>eWPxS{)FivP1nOseJHrBb= zk|pS>W%XVNZ(5KhOO7yUG$g6n`5y^Qs#3X#TjDl}|!gtC0OoY7h9KO2bTGO~v zOiJ5-I>QqDWo!pI?nW7AIdD*OLdNdkgV8vPrCj@l^utb|@Yx(VqPC4$wDXzTZ73sPBKKw3k77z6w*WA2hl6l6}wOgVO)aaX01TZrxwU-HtzaT>QInH|5ib$%_NZ zb-r!PU4r9n1Lb%OsJ_(=>3~X90AQ?JRR0qTH(l0Yr*hNwy;s%q*Rrm5zM|XClzca# z^!|X}`9eu-m+q5d(CL2G(X;Jg9fafTPzkMNc{w2jyt=5Hw zX!L%sa{9Uur&+yuemYu_H;@U7u3lt;=f`LsJi%rx_(riRNED*H3-4hTqg_y}&&H2j z3So+@w6c@cYN;QbcRtTdG`M|T_Zq8uHOZjE7iq;Gw>k4R=!!+yMhm+ht1hf6N#PO8 zaKOW>HZ#52S!k`v)j>0o@ZQBzi7m#d!MduAQPOPqxW-2xMW0H>mlyo|5UVj{r0hMT( z;(jpmffY%y!ZcrLd!!v`@?mEuK~ag?^dA;842+3kFRsk`v5J{bJ?;`ToG@LNz4}s| z%vTB|qacR75n*cQrF0sd=9{#N8ekldH>a6jWKqWJ6&4{=Fa&)(`|>H^-Xq2k)vjci%vP zkw)#(YUrif?Ms2fiC~0lS$W~iv@er<8Nn*i*oeFoIM652!cBz}2Dc31OIUx^dRLCt z9Rrxh8i!Xl5_7L82guH0>v*-JASC&W)zYW!JZ_~%4+RbY=z~adUVY3d9E(uE zmxmknFvcf}&9NruLG@6?N>HK1Xj}Q~7@k^H_ecC$$Y~~|XT|3TJ3iNTPv_Vs0`GZ} zwuYi<_8v~C`^o%wzCvojd!g+6I204R!dll4ezeMjQ11j--Ryo9hh`O zEzs#qx6rP}i0Q|!gWq8FXxmgD*lL-I>B5NihApHaPuTXGXx>@tOvLP z+_kI5TL-Ey@yz%1v<{?_M4AMMXJ(wl5mj?9ZG=ldPx>DcCzeIE9~HkBs!@}dpyI{R zj>CGPceEtn$k6Vu@hp&~tC{yT{Po3aA^2*&af!Ra@OJm&Mr??5AXEKat$wp9dEB&z!ttcT=B{CR#;i5$E1!rTBnDXj9~3YwdOpd>|qV;k35YRz;dtW3!C}x$BxQpHq`|y7A!7vqX{RM*VSpGeaR7hHuoz1KXdZX~g^+ zStC$mNblo`IULqyMM#w;CS??V`a|#LkF76J`Z%MtPn;R!u}zs~8;x6y>k1#bzq_2&e+=7)Qfds_aLXBMi`MFxJ40 zl0VSEptVy8a{|nu z*<-%IsSGsEG0sOZVg;xZ%Nnz@Oeh2JAo3XNC^cW22znj z7^lnwF_3XaC7!xN6snR3{0I?wQ#Tj#`YVrxB26Nyt$gSZ`>*vh@6H{W1Toxc)G5> zN3*w<#CAArM-|+J(g7CI%7#^MOadWNx0alq6dTYpN&pQp8_;=S?+)kDqOOiCUQi66 zByhkgNYIin!iEui*QpGWlDSv>-Ea+dZmJ{}A2P6HZZs=^TFPTE^C?AYz3^_TimBAC z#2gm{^+{0QGyTX=P7(sK;0q%1WJKr08Z`=I(#s(vqPSm$t|0pmn%IO(cqPoXH~k5v z`NkBB#QtZSYwlbI*KXU;Nw+-;;Rs?k=CHxguGLhO8zSis$mG}c=iM&t!3;ickPf5Z zr)ATHX)R1^M}|#|eB^8J1@wl-d`_BmEqtAd6}8AEG`%iy&;J&;?b#bjzft^PehZ?_ zp&4DTrMMuDsR6ryDPwDd<`&1|>ZJeYMBPSHSPS*`hdkBBfzQZ?ZuS;HI#YMyT9^Qm zVmY+{AI&i$m=E+0l6MV98juw0u@W!yLy?iXWxK09f1p_SyTMn!Q>^$8dpWsF%SwHQ zO_?R4^hz(*wfgEuYCi0jc${w-5;Tl;{M~-84BhkB@`azD5H!wWDj&W1$$svCPO*O6 z&n0NudG>uj7s;!3|fKa!`h=@)SM_;GC6j+=a2{AFZhAY?I0)5K1u z8au`0243>CZ3VbLhiXJ`cEAB|YDwPL_0?Nlp^UHry!bC9 zYUSCWqGb3`^FoL2w800eT;dGi3s>F~=bnc>E!i2G32h@^$`CR9my5qGlw3_~$r3tCn$&7!88&NHr4PgbA5Qzp#glQC>33&ZmJZP%W*bssH++I^qKi|u)Do?lqfP07 zIa8ZvA|iS?VW3ty7%pPM>kkR{wBOYcgAy;sC;5-?nZ;_nd1m%th_z!}YzW(*B@ufd z|89DMuek}k-TJCQ@W}qYo`;lZ2s}|)e+>YL4M{>vN_>ZKCkxhKVgmv_;D(uN z0|BM$#9|mvmRd^7nRLmLJ(|`4zB`d~qj~6dxnMnj9))H!+MFfz{TMcOd!1(^I!n;x z+obuDrkmAQBThw-LQZ#;DxF?_c;O9ATc?T5)V}(<4aqgZ($V4x#jCMy0@bIPp{LRc zSGD+(3aJuYC+5=`zS>oxlb;Y`(u*AivVZB4?TVlA{QzoX_7QDjW7R*@FDirLHw5l} zkWuZW&)^sGE_36T*_(nYW?;s?n-8;{t+7Mz{yHRDJi45UiC<}wxB3FRP&|@u1Dcjh zyj2bzMUmg1xE*V`9i)ef129p`8%+~ysatW8#C1h5qJWFaIgS+BYQ|}NF@#8pRikFd z?E3ND819QfZd3;Q3R83r7x+CAjfsHP%+rPH(sY2xjh$FkM3g@zSV-KCf=z2qx!a%0 zugV%hM!L_xE`_bvB~FLQj7Wf4U6Meq^Ols^(5M=j2Q%ueqe3GZhEc{Zf;uF0!Osbf z-?rx(G_ao^UthZ@+j%#9c0IRwn6Cc~Oo%JQ^Rw9A%{+^cunPpe(Un-8F9e)sc~_I@ zgPsfcK|4kKags(Q+(~EuTAh!hDQta>s}I6xAh_ zh?`BMG4luoamJ&Z3@nL*+P}cj2Nc`wc_^uyR<$9w7OcV_Ci!UfM2PBPt!V^wDrIoo zJz9wDv3Gqv>uq&qR?tNJ0>*$@JFhOgXG-n>Eeuq5W-K7#>e*sN*>prSrf^q!^P9y?8H%3SHo92RtGI)uk=T+ZZ&c~U z;L%;5d0FCL3MKK~4Qf88-HsET@MRCrLeS3n$XNwUrY7GW4q-3x7n6G29ogFztVQ9J zI#`%JOdOz`;fbw~a+DDa%bB_}F~VI%RUVV+j0^jb`W!0BF51OutteKJj|Uw@&p9KQr4q-Cc8twsSjl zqF+Vr?2V+_U0-MpT-EQkoFIo+0lLfKEi~3VVqrVD>QQioqMmIbniVE_4uF}Fj1>h0 z_tqM~X!WslfkYtNF6(nfzQ*>*p{gcs3(S%6r4FLptCXPxsRd@VbkW?8WZPpZEqN$v z{={&7bD4rtgf-@k$ZFyn=^7akOhhYo?wVLGDxW-@-M|XRtX8!;i(;%8X5@*L7!paL zsWakUlDu{^e|YR+&GiYZ3PWqZK&mtyVz08RYAP-EZ%!Jq{TXQ$t|&izAuOO4L+cux zY3t{vp^0ZlT9^U}@FWbmRafbI!zZ>tJ*G6^O=<o?O*Q66d~F#dJ}dfL zk&iUz&F6v)G(;6DyaiTBa$dNrEw2l<5{5Og@-xG*>D-u6nRlSyWwP$|*np+tdRu-yyDN@;@BqR(&RJP;(;?qF1ZeBPQ{?&jlQa9GaGpvv%oh_)vBS?6b}SITepGpO&J zn3z|MN))Bo8sC`-Lo^|dI+|&hKbclcGd9-(rmq|nUW?p*`qbq84aCXh(}2e2-=wf0 z!l!`Wq_6~UP^~xam^c2>FH#t>mJf-W4_Sf_MXe9jm=Dd74}{E@PQaHz%a_T`mnFfM zt@iJEnz(?!q?W(5n?EeUU#`|)Va#9Y$X|slKusV(Ln}bjEkG+FK&Li9Z!EyzD8P^` z&{!bQR4b5(?1{M+(Fl)`dB8&}GNK4Ip2>ajd0OdyXPuQj$48br4}u7*p|{CQY(3sE zkJDSD-VO4#4Dt`6r=VBxLgdNvWIh%gl8~zcZ!rX8%t=UR=tiu97yRk`Xu*>=L!M}a zWN3wCVTs52hZMp{T<3#cth#0S%iiLVICXp;6GN9A`8>DmdG*-y8m!Rfe(AC?FgcN@ zF)hi0e`u==s5c?Bk1VWTAguQ&xZN^XhKQS7jc=lpF}akShxlql88k94Y}PV7X8_dq zC~UM1ihqUY`uvT9Gy(NF8r_|{reKTm1s2p+@{6&Eh>mb{M+O$6h_eIY=CpfihB#BT z8l4~UukYe;nKFlqQC(O@o+rS8b>NPKP_ru*SjGf%JW*hB&jS@^mvVHqR=VR(_|Q?* za8M{E`6GBMJc~$}524Lx5G(ODPsH8j+NWAZ_x9)&tr*&9iFJYKF0(Mis{V}B9i_xj z)$tfL?O5`R80^Rxx4L-g@p!ky7?)tq*@q%(dqNtI6V4M7)Un|{+I9wJ&tn#4ZpBDcCq$}S z#Th@2j3;+;=?bIUlQbp_nYkLDB^cjb8%UXWv(iV%f;B``l1gj=-aQvzX%!Bu3zr*@ zR5!X8?n`f47R-A^so&D0PasKCFpR}GEKC;eBE^P>W^iB}?ZTZjs~#8s_=QDRqD!5= zs|&v)iPAe-Is^h9fo6oW!ApoD82uKDJkKP$@98p0OiB^e;dzm9^ zvBiRMX2I!otU_eQNv(%*Ah`rbtCZH<6qmZxlk}Ujuo#&-4P$IrwRZC3HE!LWVs%Gl%h?F1_g>b>?K%I^a$tdxFAQ% z^U#}Or#{4!Tiin%oO1@B;=aS+8u86{GsD=o_?t)$qf%mCwO!11ViDpfqH zG?S~8dn%J=3CVgu=@5J#$|^beY6{&7i)8GLQqTmroHrRSqZGfgzY=;{!C#2J;ax`V zRG9(6-z%-o*s1Y4ttm{a-cTW!F9q53)FhUI_F5__}2lfTZE|W+^C>vVIz&OAuaI zUrt$b&V}zP-yoJ;(^_AnSlCcDS-AnhF93rI;Mj+SpkSNkVD>7S2K@C>P}F2&WKUzf zM_uCcvMsKPxzhTz(+WqMM%luqHJb)9n@U;A*IGC=6e*1d>>!8&ftqmLp!^%Al*S>C zRvkF@bt=$!|C{TZW!esvT({p+_Pog~ZB$Ig=IebcGx=7e_l=H2+14az(~w{vS&pMZ zu)jm6phqCDM^FWBm+Ni2;oBzL3j#nv%AW0tp3JI_%=e4h8nf!kEHh$Y>5}Zh#05Ep z#s$$q){avWNvf}u0fY~ay&4_uFQYqo*eBDrgs-%`kjst`bGL>C?aU8`r z0XfTqwy1J-#TGlehfTXv91Nze6J90C5pe-V@w{csf&-Gu;yKxhT2F$rPl)$fc&b96 zbot?q%W)=-^w&OS1@tD6Zc^uprNY`Ce32~>N7Y5Ee2&$oBte%YbyDQs5Nb+$O%W~i zD@&o|99eT~&T4v=U1IUH@w?>Yuvnh(7dqh>{~vL0`4$BLZu<_y3@`%>!_Y_!-AGBJ zLw7d=NK3brbf*r@P|^+3-5o03Atj)Kf<=gO*=OJL+%&V@~9q7t(P|@pz3fHNu1mWuUzV$KrQ>!W%g^diHceVAOGI1>?oz|x_uHKTH zmHBMV+0aa26S7d0byW7I)G{Je_4D#kf)CE->G`zw4=3ku%GkGOI147IdlsBieVH8K zDaQ-EGK(U27K`6kUyBwjO7<;EZ!bRnyNIG+l9O3duvk(GSyCxjQtMmN*k025yQD+E ztS7TyXwMdz@Xp6PjkhS=NwZy))uECU_v>$!dF`P=J-f7grXH%eqS$}Bc2LN=-jHk=c370j|MBqr!S%^`1!!K4-0D)l_m z@)va|1s=pAcSMPVT=vHO5s>>*e5>drL)@Zb$Zhsd9m>-=rx}vQ zzcL?s9aW>clN7o>h--$HvsT7%fW6z;D9&m{v+6%?JJ{XkSprkV|c&I z_^;w`cDYqzw%JB@P0)VLbhg0sKAZa{KmYuh#=bz%KKsjkk%mCAm#_cC?J?U`Gci& z>ys`utE@wla#*oh3OiiDBZq!^GuX~()6Vs~?eeM*?k{&9OCE<>VsBS#E1F~XH4utg zD<6pp$mup>li$x?{x3$R5g;0%k8|+f7@7E{5}k2P|7RFn!|IF(M4F1HXIstc8!Iro zijb(RJlcA(W~`c`7FF-r;%=ed;r_nPerouglxXetK)C(1CNmrV*047&k7d5z!>1D% z8udaV??(HPgbuY&YWEMan7|7;N*SXf5EuG!t)&IL$$B-4-chkHq3!HFnlU}rd}SzW zqazAmG!GEJ{tlg1I_|nAhD|`|$sh9e-n`Y!6I14p|J)U&i7q?6`>LKLI#%CBmhpYFIcT|0vFV5Cm6`1^s<2;w=`L18W*5hVL4@ z4h=xFuI#5WDXQ#6?^u|uy)0{;C$;QPp)SE?ZeP&iG55nSv{Z@xG@rD!SIHPU`-{pF z2vFIzjHxd&BsF#DdPWle#QRft=nW*A+Smq9Ej3L;?`oSeO&Y6^$e`=A8v{FBokqo~ z&F2;6JdWN7kT%lTACNZMUiy!$a|!@;$A z%F+v1epDb^DlVYr97-WlhjPoX*~^(j#Jl#<=?vWm1A4!Y z_f&@z9N`~y#IegNbu+yb->+O<;Sfs3ZHjd7h7EDLJL~yUdySInnLm`>H;lKJG1bcD z@ozZFWlZ6e`f2VwRnC4kv(%qcf)xy%a1KxZXX`2Rdrg04EPuzpK9pH)DbY7PH?g%> za1~wr4lgZIV3_sa!pn7yuh)VK(#Nzrv9^nn+yO%Scgo)3lZt2IOL{+O4zQuZd>jhf z#YbqrzzOv4`uiq&?mL1%-)A4z5B9NUpQ$K}lZVPN1THArqANmPQ5|&-HBvD+wQHm| z|B54JgVzN7j0g#;a4%7j;4-)KH*N7kLe;QQht8;5u8$}Fw)hnP_Rjf-LuP|3qzSDUvh2prki!aHZi`Xyz-Q7;du znrHrBEBvz5b$7eVrU`}qv6`Jd&2a0ISJ@7JViQcRNG5LGNhRw09V|Qb0^C`&04Mu^ zjs~)=R?|;ZSUdvWVC&qRb)&~BOJ-K~$#7soq9_HFxic~#vlgVmY>rf^bWW#5S~V%QNW^!lh=F%fI0(R> z6M-V_Y!RG$BFi@h876HpXX_lkoJ1>?I{{_&aCl_h56ysfROQU6E*eg|SO&?12zgFsBtzEhl^p&xRZ9Y6YFK$t3S0 zn07Ea4(M;n+iJBd(e&JtE18;RpcuSUhx|-Wfx=%Q5GAPCfKO7@zQ=acj-|$=p&P9hcYcBUmyLwN1utZgYem=L|Yh0R^Qp9AHkwg$J znn)kIE58r@YquELDj#XFsb2;vGZ=3~D3YV~FSpWF_;-8=CFo}ues$}Ies8J#T6CyJ z!W;u3DyvWmp`G8@z^ZOcqKeIyXCqCPOU{;>0yJOp(qr_)+HER*RIA7r9O1f3E!tb@ z47M^OR6F*f5`LSbpwmvy=(~&(qStA|PoK}s1X_3k`{i9_HJspJBG%$s;+d~RzJ^?! zdxmZEi^V7I_LLjRrFlQ_d~tOEI5fm-nBA zxs0oPk@mZzpmyb%(BJ9xp*O@%Tqm$dm2B+i@+9&VuwoWP%453{19#&#j&n#ha{Lga z@%N9#2yIp)NCSg=y7_3|PjJXDfhRRyDQ{_O(a@Z=+6>KP8=dS2%|5L(A&wLa@=6MU zaeDsMp`#Wt{PlPRxR1Io$7p*on=e07q34TH?V|S2hX^{rNe+39d0*x(vZ(|m5K*vg z)CNIKSA4H>57Z@*ciA@TS*YX}(ms5(gSR*^@2T62@Wj(80opO2;mHJR8RZ_4X6@pL zmi~2OJ3>IGeWqs2$CzHu++uSfs_VKfV%Ti_J7KDnERa0Jjrrk=v2xtEHd}E;WLn@M z;mRQ)Dz1!3n~*Q)2a&BVe}CqZck(H=Ux`SK$S5040R`k)(U{{1Y)?y}TB5XAu@FFN z>84baYuuG|OYIUV|MItiuUOfJ;akreQort~vacguJ$_lV34C^%7`?0BvIqhZcPwX@u@(R>%8h_o#zV-QQ?g2R&@7bE2cf9+u23M^;Q2dKnf- zb{`j`n64zdHU2LTvH(N|Rm5UiI5{W#Z~y-v9%K#yv5q;h&YiKYYq9QEv7T2^B~)>~ zCUJfNaRE7TL7j2IYjL4hapBbQk>c^uCh@TW@$otFiJkGuYw<7ruHqd}f-&L=87gE4 z#tAt&3AvpK`D+PHcTy$}WdhRy~UEQNQ{BWO0^pj>!U%5QHny z=d>yfh}3@)J@ljWCdJp7+2qm)bjw_sDAkL<%Q~9*ISkw45iSxZmG=W z_AEmL4*yXu6)OknwVnRGxtuMG3WKezxF~*hiHvxa6nUoJ)%dQ; zbS=}9W@LtN_v)e@qE)%F?{h_J50*kKcD1_7_XVI z2bc3U%bMBeHXC|Rm@CL4gh*6{CZLs6bk6NK6^D*1m*UXU6YO=e8;6w41O%L6l;L6R zSCb#_`+ zd2l~dm7%!WhtUXwVS9C%-%C*z$`~9>L9lK`HM=7GpCfaO{ID|gS;zV!R7K6MGF;o` z_oripyhg*E1d#nYb@o1uLynW`WZY6A@K^M~>kK1qIL%|V$)`4+W2UUu#Sjq(KNu&e zX&Jw14R^V|JNwQPPl~&ZokRpI+Nz9RE3?S2_IIvBUX<#Ub``dbxd4>6l$!&R`N#!- z)1LPEORIJy6+>}CLhN3a-4fKLw9C6QMte>Yz}0rL&;gG1kbs*NbUtUBs+{Iaa`3Bc zFmms{U5P6;i-!JQX-5N!jEa%wdUU|1-%$$(3-7nJLtQ>Ejp>AVlk* zucxi1cm2+DGX_nW`^#v~&WEjHWULv(+Homqla>!hU6V*(D(94BPgk#R*6;SfM=;ww zzqhHGmN%5^+3r{sJ*L>4ZR&7Si?@?}1pRU?XmNB!4XVMZB0CvUj3=0a+!tXmt*gFby+EIk+mL*Lo85z9r58DJFZZXz!n=LWfuG)B9lk zeHbp++k!iV`+@?j@da8EW@utG3~ZmoL4Se-TLGJBjowFDcrnTD$Y&B);K_UaNaYhv zm2s#Zqk>f_LJnGs22x9i6U$dmqeHT^0C)jYka#mmu(@6VP}~2 zCmU?pOa<(al~0;k8|lTv#h*<UUdZR5mq#n*SkXpxuil`yG-n2{0%Yg; zOYE|E>BA{IdUcEm&9>PORv+jEXkqyCwMa-3GQ2)M3n>#@06XTW8CE0^p5c~Z^45(ruW6ZzTe8vLoz{vvFAeS z&@?3LpOto9T}`Kyd2(&p_)KbU3OqiYR>ODvx!RvQtB9qx694pj>p(2(d3s9A|CAvH zjmF)`hx8s;BcURCRZFSeCDp{guw!Z7B6^$Zs9RB4SwA2xP*M~G84We*BMFVg0#IdH|TnnJ7%Qydf<=+4~)$nA$CUIM!Q_{a#4lf zRf`Dn{!PY3=04KPkTYOs1K(=Y3X=qB72?rQ=@F=MgzdJ~5X|!y;E7mBQjB^o?=g6F zCCKY_PrlYIgH{u8wf$)P-Rs447{DM0W$T8eSzJKY+tFL&3}XF)kBD)bM0l(1=kxIA zd8-&~2$3o%#OlR6x=%AxUypQ>cEOy!K|ePrKf`k#ENht3lvEw4*vHb*^GC78ngLu$ zi-HI(++u%ysCnG}`t#U|Tqw>|d(JPt*K|#bCBu23P@$gVx{IQ#ky-q(4mYfBmRwGH z&L4Y7)Yi;K@N-_l`g3?Ua8C}^q#*MCYS@IYkSP>bk%8vR1X3g`QVK=&mc#w!-Sl7Y zFHtl;@Xa;?5wnjju*;3*rnFzP2TgG_!nUeZ@5$fa%4Km-r4+_f2utT@?)i2iHTc~t z2K?yf_^PDp{<#-Fr%7`&AT1DL7!mNw&p9UliqFp}L_P_~6abn!)Nxr?kyHQMB!^}V z5=HP=F|$8^Q)j;1*Y37_sqWxx#}#9!j?^w$f*Kl3mnemt3T6m{KYjKab;%=aX(xMjEB2mK%^dLk*Qs$@`p(f z8qq#XkGn3Brh4>4?c+o2ONzr2-yr(vFC^*EbvegEnTYnBDbsSH?9ncaEie7yh=s8s z{ycWbY&w-l5xbKy=hjubUlFV`$~Y)80~S=y zQE)z+6&_JyMZs6Ebd~T_7k@eH7emlDoZmj4gqP?`=A-a~fSewa&w_(&;GV{CvPON_c_?_# zEn6?lDN>95So#kbUGvd-MK)B(`Uz31Gup~8q!fU7#t*FoV8p<%HM$l>M}7rwL>0@8 zzs$2zlYT+|)YcadEq*1zQPk!4Tc)x5O3dAu_AE2~oNnl{uo$q(B}NWT zXyhMtLLVk83Gt&RIx#GJ#NTHtI(C3i_a{YToF8z&%XRP?))IE+L%zy-OODASmLta& zl3G5h(_X6LrMc1-t0MNK^BoCI;!Iml=u;@3URA;a#7NhK5%SDo@2Ht~z084v(Eirv z1NZ?CJ1G>!UW(zVAut}sslwExVXPSm>yyZoN6=>{fYNX{(&!b@g^HLSqNs)I;)?0T zI5T=LrS)eV>>Mqw7&lPvMXc%w9D?F9rM^CrSBWC6w^HM^lfX%!dC}}hTKtMwRw*}% zw0NHeMDdt@3Tci^Di3FZ$i~^8pdA$Bz6PYn+{tTli6TtmQV3*unY+>gWdkhWN#%1< z;^P$d7)AB!jF=x!Tge?R*l5`I*l@iFq1Fs?*R=UM&;l#G{$I=woz%X^>GR#&wN6F} zKbV`?D45Ay35V>!UWDxcDu?#Wk$Lb_rwq+?n~?SFhf6jQQ;vnKIMZaLU5_5^Et(SG zU;>=7UzW%UIh}X zcCFM55zCcTJHS=i(U&XC@Zm_!<*v?c8Uo0nz?n{X7FKv_I(SY^`Nju~=0nt`%~C@k zOS9kN@V&e=_zJ zRQ1Xhhq6sFmzGYE?_8I{m@TPCOO&{uB ztSK|AsR*j6%B`vCuBqFoX}GCrq^)h1tZg-`Z4avL%&qP2uI=5Z?Z2rVq^%p4tQ$3} z8xN|R%&nX5u6w&t_x`4Cj<$Y5vVO^|ekG`WEw_H7yMAkPxJC4-lC|+7PV%UJG8NAUW-^B=XpYH_DUmRQWKFnwf=$=xs;NkLK78XD=&}0 z5VyFGm&d{oWxoR3h<+Y_xuM=%qa@_#5TU4NH z%ko+V8VfplTH4fW`*%tDb($i6ll%j;M(Oq1ek2*4Y2A@NWfJg6J` z$phV=8`?t-U!sSv?oDfW9dX?th!?tUHOQ+$!gM=EsnD0!a_P)+L&w-n)Lroa^4)}fr^P)w^CGwe=@{p zMVtVF@#q6F8N}}>Ke9hWsM@EQH)q&JTEPy}GhqNhIG{7+Fppf%6(5vqF>accxh_ak zQlLsFQKVd-%mnB9%p{iTJJd(;^q$3ZQ<|S_qfmjuGzDT=rN8EshFJbBb&|64?0%|b z0%aX@QxtXntdJU$6`uJX%MQ;f6}{^!i@&!vpN3V|nT#&7y}L|Lm+?a7a5y#}x@jdBRy8NL=J_wNmn(%-8pQTHUl*}!A^W5OUB zs>2!CXi5+|x`E#HyDXQx9Mp@qAt1MBZYNnH7jc-$Fuy78l~yD z`Aoqk{V2?8*8S^R#Ty>Drv;g1S>uUO)z`$mjZ?tkOXG~_B(~$r!`|txxfv^BYjpL@&K|fulAj^isg32y?8$%LhwiGQn8sN;7x^f2(f2;We&Iv) z`)55rGsjsLq|z||4yBA!hbgFpU@MrYj<=j3tyw}U5SwHFj-jJPC09z4T!%=fn>BQ3 zs<@H4Oni~|nNmIHSmhmPKarX=noyk#TWdKfXN%)*MQ@&8%=)}@cTi2`OlpgQ&0`)5aF%Qe#C1ZW*=Ae;ch8xYs8lvF5vMMd&|Ng&k@0QNFCH6KYX)w?S85yB|sS-NE$1bmA`mM+yk0Sp)vAP)#Mn;M5F{o3}! zS`HDuLH<&_5qf%NX+X{bMREVYG?ns(U3U_px$6dmy1Vsn9gt@XvisgwJwB5YPT| zD3j7bd@4=Uos%yc)OsfKQ|^tqEtG@%-NN32ecz8G{wEVNR2D6-!F+lEqh-t&b3CTE zuB_+Ma{O5h&qUQ~i^!X%4CI?3`K5_9&&fTDlv7EVJ}?oip{{B_{C!{bV0y7uBWlL# zUCZmN^@DUG`^i~4=gOFTtbB&&NF-6SM>2@Y#0~VmOo+z-C%DEynXP7W4pI;wlKjP8 zUMuc4!vxd?54$<23;Oz8W`*nH9;^~9?_R9>!wX?UoD1m8%Blo9oyv6!$8aI%RY>S3 zD@A;lXYLxtIrK|)era%Xb8#|BsTI}WPF8~;ATfx6A@8U&c`C8qCs~3~46eX0!%eLT zu}->}ZUdw4?*5rhrbsHgQ68M{-N($s`*KaLkI;^0#*bj!#IgLo-52y!y+eHNq3K^l z#%vT!2WwB^KQ1jd4t-5v@O|$Zin=};Zk&VU?0{<85>m|>Cj7JdpeS~@mifz6@J_Pe z6Da-5m(V9n$(&SHV6|PPtIpe$rpRcijo8DZ8ngh5toh!{wcPP$rpL)odI%p%-yFwD zFWKfvE9|gOxQKzO>t#LTF@9L~c<^CXhN)%JA^F z|D7x~jSb6;PJSp&*#xfYPBw1KzL||ceKc-{FH1BwW&e{r`O8 zgg!;Ide4TM4x_5(p6$5p%jB@aLU6aHDj-IU8V6b+1#W~kF~MS<^&p(H5d?*cl>Hd8 zZ44I1!@^oMf0gmdP73TuE&s0Zc8Cw%(shdIl{9GlIs+8x0}17t0CkZI)N&NtpWI6p zArb8{WS}&)P5I#8j_s(WGk~AE#D+HwibC8vRx2Zd%pR%8Wpt>?ure$@#-%7zDr#XI zn3bgM-a4rkkooskgXuI@%raI7tiSYU2R$Rsk#l6rp!Iue{Riwczv4W8>i~Inw_Ahj z%#KNat+Ma`DVnQ$4!pXNPbjL)(rsq{QKwp2W>A;a^YJfcn=r@6EDHo*%)MITdmkLR zSIw6Uf*PMBGyOTaM!qhLZ0*D)%~A%<>WC3hsCivzS^eE{RA7<)`d3;j zfYpNGcyA8Uyamms(<57-IKm)SGP;q% z2|mcALl=#b3Wzh(Pl|^@z^>7s>TS3O|KK*#zt7*)%jwdy{`67Z?yFFZclXFJ)&@B7nEbnszq%rsIx_cLyTe zXz_t}qvJ~4e-PIl*v2QJ+1#dm8@&1S+O`<#C(6YgZIvr}jxxcnD!oVTiy9sY~IPAB-(sf7h zQDx-24uQE%r2CZW5=(2xERU%aEwIxO_U<+x=za08;e zi}9WhLN6!6NG8K(!~z96W9G$}1jhIl{SmC+qjjz*Y2iTb#wePTkOm!SgB8^61PWM< zz4a#qq%i`4o)`L(gR-&qIjpvg(8wspF{U`LH7L#qc#2Aa+*{=R9hfKVGR~_62Zl<( zOV!vcb81kA>I(pfb^$~vuze929WF-|OP0!+;8jdr^N6{o9AIwcp(X&pB~6;$ixbd| ztl^{{SAgs5;ORF43JDVLC3?O9*uk5;x--ec+6|QY{BRW1HVICcNXC?z6`;T)CjfOF zyn*}H#Iuy&3QFX2kj49AO5-CS@@0D)$e{>CSOkE2%72-B`JxR_Ab>NF$+1svPbe7q z+mTncQEa1F71#*arN&^Q)ojVlWe2rzi=3cN+8+(!a!5F_4qR6t6%&owx=J8MfndlK zItlgE`6O^e8eVZ4V?+|$I@R79Tu>E0bCo6$&i!CP%zC< z3d~T!W~g;#Xsl;wU1#XfWa>#|8klAp1!kH|d75-(nkOI}Rx_<=vTP)>>`b#90<#>k zS+EovoJfhBXw#h7z?^t&PGVP1 z@_Nq8>l_RXHcbMXVT#QP#O7eJxn0=&b!_1^wumOTL?XA$G`Au!w+fqE)0JDdp4)Jp z+enkwERol0n%5qf*NM&R?#k<3&+D%a0AJ+|L#XP6^Tz}8C$ag{UHNa<^WR_R&(Rbt zNE9rY7OVsotOZgPV+yuZDN5!F7@G=q-6RSXFA5F=3r{2{_lltV_W}`9NG%Ax7j0Op z!fk8_VhDP(4tu=}{qYIVh5wqo2?D@?h**p6)reg!1pN7BA z1k|5rQhkO$P=i8HV)Wb+;v>Z@)9?cCod0Uk0sz7H3gr8LuRwY^t^b#_pqO6hrqhY%TKGoW6|LryE9?O=>%obA~m93L*qL|$AAJe#AYRIw6 z)q${Z`rGDbF7@cn#Mi^*#A3~#7OV817%bE*JK%@jL0iYB-88t+?L==wmWLK!)T2zC$>bI=#`lSV0tTuPi5{}Pmf9J74^qZzn4=Fq@;5uHp_*~w8+w0Aj`x9ZI!TNgW5!F7i>UPd{x$&fOW;v9$W zbVs1u@M=Jl;hLq7D#n|}DxB1)`n7;X&8OPNox4%CWD2vZr)cY!31zs!!@fB{xgk3f z*}-w=)20Ur%kLd}xJ{4IcBhhDvXP%f*$i+YiKp#bqK73B?;4iXa%L~$Og+?C4RUI? z+rKo(^Y>TLS^fC>tE^yt{NzDp2<7Or1PF*JL*pCeZ3DS>bLDzmKK)vLMg_yCZ1sM_ z{OxXf3YY33x}HCWl^~q)owNtP*^c`uetaoahg1dIyrQ3Q<;}mdHe&F3q$W^W*xx0| zC!4N@ahKhgc5Th0r+4;tz)f+kjH5hCSe8}7A=NK`Az5@WZ{7ppa20(R?DC%YfeK!a z;-88$_PFO~etC?~jA~J=9nUT;6Ntaq%0AP-oB7i1f&YGA&CbkkeQ&0^W6Dmado?k` z#Dge2=>zdk#AYgCLsy7#n-R^k2Am2@7m0rIZL3PcWtO*~wsvR43b^O`^e0yq`sHVd z!PTHIZOgIfw8mD&=c6PZUBP;7?}IAc7Qae|*z^&!4Hw{Cx$5xSe@N2?7_7?x(igW8 zvW>Qv_Z5nv&~A6vKJiUdr@P$6^A8rk=yf3g9KfcpORdliz&H84CMu6FT2&H>*8XMU z)hGD3gq~raaLM;s#nzBV@M9oq12`$$*s1{?{bO+|X-Kop#T&}2J7YpVS=iRvD15g^ z-+oV)n>dUm$GwR{KfTHVX>OI!xNUglKG_i)yd+>c~aqxD^3FRFgYjkd%?CY z{F!wLwXYv}#h&Ujfd$fd-+!y4LhfUVDz3A*su9#9)YT6k`f8gdr{!(=l8SXksFu<` zf(zwdyiyBfZqQoIs*Nc}-P1=#JV%Ab$ibW=`g7&sBQhwn?<|BHyK?7~Lg&xlumz4< zqp8KYg|Ck|jC-`MnN4%Pk=g}jC)+D5{GN1iOJn1uNi--qFW5`5CYQ4L=wCA_K=^5j zQL+wZ5VRZtALYz- zQu? zQeUk(5KzHq75x%dNwzy^4Of<^?Cl;3%#D9_peos_nIkY=%O+%yrIcDJPZ-ry$Exrw z$9hIl8-LCyy7iHp^+>vikNC*n5h36;zNz;T*TV)j^urWqg&(Ukt<)H?71kVCvsf&( zlAAE8>jt4Ro_q{FtHiAfn1g_<;&-o5%{RIup%i5}@Nq^Q!TRu%x+{s0n|);1qj+Q7 zq%wg_>ktWqan5eH&O`Uecw7mj5m~spx*=tD-eB^>)4f-oHv(GC5Vtgiq?(AU5mkC8 zJ^EVZ$K%uAC8Q(?F1|wNH|{Dt-w+AUIf(ut3F|#-4Zm>n@Z(#D$kf|k6w z!X-||mYVznMh@-H;of_V(e?qCbXt!k>>GNM0)7F>GEn zbxoay2seWPzVqW5PHxFFYkLBrCfL-BQIy(SQM}7e@Y5zA|#KC{U- z!o)xqXs{C)@crxo|5_fQJzRy$Swl<^-*;QXwOQ$P$llsV!L)AOBX^Bn+h8<5j>|;? z!l*gssjKW3*IjNTy=tmwWaoZ0&c`=-k04$h5bETrKlC+TZ{Nsv+`I$%1KNEgBwpm3 z1ED$LU(Hg(ZMZBxNgYMX@=}}nxO5&xy0oX0X%6lfJVW%>*hYRPun%$JGePJLP7d@% zuyR^3H=M5qWu`nIqBtLS?)NO+*z$>~+B*G3nF8eG0i#{z&d37v0PF%H_(W%C#JbvC zgXUS?rEjtqySy#p{OOhCO%K96d?#Yc+k8{L=()l5trs4Bg@CrVw9C7b_+ItzrP_39 z?nfs)KYb&8WH_Oh6N#v3Y#3T}BR5KTzu&PUszj!cVaYbB=Je{ZcQ(}w%T`L1VQ7yF zq0E&C{n6cI0tLPDbhkYj^56@_Lad|y>viGrK&5K}k^ars=~t@^oT#y0z7GeR~!f&ihu-& zyli{EG;bR`p>cU^86TlZP6je;HpIo@<^P57^@k4}u@aa>THvCIIxYQ2{k_{BYI{Y~ zM?As1&|qDQ$XMX$@9=WR^MTEUk{n05+bZLcn=Um)b~eexMQAps18{WM?AK&&l|_gy z5Lh4oA4+bJ`6!b~L4#D}n7(v?hz5!@96b`-&MFmtLTaf1@5V>ku{!~+W4y)VCYY&0 z?jkL^Bm9@VUdRVf5XAbzhPWieNv*P^k^(AQ!2!->hpJ9ygQ)aH;f@8;N`2sQ)*OwA}=r)-H!n8nO_;3lxCg`-kc% zu>KsFh8eDFb-&wdaJ*-8=9>`cld#4{W^7E_u?rx)ehePQklVp8G07M4Tn2Ms^Eq&V z4qm|^Sgi<9SgHRxH4*wfOcfsfF(B=@Dq2JrFW|s%enNx-!b2zkHup>=xLbu-2!P4p zpwU%_i3oQI8;`&Mj8a0{O9iq4op@>C^lw5q=I~6~buer<)mb@Mzlc|EJ;sFesU;0< z>vA-$pxEUcp4>Wy@Zzb~CwA^<=?0!2tD?akekLqfB(MYt@wAnqqU@+-%6v}x6;4`8 z=0823;WEXi-UyIy1jrTn#Zv`~c0tT_;_DQGf8j9B#+93uJ#$2PlNcT*@Ihg#_(ZC#`4iXb_41U0Y*?uBpQ`y-jaCW(=|kiePIv=Og%5YM(K(5^96 zkK;M?7+P)xjc}0lHi?I%S*e5|M{ebg1y0sg`ArVbb`I}z0$kj;3K&tk z6quC10k1o^e3D4|vI?$f2IquU6PHlW4?%q~#q*uxD*D4cFY5 zZl+pNg1CX3XQ`tZw0sWY4I%Hj)dn_^mqlQ=b5k z%KUw`VsdE1fDyDsvX)N9K%I632;B-Wiw*HLFW z5L4=&Zz#|T(=1$6h6S1IPkWO?n+}4K{z*2;UOD19B4Ps@vCQ=40#G*rXd9D3x#ycQ zfx5GRhBrD;(I691ZYTdm7n#^vM$%fkyIL;sPL?n;N_!L%G|T|nXW&#vrnN)(r;^=t zn==Divde7EkU(ug@C!SX=#;l>Dad>fWLQ*zKmwAx06J}A8V}SxBXGh^xbS_`V1odS zqErShfEu9vok%+&1&}a;WpD^U;69cFt`_}FVy-358_t5=EFZxfuAZalDr|MZ_f82BzV@Dn}o`^CUj z-oQ=I!0qP1zdr*2x};PDSE(d{6dZU`YgL~cGr89YRtKSbL* zM7K4>a65#g8)lXsW;GvX4<6>sALi~I=G_|Rza18!8xfKo5iuVT4IUBCACc@Gk=`14 zd^>VKt0yNts$f2<6g;YuKdRO{sM{&W?(*M6g*~owPN{ND6}?r!aJgVx6g+TZ+?Nz!%IEjn~wD4Z2PM2J@UM zG$*a7gQy~5K;Gt);~u>F zpVJ)SxVCL2atnw*+MoTzH#;g_xdcZHLskt&WA#3(}8j+@z_Qy;a92wpv5(pnN#L98L zQUupdc3h;y(F+jU>H+Fs#;CcJJc8D+ActS|=pN(EG(>)}{$sYPGz&!IV+VKoq;K7R zQ=S6UyyM)f+aY%1seYX1`!um*Fo~AK#g-Zm+x{{^7F&;&uYjwecYMhwxaB2 z^|i0q!mBVP+?%|reW}GoQS3Xk9HWSYZa*OcZcG5GRuDzoqhiR$BD1Ei}RF|30& z#}{=jFY3A{zfuxbG@Y?uuqr&zaSz-o?vQo&gb8qBKIZoeP-TT1DOEqp>mU!ZC_j>R3W zUL@albR~n0LDj*V-jzr5?;a}B<-JC+?g4lqqp@VW*daWnLeQ-?vxmIOgS%0V zek18h|HdH(sOf%3K12nj*Nj-38_VZ5YD9|GF;U?O(H3VOtEQ+=f@1A#8 zpru$%R?h@390ggU$^QEgf&V3z8MHky@oO$cBHk1Me@`|}mePcD=*3)x3MYyUr?Qy^ zSiMiK6c)xijZUbu_UQ~~!zr&^A&9apLCWv2 zSRFOH?ej^x6BSYmlgJ%Tus2O2iaiN`z2r(w_mQH5P!=1O?E;wHvIlx5lh%S@CvzJ6 zW0F85LpI4dQU=$O0EDM>lWZweYAWibkjslOibx2lOSY4|!uev)xR`lY;`{getC~D| z!7-=QLnIkfa|AK)I53Ss~BVM1}-V5!dtu7&qa^1 zJGPE$bkl8;?Vc}j=WQo$vHUoNF3;&nIiGZxbmd5fV}V|A(uNzUoGR8tBtNMlSSNcA zi(K3_Q=FA5xwU-U596IRCU@xIk4p*8**R75d%vt^I6S>!gSuMD6K)ytqC3hO?53KfP?FNRuGt@ z9Jpo>thM%C;+fmADsDwLSCv+M>vXQ_R5oCO{^89Q^n=P9@redHh zWl{8rSrIg^-u-z!dYcma-lEcFHu?7wD}U}G18&pAD4icOC@(D;I$4WbQ)Jbr6;a7A z%2ybT#{=m~93SH)-V_Jg{H&R$OnY>pNY0C4Q*Z?4pU81c>mB8*&- zqlh?wPISw;Csn+8o}_3i`E-2Qwp&=)yBu@w)xC&^-TpKx5G$y_6sGT^$P@j}m~AyX zJ+_>CKN3p2Z9 z&1E7R$J%bLAo+r>vbY0&+&=rCi&!7#lD!J0YGbYc*!q7F_f}DD#SOb>0!bhV5*&&& zK!D)xl>~Q!ySo-zoJ!DQr9q1qcXu!Dr9fMp7AR0kDaED6@V)2EtncE?oVl2_=5}A? zVy~UG_w#?`#}uE>rdQalnv8E#rYKxq3!rVDX?oB`^wG-oq>?UQ(3of1{Nul|E_R~s zFx$Gd@7EutNAe;bkjI$A9d{esU#~{_ax$mo?0UNV-n|!Q2eTXz@UEt33p)z`fYgt{ zLmH6~J&$(*J!X%X>=Pz77fm-Gsan)T(HehjSDxc-l#!$3e=g zWrLB<>7{|NE6?F~Lh=c2L_!~bVWxycNyr+=OBf3|vd0NFRd1C!_XV*Mi&DBgLE`Mg_e95Uwxf>@$KFNe^B77uK=QU zN6itf=yPU$q`(RTEkFWXvTmkhs9Dr^V|_wy5eFJYh);cZa;@*|ybd@pfkj6<7X(@= zF5vI6^LKAZGL9)!V@Rs;VXxXknHHJ5OkmFW5v6^O_gr1M%EDFj!sygs^g)rtbFgX* zTs$LEy>BmLE2RhVc-Qe|Hry|ystDOzucTKHybpnRA+Uj~>+6jF8F2eZ12 zVq}ai>Vt@1iv48}^*=T6G>xLhhx?*w3;QCi)#9vOBmIKHRAi9fRbg%rnXU_ijcDhe zfidh1ad+4u6e18?##rm}NZUmx@;QoUO>Vkd0Rz#lCC-piTZm!3Q#&JV>nN<{Fvc1U zHlGP-!QWaXji)DJC8v&h@ey`&T2R>v*xj+~pnoCF4x>QA>;W$i7{NzqNLD^LD<7Dy z3Zq2=fEO5j1c>SwWj_K?>Pyt_kD)+7h=I?cNOz}t5d6lp%?G53L*Qe|s?Q0UNl-`u z7?cEd1SG2?ohkZ2-Bbh?H@eOsM1l;=0RS|WV2No@)+>NQt_y%g`9K`zzN4*Tpi_!z z1B3zxZ&{D&!91M_1Ms3#EwLo#`CyT8m;usOr-QB;mufG<#%PveqE2^Ep0-L4{4T0# z<3?ABM>ynjLTA!kmgv;g;a^4{w_T>2^us9#smtj+moBf=XOo})#{-pThbgIN#PCLH z5i+bAGH%k}|KE6^SJ{0`IRmmeLuUVv9%yFna!2m!Qtqd#+;yhB%`DlxEwj9x8xJ%y zZ?7Y7e<|hQ?u9S!LKhfU-L1-*sc^flEyc9&D`5P7a zzk+kC2;^Ji6ci#9n;jGsxUfPI7~9h8HKrRc)e9g31OCcAXou~vQ*c)1*3ZKBkx0N{ zq0(vYHGmmVe`kZ2uNcn+Ys+OJ;shYPR$}=BCGyhr^T?WV|GQkVzd><9h>ZUC`@{c{ zEAbj*D9@9I|0PKfO0&K?PE*ED@+Rc}R<4Ma&~8PxRNc(0{GX9ck+p*Vb!2nZ_$e{` zzX4M-s(VHVoSO6H{x_Z047m6BREM}_U!G!oE3@MUcT}-TmG#@s8%~5E9jT$10nh#l zJ=c1)j8ofxfT85cGd=(a4}y)^b}HbphJpa0DASHUe7m z9EYQFjxmX-m{m%SM&5H;abr(+U3BK?QHs7xpS4@4pDjDXuJ{iDGFL8MY+Q@KL(c__ zm2O0VnJ#P@*#hnsN^a3Re&8WI=I^klOjS2_OCi$tY*3FA-Bv5{o0VNJPIL0=-%1xx zI)0bv*m|X(Zjrp(_lozMii*5oXT?_y3$hL;d9kE9SoYhfjxrpSqj*KpC)xK_fk15W z7r(~4fh@_-H&cfSY4y>sx`}12h@LEv8}7pD8U(DaiG2t z+3meo<((r{Y>;l?Dm!ymuw-O{J7Rgvs-~lIXs@|fe{wIfj{4L+!z^nF7EHRmL}-Wm z%eXbGpYsjZL2>dMofIfNGps&}(TbYJF|&kNRBC8Ksej@dfaxuLGjAum`AQ{7UnJp2 zC9S$BwjukJH;lSpu1^HZsL{|*0A&U*I~#2A6VxmxF6)R(ICAW|pn!h&*Uob8JM?hr zc77#|neLz6Cwu37Z~q=oI?n!)q`;{eH4`(ioV+#0G(`1kSDFi(w@ z#drR{zYSAJ?Bj_TjR`qk-O z*Ui`GK}2(Yb=G}E4~kp?&z92VYiMBw7>4OryyC*8@A~j>{d$t0?nsym!3I63sUPSL zzk5FHN>lu3F^!?wSDxuXt7{uGEq`Oi7|m8EM(-wUUzP}AlW}$Zv?>BfxUPJ1-ty+V zhhM5D3e2FI(yz|+Fn|%&gq3@M{9gM`hA^LeXX>zXftyO|fH6W)s*YTq5j&v7zAK|- zY#~F3&46TlD1Y$ufD@Nq$WtDM5b~lQ%AJVR>_PISM0v_%syiY zTdzcK?WjW47YESACRmc8ShA=ptziN;;V`&f_q9egt&R)=COXTW_1&a=Vi*4@KMpC| zY>%f-0;x9(y*wGrHumHeA=N09R?}KJj9ZjX)B>=J@+~JUmyP}%^Pmay7+hCzZZ4G7 zKt9^Ct(K9A!hwAh*sv%#4O6cMwVL(oxX)O=`RwiBqjX5e3dYb)$;3*C!${x@ZHVGX zcmni(e>LhNVU^2~rohvNU%yr7;xvKGg4UAPIknd!@0(-U z5%LZ9avg|6?-?M5iSL^~m45zS24%+=%%$1PHYo;bxDH~Fo7GwLQh6vZL9Y-HH2I0P z(TL4WnfKu(dqgUS+Tscl$%F8ILp&NF(Q(35mQPEpW zf^~-Hfb=vcV_Y=hYus<85ID z!v(_3*G=~ArS-@lN1iHvA$pFa%!O?xeoQoxBULf+0ypAS=^xa1d3ksSc1J=a3VvH10%((esA0LurA24ntKEO`zsDsFt=0FY+Jb(-_Kom!FZ)tbSOGJ}h`{`WVhYVw6Tg*{* zQWKg>34^rv!84ACz)t)NXf%5yz_yxThyZW~o`0}B;eerju+_c&5O2G7$73gh#No|E zIPpkdv|fD}t&@xm&qQC8rcFpEoDo3$K@bma4k*?tI1lNK6-vl$bm=*0$v5wp*3Z#c z47FBhB1+DhiEr>GLWD5bSNitO=Y#`r z%q{kx*HTccv;{<`x51qarHmfw9Sgx#=$HFfMH)1WKH)qoi$xR`i=}7DX}YK#$~SK# zCU%>$fL?I(J{dO)uX`fVkAXxY=ba1ycYj6iP{m;1IXG99pdcmQyquB0^b_W!1K~$g zzgGTL=#a}YA>eMg zC4|VR91KXM-$U$SRmN;QGtqY+$wYN=e6F+ebyqBe?x2rzCmvG(&fDda=A@`udB*gg zUI#^Q^+iqW$~-yFQ5(T`p0|aY-S-;SUB<=ziXW%7VwC!Y<2}!mG5a$m3V!COYhBD0 zAO`cQzo~@4vVn}n!xAO75Guy791$R&k?>y)ePlQ7zw5 zDQH=k7d80id$~pgcC&bFy6BOCiX0h=8uh(Bils&lgK0#9^O{tqX`aHRAk{No^kt!9 zb6%`sFrtFcwP-Q=)aMk^%sgqHt_Bgf3=|~?tlBoJ3WxARBm82x{pv$^ubX_eN+noa z5Oj=y`)!`asg@x_(batv^rHv|Jk^a;VKxf-O%oF;25YvBVvt6dWW*5r#t_dMY@M>_ z5}sJjc<(s}S8{qBypN?{h^6SGfHa5|&v@OqQ-XB5#EUvk0PhlnH!%`~--*0i5WV3` zIU@PEb||i;57vxC@GHXm$6&>{n4K}$Y{nhqpu{;&M3@02*N4R_Kc4I`(03c}_D;KmWr+Q-b zt2`A+{a;F}>Sj{)#-_>yYh|W*W%y3CN31yeIx?A9KLDF_4>4bd`=NzxI1wRb2xNV> z5eFQS1Oc&Ay4&Vd5r9|QfX5j48uyJ{1qeq*gYv%t*bziZNskZFxnoH;56_Ltg_{$= zH|U8T0HXsAu3qnFx)FcS!Cb8lzwterG4Qi>0BK*=N7{TPNq99Ot707D;Ny|`EgwDt zG3yhds*fwgfREbjN z>P<66b5{>Z`vI6NzX{{w(1)+pI*YZIi*@2|t6dc9%as_Kml%hXm}ZqA*on;luTHC6 zsiS$Rb4aOcR;hbusptQ;)4Hb-E&HEN>mJ9;^#6Z5t$dP2vRR+y7z%K;Uv4pMA`>%x zYJI6F_T3paf7KqlBd@9JPTc9g*T-E<(0f)u8{6w#*kRuZ0KLOHfF^xrA50wpNV2Ub zfz#8QP!68dCmvCf69M$sb!g-1-W*cG>cLQ3O6&%l8BTva1G}yl=F+5ZC4k~P8}*JT zXNa04CT{~O%$sDgo8-Eh?yNN3``v_LzA241D_JzFgf^>XH*0h?Yppcv{BFiEx9H2a z7+SO#hqjo)*`>2vELU2rf4A5&x7y3MI$E?khqk(Ax4L(=daks3|8DhRZhI)-=4a6s z5ZV@$-4@c-_IRc3>F+i?b9=aad!$8sbZC1_c6(e`d%{Y4;_r3>b4Rj#N2*0fdT2*R zc1KoMN6tz|-tUfl=FY-UM&YH(|E^v^05?Dk(Zm0j>h*@6Mm~zAiR-Jo940as2!wPIQ1P{=l{fgwG*zsekRfs!GM5DIJ5#ilcVScHLb?wdJHN(CK&-E zt;fd+2qA}vuxLOS1QD4ZNz6w*(+40!*W-y3GSOQEC7~fkVk8B&AU?s(4oA!ASb(Lq z)anP&&|5RvCs}&8+Po4uD(8GDz_)JBUn7HyBQ7FPjohmGz=4aBqwWV}!cj6fTHBjN zriWOfilH>KBYZxEg|jx3Dq*7nmMga6|Ni~PYyO)HJ6BGuj;wr2 z^5m*QNmdF2AeQUB)^NU=u@EENe^Wg$$>&F^G)z>NIF5XfzCSJ9;)o(Y~WU6_}Wtm|P@c=dVD;&~aNvfsHJ)2=`N`MJGEf$>K^%HIG*@ zrT>xy&b0JB?KQKCo2NARTbm#G^9xBcSJLvm$~DmWVBFP5wBI`Rg&Ja_7sX)wSTt%3 za`gou*p0i^(iF_mLUNCKKdb%{Z@@!A!(_d3^6oxp$(}OHv9G$C7+SvHcw=a@tCy#i z{4IMH=}cM}=VLId%wy%Z5yh)6&Np*+1GWVhRC#ToGNvhk=K^ZNaGmL~pUN+f(AwCz zt?NZ`!pZq#?Fss+@g|Sh4m5=PAYkqn8B7Xe4Y=qpd z1{?tBEDiO5d3VJoA+>uHG54P>WSWCMSREI0z_7ovmPO|ToyCb}&J?e|AYFC)r%Mks1 z+pO#E9g1&u1W%cQsfs_eVPM8-quNdb;;eNrUq(N$O~wwZaS0FK^`fV%N+o8I1pmD( zf2QlnoHF7tD5c>@194>Af)ozcV(alQQgYae77}5fe36<0)DIF*`x&h(U}lP-r-qrB zOFA_U<$l$Ddxk4Va1{*KPfG-R1tl36>^ZV0@6k{jgFG)|s6adBC6p$u?@oaD>f;HW z=99&QNc~eP?R8IOdGj4WX(WY&WvAJ6dUF%7J|0HtMuP1`6Rc;5bUIX z7C@O4y={sJ)taU+M?rbjHt0?Jr?0Z|G{jxk{ zo+z^=%Xlovtlb2BS^_HI#)1_z24ACYMUR34SkS{tlnWsm9wAtuf&!9zw(pRskzekC+;kTR!Ag z{kjJzh80H=Lv6QMFuJ|-MfC1!rI?9wko#J)7waTdwamN`UIQOqYnU$x+SIsbObCHE z+Me!XdvM!BHTe}w5%-3swJ7X}G?AnX)YN^-^pSKvw+0m;-|$-3$DTo2Gae3JGPqG* zT(zaeENrKv|vK12A00TxQ-VSQqrZQ851NsHj$j_fAT_04MY?@ zV(Y6VZMpX2h>cnG^FRB81?7qVI92@-2*?I_?{SoXvFHY3G7g3R` zR)pA$517J|Q_L_MT}2R}NxD{K=)4g5B@1IdpF~Hl!ATa|&tU{$$5B$|1Rl952m%s3 zS}0%cJAN{WO3l%OyvZ#asa#cpp@fJ=O6G6S-JJp51fjz;6^C9 z20n#%ex0#jg=uzfGy)=&8dcbe=(-ok-djEzu~e@Mv(UVDE15)*C*A3zcrN*{KbK8C zLjZwvzM9JLA~~av==eKV7TXtI=r=BH6gSh9p=||@bm_FtnYu2@NH2|bkiP?3P@79hg zpUvW4Qg1~nsmXQ(t3)#KnyPP3OTyVFAKLI+CcQS3s#@6|cRI9e#^ZC%*aNh2e;4)Q zLy9|YAN)IFEX6={Qh{m>++#vNB^K=X-#2E|G&S zkUi;0+3J#&9-J@v7wr994GYg=j6fR}#2HmbY;j+^L~u(Xqo7)0FoUr(1+*jk%JTW= zu_kl*a;qQVByA7%7dz18A@<%d(5h^h*#hC;=i@0JW#TGA9IXh@Fv+ozl!}|WnE)1z zv8SudP+oMw#v4`Jhw3l((cUh)RjXy!aK;g$%?b^KidM}Id=^nio zFTdOxdh$7x!fgXm2psDkg}JHH5&&VfFCWu2WsC}Z5RLaIU}-EDBbTibn}DQP08vm2 zF#)&X&t2gcXp-|$$;{sMd4{LuiTQ!Wk=M_oK%_pNr9~`o(<$?Lx8C*ZRVYVovdYKN z8pdJ9d}Op%3_ES*Wys=!Z-9_z7@P(pcuhPX9RdVFfpA`y7Zvj3i<6qLV3+kL{F(&J za~kanxv@;x^`Tin?U&^+@z!m5hgKsBJId;MD2M~Bw~pf22H5A{=rEXNAJnK&aA*(( zDM!#pTZnyq`fy#OPAPX+h%excD$Qrs+Wg$dL_08;k1@r*@y{NQ$+V zlReP}N|zd#fq>0jJki1c;kF{TzbIv-TNBUTk8yIF*@{H&@&ug*9v2&=ei5UT#xBrE ziHjqIGmHs?q1#)}R#Ji*snApiaI^BGHzyKcQ-rxAB3lG8&}`+!2r0PH$Ra=u4A2lC zwo(`dp~A4G8cDj`feu6)U6XS2M{rxczw?^jvSBFP=|pVRfF;LN58DEshT!>kSoHA# zDgcmaJ(@_=L2pQtwjbBBiT0}ZFF-(qnm{x@B4j?i*YCB03laJV5lMRGTz$QA^zFWj z7{z0Of$W%Ms(c`|2#~rS$j=L;?h{r6 zo79(c2QK1ruA89A`6<~1QkCbH1SG7005eB|yC3m(k8$4F)PmKsjrH3&CxJ)?0Cek0 z>T3R}Kp<6p8mUNfg<2F;{kC`!mj6VAze)A<)Z~YVjc|%ralY=lgvt}ttM%q|2R}a~ zQ}Qu3ktH0=jt3(F5OyTjEhN#6K4n4>F%f_W48i~j)dyrIGi9!((!LJ^#o#l|2+-{R z@~U9pFn9koyo`(y7gEiPO`?e{pp8L-u!lnU7;&n6FcOoD!v#lV0!>A3-&7x`sZwMc z?$Y>~{Z5vJq-oQ9RTVa1QAgS@4vJAk-KA*3QPe}1z5s;Pm>fu1Qu{-=uX1^q^0=?f zGMJD=+nE_GL?CSaEz<(fo38+58`#R_NkKiVz~@ON0oI5JC_;cWM8NGCk(ziBx_XdR zADAu(9>Qry)X($BAF0>}VlM*GX7QNYCYus~q)4LmarQCB#NJresd@CKqs9js@#)<= zKXCAK92^G`@4!m&HQmi_5|c775{d{|>|mIhjb;_gc*aCzclZh^Qf!ALvPTlJBa0(= zAvgjpF*}q}4e>D9`Nur`YzF=p2X`)`Xhc$Gs=_mUoMbp-=zJnC9m39cH2Mwgu=(mV z_IDVO8K(H`r&=(0@e!)V-LJw0G-DpxNmF)XD60=&KO~VRNx65Ehj!{S zB%3f29pI&v1IBQIpSmTJ;*vL+iYwd8mXiS4A~u_bh35pTKU`qVc^M%&n@{O9;wJ)P zA;Jq;%pFM}EFFs%BQPkdAh0r9i7&(Muqddrmbnq}n5eQE`Q(`Ip+_HutxG@^hOz}i zsZJb&ZwI?CgXtGxua`|=L~2~@?AcqlxecQ@45z3@1(veO-dW!s}QZq$S}_{yUwrJ3`6`w@)XIzj(#;2 z*;bawH8%q+4C=uKh!E1fCp4!OGr%-oDv&w=X{hS2zL?C2%f2O-ypdT@SsqOXXIX7# zSY|XV4=5tSLM$S<%?6{!LW-pKqBfeH$fK~t8;$iFMO*H*Onh7{n{Bu9!JuP$IZ^Pu zI>q|22hj$m`DS(qL;3P|`|n#F1Wn4G{JNs`Cv>Fs`9rX?!^g=!j4t8`(eQXdX&`MM z;8r9M1qDLXYpL?f?6O&l!Y!Q)8r5;BrHx|MeK=YP*wWx#F+SOM?;oMg8{Cq+=?rr@ zT3JhD;>s606EcCkW<7lB4K9qC*&@&!+gyr1*wIbg`av@6xORGz`L%B2t#Wosi*g;frU|kH>K^f2KRSDJO29g`jUAXMyH)UddOsV0K*#1aM_H{$1^Fq?o0y}$&qu3(QKSmIWq~F3c?~IO8(=GqbW_T(`a$31y5kxZ%gH_4IH4{wi}3S02AXSiuq z*6DM{=@v}4LJvYb!0irsE4N^)(-H+?;05X1fo$-MrJyW1%e>X!kBGvtb}^D)+i5oF$!tx|XzR>0RqK4bC|YPp{I=;wj!v*(k&juAk66vH z;EzQrvL)~lT)ofpWlm@y)c4|uL#|P8OiBfM1CaVNyY{%h-E#IP{R0bkT~pj_8y<&_3Zmo1%5)ANI90N6>;3sgj7$;NqP@lMe%vvt7Zx^I{bw~;8~)_) z?8)!PGW52!s@|O4VU0gn2CkvGQ{ozY4cKBFjCU;pWH+|#t4Wcs;_4X4uZTECe+IMj z6wh?^tiaC1D=&IrMV*5WIS@yTwh(p`=BT!{7q_ShjRFQ{+NIQb>5??v^IksB6XV#V zo5W*?LUTkA{-(Lm0Lv=)SAIi8$&M}`o@2SWHzGf?O?Dt z0{;s~Iru11Usm+oiCI!cV+KrZ7iR_lS`Nat?BXmH;Y$oc)Rut^pBn6(;d=;9Y+AbdROGs1;L5G8ms&8eTPO_0qc-nls~h2j?vbzqh= z-Jf4IK>Bg{j+B#Dxzp1#eT}A$H;XP!U&(-ADjS5};o&Wj;`#kuQeRWyLX}NpfpzOM zgNCC|0W}g|1XRTAn3Yx}+>5qRMVveC*)x3>c+d(>tl+P3nTd|C4WS60 zuymarD=ueW{4$`=Os87Jtiq6M<%ALsyD0dY!?-j&0E%CTHBRK%+hOPaQ_7((BVB^I z1Z?#6*BDbsLHz(&C0Y}X|4dZlX-P-UQ8bpfxozE zc~P~SgCdIL(p!k$k{FJ?vV0X#LpinP7F4>nSk0qkEkC)CPJcQXpK45q*+Y}ex>pHy z)DOg@b|0J9^-#Q2(wF=|YMTs&l%o~%Lq#^X8mIEd&=CS0eRIY02;vk{kyj$slBjn| z;@Xn4w6$+@vTpG~*YFCpZ{;H13+g7sq||o2P7Ik=A@NJ`;4M2&6~BfGvQ+NL?n5NS z?vi*?`DkmpeOE*MBDKZe12Sd|kO8?Kp@Bq2WBG<8`KE`3$+YVd^AN`uX~0Cp!!v!W z!0ncWlzXQ?h8RM%;FVOt3Q0o@!S7-GB;b%eStLulQT}cJTiYs7r2T|0+ik&du^u(I zQDK{RE$TNz^t354z1uC#bEM%frb?xFG;H~n7zxk|JI=LL7oslxLI z#!1Us(zz|~11ri0;JVfgQDTt@1aU;1rE(TWyrI?GqTjnT;@9`9n9J#1YT9-}>T}nV z`90Yw`2uvDqO{Meu|@7e%B6)9F%m_^mxl_k4|MdZS`8~ZUi7#h-1-^@*D(bE)64r( zgzt%dp)~=0z#ACnd|Kvky2JeSR<>+s z>|A?*Yj5U9U8Y;ET^Li@5AJ^cJ3BG0LrFe@;v=&zv6l={$HyRI#2} ziY<~|*VWkMQSl!Rd&x%{x){Os21xPLZ7xTVG=Nc56nibInUA5PzX0n770_7S#M#Sd zGSNyL&?Hwo7cz%>Q9)Zt$IgPUGA3E@^O@(azj6<)4f8t2T!rZ3Cx=7kas(IM90sqn z3o~NGFoGrcfk)7znWo`1mIuP(zwNTd@T@vM1u$b*1-cAO*sOm)%%*Qi*=yIqRlFBsNd$BRiT5a5Uytolix= zc2p^VoYsA=lwqca1m-w>l|RnWI#Wq7Lt6)Mcxk&Xt`5#)SwL&vuBjw(Gj1+m+T}+o zC!RZ(G1~lsrbwTygO(~_%JV}`aX7=irybeNB6;pu@tFLlFfFNi8XP}NpBJu!$Ydod zdN%eAU=YM^eFQT<>jsPpk2S!p2pnuQR8dG2JL=iK*(rTKV0LRSheR2z&pKU9)L z$z{A!zKLj)sp3sOq+hlDAoW#7`RP0N&sxju(^5(V)Q&`K2emnKVDT3H0cJz+fx1Fg z$Y#3Jy27J?j(19EBx&3gt;kYKtr)vciK?>u6n;Szz2j^@ok~U3CZeLIVXx+!$v12} z-<5zaaClTWO$X#;(ujSJD)s}Ii`rARaHomzy(O(+!SHG1*2A3-hnOl~Ep+AKpcZP8 z+(Ea%>}YoPEc4rC(S3MO=f?(q<(2ED;^UcL!(4(6nTwx36)Gp6y1~q;)|;(QC_9o{ zET6b}Sc=*=kIwC|6^GQMs%=vkCmzzo)0i`LBEjlP1#Phe1&+x2tarZN(XnOf*nWr=ydm(& z!hRw|How=PvrbUU7dAYel4gY)pygm+M571lH4&&^9FCYPsY`;Y`bvYXU#jv1S7pK$ zk!34Fe)88YYLizt@I@gAu{0%B7UiL`ykbp4T-u9D^055r3pdHxp#9*mO-*s!vgJX}_~Xwu-Sc#{Xl15i5wN`cdTh6GyY;JB@?JddTQ`4|wOPQ;U|E1iDZlQc)r zWG@a$p$cM9paGrFyX={Y0&Ai^?xH`UyT)<+6mzgN z4d)&rx1XW@xzq*|O0}){Gbt(d7is_wCjoXw5+3 z_@Av_ySM*g)a0KU)?Vw@WpkN3*5o)?*2yt@jW|h}%iFSgsG~Tb^e*-NlAlDl?gx%* zbKBS31@8YeyjryQ)Mi+^T+Xe5m($oj(6$$7`l7eOE~s2}w=-8f;isjmp9>kk6l&$}{4izdu3Yh9 z%_2GSb2qA1Z4$*T6l=b)Hjl-HeiHoXA%B-yx6PqYF@Cp`ziD;R!dmuGZ_z_Fj_qxh zN@apb;T-MvHB^Z|v>{FCCg1aWRkZE#?&tU3*Ib%P@=LA;EX!Idx4z8{E&rMiHB74? zbQPdR9wp6rC&S{d+1M?8Fnr*-xnxrjjS7L`zgZD_@!2bz7{cqHCD(b0fsZTnR#D%> z*Yf7Q%(m&O8cpf%KYh>v`PB<6*)^FD4ZBnplV~+2Zn^=c@fMuq2A-duQ8JSX%b_)9 zUsvIJM1z`dCrK<5%Qr-zG~FdMV>{fJ@24I%lbFRm6_d7rN0NT%Tk;Y5ye^Ag=6lTu zmO{wxS4uaVO7U0q>|9nShSMCy-IJiIAulHPQ*4_iCYmYgXMG$?T9lhWnqD@OR^i!y})vRL~v!Q+-z4288g2l1uW0@_{#LocXy5vOLBB7ri zna(E^1YhZE5TO_pqd=Z1D@HxBudg5f{rgbppbCHA>_#fB66B_-{UnnR?o zBcOL3hfO0DRQ6+Uq=K$t&#y3aq-kH%dbyHBItw&CA!XQ#iqPs2%PXK_{HI-KSt(|= zbO%{@!g!OOWd82X#NCK`8Oz~UffkZT-CBWPypR8*7+YpK;)Lo!h{jTXOYoi(@O6($ zatDhsMj^Tc+`^^p5;DxSR2@9;>l3j!{TU74k4Np^-VzZ-J{J1qCZ$JR)_5!XU?MI( zljvIZsFFvY+phrbyP@zBbZ$p1MlpTc}FH2u6jYa!K>o)?-9z zkxt_h5*6L2Uj}7SN%SX9(!0ZOQbhf4VBzwwo+OEG)mCvpUd1`8hS=rs=6INF$Y^#xCu3!^n z@9RNQ7m%hVs-)Kd+DO*1>r=VwGZ8)(FKR36U?+wqii@O8jQT+LdTXHdchnm5RI;N| zs?Vgo$7E21*hzhxtx_!a-s>FKfr5MmiL2+&Fe>W#gM3gqq z`l@<>7c<-PE9%4Y-0k6^PZ&0IR%3%3>zBGpWi_=gVUodwYwuA;15@PO(^MxBrw z2z9Gdj;zM`ds6}7{KfHrrk-)J_b${Qagvx2dD4mGZ~*DRLh-PS9r7QFtf*hlw_E#V zPF2Y4oYuDD=g9Pp@-ap|Lm#n0TX+Xna^7}@=xA=N!m*O45I2Cl$MRx02Gk-pX=JrM z@JEkM#Uncv`te(`YH*~OKAKo1Iq9MDf-gC9XN6vKX8nhVHu8Q0q2hP&;dy~!X4g<5 zLPN2`nThe?f-QfPU2eRi|A!~a3SZSs)o97ytq$^zkv{BRpsX3b7OI+k0y0wJcW)Qv0hr(WZBXwB-u&1-llwwmmasYFV?fxcJQ6YR#a1 z2)40q@)cj1x3+|$TX5id8NZ!jW3^a)x!m#ggNzM8C>Q_cz$2yGhEi9dpNVRRXza!ojBFF$CjGTa zZ_gipqLp{o%nTy24!0h;+Qf38GA2UxQ)9vqB zjzSOK&7EKxU%=#MDOTBM6L~54OV?|>KJ!X_Vg0av4IM6IkCIw--OP3}arvmE8#zkb z`$>Gnf&3J!_{idHnB0Mi%|Vp*R_>Q7Mw|4vUz9%G7w(?Q_+qpM&3IwwfZ=7^=Cnc^ zZ)u(1y*~s!0MR?TA%wk6*3MW9weCiL+%lY(?0saPFt%VEo$d@yw0@z33}$NAwlkV{ zY6;z#^HA0Q2ff%btVN6V-*G%&+jf*{ulK4{fhd$xTXBV|sQar}_HF@7?`y@G zIgZ*|m(Ty$Ipfk0o8Ni#N$R>}mEh|%(R1(AiYf3Qm5QXwoExwME4a>Hg-T`8^biE9pjqi6@7?{rWUo#Nm2t4$(3^eS z<92SPTyOmS(dIWNe-AU24NW$8($wje*6;P_Z%U+`#GK8-dcVJs;;uUAt1)&9h3pUB z<8G|AFFf36inbbx-ruoze0`8ukh_~UvNJaCS;FQNc((ga=lffFFNaO}0dDg;wjUpK zB$9okKgl{jHU6<^&8smWS1?TaA^pcH1?S9;&~?VFmz7afFu6wU`S;IK2MWtcBi{R8 zoDbG|_rH1{*r&d)d-5YZ(fd~FJpH{*K<~jpZ+;(m_08GA(bLp(6@LZPmT$ag(^Uv}}rbGdx#ez_BL6tL|2dC3NN$)g0coY+k1YdN)eUlbD z;&jD{xqh_#yc9b8R`v6jGe7WE!jJVs;QgQSbcYDl8p_+gbrL`GLw}z3`jEXlJU)h} zJ@kppzmu%iz}R+leW;O~^OJ4#C;iLLB_-0iEaW(ni&MCXQ@0A`@(^_a=X!q3?NXJG z@wjykEC9m$dsMP zx(Ev_e3CFZVfcD-@8U%M;snER`fkemuC&aZ*V-omCrUOa0t<(#x~I6oR`xPKPkuke z(bMF<<6n6{mCJr!(jV(w`^mJms<-(Wkeq6n_@|mal40=EeRd}I>df%XsnO^u8Of>X zyEBu|XV?dR79;_hWgj$N`Kf;Pv%ei+sCzC?dG37wOxxzvg~8uh_}tL4TKf^&0-T>$%}W0* zeHZZV`tip+?d6DzhYzBz(nCEpXUXALub%~fw0Uwpd+(><<@5Uf_&^3OvGt1+gu&@0 zRnDvM7rK|=&z~QWACYs;-w(q8MFHAF?I5TpZ{zS z$+hL9pIxp{R+MXP|K9deoclDLAHqJHTsF(Gg%Oj6)~F>lTucH7jI&u5SLWgph{cLo zJoPUhq|`+H82j@*=8$uYz@eHf;C76fNaZtW^!#?rHI*UeGFR<(!abcM7kIos-c&?O za_uQwzm1EVjaPZraw}sN`~G=$>*G~@-$?@!3sQG3<&S)s#;xXmPu$K0mYdxd8oj=s z3$C_5^awe1t@4zQ4)j{;`d#(l^UG@~@4dx_Z`Ri@Ya$htO&iwU^s;@`ul2kV+nLIe zesrMqun{-N`Xg3Kt5ZNB)UmwK*|JsAGZF!AJNNu8b+FnQcye&}QR9Y9Kl$^2JS?r) z#qu;xN9$GT)7`l;gF0_kZr6TJ4{;P*a_GqqjwT!72mkK;I^BB`a7U;!_}kZ#uWw2p zJp1?S&##M8dXdHt9o4Tl4h56u``AZ3j7Zc5B^_bCLK^!Y6a4Y;hA=fS+CnWgA0 zToks2N?#$VaZ#9=bz&CFs&2?obygttEoUUDl((j3nU6gosZuJ*IQTCol_D%jY?eNW zs~MNa`;mU9=B?cCYCi}a*RZjPzTftJZ7B0QnO|+lM8Q;MKykiLL2F09MTV$WQUwCer-!PC zm^`|Vf|%!47Dihm?=+5bMR+!jp;J70N3R9D5)K}hrExd8N@T0Nep|Gm^=b0%@5kRC zDpE+lp7}9r((J4HP7x(8afR!uBer9U1_=Sog`eeY?DeB-T;>pE#k@hP()(@A$N9x_MGjUN4#*`itI zPCr)lwZ3j&C{#hjdbFFHvYtatEQ_r&;6OSBLTyx*PCQV%vG<> zYD10_`hI?rb-WS(Y^95u zNhnF725Dp}AANgXhX??`nJUwLi+kF7T_)LkdinSFOS4vUAXC_>vOx0qe9kY0y8slx z|1mZnGo~Qjt^VT~eRsa)3`A;{RFx=M4KuxO(7kC_AIYs1zoviLv-(#N#?r9_>LF3= z&aID@no@T=cey<|tnpm-gY748^bq?~ZUrMb`&WlfJnxaSF*Y0=v_-DT$XbvH3HwBZ zhQdwV?b)4NgJ;uYiC4;xeR{-Dr`yc2rK zjj5$~xcCezCX5;z(`p}cai5V+UYi}Or8jqT-E{pXt&SUC{U6M|^;_Hhp1m6&K!P;{ z*9IrJYbCf-thhTAZ;MkjxCD0(?pm}+@lw2a1&UjN;w|ON^X%C(d(Jg;&OX1K>--b> zj&@+Im4;n zrN)X)8U3oV?y;H1`XNb)7S5BNF`09gz3^vmHTH$VqX`sXmgQ!oF{E0@V={~al6=n6 zm}5C?(l2KyOm8undR{QdF4vMntenj~Z7zFq3)cwcm@9;~l*>Qn&`PeHD-md^P!HhH zDdzZ8q195U+s&cdRQajKqovC9mP7wN$9zLlOSSD|PQ%&C`IbhXmKv8DGMcX(3+*#4 zwVvIaravnex=&l`-rRDUV{tC_L0jv?A9GofR4on)v^K;Ca9J~PE{$rnHl}rR*$P%I zee`H;%Dd&Vm*HHVPHJr~ea!8sUA6qFQJ0(Y1-FwG=gQJdYinyax68|_l~;sZneWs- zx_YS$1OWgH*FbDM01<#o4d4xUih25fi~bsn`AdKF5A+wlJm{Z(=zpvcI7)i|OMmn) zYlQMCZ2AB2Ll-LN-LDZ^DnC`}H~n*s@Xsy%|ENC_j(Ju0wI>LRqM5C&-U68o8GAJT z*BT+AQy-1}mmiu2Z2s38VSBPb<_8( zR3h*Pan~bXb9)n02}UX2!^daR!+=W0>|ll4W_CTAvz9WbjdH5p_XO>8Otb+%hfuT> zYZ`hTrMj0gkVHtgu#sZLa%^eI)mNIGU`Qy%^6Z(kj~3^}@1L8QPapdv@q!X9@ja>k zgp}&&cQDIww$`)e<-8oSvGHSnmja}^P^2<}^JFfSX~iTKm8fK+D#~3fc~Ult+?_F2 zih10nS@S;U%OyfdMOVQ4lu(Zgpui(vU)v9)-dY3H z_UNx1DYa5Rm9078iD{!|iR2b5K^-E_G3&iwhpISwKJ(xczc?S#M^_paiE;Llnl&Rk z`}=MVDvt*<_J$d^LNjb&R^axdn%Q8R4dmeIk=p}9B)ag9haO&TJP}27~pZ1o7yu~u|S8PLM z6C8<25qoh?6(cVce#)EO5q?E1+Me;R^k*)&O-C`kyU2a?(tQQd;GucZoAuHi(&qbf zArA-p6NiMlwagO{`*@``EHGRqEv z#~~{z*~B2V7bZ%!X=}jR9FKRW=becE2ks8@U&HQXBTk??a*QJxm5cU-;Cf7n>uN-T zfJHK)-e5af*^ygwMS0Uc_VC5MBCNT{M_d7Q_FaatEwueCJn=kkgx6&E0PL*WutZic zA}Dpf^<5JgAt?Gg{pH*S>Y_lMRq!Am0hy}%wyF8@L*n>Di==KHDzt}Fvh*KJMR|&> zQ^%;nqP0kJ=!Z4iWM<{()%tRs=SXOHjB(MQ@HCZMpZW+HpfrfvBd4EgL(hM8%^?Y_ zlG4m+pTDX*EnhL9MN}U)Wx}caQO#5@Z(m(IHQqH!|60Ug;JhWJCIFOkwgR}UIL*>kGrnGXEUbWE>g<`cXDh!U-eagtE^$nze4d);m4q_oy`%w%DfRU1nHCeO{kku?! zoF7C{?|&p?oOJpW(ws80`euS)txVS{O^z#>cg9W**p=1aq5A_2^r@C^wQuFGv_3q$Ra^4aoH1w*yn*U zc^wiQu7fc(TRIAzpL3nvV@PXMDp@to0sR=;B|QF?EUT-(kL@(jIh_#9st`Vk%I_<- zYF~^R^Qd*ZXO*0tB5rCsr1%O5cK25qvlIb$aaCJ62dg6mm2(Uf49NFJ3=C}Vat9+C zxMmJrV_0>P$XYxEu5|-Gbbjk4J7>FHjVqTer} zr!F@7ym3dKAW@b6s~GNDgI9-5Y+T3VXZcw0Q|yD+0LJYc!8azcq}7PbDonQIm6``u z33FUh5HR3mVjwtdYchye_-)h2oq@rC6N0DgDCJ+kip<();%Xi3hXRJFPVXtBTaSxE znS*B1CX`~QXKe!M)ymoE>VvbFr`E+0U_5&hqI}L&(=rJO(bAIQ_zz2&hFU$K(etM1 zl&6R~$KE5x!JqUMZ4qheff%cv*r_)i&s)5-hf9vRX>#9belYk<=C>^)nmervq8YS1 zTbw2e;bwY3JaBac!FhTQYT6^sx7+F;W)2!*EOCcP;up4(sF%!)$_9TJvzHt}R1Q}N zB`Vwr+3fR7oIH{9b)rGj2YDI?l$kL|TyE$iMi0 zhl*}+o?jF~%Imh|`RaH25t_wzFmsRG(-lJ$!wB~qiD(JMWdX-FpIyv5xhTRG70yeM zG2(%s%IJrg$K(9mN)|`_%p*gt`Gr#A(E+4s!j-S_ehrAA?OkWZ)dME{!3fe zmR`g$k?Gf6+2US!?oSiSn4Lsyq~WlOk;_@2`^9k9~q|IVA^eYvL*pTZ!!M3JofY;$a&Z0wX6TclXr zym#DUM%;2+-0EW7m#esMl=16g@f-T_Ti)?I8S#5<@du0XM_2L3lnJL|31|8V7v2e1 z83{LS3BMN;{#+#hs8E>VD4+of#|H(jUHfKfb&*&vD4Cy6~XiK9JRLVKx`XR6#mv9;U=bFF{ElNQR^(}J~yDy^C33MO!d&@QB{Ii_&m23Pph9!HC-Ze z>4zAJ!(GHv?^Q@9Cu&$00Xjn{S2)B6p8i79)Jc)j^EE`iJza?^-QR$W0htcA$guXw zFz1K&6tLg%Wvak4)5PyR)0w{FnR>4?b9Xb0*IZ+xAjRM;%aaE+0KhZ5tT-t=KtUF3 zVFoBMxVnP0{5lIz5Zz)xSpf$4w%xaMvg))|>0eL-XGnpJ$exejakQRffR7qmCv6v>myk z9@3fT29)!e`M;xB<(Kl+i2v20ssMNm5W_tAcaI1NOAzgUKO*?7#{P#RLP8s3`X2_P zX1GkE`d^dg|Lusdq=mT!OKI86js3@@`RCr?o~JoysQ(2Xz3P<P7moWQ!m8tt z{0`c-)o>5ws^B1AWc}-i@M{bZ6aVXo@L5*52XehYWn-s7#oEvISK8bK-4VSo3gjVZ z-ZWq;F7#b{GAFM;<(g}VjiPux8UMxU{^E~|H1>9Ln~+){$6Y3>yUV9rxm1i@*zX(f zI=-mU(`P+zmbcL?cny<1PqozX)EbajGnx@7YRubBK+w9>=GRb&dPxve-o4aZR*S3I zER5E3ghU5CBC>+S`z(mM*PW&nVsR3!t;O)olLDokQEmGE*zh&;*hd#)v+;!2mQ(%@ zSk}HLD*BS9Bj%R208vWva26G%@?l0QtW5SPZbRtCWQut>cqW$Ubp$fkE;_RrXlr9#B zIo1xmY0bv+$BBT1=CreERt?JIGqK~hlT|b?cChA3ACfgYw|?WGD3X4QC!{1ZM;(?U z^$UaesIy&a9a2Kn?8qx+*jwdl6--Nt#4@lCmZQXy3^Jz#Co1G2Qnbd9zE_8w{HFF2 zd`M=TPt(tMtH&G1xPDFvOmbDa;hpk;_@(L)d(Ocnyk_cLFHLbgPF%U))i;K-SCvbj zP69`pK5#V^u+vxRsP+w#KX@73gvBQrG%&7H^_)q{=}ZvCY8g4xLP=CEkibzfQWVc6 zJt-(p%BY0;Qj_i0FiJk-a5%|})O|c(cdUHJXZ{xR@nJ8!Rb-<)dnGInZ?rMxu!*a& zyeOR1P_Y3?ZspW~+$^4JG#vNY=l0d-TwhUnj5#eZMx9gzz2-XYjlbZLE_)oqPHkV< zj+GtTFh+S0%aa~jV#T=~LR7CAgLQsYEI9e(>AM)NrV;61=hBmnDwK}?2R}I~XBmHA z*((i4^Opb8{;*e7-55U%d(RVic+b2FKX1^k8>3!NuA4t4pc*WrtVhifqUo!H=zsT? zbsrpB(m%+_|*-3zD=*d|dN|D8_pu3h;B^?@Asd_5i%dKktOYL3TLjwe1MZQZPo z%PH;kmQdH)n09H@`s9sPu!T0_-bY3q#yKH-+dz~WG>DPsL-h$;%8G**yU86K}~ z>8F2rrtnBbyUPJOn5Kl1W_iwdhwbGipk!=L9!!hk)r}1yB+@tK2I$9paVT=D`j*Kq z-zRwF5KPo}{h_YQ;aR?pHr{+nNTa?bzMtDm<=nMgGuqy0etRi=%_#u%p1E|7h{eD2 z0H_V3kgMX>`gFG%Pku%f`BtLISZ>**#l{%8#YbV)`uSL^n*g1sS@YXw%A*T924 zN@NXc>=l&ql~Ha(JLH`?ig$mOQ(6h1=ewr%vrg;U4*x{)Y%k+?kDp4JEu`wh80olRoJweQ@t*8Ek4sF1 zS*SU*Nmr!Kvpahf$nDu~v0N-I4aAUsp%2p`YC#-RF$xEMsBdKky%B6)`GIqxMBs85 zdL~hMEKAS{|7`h5-iPe1FA#ZN?lK&Pt*qb5S-p|j@EZP=f8K1}_!7x4;@?PA()7LUnK$de591}nXkP1zMev?vT< zY&MhFhJA^+rJ7iiWOBDBs=2D8tT!uNPM+i-h^O0pniaPk$6=z!LBM7;zHR0C(8%!h z{=R5B?Ht*i`vD?f2$jNaFsttcQ|ko{iNq&DEKavUxDu?wT5hYRzn1Zb zBi)Sp&U%_dcZuq~rId>|%D&61!yiYIRcl}b(|*9X-fCCsBJ^;5+s?@R>}`4A$Hbng z--n91>Z`b?HJ&M%F*bjGm?=u(r8dd;`aBq(hdTnx*-8QRVM7~i)y>7dE z@!&cC{1@xvUkirW+IryNXa-)0I{D#fiR-G!=mk)Ed(&iiSK|hRmwB^lQh)a{ z^uB!XT@O-zj?ZrYz`5W}g(meSEL3QR3$M_hq}`20%wBt4W$GuY48n|?7kGQtg!5dcyk=`m-7Uzx@t zy?Tyc5$;g`poo|fiZD5S18ktSEkZ*19adi3OO1qDd-)D|dMr_p^q`!Y(t|*2VOUbn z%kB!pC#2u>dm(}RV9b&TLd{?~5q$=B{p=AtM%!R(J+*mUl72lOokfFWZ^&4YPj%lL zQI7`)!yedDbf*zfa{ZwpVm9XU5z_3DK!%{Y1!#$!?m-K69@%Ty1@+N4zim+nP7zz{ zv7f4COi)Bj=9Pa=Td?;<)bb+oHa(c1K`m+%FSm zBkYUN8nTcbv^2f2x!H;MGUy^KMW?|=cc}}}Sl27m#0%K)oV@ZOf>=Oo6DazSMc#?> ztx?q1{uJ!tT{a{Xm@N8@@$J*}6CyEz)AR-k5MISZzqZhuEBCFz1VOk%C%dKmooK8W zvAPf10}MeHta%CFXFIQ7@_-$`vPWN}GSE0!8-qL$70_~FN1Q_EV)E3tg${TYVG8XK z?u!IjZ1-EmWRXmhm2F>P;?##xG)DEzU@dByrBsKlDB7jCkt92{_BiG1myi3>`zW1* zuBkITqCAwK9ak|*C`+q$OB*nXjxAPHGaS;0%{j`9+$AQzHlc*4c~{su%ZGn&OcU0O zK4aienTc(5&!lCrxn@sh(9`*?n7m};rXwHrNGj{B!L7AdztSM_bw!-dQVOe{3#Jc= zqBlL|Ho(9RmN%14>Yfo#ZsOh+RFU~@Nzd+Xn9;>HRXsR$ zY?`XJAocTgPPI=4(-7x6*m5|Pl-Y+q)C1DBl*e$Ay*BEIr)1gk$%nN_(`7Utzd;;t zECb(Ar`tvxREP@P#B1u$17$(-#6)uq%r@YKBn(+aOjL~-um`?{eclGQpnRLiv?ZTh zBRP&=a4w2H|KG?&y4`ea;?x}t0;s$>8mxym>k|hmuA1@K;n$HonE5wt}VKzWDeY=i^ddVK^)2 zx=mz-^JB`OpPQ)Xpu~wxEA(QVZ)>_m8#?J)&t0mdiLo>zBZL0#B0>$%-T0==<}y%p zp3Z2!I2$V@XxTAjEY6}WIK@UEyYG#^Z|1AYK*_7T(48!fu~Z45aSb*MrkrSF=L;Rq z@W03n*?bw6hMu@iJsv9HY)uf!OaSawHd!;3ENA z&_r6ph@Zn8V>hi(1KWT4y~x&o$LhOdHTR3U`Lsq7_PU!pnm>2C*5SVlJ2TK{LtFD)%pOV#qA!*)yXS=)#~-1KrTOObDIB`KrYD+^b4|K zgO2j-j>^uC>XnY#Umf){osE*6%|@NAew}UEogJN>T`QgMes%WJboEPi4H$I|`E`wC zca3#+jjwb~{OX#b>7J47o-^v6_v>EF?q2TfUR~+_@~ivXA;qTlKYT>7yMQO(*au$grSIyu zwV)BSrOBG>)v?o~>3WYb{$4URmS6e3;dBUC%8-cRz3d|jRvK3a_TF;@dd z#Dj4A!O`gu_VU5@=>e^S!J6qoOMe<>MVzALFq<5z)^CL`XsIoJ4|&kGx{3{ZuI8%W z+w-c2z5iPR0J}E`sbV_)+fXwqJn(-d09wUiY5$S{WZheh3sQm~nJMp9G?i;+UB+{m zj5SwiqVEs5UXaeo`xh*GZy75C^HW1O^Z_VXC$p>Br!$JDx;}Z6N`<|SBbVOwdIqh_)M;iQD~JW2ZsQ1Ud@A({CdbT3X^MKnLzVE?BzTM zEHz<`IMHQ;*_^7DX=SM>4vt+kuzg|E$&|IcfE3y$O6&h4F-aCUN`{BP1b~DnOT^WGJmNX#SbY+yg#dIVs<1gph)qt;a6`XoZcO-7 znhEupQASSEX^fj((rK0vCPr{2R++qEjY(b2eywrq7FCVUSE9==b$5IQb&q8T(ZK53 zLZi)20r&@0I*`pNyJVegWId|2dExNsX6o<@=sEVmY{hhq9H|4Is4QZHS(}+F*m8-@pZ)dj zw)N7<@i#2(&~6=3wfAOoNcPrk6ZU-Fg)^j=BaZWWle>lRz_m-F-5}rRHuDtapde9e zp6$P4C{?BMZU7R&Fcm~Xu+i7}^%{^sdL;(N&a(JQk_vx$iL7P0Y zv`f=nb1b`nW{T z<+%*gff5BD0*|oi=R?dWKoU{kcz)WAu~!xJ^@iL&sgy#?KVC3L^MUl8FJ{ns zH-!C()Ht>ss3{l`9;LAX^5%KYJAi%UoIqGHrHq@ex!Dv>5>ZpC=ylWFl( zW=$jq02t?vx>-MM70J1`wj@7@T4tpkWM&~oiz2vaCUk_!)eTq-5cSOC^q=DA$sElK z#!Gm9**wgnoq0T&9ml-$|g`us!U(z+`D zb03ZZ^Xgd8^Ehde=&6EFg87i#!q7ZiS_a+nfLx15Aa{*m3o&K^loISQe!|yeyE`LV18j3>MIQTq5Et+0lROki@HxQL@%@ z7DoR9l6gbLZWhO1u0II#ZX1!CBN*dbYruY@M_$<#$&z5VhR=w9N+0YdP(|9uM!BY3 zU#KHsFuMLBj67wgQo79Rjl(lDZ7>&zP_`i0X-j5zOuti3t_&qt&Z}@zZr_S4fiIk3 z%PE2igw51r8f?%wD|KRzTbsr`&v-dT(u%1&kI`aYfPkfBrr&{G^m@KQYduK}!+@u; z6@*7q=mO3O9wq&wUAxCZf+$T?p+#FiX)RD|<#Go^?Fo=y^$uqz#&gO?@g?&Unpl_#&-KXE!^|R z3sgRFbYCkRLuR7HbUwCgx!+XjK-J?QOzSoWVDU1)cl@&cNkR z40xvc-M~jhjHo<WxOe>V~8m;1^@(i_x4ofs``URJe61 zUArXcCAmtc?O0f#%2DF2ehf4Zq|?j1HE#5Ne2cz2?rt!PW%Snfa!A;t@FOjkW18S% z;u5M*{n*7lX_{gkVLyhmGJGS$P^525JzP6qtzfi= zz?cgBP1GX+Rm_)E|+~8fmdW z``+(S;rM421nj#F%Y z_#k?$Zk50dgl!O9E5Wc7PMJCDwxGLUQnx%lmVil&;&NnmP#!Awc~%X!!|SgiIuLC> z*?rZrv>?)^lHsJpJ%nIM9bsc@eP=FzD*Y!`^t(j6ceh8eQWp3RUwC{i++dTvo-U*7Uq;;?8R4AGCp6q$PA^`cWapoVKJB?#FuUHJbi+G%V1Dxb z+1<^GnZ?JRom|{kla$A_{Vwn0>m>SrJg+mObK z$a{m3Ic2z|SolM!U~BJi`;2hMws5D#aF?raH_C{6Kk+O52v6?_?~DlFwg~^lh&NXe zL6ni&_TeEQJwCn2iWY2$KwzY|mi!$$Qgks=YE$4MBp?Z-)ANm1hLIti()fX=ZLXr8 z(J`|Tgwm2U+5nsW+s2!6d##6}2>2#T;$n3Efa(X+-FwsSKb z68?UBt&^YPd^2prUa|G*u<|*){_WVV45I?YIM#Eg&4{>y6qxnUzx|B36Q9=h-=7gj z!v(xicOFr>_U_-!Z>x`uk_K*0=_euJSN zt)ImFl5!}+kL#Mpc1DO_NdS~2BYYQScAJs>Xes&0buxk~MOr)s;+`bylcJcJqP$B? z(Vn7youWaNswJMPW00!rld7MYYS^A?yp(EsoqCTFvlLIWHb}GeNxOeKbZk#^T1s=d zPIIG5_YhBiWsvUalkT0F?%SU3zm)#wIz8xbgHV`3Mz~K#Waj;Ujf~i(jQIbL4MINQ zY2`8M@-*Fw-gp>}gm=1-G%<;%GM4FS{y1|qt4l_>i42lU2E2mwpzjvM>3OD@j@OuZ zxv8AT;wB^vCT#*Szm*^-QILyvi!P|c>|gqs4d(oUG{15vuzJdeSAd+2 zDaMtEOiTh!<3Rz2NA58*vgV?`kUZ(**TgCB=kWxXGPWDLfxR&@nC-8Do`uTIG+)sE)d=(BPB~VOY@U-MO z3#40wDF>u*Z_wPJrqAs+9tSaPYL>sdeBl1w($@lCi(if7lVmf03D>5V)oB%)!@E$J zRSOkmjE3b_CS?{TrQ>+?&fX(DOc;ML2=LpoO2L}LToIUn-;qKCrj0~;GvHMX&fuYhpNe4BURDWdtx)p^+%-qMn!#OTonn8r4|%rr_<6n z6m*#{+ycU=H}H$S6CDXo71O;a$2#S(&`Gf$vJzfnQ5drTymvD~_H7Y-Io;RWeMfs8dPZlSO^m3ETKkHIAcO&J6o@XYCX-PVJA! z#Yghq=BLP!k>`8&q2f>a>CRq9G@>6C+2tbw3#GhLYqHW-L^|#DC=HVH_4(3Qy$^c5*ga6$U7)G z!Fq_LX%zG7HK?`8{Qcmx5KY3Ep|fzCsd9U}z0>1i1-|#{SZDNk!g5^)v`c%sT^Kz| z-znOB72o%%FXXtot-P%FFRZ*#^))m&Fi`MybRwF<*)cZwOkI~mttf6ZHFG0+er`nk z^Fb(0-H@ODj=$uuSk^#y`n=6P=FfhZcm)8}JUOX;j@uc|Tw>s|K^Of^3)dlJdzbk9 z8uE;ThD)>QGE$KzfbVD~?||Z8OB0L$Uw|H_`@bET$l%Q}HvW$mGqIO@tD`?RNJEML z%VOrqRq{^`ykQdAe>AV3qpLz*bVSpsv{o-QwN6z2Z81wZdei-%rHRiU^mw_0b${KL zCffMMIPd~L)9A;*sNSQPE>jrWE2@}rHpgnl+h3}Ur{@UP)|dCC3H$Yrhx=b$-}*WI0hpdIO7HJ3Ac8=?7Y}_i z0%R3J{%&5A>e}BougM2>q|D@+<-%d%SH#Y=6^!dqyuy*|QbnM-bt%$%k=|&bdHe5i zCKZu%FT^eu6CXe67_dS?TGt_P=%4}`vBAA-oh0J26O<^=c)gK&N<2pwmIG^6l6h(o z_01oK5mXXosl3RnYMWP9ETfN(T2FVtfy&A^jtIse3`TZMgMr<NVg}XtIFdgp6=|C!RxSO*+9O6pwNzhTM3dX!!c{Y7#fU16Y z@4zSnkFIN20kN?;Us-trnWdjEi%r&%;)EZ_4{*m6lqVmpS0{WlE#GSvk~T`L0UH?R z<1B{1D5PWwHiRgxmvZLtid>f-btV!@COaO_$57NAELYXJeNjg{E8Vin{&)wZkblt! z+8(Nr4`Dqxeh*Q2lqd<+b2=HM{66P4L|Z3}?xK{NJ{fU+j!)ddT=pp4hiIeh^aC=J z;ODr|!tae-PexEN|r$1h>wJoc;SoSScL#;S{*m$-2YT+?t)m4T$>a+jl-QimWmzdkj zZ($TJS`kn+%d7R+P~37)x;Kk$ZV62hVjq&Rwmr6Tn9%4qkzVvU-_DRc9WDa-wKsd! zvtIavHGXNY51QY4eb{Pw_Rjt&v}EGfk6v8f-^T-Ger_itZ26}rH>ricmrI`pQf$r0 z7>lcn>($*}ta?3wec5@vdwaEE#rfviN;~1t&B5Cre|{Yg^WObFTX4O*z1pt3`}6xU z|9a>T6BT@m91(wOMY6zIFvxtI5J;dA%&a1f^#CN5v}6_Xp!(b3J^tLxxSp&=Q5sWN zpAWnkN^pS!0F*N7nVlHGXueMf`H_AvmI5hjZ|w_55bvmXQ0Ui0O!ysbv5w#PUhJ_job=<;d`po0Ehf0yGR)X+)a(6cwq8X5364lG7SXOiseI(FG|z z40cmauii-ggMr2mQB9U|EWkQAi3tpPkRs+dkFD8`#?P8brMG5jd9*8OP+OkT=5O=G zNr`FJ+XL48o0(TosQP12#w|PxV%`Ib78_&px%~ z%r;zADa$4LXU>jlnZ&~AglEUk+~e4?N83u1zRN%JuExurT#nvNzPb6C4BC>b@QORO@?QWlmV7Kde08m~~!luU2KaFgD-XabDvVS7p4dywI_H zUhDm_%Jgz<;oZ%7T@YclIj+iLKlMd@q*}El#fQZqiHinQT(vcu%F>wOMPtUtYFp6{ zOB22qO$CJay$Y4(nXHTEaIoc83kSu?*48`WM-vcj58i3yN%4WCEQ_gS;>|f7f;#wf^KuoVUof-GaiAI zb%6|A6z9KxZkEF1T}8S$;LLo9{5HpP@(JwiqsYp(xxjEIydGeuWmZ_Qz%cvS8F8sH z^{+!9cR(-zis|@oevZQ5K8gOHI(#pS!kD478>HTX+Y{kWU;L+36Yrk9*Vmh)>ME~h z32~gQ(xMZ4KGyO=io^7N2!!9nrkewX0y2G@%%O0lR>j2qZ`>0hQloq49S(mDfxxCV zW4h4>r9cwd#C7uzrQC7&j6|viJ9S|$9523brKp;9Y85##*i=2|)UvMMdj*q=-d;d$ z3y^z@@^0UMj`qKB7p8LiwbC|Yx=doY&7xi83&wnBU(A(1d@G{rw|}(H<81YHBA_ru z_wdis-7mI!?-Sh?4Hb*A#gpAjw4pQOX4mW0J=e~CFK?gw1fSG-dct+%Ryq%>2e6<{ zQ|#oPN{XhmR*@|8*`hRtRx6Ob1bFVOMZj2_!NK3@>~pXV(F)-fV8uQqPR#a~lZZaB z9)oq9FgC)7;lf)Z>v_r=8Hw0T1Z43sV=fZ)|aN&BZe z%>8QF7DemqYzahOhzhkWbu4LC>ke9-xb*qG2f3a+f{6W?v}Q`4)49|l%f6^Afkl%# z8>>{2?wJG&Bv^N}GJ3X3fFCzgmmgSNRd7U991re?Kyq`` zHJsf#W81J<#j?zYQie^egYgy;8T#>te;&_pq}dTAzIe9oXxz$bM zFwG9Cyxyyrn90Q1OQdf;BfV zkvi?NN4wKE8ytxY3)6XF!*$+pIc|)sQiX@wn|p6xWMy*}M>@Z78Iz>{5@VLLXr$$2 z=)YR)p!3V}wCj^T&>HJt;@VBPgPB;_e1S>bv8a*y@T~6Xn3Y=COgbXW&EmBp6~!-! z$lRPDHuZK1R1UC}n*$qH#?v9EScHK-m@)yz*`b7^WKYZj0&;=jF!{To!S_Vm8m4z* zT2L}{6D=P8BaOK!YluJ&b-+HnhjU#i?UW*2JWpxkkqT3k_dD^E`Acg}1Qp(@=t zS5)m0pa3JroB*L{YVfyJasphtpA}U>UlbWnjMe#`!eHJ*j{sKv$(S#h z)s>*g3Xcea9?VHsLk79P%@`xBYdTAum*l0ZV?zCfQy~Q;93A@SHHXUsex=tj9J%;B z)}Yy?QlG4n)$_V3AVX}B4Jxq}T8o*9ZOPp-u_G3)dC44SXoF;&<%_NkgL7`n>!QpF ztsie!MxX%hMpFsxYj?6q)%^*>UDd=W>JnuMYWkR@v#Os8$_(_p zksrJMLaM0V*YJqVgPN8speVIL!4AB3;02bjO@{DK8B4u%2e#OR5crIMD}=hU1Sqt) zG8xYLnq_%v9E*TR2TK8^6Hj2F;!p7i&jVP#ne-Q3ros30>Z7dc;@u%`BAU;O;!>XO z?XQH{Jt80$mX-~G2|%)QK@8f0yRu639(63~wuq)UX&72=g%ORK(|T5evR!t#_oI8| zK`7RISAKngTnzgfH834W0~M%EP19MDkg<=RMV{u3dL>2v2$y`+-=pZ|zl1tY02Qta zN!iTqnJ^Y(IF5V@xd@e^FF$FP#vHhN6)P=<-%lt=^F5U+(J*z+s;1Ol^O-faa)aR# zoAO(AC}0P{y6Qq15dIz#)NX65ovk7LiNB`;8*tH%tjW^~6v6sLjlWJ$`MP83`+&>l2LH?Pr6mj20e zdxCXjnB=`vA4OJ>yIfA=+*%6NRMc?1Yy34iOUl+XRYk{a)+1wTyFX{FQP!JbcvRQ} zgY;U6ezkEU;u*?;PQ=)`yhDO-FMFLwS>Ke`joJk=)|O%5bMig90dwcvRMar33L*Q` zs6su=lF5c5HGfj3TELd46}ELJZ}{Zc;MNLX9scAJxs^4!=fmXvTcQz;U7l8F7Lc($ z@{1%XfI*x^V~2vo%pCi2n`yc54ZdbTGb0AUwj}Q~Hg=n6aRei#=9@DL)>eQavAr?T zcSxB<;1dtY3&<-Pb{p~$HuXN&Q%&(}y^vI9=b1*bo{f;flAxocH+NdEy=OxxF+znF zSH9As5)D z`DTa5M?aF~y$d+;3F#e^S2Sf5Z7|zw_NX*Ul0i}FDDSA8#i+cisDeeoALP+!{pivW zx?f(=l{>`7ZPB&mjvfRVy7ZwtSRHrUp_s1{0^6S5v_)Vg zC)~D$&93QU_#kI3o?$D6{t`loB%@fop8xo^@WIik8QEP++3&8id#Q5z#d8J>a)x|zMly58+H=O2awe{G zrl@jf#B=8ia_4<=7c+C0+jCc!a=%>Xexu4;9}>^oFv#2T$%8e3|Eae?t=N(h! zpNi+78RTF1gx-?ZodUdsP-oe!Wcz?3Ke8W!OA7J#w}@Hz?zmJ5h(3Lw;lP>FjM zZXvmEA!Sw}bw?rXav}XqA&k0+QKE?1u!z;Sh&`)_qoasxxrpbch>yBhK%!X4uvo;m zSS+hpqNDiHa`BU!Vgxl>dKuCwj$U7i#tKFoGQY9`+efgID&J(gjT9>@^F7NF$D>Ss z8*vY2g=jjWXO>D}ETz+w|C+Rk0Nep;n7;q!X_EjW!-QtA|L;lLe;F6c|2a?kr*ZLr znE5`g z*ZL2}LC5+2ebV-IqWjm9*+Y=7^0a;n~+Z%y5+_wJ&|l%Z;OrWT1dcm}k*v|#q!{v$pd!?KGctwfkaD+#jAcqW_d!k6ZW#%N=7*;?psC($ zOf}G6CAGuNBaAt52zYNHsB3Y znA6dZTVtU?P^@yi!&X8TNI7W{_tcgWm7Ao!q!}J5gH%t}ek~$azMcoWCS|P`^W(d! z9|))uLol=zRn$vLwy|*ZZi}^k@ToR%3QUI4=J5e|Z3@Kf_g98t)1ce5lxff!sE0$g ztcg4d4_u~|;i`NZ_hS!IQb8#KR9E5uVedWPn&8(p?GO@5Xd!eE3@vmNM5-vA5PI)Q zC-fpxEulkbp;zg>NpChlkSfx<3P@KF5NV2e^E|8UwfC`R?b+|l?D;Z(0AI+FAKce{ z-sc5Mdz_}iW;rj+H|8#Oku1{Ytv@~pQ(bGuYVhE`t2#iB4-1Hmi`FN#n!qhX%wX)z z0v)-8?{nW!wnqzmUh7rq4mTE#mpn4lCGT65SdTCNdh5aOr~L)L=Q&P&kkGt9<}w&d zTy>r>C;#*ZdmFKi(B1jwOd|Hc6)R2Z-6gyGW3-=v$^LPh7A}hVYq1Lnr)vB2N?j&* zmDjN=(2+#F~v3Gq!gK4*N_<92~AOwFbTt%Q=ikYn8Ch4ZfA^A|!3`C0Dlov!sn_Xi!b| zC>a-D%EPBIgt9nF$r>$1NDU3?1RtdqQkL-4Vw@~n}+x@VP}mI zi^Zdi4g#DMFf?-a;wZD5viy3q#;6_Z_pCv!a`DWeQ775&+2ir$5)~TnTrIxm%#W5! zwhz7Y4E~V!^dKLq71IDj z%PU__o5;0}9s3HZ&x!qbs=@0(C?ET~a0WoQ74--D{rMR0$uJ`u3VXuI=mf0>8;agU zL%C6T$j0J-6wWCB)10Zf{9W#!YmfiZV{B5>-SmfWMyQqQKYNV#g>3(*zfDENd~N60 z7%?iN*W%)g-Hc3-(_H;pD7Hxu&cx;A!O6cw5(pv;o3ei*gcSO<_=rczntcEh2 zMTa51{M?Z|Pdij?8%7}_SCtdUD-N=+mrY)1l=c(ebd-E~*An`WCaeuuw zpTam(Swg8M)uX7be7$75IQiF&3c9&bhuMV%f{VljSv@S~{C3 z{-?tuVb$&a-V9`~am_EybJg*n&LFX$(-&@$qsRv0)cA^mH&4?xqIyLsnB z6z{MK6V*hoL)(kpA_w6Goyw|Lr^3OqQ=5&oo{)|qH)@dWF~NIVD*kK^h-#j_+;Agb?5_APAM)7GXNacZZuSk1k~ey8JsE9jb&rDTInJR zgFvccHTTPj;i})r7+a(VVqBId1sg3B&xhyUTHe@t(M-wiNkMdWh*0*l^9JU6i}|$_ zsn9&9FKa^SRT7K6Z9rAr?aWqn zKw_qsq{g+dm_cuU+)maz|KIkUeq#^%C4B{mwRRqpMxMGVi-(*K=ED)pg>~0z?}eMBMY8P$0`-ON2~Z{HG-P>$NC2q zDsPSZAa1Z<+1GJeI-Eh19I?D_m`Lq7PRwGCDvs_?vZHa;O4y{=3L`jNcF$+y86*3i zu0k`7M>bp}ZQ;_LLs~cslPCP3LeGr-dn+&Ky7wIlFC#P`S_GF%%VD>Nb;|Y;vS17WwR`oIopDVHZgp{DiN-e|YOPy>A|V&`FZX zwcJ%gVO$AYar2q%Miz+yMU=^oDvcP8kJ{VG1CW+=(>A&;0>OGBvt7J@F@RZK9|y^l zTGs{Q^t^IP$cFuZ;y2^n@7~0jbfD3X#Vz}D1mAx~dUF48U(* zd65hFmF^TQ@T(P;`_|tiF^+khgN4>P`4;Lk3)!J=mWZkPIw&?pUjrE=sbalS$!NzE zp=7*aU!4=CZGkEmoUm=$KBnN8@sIUnxSx7*5-D+mvjH1?L7iCp-?ZSlACk3oD^moBHI6NSF3x`wGS4Qo0=QbIlnWnEGMV~A*6UxPXNgj~-L z{c4}FhQJJ7hY&aRDy9@eo&CGmLkh8a_)0p}GiJ#p*7cfc)zK#_%AatrHx%bHa@4mR*6H=;0kF>sYyVlegytuhfm7%i_w z+p_$Hb}2`L^NLZ!J(vR4O{BUCXQ!M~e=eGDGHKiPrZJqYi+@o5OaHaRd$^wU#IV{P zalWA%ELAuXnSP(1#tz&;5P;}^9q@lr^NI0MR!>m=j$wxo+19IL9#WOi0^&w*_30N5 zeeSFHs~(q*-p+k`gph2EOvj59@G$%`Gm@WK0Tt)(#{=c0COKdtA(YDB0e-M%3e$mv}Y`R&);t}YZKt>XREANMR< zws*yL>H}K1QUJwFKuG zKBMlHObG@IEre6*A%hEyN=}tHiCMuij=sS#gFz2T%Y+zNhBvISLZL*@C(e|%PgZXN zO}D05_6VOa?t->&ckzvEvV{*{iR5}wR?!ZC`QQi(h|94bR~Re$&HR2Na85SyXZR4SfD|8xpJh@|GZPE76|PTxk(2p2I>Bhr_haFOx$3d#hx-zAo#uAwiCNKHhAISXOZkJw0ge^WxL$Gxz!M5)F2yFE6H@ip zh2(UBnvAx=H`3VZ#C#~c{j|J&s8=D>-Q=v{M3jdieEiHz(?$d+?q?gcJGxSA;TBR-9=ZwgSVwN&r&Rlrt z&nRQEX7CRKx{q(8{1mk@CQrmU!?B9a!TciJ25gqz5zIYiVHt|F$VNGnYxN_(wIIb;* z!R<3N;Rt%>ANOjW?!_AP;5e?YgWf`qw#g)Z7)h^XX4>KeMKr}vk}il=4=znL<6zPx}|F22WoeVCS9Kv>?GCQZbGpBZe z@CN2Iu;ez$ zR#^2g(w8gxWL}9Ql?xI95-N>HZe*o@SOZ|&96E~?^>Bp$0N9cRw(Psi&7CuV9<-$( z3!d$6M60`)8vT97uB>eSk7$YnYVTDHP@`o6!UAYe{Foc%v^f8e+M7!i28m}bBW{DT zs$z1=S+hJrtp-u_5j2vQz0M5rC|_ezo0eA?P`qodBwh z18PF^84y5jWXn8oQ%9uEo6{}A&PmAg?w)jEVbbUF8q=Usbm9JU|3|ABmV;ThZ!ga_ zYrehub@JugYXGV6K{trW{h)`8ulAsqQtD5FO!%;m-c*aen$fxT@a>g=uZIKhXe%2S zS7tozP%crE8-ZGjzV`cUJ=5zqA=i5LKO)Hf$h9a70i=J;wX_IjcZ6I^_8=7c-<4|( z_KOA|#@SGoFb^Q#ivL%0t?Q>ckZCGAY1VV;f{GC(N zWL~|>hBTG<`}@O3PjinE@^7;7IzEX!neCu$0Sa;L$6)#!ng%YFztXIK92wJTlvY{AdX;CNIwVb_>0kM2Tc82G7*aP?z7jVHpjT2 zsAe$x84BMtfS1CXV<(WZ3JnzJ&;X=jbG|H~D%l#TE%MV);Duk4-(HPKsm<63 zbsPMuc&&rukX|r8d++w-wIh#eq2`09J3 zq1V&c>F?#!9OP#8kCw!=q<4_7HqKQsZQT|Iwi*y&Z3TNb*CffTXnMf>vvlAKxcJxU zo+Aw<*Y_hI!lQh-$pO9BR4AuS3SlKdH{WNgeC5>Q`oVOA-7UwWNYfx$sm#SD^8PN1M%L zGwu@Lvf!2t*PyZx7f47)Nx{ul&nr~Z{*+x!J}2WkL!UY2O@F@MPre`2 z#> zRzv)i0wW1Eo$hghiD__#mcMOz?dD4ZxY7`5=4jE|r`7FBN54X&VKX5tLh}%C1zsx3 zs-u8!^{OMy*UXSVRgT+Crbl1sgNu&GUITyvxLq{I%hNY}+T-~E_xv?qG@aZet!^^C zQOLK-b~6hPUKu}hY_18xNI)G?B4b$jg``qSRsbz<_powuVIsgE0Cg9e#HL~$_!Ar+ zjy99;h?CbWbB@0J!r`0IDA`FKMr~a(%)S}c$^f%54Pv&!Y4;7?I_bZTQoY4ds5ULn z9(`-pw59|EmHP5o<}5o-@PvJ#{p~b4AMEM!J~yoC&sw{$gbHVNyuayjvN}?B4~^G#b=1f2 z?Xl17mM`|}d$?ZQzw<$U?$z0TY&F3ZdVFV2VvLx)%;H_^lhmA+a-^w2Ngwx0KNma9 zNZFs413`39&V!0F0QftTcA#ndIgvjMpQHfB-ol}0K52HS4;${U30lMEE$ z6t1Aj<3ljf{}uu|{=hsk6C{iD;dx`<#bakn=Bm44EeEy%z7;@|S~H*0z-;bq zflCfre`e*0@2 zIa0V0e%K#H*=_~uaW?03g}p^zvlE4NBPH9N^AS-6lJ~upoToN}_#9DgG5(op0B?RB zq_daL+nCfz6a6wP3NBv1t;f7(qVlTNkuhE|S$w9<8kPW1BNsMtD~h_(P*@zxH)EW5!{M)S%`TiQlG9@CaU+5^Y7pJcY?NpgcC|O=A)}S1fis(}%YsQ*{Gj&{;;M_P zv+x^af|KaANH1h7*9?Pp?Tpc#HZH|hF0)>AfiFrS-JUtXalIdP6>LoJEXs@wDm?L` zSuo;O4ah$=zZ&g$V2gD&aFh!(k_WrEt9!Bx+`lnnecRMfG0aB{-_Olt9+sBDhX?pe zcAy*7{NI;ZU7ay{$;*4I%tm74(Yh^Pgrc)+FedbFBw9{8=dvbtqRhU<-`Tv4p^6tTXM9z-Ads}tc3e^az{!D_{^H^swY*b zIs+%HY0p!NCB2{ZKbh=D!`_<9wBMI&qRm0Lb;m?eVJy}*Xlr455LZtnl zUYikGxakNaWglU56d)_;N;5HS^5_8N#Y^VzFzWxDA<+hFvNWO6riIXDMu!_*Ax?Z+ zWyV`Qq9KU8D?<*{C=%Ho*@f2-G0vFWwOM3TfpoN;AA8 zDUikEO}oXV6@_{p867-}#zz&cn>@VPZ&v76Pzgdo>?{Hi-W+9cj&ve6k9W0hX>DBimfV zd}S;%UK~gEkVS_(c4o}|=tyU;5+~88vlcz^cJ|e|zw^^^kT`M0#>|M(8f-)k$`f}Wn zw8%nwML=9iCkcm!`d*O*%f=jx84+$9VOG0#nbEY6S*T=_HAxYwp+)DNiZ)fz!*U1R zwFutYUSzdOos^yBJl2xNwr-;uy0&Xfr?1qiEL!pKTA<$2po4&Cs1g zG!=fB)`)AWi`9{6>K2yPGxsz+Jk%1RZ79-rZoSD!MD%a_GCx2TfE}p+uZBD>r4Yuy z7c~5*L!NG2?&H66*?*cf}{thp27!v&rUZDF?@kc=eqjOcK zn>WY$NEXG^aH%T8v(SPYaU37gkpn>%iwWkcgfpQR7Ov-PpUn#$Nt^F}`FPnn%O7U3 zd-=0Hr~UA=`I8^tH=bqilUAeqIrfw29oOfZDDt9KWh?ba@PL^+r;g1B8slfGwz(g1f zeI1UA2nH0e`JAF9>kuag^bjjiQfU$|CN`9;;!WMV5>b)}<59p}qdwcl#FR>V+X^|j z?`-BucNvzZffuIA6&y-;FeJ4&&i-5suq#plMh5C;{z1uFmd?Y)=~RdV=BR>@8RuI8 zJZhYZFqGPERnQ0CmRNc_JE&58DRNR#0Es>F1Xh!sYXjwJMXXgx#VM%(0<1{jKs5ZyS!$< z>ucMW{pSaeG{+am|8dBx9q&}X6!_baH%0II2I}Uh*+*~x<3NeTw6;-$#p|n&HTx4` zU#)s0m4iY4irS-L;gD+d$aOD2=S;D=uLeb&OSLzK2VdrNcE>`g~I)+O~(>W#p)Z8GJ{or9Ir9_YFN=oFqwjcf{Y{XL?OOWkeR+bVqSv z_{IG9Xl-IL;B5r`9W^CCG{(XG)XL6~It`u?xY;>Q&x1XCpF|y~;SlP8^qGG`biuz; z%>K&ksULtc;^Wi%yDmFr7TEc+Oq;d^xIZ~RbO}MVxHf#v+V$dnVbbqSh0+QtywRt! z7Q0SWq1zZw~6WNmYOfc_E&_ zx)f7B_ivK!pAhwxtd)hpg<=obp~Y7~eMj33TgA_?JWL0v)I3U{j#+lUJK2BpU}V7Y z>sDWw|9s(t>YK9eLTzI4S$0?!VbR!q>2Vzg;0?;}lf@cKI<0QAZem4G%er35oiRh7xh5<>)%q;({l#pQhVYodsGDv~HH(zvED7I1i$bX$9$lnhC>(Fq z?6QS)6{@sYYO9Fwb^fvJ;lC;FN8Bpe)bV=x#?$%XlnU$B!k-UniX}{6_z2AgIcegE ze^8YX>+@5wJb9)DahfgQi+WmAboy$pZZFVGq(9!&xpL-S3g@|FH%st7qsRS|Af(UZ zuRni0sJrCL0_Nuj!)m5}((E^vGfj5ZwOn>Z-pbdIJ~?QPbc)uakXW03`{iAi!X$-` zp8qpJcDG#>`B|RAhliRr=7H<*hR!-ubK*}Yk0oyRo+ZHF2PI5IfJ$ox$Tap13&|Fg z*e^T;RSe(g%v7gWlg|hQEZM%Bspowe)~5lHWG$k8uT<^d@b2+RaN1*hV1MPS2~vrS zRci09=+-V;l}NdGJM-VluP-C36iHA(mKcdb>Yj4x6#Ka}yD9FQGnzrnX{q#c%o$q7 z$q%%en8ze1RDsEr3;^X(#nNeoo5?Zs5z25jQVj+{3o4{_Fx|{J2rk@4kR(VLx(}Mj zKt0^;XLhpjYnc$G#7Lu@;*|ojFxB_cHuoZ`6BSEU8cYeoqG=h&Jf58)3;#&vXouBk z9SsP7|F*m(4yQ24C=gmm0WgTsyB-=_+xG&S@{&$f(a3h>nF^^Hwd=}qo&(%_qvlrb zL_G1J+L+I*r`l!cr2Uw213*xZafVWpoT;_?UQ3nsFTpgBZx)_8IoZttz?%)uz0r_v zu4nZbTcPw6reWazRrQfL`!(ahED2Tz9q-+Yhz4bjFz@}~nk-fRE7xgA2kqf}*4u`@ zH$>wfjMyE&nUQB}*Y%g@(czWlje)3C8lp&}iYz0Ejl|-N9XRP*m?bTQ+kt!rRRb7V`t29TJWds-plwbJT= znj~+G*6le~g#L^+)x{@k#W{-bS|v(+gDP{%F2=m_fk2OzK?y+Ps)*=rT3aP4V{;(S zyaUcwpNmW&EdmN{<%}Yis8JZdm@li0s$l;~x+@qm+=qWu$#E7U1Z_#py^b17tM%Dd zT#guGd*$U)0v!}qD~i0fz)c6Tb$1KzRd|MgB)!v6!UXn1Nk*@OLZ`8K2XA)QCMWVTO^)^| z)<1X@X~kG70CknMq5g46-W}mDI*fC^)3lr!!4sNo8~QH4O>gV&=k-FY{F%1h2K%q- zlE}1~ULrS}NIz1$Rm#)STkGbV+2YFB{f|Db-5PE-TW=kVvPR3?zx%4pex5vSx%?pYxDsf z+kI#vg^c@%61S$U%1;|&%y4&I5#m&8G2V}!c2_X+1540gKFmAMRIQuE-x8(U5TZV@ zPpTLOr$@IKAL8_GxTPK#YWWg@j-qN*3_0;!#luXkzCmA>h<*~&d zRBA?XG|e@R2#BTM6@We|#ICt7w)HPK;5?p*-(y|3REp8;yy>b);i3ar411L#5aH{C z2z8THE-p@_iBL!<+-{`gfa83vd8=9ODst5B#6~RXvA)(5&NYGxn>>n8_;8`3c61W0 zko0&CYq7@Uwbvgm|I!hA;pffZX>f6><;A45$|-(K#}#2nOmvx}pnKsK`j`%om8^*3 z$5pfLr38b2ZF+GJ4`ZZMGg}!NEr(6ouh)WW#BsYakR1WVpBMC?Ps+zTcx!a_p{o@Z=*7PJ`+ZDo$LOOB-~@*nV_$PbL`V2-CDitj};erSbO zq;snp#)qvsk21%(PFZ1}g0`=mXPh&(0jFKwCE?OCTQ^}E%w{{k;N45!J56T%q3N>Gl0E90M< z+qgTafJc86-IS|0Pc8=%DnXywSgXmi8r#e@5H{|{mA)$zr52y+|8TbSR0b|Bei%7* zU9Q8tKVjDjtTd>K0q2SkE=fjsyouDub~~CjGGe~#yd3TPKJeOyLhwYZOQI(?J5^=y z>&Xgws)4;m1@*J;Zf>#t7sNw@`>vk?11P@5u}a`Tyfym6X<_zd z?#W6|FNU^P3e@l{(k$LUfl|=CD<8&4$e^?%&BakufsMD2^V2KlS9iv~@n5Q?0%ORh zAtA(<-~U{vCkd4W^1(5`jVn`KL$jrDB7ck*VJE-rMnvk!x~-#%boy(X zbLV`^k5$`BN;(6jA$uKb)X@$t4+<4topD3M<$496-V)mFpNiu$Dy-ry<0m1Hj$gX0 zA%JOke%^H8abna2NsMaDV03aeuyZflX$-yRe&rC~i?&Ar* z=HC2?ELG;>o6wvTdgdY(J-Ir#;`q$oxCc(?n~&W1W9HS0h*bmHSGhrh;8p)MP!*;0 z4%r7giacK5d9f!>oYnN6`5}yo7zgn6*-Gk#7?)X~%)DCgV`9-Z;0e~kWUoxMtr?eg z69ihraICMs_Ru2N_ec@bWxYFab1s9Cl$Sa}`8E0yE+98>ZE@@0`tXch|^$P>DBgk z6oEQI6JChFjp)W#kaJ76i=nHi}fE#l~zG>+$6}n3sRby`~BpLepDY)B| zdT4xwY^_(focCJjI%Ix%wU8>`zzu2n-oL|6#oD8nf!PoIdCmTY+K0G+SI71PExsIe z!cpP7onSGFN$eLZbr+@~h`{fDS&@D>&Zf`yk_ksWV;WRs)8`0M=S_Sfx=4dlofFD( z9UZ6f*7?3KD&e-SVUrpInH2rv>a7HW-1vC}5fZ5Y=#>`pu6Kh2>B+zp1|$hQ(R9`K zKUb?%jp!%WM}MGrr^&}k5AYG?B_q41h?*eDzmO;mP+nKy;^7l$;k5S>=f@csh`8V0 z&r#6l*N$x(=$=31fedmhqIzNtI-(yr%T6(N6tb6#Xh5vI!FeWgIu(l7yvau255R8D zJatzILXS{Fb=06Y&Rex|SCq1K{F-_tzj~)!r(>x-n-MRqso|rf^+eyGPc6D?Ak{Mbf8XOZoX?H^i(cwiJ)#gw)!oitMf?30i-> zdc(fFH>yT+c`&t^zH{g1OMAL<7M>^wwm#9UhXm;pqugrK&#cmjeNemh{EJP$perrc zlY=;GG9m`18uR2BuFRtQ3C_28S$U5R;!t1AYlK&ou@>VMvC9mRf+mV_LF0Dpq~+ky zFSd0Q+KYTF9&(o81*PXjS*O>3xCXYl#G^&EangIb2$IcCZj)1Ecs zQ9JhL2JsB?ct?{nE|Z&_O%4{Q)flij&+tvFrYizC?Qs+y@RX}EPyg44{V^r@wXyqg zr(f5I+m-0<=r3o=U~sN?ylL^5(BcbdxLOn^tT-1R>EW3L+2MUWHLa_^M^!M|G@0ytfn zp4r_Z_1R9mgDCCtm>sRHN1ArE&~iK&oVwBUhOwKw@Kfn)cN z7IIY5JWIw;UYA)WdDXmF5xEmEZOyT(9T&C<+Y4@O-=}|LZ3%FPUd)#~cQa`qRB3F1 z@8rKa>GfJ%EgA&U=jV8JNvZnF-J}qR`Mm_vzugW(9NgNb{hk@}>ic&nn0}G{xx8$? zz%xc@D3mLd`rJ}4_ky(G)lYBR_Q2KWF~R#q`^Q1GTy)sXv%~@4;PO$D^1&tG0ESWM zv@$y3#Cyiyw8vVA@FhFiJ{E0ye`($zJta)?7*CIU-IBrhT0pVZaQIbgd00aQgK1tC zs2ColuXm5Km`oXQQj7gv!^KdIqpku#Y!xtBP?9Vhn7ktp`$lGKfZlWCI@!cEiEw?O zo=Xj!q$C<_+dy3qg@MPA7Xcte@G#Oqj2RB>EoB>Uiji-$2ZcM7gF?QZs@q?O*a04r z$BL<}s(|aF=!cM00O~*&xJtc4tjnAZFz<$#MlYu> z!g?45;*^1e8Uh=v&9lIl1CfyVXwu4XbHKwAQm|IKt^8bAQ4HNOw~Ca?)kR|6(I^mY zA-P3E=rmJYwpkQ>F!X6<*df@$b~a9x=!)B{sBfTX04DeSXW<1v0bq%Wz@4nf-_kKZnPauf+;2PKcRQ@>=h2gx0*L^to{@}?_=nzxtY#w8-XCaGoU)8E>~12F*h zNov2Wh+CPeTs;tAccv2yZR`!FWe{i?rd+Qi^#+#ZkgN}|p@1ksqQlWRT9`Wq8gQHm zOMbjU3_zT#JPm`>Ov~i3@J`H7N2tNbFxd!ODPovlo{VVnTiKmZ9?YSn7`==oKt858 z=Qs^IlgzN(D1%rK^l9Vx)}vi@$Q3_DZRu@BzLD%Wl&i&QQr`l0z$LVs@YWh4xECaF zL;wectU5e2`$KZpqy~e6s+b4hiOmMm*WY@o#i%x!sqTO+S}ASooIzJj=6WCZ@>?kv zuIy=B3Ns$B2(cT{XUJ4>fmNrPhv+H?g)8`7I8eM#*L0@O z7!ewf7;X{S?4o-;0t%!qzmAG;`97861rPg4F_st0ui~h)9kyWBS5f>#vbMaz4*bK+ zEbEDv#oYCo9!kzM9(siwF6PAgMGGYlq^s%FyP)Q%oI4jZUvH#LMX~QD=iUw|yVY1m zRV3wFEkDu9-As=*L2(Q?mWwx*kSCX_eCJ$bDTS(4pc{*B4I`+?o%MkQ;(|GkSs5|1 zP=7q@t=}wMpC$`E79d<$`dAbbS`hj*RP-iU!CRKXpjF;DS1<1rAvRaLdtjbIpDG(7 z53(M#BV1ykh~||4~Cht zS)U#6hILvHT5BS<(w_b5O5Iv~24HId$~Ay28%RPL$Z{JX&l@P08mNCZK-n5$a*gzs zjf^3U%(;!M&l|5SHFErHgtIkq$u;p4bk&lWwlRs*?KBg;c z=!UH$Ozyv4bYt079`b*t=mtV4y2))|`dsmkG^Uv{^ut1N%|GtFT)KvVr&67WS|M8i><{zxWgZ0-rAa0`% z1c#jQ6JS_WtFzE%cfno4ZSR*O*YP6Y;)DZXJpPb!3X-hr->Luf+W(zwL`^%~qC1Ap zl$T+m&aw#v7RuKO+OrJRqeD~*dpAe$6!4PGk9Ho9ys(dh{SvS!49ks8f*`N5IdS7f=;FYyu1AZABS%-OcOHY^rH*D_DFImtm)<;JdAio zYDx<@p2qHZv4?>A;2(61Uwf@MqZ9gRul-Y)9B*Nkz2G zwH^m(CsQ#I>ShVF%NA;#9KLokuZ%MUZt_QBzmfA~KYiU{PmwFL&ky#vN8MLcY#+?) zq%ut8SW)mAlg_UMt>@`U)roviA!3lCwBb(MHi30jVc>C2SXy;nLpMm`s~Oe#KHQ+s zrE-Z$rLT+M-cd+Z;;W`txFX2PqN{YXN}-Ti5RfZ2gMdQwhg|3UIM2Cfn<#B_rx<~< zKXL(nVX_fu+N7dsaK@^G=T?Q!Kk1ft zajm?oTa>(#1SaxfOa0}s-DrfO1XXa;#s-m5%sycZ2Iha z?KV+i2fz-cKV4l)sWrar_WU?!!e@x30dOIL`lPfh8{vy0F}-rpTW57y+gFjlNS&^9 zmAdUkuLkYcFW`6e{u|Oka!)~J(sJXQ?{!4={J`fa*+TvIL-V|U4%bXMg*3bCrPcat z(3|5FU8Z7zPo?y-P@0N9otKj%a=Iw1+p5*06f0P{`UV#_ISWdOImPP8+k3AR;Y&KD zdR^tx(XJ}Vsg)@Wkva?x6n%$Rw$_brPszLKmrl-Hcu!V{&#y6#-UpL;73CD&ilppa z=wo&W%a&~&f|rbF{ODsyt4aG}ZrP=6xDBd3by$zyjf-8wZ}LWRJ@R_^b!Up?p07-3 zUlLrEDC;RI18US*qa>SZqYE)>loN}yH4PHRAG9v+VN6ED2_9(O+O5@n2EzZ?X%(Dwd;iq3ND&?!)>hw1!l-VnaREP z2a{)cO?}0GbQaSC70Q314*UFfbOD)hJozhzEx(T)qWoO5N19HvRT#;_d`3TbbC3fh z8J$wlMR(7lvQsl9NE&ulk!jGaoAq%m6H<01SmyNQXgMcYMF;U@JVuA4w(~pZvLj|mpxr6 zgfBP{gpr{FsidkDKNjwy>+tCf0-jZ=;7p6cU+BWsBb_G9I)`@xM|i^GSy8XEWal4D zU``5Q8tU940^>uG3_l%xHHX?EZKY38ksy>`_5mkMY0kS)z zRc}+Wdc@6i+SJa%u^20Sy|ol105S0Qc}Dds7OwRUn@Ubr`e^1Ww=J13qL_N!dfyjY zr}9(WvehoV(zwjEonR@UY`I?feDPi`L;WQ_Ft&(A%nZou^lp|uu8CJobKTG_F$ zMt-UOA*{*DX~^q_i?ypJS|y|EQHDb(_wc*f8R}~yJmg{1%gytpJuXC2yt*48maL)j zQ3Ek0GO~RCRI(EFSWdfu1bT$ zKIxdVr=aC%%^SWGx|PNsAvG#WzT$(~^sq%l#qrRS53BO-V&KbS$@D76J=Jw1J0iD$ z7iPCIQoc?JmL>SY`NBVYqf6Kp^>KI~HIpG-+)b+(o0+TSZ*G{JT3Hik6yKaOuXY6E z7E+{B=r^+Mp26GM?b!z;J36U8GxC)O5&o7^MjU%6rLrL+Z;T0v8H-b_iHA{wQG`Lb z+AzV@SS~VTqk3MRe-k3GojGp$>ZT#-(R3V=$UOYQwc@Mo^7P)3Lz4_kYZ_IXQ-PLG zX^~x#ifX}SGGrPNnsAHOp(;Ep@%_s0whm%rM@C(neitgg+7k$Davq5~5G7lwSF;T^ zj>Bp=aYo*b-b+IlbDdCibdx^*bZ?Y(q~?QHhVjyu=*no-f}-YxO^1qHTXzJt@tRW1 z4JJ0)Qiln17xSOm$%$g++2r`_={qe9Y3qw~8#ix>nY6E5_sg{$&va~5y`qvUwiIPp zO`Du&Vf-<8YTJCHiaggs(d0++GB@JdM`e)Crwofr5s~+sjJ2cpgabajrWG6WH(}5b z=o43{s~qUp6^IOa6kRm?;$voJqUMhLOCG*xvJvvJ)68$<999jTE9SL!N(H$GP@i?H zUSmf34^D0OGGIb6kN4Di^(RS^M->}Nlb>^!eJd;wi+N1cGvms-n)~)h*;BYe@iP1c z`50M0tx3|MofXjYliv9JsNQ?7>o>m5G;MJ=#fsy?f~c4V2d^{-yr#I-DK5p%q+tJj z`{VM#Y;;Vj2`_Jxu&<3qr79lPZrLPXCvyS;zN_GCnp%C*_n|mHxVt9t#|1^%$_YBW zjv;^c+3Az?dnpgeleuNN1P6PWqs5(=u3q*8Pgc^TE>)xE55zoe8@^T$v2&i%sJ78Cc9ia zvPW}^)Hlo4;^f8kxyd3Fst;)>z_O&PA)0}-NbWm++|bt;!Okh_-+DBVFaWt84G|X+ zQ6ZN_B^zYr`o7{LDSXBKnSe*Jr#uF9-VA(nt%d%4{SXSYhc{7A`{n{d*oYj+Wk;8t!DKk#D$rT!5V!l=UQdZv4dkRXy{7~%xDXd{{J7xZp`xggUGD7N4RR|E;qm>Apv`N{~F{10r?txzLCYS+Mwt2>Min ziyd^T5q^S^qzD7Gj#Ja5fU+av%maFa8}v2`Z5%^Tqdo^)4QQ1hAj z!{AhC=-F|s$C)eSMg$Krpu>l@LM4N~CzMtL>f)l-)TmI9EKA$%RM3<5otZV%Bq?&v z?v1{e^QwaCwrf$kt6!6A!=`KPiR%KrENkpdGFvR;nMq6#?a2XdT^bsB!dgYgsudl1 z>y*_z#+*Vbua{gv?*F6iJ;R!c+dbU`k`NNa1VS%{-g|GF(7W{BdlTtR#Lzp2-UR6# zq<5rul&*k)fQS?eDuRfbVZXEY%zO6CnLTH&bIqCaEnjo3b*;6Y=l}cNw~^))DZe2{ z@Z2TeAVz@F2^k<=NNKOQKN1g4N8;)gHqGxt)~ zVS&3Lh#jetTlpoUm$7BLMgTBUB})(fwfM{WJweU9CO`IRBHn6s#3!zDauM*81#OMj zKFnd2U)AY9QfEsCBg+;sONR(@3wE%BZMHguzxOeNqO~49#YiL{6&IIpX80YVh@%hX z&|k^5;u-7~h)cf=Ie+0&shaRyE9-!J&oU7G-^`l{>s6>-bILjd;;_`0%Q~MYgt>+1 z2RN+I<579=qw))n1^eQUUrou$LvympFtblfRb8{)U}>Tm^-lFsnEDE(;<@mm}8EWFtuB-jE0HV1&s zcN+B&;O>Hu%r-g$G^y<#TV-@rVJ9hex5+$4nfz;o+Zo4eH$-cG9qlgr%lFD&QR3yq z8KfqNHHVT8i~8LHaDH?14R})*FNGbiLNc@}oidoxH*!&=hJim@pchxTNrm@1K+x)#4DZs$498UqHvwMSx=PNf_DVCCm z_BddAC<>-Sc3B8_zJXF85swUj@!SY0vHJDIhRB-?0Gw3xFRbSKews)&l>TRUwH z7`!CKHtDaQCjF%)u;*8UrNTo1`5^&@rXE@3ltcg7ZkMr0w;qg!r5yq`?E)q9tU1!#$(yd%Ok=jpnA-tQo*MN#T<;W<1j`$1OFG>TvhsbIPofv3KzC!mHt(WKwe+_}~o#&CeDk zZDiX6bD#FXo;QP|gg2uubE82Fkn0WZ`=nm)2I^;Pc}V?X4SxDS#*Se5p~6Cl0poKc zD|)Yw6Oo$;oBo;HZyfghQ!<-VMA{Q>{L>!tRLq4j*}su~o3k5zV-_W(!~K1^e6aqj zfw0ZKg5)0ap-DZ=h-b^QKC;+JG33lwH=%Eozb(52XQvbzdWiWu%n*t~6{!qg%3Z%a?zXMx%$G-r)x4_D@0Jm%kEUjYrMA2C= zOvbRh^=9rafnhm3g%q~6RFVULq5;gG=K0`FY!4U0TgnLU4-gqP{zGv&vZ9Ym|J&UB=l3G=bncEUU60i( z_Tgo-Ka00g0gVeN3xy_`0meqH*Ibbxi^$cE1-}68wJedT0IoG@Y!hkoYpQoQBR{Qq zVJT~$P%@4bVI$@Eyw*R)FjFeR#z7leZbIrq^ln${RRh>I!(QJ3p6sm+-<)tS^*6QL z(k9Vw?&b&$LCwNq9AhP2uYU-G{}KFd$}anN zOwPN;CI3=u`8Ou#tRK*Bd#*=J83ak!^LpQNHeFNo%=;)o_L^PbYdTu2!{DRN6YhDk zeIxJ7F^KNbS7zOQ9-o4gWIkI#!M{j{dI9ZdM`c=Hkb;Uprk z41C>TIqC457dn@oDvc&;r_7G7U}w=+Cy5N&O*$=gD^nQs;(jLpDO$z*5Un`s`SG8- z?fR2!?CA!rldf2+SZcH2DQ-(%ZsUkpXdU<}dZKSBN>dwEV6}NmF%+b@e8jbT?UhA7 zX=G2LfKkShCJ!QeaRCL>E{OqgQnxb~JgJMg0rQfqShq$GuIKE->h zR$ZqCcCNW^K7Q{JCLUj*G4qwidkGM~OoPN%WA><2hwp3!d#cC;ud6x4IE& z`Hjq>f$BIZ^jzun-x)6aKH@Z5dOzVSwVzUqwhvlt_BEJ5NBKM|>x=HY*-{;LCo!Ie z87grLyJ6iJ1YuFvXA=9mXwQWU7^0VG_eA}LRTo_#o)T9j?i@Pj@yk2)^~M(Bi?TMUmv9>8&x2158oH52 zn&{6sUA43yB2iFpwS*LBeoOP0Va3aAVxyZ4b}oeJ2chYOyJR0YiD#z6=s}Mfv|PM1 z@CuJV9yyvTZ^3gz)k((;bK;GhxNiKyf)D3!(=Fy8+AdXvBJY|4-m_DHlg5Pn&MK+x ztI7CGdz-P8IZaty+DsX9PucNef;v#!tfAN+MH!E78@cdy(N?`-@`Hi4sI&&Ahl?C4 zo#yf#)LNmVO`3rPbe|jq8)X%w>5Pj&>4tn5y7Xk77mYOSI~Ntav9)zsaZUnU^duvk zanO5l6if(6E{$~Q7OLF%#mU(cDU#D<%;wJ6ruutXIU%OjLO*4P8&tEs1H8(f@ECff zg04GJzm0*y?DQTtu8ie0Fu?cG_uOUV1}q7h%8F&#`m4U5>2 z-me9Y{&Ji{e^)~z|2#c1<5NF^Ep&%B&>!*oJq}%eNBzcl%G)vLnPggf>j?iX&4FsI zkDT`mydF*+GOM>OW#njA!7TzEL%7yv^m{++B;6YywTkWjG1RY6%PH1p_Z@Ogh)edd zE0>dgR<_b%$!LMfz_*cb-IFMmn8FEV2z|5BYJUIclMfyLOKv9?7&0LW;6xTn{=kgu z>-)J%-l&Cm%xe{-ZWPL3cH=Kh07jn>MV&Rb&yT?Z^n6-V)LM&ExAWMXl&PbHTm*Vx zFIwSgEm9ICv7)Xll;#L1bt{gPXZ9yy29ka1@9wfS?3_1kfgj1}z=K5^=-@#7LIhbnQ8;E!}%72)alp+d@ga~kHkUcYn# z*YFKa3a*j!4hVJ5F+8dMT<@zc>gWs+jpK*T>+G2yZyAsC=vu2-z?=lzs9gkLz!*ic z!ib>u(icY@mOZcWC{gd2xqFVG4D%0P1~w|O!2IGBsSY|j8r}c!dVN7jF{~K(^Q|3= z2{9}aEw>XbGNpef~XP14Er+<0h=3&~;p2~sG+$p^~?-@HM z-Z41>$t+&IJnxz!Fx`8!EDNV1jD%=TSTGs3g0^8?1t{(TFAF7x4aC##v0H+t!e&;0 z1QVIT=CF)ZPsSzpiL)uS;v_dIg`Foseh*@Ar?=U-jm<6X+_Ha}%kg0IpzG!3%fQ>d zmRIseMl|J_jI$KwG;$NJCSlcTcv_er?~foqhCm{LJ!aE@b%OPjfk| zug%Y-H#ELXuQs?!bUr5XZZ9F-ertu2rirEJyd9o+lW=%+9+EugHY$xcH+$GqR(2ze zwYFq|fzR48M3nZp>p|EZV1~<GaD4A#vQGPkCIQ|q+H-pLOL3Rgt}4#3lL!OH5WICBhTv?2o+Er0k)@& z)1-Fx7K16OyXjNMVLrslQ#1QHpoT;!sJUX96k!J4F|yK+yv;ZxCMg-9aSq&Ze;3f@ z!tq{f@g^NyGRrJC2;U5ox&_Q~DdQ;tusw9Auv7Y!Ii1tZ##8iPq?ch=q7WE#tsMe< z=MGm-f;bB`?%WCYyVr0?xgdctu!Dz*C!2s}hp-T%vScS?F#`;&0u3%)fPpSLk;(j0X+rO{4yVjNbf!N1z#D2|gzGD6`&n6Z9&y+NYJ=+`LzJJjFYs&6xHCFdssG^@o z!-IP{x>3=eWiu$I#!Ei#E|d%Php$sl2Eix+G9rFTS>>h)U$bfM70W zh1bxq!%_f|4Z8{jMS$zmIPTV0GfDidA;?JTDsD%QeE~HX&-KYPECE8rmHwDSm1W3R zj5>6KbNn)4U*#UzemUSS{SkxLNMbH1U01WVAke}_92`ul7qY29U~jj|b=!cvjW%lv zUJ7!b$fpfb-iWf+<8@3mc8y-{Q>RWK_i{5tVfIsZCMkM5iEIS) zIs7{lZ53c`gn>6|D#KGqm&u|J&qo={4HzV5>Jr4B=t`Gi7q{z$b&Aak*|Bo41xBS; zI{Yn)JDS1`6!gLJdUnrfJwTBWK;4+}M#J`Xj;IHO2kGV^L2CU&`S71YGG%ua`bXw&kuqL9n5rKD? zX+mFR-7V^R%`(XF^MF5;Pj7<&JCjuESBUtibmyv3D!A5P5S3ey;c)hWh$Fsx%;F{k zKyiM{OK>&UebfJRl=UzWYwgGo+1(^Hha$2~yB{_BMh`Z|{OV<4|6^ zdDI(`-Bj=hKOw^Dbn?aWj)36S){T!62X>F25e(`m3x5%IiEX#f)rJzhMhu~J)>mYr zLyz;D6g8xa_w7vXT*u?0ek8x$f=vy_b(c{cQfd_T2BQh!)0o#+#TSx4+sS)RS+3}y z;nKtDADo)>IkFJ_X*5`hdtRQ#<(qIqJU4y|h-10Yum1C|2?CWd_2Bkzy7>fkm8iJ} z_QOS!PUZ`VXW56=XXcEnF|Iw4#`(B5eZt%h{=>v0}XYII5PL=y9r63S>rz0o?38 zr^d8_0VwT}636%bsTowz2hmZ3A&@kumR3QlDJerCw$2n0+%UzqQAP*4Ln8G&INY* zN4-5utTTzeEqTpk6ZsA0tzIWcosFd?wtRFE;1XT{Pb?cRK2g8@g$HN3Nt{ZDG?p2U z)^=j`eaoW3Xr=nyywigml2`t7**1ZT!|Dmbk`&)XnA@pRKXyUgJzLppHLA_q0Cd1gC)0(+#V*ZvIXd3uIHCLv>$zr9^dyDOb_L+3n zl0FgG_*fs9oMETqR9qX$e=C-!wbtQ*5(Wm?VyL}XwGo%WeDyO7sX9^&80I9z4vzU&O?Q<6_8TCsd>f$RK zqQ|^7>^z^TRl=1HWTl1(tBTiO>xsh9iorkQL~-)+yqgZD;iR{7C{1rJk zc@!P%ZJNDC?k@VQn_=+X*tt8EfPVHgnWMnTuPxiZt>sFkkb7?m$1N5{Mu$>45%)pi zWaK-(S|}g=%-)wYuSRH5&mDj(SBrH}l`-S=M7?%t*w*crPcL6I_Qug$8ge2CNc~hDw#@5 zWDCcpzU`NX$C6H|+4vojo1-tbJGhNn0?XBYojfORtC|0EW=7fn0YYf0Gqv(9uO9iN z8ZR?G$`46-(D#ukMPPO7jXf}?XT$EM{M@LZJCznj{n5A_@Qpkx1Wr1O9Xv0Ow>e7~ zeE7}lQ4=a_Ct&<_T%5wXcdx*VRpjs2<571NcE2)#2N>4AvwMbjr8fq3wuKxj?Zc+n>f z!gE61YTwyQ%coAa>uNBpDc_dc6n+TgM4Y5Q`uj(LOlxyc3{}>A{+Bqfzp(n@f$5{o zRZiNdxR|)3IB~73PHzL3R)%UzEaHQS34^?namU%6k!E3MY9RxD+<=iJM!1R0` zbmrdQuJQ$zM}p4SCt0k^slkNPn+*VKa&9}~!zd6tP=VT&NH3a0+6Fn{DzC0VE$S%# z^X8xr&yuq&k*|xIw6Yn6tHI8#a}4Bq-hiSJa)%6(Qn6oSA9eaLva1O>glJ9rN|5ew z=>@pt=EMnA0Hy*|D4I#HXB&eBc6;vlm)|*T)}rhc>99lKMmxs{Y2~O$yC7nYPXr94 z@iZ)P3aiWtmSzP5n!$tOiCq94*o-!HNji1q9~INJywr{E z)XlZj?f*z@c4qeYf5)WpCqGm6|2yFH|E`K@Rz_e%8dXuzI{!OX?^oAiGdg^K1?@ji z1lquOfD!QFzl*6-WclDrNB&y{O$s@fU0t-bV(RgKJ$qo&R2MZ&dckhs#+f+%uL>F} zb;FsQC`&KR{CvBbe;~ECXbpDf1k}KIWVZ&!B+|G#iAk%|Yp&UjL=x=T&Swhr-eu1A zTWa_hADCnX51MN-`U?&7b?UsvbTq!Tc5TK{CVdp!laj2XdF*bZ~W^r4FA`!J+gGyw3P9%E{bcLFB zV|fR2{$A>qKdCa}Ep^2q7cS{?>vdXc#n5Ulh=^!$MV*t{-RW*&jqB_kZHkKG7z?v1 z902CEq#20V4q9(8ADf1v9_f9Y4K9V#&#NQ8<$nn8`y#XVu!QE zsk~9z$imQ1vcWW&Y4sgb-yV<1(>lIR9(+BeWXC~q7!0F%|IuPCbu1B~-XXaW{c)A^ zqE7ymztkfqt^AwsF1;d7tkvp@5ubZj43u@u3nx{$hAW0|$7kd0b>tp$=YvQ3T#6-M zzpfnc{9rEjT!NG^pl56SkZ*_jLFOU@Hfg-B{S5~D;-~UW!neo!I)0z(9^Eszjo${WDH>MHVcc*YNp!!{t8k1Xz8QgFP~`EqM1}B5l+pTm$_gSDVE;p!1)l1FA9T&I!4oW0^UofM; zY1s}Dm-Nh$*t(6~sND0X*f;)~Dy%_SUa*2r+U4YGTrme~rO_CzVu0 zL`|LM|9EuWiV%spOFM!X3=k~@BA56q^|U!#M)DZL8t^4&iHxplJ&zJj!Za{Q%10_s zVb&8F%y5*V6)^yxD45k9qrv)4O)c_cjgsW>jYslgb4B9gc|_e#boVLphV=Ndz2_>$ zWujQ2TX+53%59hPMs+@+*|l$#r_VPN(>G?_FNlvSvT@6Lrv6LY_H#ZSg~Q}7u2l#H zAkBvC*a*FR#lC1RqjHl?KlK1=bf@C&XT$y9J z@fJ@ICZZ438LGY`zNjo$*I~69Cdw#1N~`%)HH;BDX31}uo<$2XmYc~<$#Z?0sw!+t z6fK3V;`=>ih^F)HIu|;ERz?CDGfr%+el|UbNNoTe!5*TQva4IESdUYZEWw#;Q4{Q$ zT^jm)>@)N{!ZWvN>u4C{RVp4>xK%}mK_MN=h@!CbW;%_JshTVuF=Xd$BqIEG8^mwL z5sp992eriu9qYp%tn8IGXY6@x!&rx$5GA*MIA43NHgcNDSe_sNT-`XmG;VAa3q?|q zK`(PUsG2+E+b2x#uex^{&H2$~udrj+h;@VeUUc^a)wUlzjqHxumsmdcN`Zkbk?0kN1&!%arSC zgX)dm#4j*WvtPebj6%+*9^6%r3GuI{Y$IWeX? z{B>hOLrl)cM1F<|p0983Y(6lF{HcWfAp@P2e8~#*dQc@vr=u7ETM%b$ngkO}6BA2Y zy<()v*?2yF9uv~~9{26zf%Qp2wB6cZbFbtMnB~05P&Zv>)Je0|KyisD<0H$kj_`{J z5$mHk34wv>1k*>$M2#r#==v%wnQ3+l~qEuyN)gMV|y3IsvMfdZPuqvaC^7{x5Sud`ZqTE4oF%< zll>#m56WL^5p=PUH5u)0{4(n|o+5x?9NL5$8eeO%GxCO+?a5T;K8hl2TZvufVJy@h zAr#QP5IfrtKf?ll@iUT}Nmfo@){)K+J_~BOc>%!mYr3c>czWmib{`-jApxmD8>+g)x5N`=Y1`U$ex+{fTgz?hG^arq|bh3W+kGa`;pZbTCuS7Joh3Zcr zBGx$?7I{l?QK+jLAwu<#p-t%~)>OWnM{z~@VFs(EvPVfNilz#=Z5U1p^pWIt({B+_ z{uY$P1(=VIPx}z=@j=Zo8%3;4Q*ny6)Qfz$$RAr{;~N~rv`F=dp!di~8foYlyLUi& zmCHBLE`nW-XM>_WS!i>s!FEyw~p(i z@Rx!yi!oGSBF&_cgWQSyZDEMv#E^3vlNz@w5q_KqKNCtE+Tw>-LP&E1KLL5cW^C$1 zh7?GZh8mWet4TDw?sR35_4bIx>iB?fAz*vAZfT&_qTfict~=J$35{-H1rMV6b7_&P zG{`R!5&JdB781&nR}M>SX&`O{CFU_IGWt%Zpax#eGYh%9=6h~}r;kkIMN%-8OUFyv zjVY-@jU6t*>EFl2#Uov)em-P@BI#rVFX9lNPo2C7?_)$|5Elrl=JfhT9jwHKg(%qPcx^fqxiOy06(mIG`k%#6AU_+`Vv#`7A>25b?p{QrHl2yLB zP^yRg)D%iQkH7t-IORh6?#9svAv#Z8EZm|E-Bmz~DPitetcnH|GK{7&xf#QPh8&Vk zwbGCCZShiu*0mYc!$#RP1tc*D7&_1tAU={yEdJPhDwHkwS9F(#A-3@dEOctWyK+|3=D-BUX1TXt8(idBR1HAgAGtQ9*2o;!>t5Nen) z87__li?Rac>nPdub0m^qH(XdC*KDlZEJk z*E!MKb=T%au(@89K5wOHSy@nefjKXgimVl8xI%?+`i(jVG{7EDYL2ca60X;(ds;Rloh)Gm-6_9oQEiT?%Co4wj)IPF z)LzE|i2z_%UI03;-gwLqdtA-7TST`cJO@`IxUuW@Ad9d~&H^154r5Uj`Yo~>I;9SsCXUQwM zi^#xJ^YT@O%hi|6HaF9^+VJ&BS@u@fKkGY@Y^YbhbJFB4hd2)#VCL()2zy3%Qn7Q< zuS;MfwYBHgO{%M}tKIczuug9K*!TS8LGN4mb27ub!ut%CB^8+--E{ElJCJl;t`9Ib zFp*SeU>ETXJ}}tEcN0Z&RAW+1Cm z_xut6WupKF@LK`%0Y1RAe{2-s|6MMW@7`e2zor@gbMcjQk@$HAMg5=W6vA(;$0_9!KquTiW2Y#y{j9UbxKTI&&)IkpV-rIA*kYiwM#`1EJV zsziKbp6H&A9)iBBFB-;)eyV5JbGAjC{y>`ubRV^|!*ZKoDjoX^!$XmEC`oH!clDC^ zEu|4I@AjXhEy~!pgA3b(Z`*p7lK3ha$BbN0u(=iK2(~cqEy~$ejnc_dX4L?Rvc*f2J7vgq(n?tZosFtv0wLF? zT_=jOR}Mkiu!^D>3e_x3@b!wBCR`Sn$7cMFg9d#~l8CekH2Yk|6bJ74N#`e2R=t(~ z`9^?k7VL%#N2;;+^sYI0^P3~^`t(vYR8f#*m%5ZgM(;jo_y|!1&dPTQHsUmR9~-t; z!%^al_hSg^Zp`0E*6sb^hSk{Y(xbqx9P*|{+7SZvtE57C@p2L5MixAk{hWvxwt-Mn zC5*PabM}-U2~T6)`gaCgC0-=9VCWT{Z4y~a?Wg7+bXjkUc0_0SY2G-4cycBT!Wyz^ zG3>y2sg=mmro3jxZcw9zoYPK7jOUM7U+Seet zG!Z^b=Li(x-1W^)*mTGDQ}U@cY0^oy^J5bd+>0TsD%A}_S1vP4ysU@b!cIN2}`fC|Wogqk~*6ax&!&_6K9`uCp8sA&^D z^LtM!Ed6!kWY^|3`J2a9g2aR|Kub3QA`)WplgWLROn4Z8B;zj)SZBWle!K4W%xFiG zhfgMQmDnm(YSqqDBnm>WETZ}vnNWgR1Bv6q4%Sp`@;0P9s+D(dpmk%mx^G(JAPzC) z-B5kh0G25BmiKQ2yr!%9WRB1aAg)z=i#afIy}kA-QcXCDnht}GqQ)xS{Bu?iz4g$MxUt>_A9m;2B6{LHDNgaBRM3t!R8g;eAy$>xnlc(HS_0&0UrZ3v ze)2QVXH2v}gaavU4N{xx;WoJ+v${?XHCX5fKpB7jU?RqCs;Uy}`;wl2vosa#3- zmDrILgcvA>wU~?89*U&}y>25rL=rcX=`egX>0<5t@<@|`gNKbWl0{`9lY-H{zd{TM zLIHBkp;*$6@&REd05NZZ;#kG2DWSAy=~%>pFpZ%kcH~R$mj~rreyT-KkPtj#^z}Hq z&mFQU17hf*&bKvJg1jP3IPaZRYM3zBbCoFH+pi;W5Huc0Iwh#vw~hmgV5Vp7G=Qv6 z?AV51_2Rr;o(ldh-_64pE#tWrRQNWQKXV{>cD@$tsV~eYagX(N_(d>RYLAsnEjLFB z053Ce(G8CCnoTGj%Ac0d)=))C#f4103T9G&O}fe(Ut_z88FXcWZb_+V=2#ihV@1Uy zdDJnm){ooa`{HsJ0_X}8$C167U$k83S><)S0KKmiMIbM`3~SOBs->Ze`~cFr{l3DyZG(F0>+E`QTF9Wxl|KTRgkb^nLXedX~0!_->uS zAF{0du{kKgYp8fbdqlsHvPecWD}q#`f=xmC_RsXxj@Zk0yzuJwES@h7_j+BPYlq=m zi?cmxr-+mqV57!KR6Vi4_aH;pj!&Gc_vscI?P^E256O6B_08O%?V$*M4Rm=aieX{s zil!3$bx`@|=VuldRvgM07+peC9R_|2QZ5ds&8rmC5$m(vCJ&u`ci$?ea4s4aqo3k8 z|Mpl)YF>DG;ML{aTOUvTWp>IW`U5S(-v?clJV!2^BlZ`HR6OB{k_w+wnjt04Td-SS z8iNWwQ%)2YQU%e#>dTj9o6Cj6C<)?Q)X<+p)z+syB*46e8l{HLUhaY~;?>sQEL?gg z*j?8MF40F`M2PY&{xx%SJ|ZCqjsWM$Ry?X5Z!S2B(idZ(XT3g4g(~8~Pz($FF>^xD zC@wZip1wKP-AaUO$PC%)y>NdzKyNI-eoQ7zijn!c82C`(h>2q|9rVjtpeN^fQhWgq3oe5FcYTQ_>arE_ru?HFH$&E z#Om~uVRQ=^0_g?1uNL2?w^rP{=PBZ(NJa!ChVu4!$A&ZPDiM7i>MAQ_;JZkTCy4#P z!IwtVsa_O4>kMr8ZgpSh`YaV(5=d`S6dMxAC#7oR{Ee*jG@VaHfA%>`Tv~pwPuu4j zj@Y+%ztkW+Z;tJOhm>g@=wi>%Jv;oS0PfME-rgfB0BN3fYw9*CxHogPI??_PrD-+$ z*?nKZEo;}-l34Tk2ixZp(j9F8>pQP>LSgv;o%grf=g~kr=#J!@Qc>DC(Uq-ebKF5= z8^A?Sndnr>29Pm^MXKAwEl&N4_`L6lm|2lst$f*pax3oAGfpgMerDi!UVjH%=OJqD^!hp{4*%)6RN%?z*hevm&RbX1n(4z-89 zovnwC7_*Pis5GJ?Q%3&^957Ci<=ZEhAE${1oN;?g#h+d7(jkcGo7EuQ64WTLjR}JB z6@Um00G0qE0`F7@hXtD4dqxAHC3%3fyG_{)K<%h%>j4difbT`%z7o$PtOo5?3mB7F3Q%Nb17h(2w`y=Z20lP2fz_A5+R%xu!tgQ#r13*o zIUA%N0h#Co-BJgVA)=^+qqG;mRztvDaejS-t{HJOMKe&?Ocv{Q7Xbi1?2i8&2Xgd@ zm-V$%Vbl7=nIf40R^(3cM`J zCdrn*S%-(!i?jS8?Uju~dRptXy(M*yLilre5#xiCWZ zFj;a}`|o6Ycpec^2#$Q(mEWIE0{}=jg|}l!ez@GDp@DfIVDHV+TJf+}G`tr9??uDR zgxMz~leE#-3|=6a9?%E_Ci0;V@y$dM4kML_qKfRJ&yAvC?pUxe1niEd+vN(%L*9RV zZ4Hi@%u_mTmpC=TX}BRmfFJ-4o+Zt~V}P*L(@=YmfMYz%qZcMR z4PXv$Q*xyNrb)xwh2frPm?t_hOB$Zd4e!GgRMo=U@DN$bB>tl`EnE`(`kMuLO-BYi zA$cU!4eWNq4!Pc)=j5_;&694)8qc*mTV@vSMi}6-Ef(N3>j`gYi~P`u--I*VYT>T6 zH`mMyE)`i(%^;S;G+)9r*a{aiSqT8*rRE)_;XWo^w7?4*dH)2^9{Urq>#@E>?@I+x zb4P8W{J}1yIEM%ETr?dZ3|WzezwCiHoaSf#EU7Xtpr9`;Z+0&ti9$<9S?WRdiJbpP zBIu0uNUH&E@j=iMaE9wsB^KZY%2pr4)Xo-l+-?ktWJXQH9%A6(da18zi^^m&%4Fc~ zi8*~GMZYlcvSwg@Wyr@VpcMwPpN~kS^kMsk*QAQH*~ zHK{76L%{jPD3^mu6A&fk?F%HUQ`yBmunpRZZ0?)BvNwH?Yg>mPG4a)wI~97eL{55e zn@;xlXg_ZWK=AeZ#{*@E$P~3uE+VNiAqD8~JQ>hS9g!s|LnQhG3ZC#*Bg0a|CczQC zV6P$AfF3;RqEw6P_6ns6X-iNCFUooi^wnPq-^&ds0sd$%ANHsn{+0hUv>|}LB4DHT zNmv6f9^%;yTht`!Kr{^KHF{-BM@j~4X;SUTMD_kEn)desmnOV0PxYL6){bfL{#8;c zQ-G?6xR;RhVN!pG)q0}C$Bh6A<1#;FnzxU&GQmkOIg|Ij&-!sq{UuHP3;7otO>Kmo zrdDB+?2xuP;Ud`*5;<7g;jy#kl4AEeMNP^loDWbIfFzO!Qs{1wk&g#-2$B}kF%;H8 zOP5HQ+)&a3^J^vvYbI$Mf}5QrIN~0}K~$J~+x30Dco>w_0_m>FcY$({GQBPjG{mt4 z{23JzPUC5gOI^(g<0*mg;2{O-u@(zmTBoi7VBYufgvH$$daQRe7z<%Y0gMB9Vo1)S zX-NUV0liYp`%JSS3m!HbL(m4kebe6M8&h z2;`2=JC)m1+EgjWHBI7(!G+=HS_qX<2_pUU2nH|$_Y8`2`LeG&l;I9W5C3tJnwJ~Z zYyk@#sfyIrYs0GE?%p~_a9@6-w*Y`05L$BVwDrvp7HxP$A;Y>=I5xWQhRuX9XzVklGy%^RVFuPsKknmsEq))Z4R@i1w8H12cQGnyOmS} zexvMVt9D2`tj(A#@PLX1n1+v}Apq!zp0GgEdfH9cYm*ejvh=Kt__cP%otvoyPpcw} zA1Cz*$bg8`Zxb(evEqO>IiQ_)LC?bJMx?cBJQdd><%qH@B=YUMwNaLxAbVc*c`=aS zk?MphSI97Ilkz#e53>Qa2$!rzCi`r@l3s9!?J7T&FmF>gyy^F>C~gVXAe?u*0gb?e zuQ;{1Py>TbhA75)&6Z54XA;m<*_jvNgn>CBz)p5uGFb>%iQYL%EAfDRY&_sCNW(v6 z0gF`@ku5*$0$DAPJF@@{7hsJ(cPUH}DuhhyYo^o6@N9^7<$Y8Xdn%QMofjP}6G+nm zw`(@S!0s)>2Fg?3hkNa0<|zf~@N{tME9*I#%I%#m8%A>Y^nrR9nph=(l?$*!oKhV` z3xXtaz^uk_O-rgwe=sq$8lWnfT7dM0J~slw7r;%zVA2w>eF;%MN*c+v#%rhZNKC27 z#qBY>W?AC7Wp9Q;x(ZHRvu(_sCDUF*#|y(Na%X3h&MjO%(V9aU3+`O)bf-bqTl z${WM5;Wh~tG?8$gwl2i6YKyA0be8jzYAAox%MUVNo!4R*A&h9C{|6HQNU!e(wS7|a zPU5xPPimuF1-Z}_Q4Z8{HgO`DTCt7k^IdG(d|g#muG~FdDx`W-oEali@es>3tf95- z=>pTqtYBrhZt!4N1@qSD%E+ckZfb5#$?T;!r(BYO}1-YoU0V7B;z1`*T?=XxPDS|G#re7xKuiM#EB5o3E;g= zZ3(I3tpzAHgUTClwHJwo_0Gfv@4|LP#aj2p71=Uy`-#BY3DVa;pow^BQnRRD6HV`X zk;W)4)7!3=e2);f6y)FPEDimXGUF?f+Y72GXK&DvVk+2KX^Vr z^2fs7V2&#=wM{fnFxOXJv(204uN@qkc@h(O^1PVluO~t! z|G%Qx$pQT8fNX#(k;#8(j^fQK`R}ska)llL!vgXDVyquW4FBg?|34Rq|7Yaq-To)% zPwcwBye0pLH6rT&IkY{Y;HUAjzvuf0E)FVfqOCHb__2D=w-HbJF23wshj?z?ecpfh z{cyS7cAmL)@ci`M?9;o0&;MKnw!M2hKR9@;o`!Jm;I2bFC^ZOY%?76d_aWNSNuImZ zsZra_-tm)F&2Ai*^VDuARRs5*igMNK}YX%^H!k;c`VuL z2l;MQwFd=Wo!4GGp9!81PXg%2l#4MWD4Z)h?Z^L+NFBdNZL@`l#OPzwyZN<*z`@<}TnbMi?$aUxb9vT`mp-qA*Z z!fFu(@G(;ngZcEXw@r4RA9bj*kE1{mwBxk)(s(fT#q$UD(FV#Tv3-Bj@^}X z9GZ~$(BSW&^YL1Kj{8B@9wS{{@p<8`1nz%Her~&>DJSyEdW+LCgizDvPr%#Xq>CWD z*yKD1*>vxYtI)FTrf_v73W)sm58fZ*`HV?9_d>EB^yzHR2!%f&@4fGYZw2$*YtOhi z>b*x{e~hF6v48B?+SYwr2zS!DhDW45_*~JhI3qOP_3iSs?axw@K*jH--&EgkN+j+=X3shkjA`)wA{T@73v~5aIXP>-&U1KR-Mp{QZ6L|9AQM zf8@n0A*}tgiW#op= zR!UK2ym0(aDWSBW zgoKoIsmwik?(^LH-g{s7zOMD$>sjkr&)a!1FMsQQe7;9W$->vtIi%aKrH-RsDlQNv z36IbsA4M#9!6zvkJ!M(mneKi-MbSCrQJ?rxJ!zRIU)U8$(bX+X(=*Z05W?RjABFLi z7SmmC^QC>AiWTxMou>b){EmAX7ShDl@GL*O0Ot`-@L@(@WgZ6RW%476mrv^4uzbu% z#DmxXPh!=pWKCa1;kx%d)9tOqa7&5&$bOz-cg1*Remz=8##YHJWhLFP8#b5%AZ^Kt20nC1{26bnJJ?5aS zt^8mw5o=Q1GvV>9E?qv#)4r>YquKwdkA?N)Y>7}}HpMYLH^uZ0Ni)Mb#fGzc<`$j6 zm&l2W<`S7Ruy_7!!U-`g`10B{~3t}pcR4HX;v=iY>9X^k4B;P6y5A*B_TDuWWlL&mZi}IGaARr^*s=MxsYgJ!Q*<@G8n+bAZSD*%J>N)Ev$!~sTX(( zGHC6ct$3eRb+08Vq=M(O(F00bLd%t1Oveu$mIj913Iz$LnQhK%8H5J2LV$JCgD29x z-MwZf933vGv1r&L~tl-soM&h%XiqRsc^pm zxfk(NE!leItbEm++}$T={odNfTkDtsx`?wiYWd*K`z$>Eq9tDVK-XP*Ve)}rJAdn; z%Zu+Tn~WFr-^Gf8UrK+h1^I7p$y7vrb6>}JcrmzP!7P~i)RSgE>`_xVMJD+(EB8LH zS!T-NcCvPDmDgWRRW(*jdZ^-1%kEK*zCISpn$oCf>wMp0mhpcZ$+(d#|QZ3 z!$~HIF0lh@wR#^)pnF!)X`zP;pF-M~0tKZ3o0+KQkW`}pz?2`8eDqUffLW9wpr#;C z{~(b9@py)CMD4Z1mS-KI+h;3+$df|*j=lRHV>8{l#g8c+%pLUeIrWFB)yeDwI<`Zd zn>~YBt%f)BFDWIOFxgDXZ1QJq#b#YJ=fW4i*x}6TGI8lLTxs5wu;DFJXWt3ODTCnq zKtQ+={4@|DE*D0c2v#_RV;I8kAHg1_3!IG*m56+!7%VxKiG#K^}jvA{1~$VA5)kuVDXqLo)4gJYDAF zNd;)eHq@3X#G%FR)5de!25*tpD3ig^Tq9-&bOCZdADaw=rVa0@H`WUSegV{eua!(C z*^QHpELxlWT`mn?ZTkOs>z_Pt3LWx~$x5t?@^flUTHQ%%$Vhw=lXMJDww_NqS@8F8 zG^>x&-f}X>Pm$qkaVrJNxXu{?=deSzLht+f*i#yjHayc4m3*9G*j*;|%)t7t81Re( z%BCVYwQ)Z%TBjB!^~U?Y!G&fM;?Z03@Ij~{-c*WF%%f(cywh`~fCFIKq;HzGpWT_5 z1ofgg=?=iXUYgF?q_I?La7OYp>VEacgH=`ulc@U(-aZbfVY=NAS9hgnse&Job$gr7sOgHrI>YyY7>*14J>L8j{qI~@|dvV z&9n_@&W#*|OxElSMy`Qx1I$C4Ey$)VmXvgc&w=EE+hqODn&fNwM5v!sEk*{(cO@S^ zj-lCcrbwgA#~TcYoh3c5q`s~s`zA>zb@jikYl{J(0DpAr|EMAu|E-GHe9J~J+3}Ax zM28QB`6#^*Z!rXp0bvFGvGn(fnMlfXpk1sd%Q_F2%!*w3pyL6zYzRNdEe zn_tScW$9I0z6%sxk5rB*cbCpV4KmqzhWd8JA}|KcSX)t1fVQU{uTnUSiP_M?Fl9e^ z@m={9)*7}xNuzz#3^IfWB>z?s!4qFz#fn+p{a6_JsCJ2AASuZGTOIKyd1{ZIUn;_M zhQ`R!KuHGs4O=37Z;p{t7O?*3D`Qs6|GmtN4Gbo5G0Oo z7a#0S6iES)^`z8`REXx@f_tgT;>Y($98Ko%SbkmC!Bmw~=04^&fyLHJ$SQ|exKtV# zD0M4up;SawIy&)yW3r4&mGgF7jX;}HAgNjaLwsw^0&&`BCG0Q^u&Rw&bldahHVN4&<`1HfUCk zV=5lOj#}4N@L1bRd@a$n-gP-RU(I`{?a%J0eErq=HF59_zZ@Gm1k~q0tZq5rc$_=hHP=Ll@4vE0++^=*}B8+Z`kHT4VPL+1f58&yYNltL2Kq z7S@9&kko}Z13cW0tKAx$Euk7QsX%ex)@dS7IkM_c&(Kr%ztZpM4uD`*%6kD<^R=8W zgDo_LZ^W9P7#;P|J#?H+S!Y|t(CJY|8IAaq)GwB?IMxVPD4A5cN4 zOTbTCaIYt&#laZ9M0iGUr! zq_28-$QZC<)|V|cUKffkF;P)6<|!T0vr+l8b@8XnJ8^hbHe`_o1AKwUZ0u?_B`$-- zRARWeK6i!_OW#P6FmtF8%d#FgWg*gNYaFfihbc~mhiGZJm6B8Qba=AlI#rMCDzayS zz=J(2P!6ZzjS@D_MN&!kU0;mpRrGIfiZv%RY#Xm_^4c00gKXGA@A^uB+#{ogVu~>( zjT1BD-rVo!NY)XS3w(sgU)ndMaW)thZ^0ST!|RzWOw>O?%!rjqcwqwCJ1&?Bst1#1|6*{9;xN}5ZAhIkhkIPHCePID94 zilmvze*d6r*^Hh@w~mxfM8~}_h3jAhwMFJ2&uXUO+qS{vYWNHkdR?ac;*<_bR$Ij6 z&i+wTMEE?h<^dvNOjxdLqNLPKnN?&sma1_Iwj>fpFS%acAFDX-jN`*V58YMf*4M$q zRA-@w+WH54DCbCeIP!G7F0QhXYMQf5A)iUaIR|#1d!`aI`;%$|zTt*-yu!!hc=zHA zM4&aFf-%}%ld;+CW!cCYaV32d1CI2!t9we}AB*_=RhbP1u6yX@X8CsCAI8qI#bXtj|=7Z1%8hBhFB0Oz8~U6A##;p z&Y5S!fYc0VNgTzT6uT4L@Oasw6#%bOkN|QLbguyP2B=juIQKDeD6im zFM(MaxnP7ZUkhikXC#quzHQ3KCM;+^2lDPH~4;_DVW+MQs-# zmgj6#&{gj~rLxHb;%ZCm2E&raH<_F#sY;iUqD#GVO~)mqY2zx54G`rRr25Eai=@V? z{&N!Xciu^M0y?}2WsMOFEUKbjxjA2`*7rxD%7g{n@^SaJl^d}`SDU6XFv<8s$kIId^Mj8I zaw$vE15BypN>gjF>b@&f63rzMX8gdvamhw}Q5198#-feRoec}Hs>7U$Wa8N}Ht|es ztn$LM8~(WPLrmlDRjkr$lXx7Aik8sh8r ztD>|k7d?6$poG~tt5@sUpp0dn&BmCCJ%(&@R}vOpBkI5TAD4X~x#!}=dh3?!p|`YFEb_Qj>$ZZ+k_%20 zay=hPYnHAqFVzYy)QAJ#IKKFK^%C!~gi2RDP0s2yb=U(^`Va^y21^(&7ghNXa5_DV zc!vV%NLp|aM#06RYZOic52t0uq-zrjp4XqA3ulpluo*)*5KngfAUti5dkc{7hS>X5 z5I%o;V(|zuF3KxxLj@SAjc3Gz1ybp&2ziM}MdL_i|46X0A}KslVc4>=tTZj&6jr5?2@sfz~HjeT2 zkMVEgF@?p5!y&;}F=1`4v_NR2F*MpA$}9qfwm}o1w#G;xn$8q7RU$UsI5yKi77mZi zX+vd#V+*cg3u)qh?avy=mHWpb;Bi%LaWxBZbysoqH1Q1*@lD3@EvU^|cznlS;b3T} zC(VBf2M?iI1C>#fWrrf=S7m`_-yNwVHf5J`;~#u64I3+zLPmbMywzDgW}-V0gK zpLom(5DpoF$`FhBK5k982$NBj4XtlZ{BE4o3+ODj`! zOJ#BMksN?Zs3`lQnIyCT#gtn(njtW**pyZHBbIAL-bMY^h*U=EG-jn_F(h}|M|hh3 zW>Uv+>izcn4`|c>|Fu8s@;|R30@JFK3Z@T+7pkJA-z_TSSSzINE392msPzgbV=kI@ zf{~yVfdms87x7h}CEvytVM@`{#ijq{8%7;5!~n@C`C;-O<%iV2l^~_I8T9)sS>&sKw`(IXJ|8T_MGf_*&jRS9H z80S!xD&gD3nuVx5kPOQzRF&V#uFF=r`;SMAq*B{_e@$PYJ>1=U*^3>tLWM!ex&KO#G#({C#0d1@6Uv~2rWr%mgXRT?>VuYL z-@SuY6I$1*sMSnY55?BJU-F}6@38a8l18!XY|iyt_tjSQx1Jvtd*5CIaPA%TVp6*u zId(I;RVCny?;pJZf}#}%N^REw6cmm%uYzdZ_K$~{V(y&`vt_xRjBr(;uY%u1wz6roH2kv> z3(x{p*8!PD;`lA+0+0aACBN2&txs=K(0bS09-e7|BFP?@e+Gc3B$SZ)9_<_b?#xjX z5$Y7#n;DN8&Fv1@R#Dp_NZZz(PSq6uxa!7`JMOQ&^#cwXw(Gthc3mER|0e#HIM}&@ z2aL#crjJ$@E}Tl#9I@V&o`vIOemq>1`kOs9VhvZmoQ!q4?Va!PPQdw)Q!8OlGm)2d9G-d zQq^A{-sSOtRPl=*TRTwg({ai*0Z{(lS8%?!NAN#BOF%#@pcUQbKR!z?kzDrwZpSMN zhg<>-i!9fG|1oo2G5JCkHFF)OEl*aWo6082(`p>vuV`nOGTjQAs*4aVfMm zo2~lKXX#)di8wvPM;5yVquw{4(P!*$<;*>(q6H3|7?KZ^{>J;`4H2k<1QZq7%(rND zV@ZP(Zgkl6@pWr-G=2SmnEs@3<-OH6S1Ut4pzfFE)QxUd@#$SB>bA z3U1cbjC;1iYt;(7mhvt4SpEGhW(S7HRov(}TqfZ5RI#RI;Ar#voH&K3`1pt1gWuJ0EwGgPGYSdU^yu?kq zqh1s4@>WKV(55Wq)+Be<;|1R0>Y$6vrOP_ZxQBm^vpIKEm%i}d3FEDe1Q&;?M%k}D z7W#c#bulcWu=8{xNy&TeI7KyTVgi#!PcddP($zo|N7l*xx~)32;-xS{B&ITcrWCUp zoo|-gfLhv4<6#e@CA7ovn1;VtJWiyde(r7=WerGF=BZS`1NULaAW=l6JoI+)t|OWD zFslWt=_0e-!o$39*5`Wc_P#LoNKJo~JpDyB z>yFfzjr5qaZv_VKCpM)RuTNOn8oWuaM}4?yO;|796iaXO`)I0c=v{5H17mzrS!$E0 zsl0bP6b{SG0R9}mo+XviBAHN^szaHAxd6vU#9XpeSsT25=0jR&)BJX3KRz_Xl9&_UG6(Y-&kfE%hAFsByt!(zjJcig8}w%N(X8sme0x@!cNuk;S_M{T1j`XB$13 z@AEz-V`g;hT292l%_jT z2Li~wxJR2H>5H@ZZMt~%$xKA#&_Hp!pAQucno;Mqwx(fgl9V-p3#pzI|~UNCE$eF>VCc( z6rbqpC3n~gpZhf`%_5T;8W$I$t+7yuD%;CQNu8t^p;3)RD*>f=RUX@;m(*jPBpWi>N8)5p(4uMcZAK2Kv+-C3 z+2W2EcD(1zcyAfAAX<7jQloLOlRhOM`J#&X3zSDl>sd6nMnE&?)0Z0MLeFjCL{TqO zSIAd(639v)%JJUY3?eF)Dt=iryBW1-QZ6xcoyH5tf409{qzj?G&pqd%ZqK|<&TO3a zh8<}6WxV3SBVAc+KdO=+msICHOpOUFB@m2R1V>yYFzMreh!(?~WubIta@VUeHc=BN zlCQNHYDm<@Jfr^_7Nv~P`z-USibnFefp!Hw?z^|6^BHebwHSU*4T9OUZzSFdQcEpI z&TI=aJ}*Gi7xhkq7A88;aV^CdwXybe!kIyh((L;<|`JxgJyf zvwL`{)?|mqeF_6)D@SUOszGkKs2AvcgCMf@J@0rni@6S6G_33}-wbYY`b5VZSbH9Z zu^ihpo`=I5ys?08$U>Bz5A%E8BgIV+5POn3m3EZ&&3bX!_$`a#Ibb?Peh`5!C!j?r znGpCoZpna~yaz+4KjMf7^fwSI!B_wM!pJUHs|1T%YXRy^IW&_a(T6CgYRvjx4tc zTj;V6lHxIHC@Agy#>8S&!@Du{-Xk^OVw+z!4__neys%;&kW`9mtO~Ho2HuxRNZq=vY7ndRWHm&bVenbKGByd8XX1~q$9AFF&iLFUaq~@nI>BJwasoDf^IhJ@HC%cd` zt<(a|yY@<b?LIU73vTR;!iCX@B zNMhd@{Rbmq7RH_?TO#s3=$^)oT}0d8+a^AyqfE;q3T_lHs*SMH*mPg|Pjz)7>Ae&?T9%lF z_`9|mS)&fZ?T&4BO~r&mfq9D+JM2Py{GFAjThArDu8!80Eg&KUXEh1xD?qL+oR%$RADH%z=zgBT1NjG~iLGay~zp*~HQSxt=y7&&bAGfvu}z0wqyjW&)TDgjJcO zqNB-rj-Iq)1iI{i$5>GB7cp5FraYX?%`XOGOuOYxFQpXmkQ5rx26fWm^F%VE9SHbK z6hZM6ViRyxYYMSwsSVkW-AJdOXVJtdyb?}zA}i!FRM4gRnx?~+Va*3 z03Sk}D~wIrx#HFJ;utgSFkl@0!|@l-BK3~q(@(_*xIDKUJT#sq7*5BHNhC@a(agYI z8PM!nN)qRtd_?R6S7?&faFf;%9`?pbJMg64wj@w9=Kk+;X5P)DlYd*8Mk{V80mJ5| z-1djzOR5;x!yIj5j%cumovF_2lhpvIVyzUq_7wWX6vpcmCfd|ARuUGIRE~gDJ!S%~ z_SAcesk}w0e6(pol4&9)X<`9s639O))3V8W7Sd#C)8!@qJry}#OVBmRFbv2r&dxAx z&-j*tWqzGuUHOb+6+qMrB%{rA%Ff(1%p~grxGW}zUu1p`37Y9XJ-YrX9X{2 zg! zIiC_n=60&6cC`mmW2d~9%o{MtdmE6K%A7Y`>7isB?iUp`7VCNu=FDRZn>H~S4G1pq z&&QZ2#%s!7c243#Viv4ryIy!|J<%=Lqw-P>6HBTnn7YsiO4m7}b@wgKJHNK}ML_Vf zUlcin-#VKV;uNAv39thTsUu(Db`%mW6%yYR0_lpnDhtU>i>LyNXmX0^I*RC*iWqN- znCOaGq>9;0i#Y;|xpInmI*RWt74zK`3(%DaNtKA0mWTzGNaU1Ab(Gv+DtT~IB1=~) zFIB2&TB;ma3eG82>nPP&D%HFx)ut=cl`7LWEi()(GtMb9?I<%}Dzm&Pv!*Mzl`6M0 zEq4ekcgiVu=_q$wD)+c4_oS=vlB)1Ft?&)3@Xx6T?5GG{stCEM2%|$lq!5v&i0D8B zGzSsafk=p7LL}WFV04wKQkChZm6?H+@SMt=j>^2H%7UB9Lb|GAsj5=bs`9`pL{3#z zM^(*IRozWhJzaH!RCSYSbxUA%TTXRHNA)JSsOzS>m#(H?s%F5nM)7NPH>BpR3u)(0 z>2h1mA#>t=xdKMH3~aetW|vx!TvFSRy-ZOJ-*L@UT-7Rm)lZX>f7E9HKn!3M-S$80 zv*qDGysz@!>H-?7o($8&a9{?upxNAGL43uK~DA-?Bk5e+tt z&=bcjyjg!aSO0kIccpbJzQ^9Dce(aoKlMfs+|@L9&s|4hqbL4>DDUf3#1mTtd&hZm z`%4ryk`c~6{Ox@uxfMluU%Ay)CwoxX=(qRv?$?`}tJ5I++P`^U3-yqMPOIU#9Ed_) zEWVvz*yu{{*};l1Oor??HuBwBi=oX72XbO?qpioHyss=_WE3;&aRR0lfLO}zov=hf z9{(5q98v;u@@$*NRuRORUfKY84rgm$HL*%7GEHUf&Gf_+-6`)g8z_)kpK&-YL)50y z6lM_uE>*2fuiWx9<4WJk@qAlJnd&9wWQp>=O2ShDZ??z6ST4A^+@*3el!XvZ$fwM`hhxxF0KC~S0iX3==tjfcWUhazsx25ZoR79Hn1&LztpbFOV) zGF=bbvD@W2I`*ruJvxuxf}Vg|2z?F|b;ey?YHuz;dO3$zpg*utA1<}IOFyCbkJ&b2 zmEhf4G9$O+L2;d$>4!gT$Lrr#2L8fEuBCD#7@Vf0*jR&c4ZTdS?+GgkPW}xWnPPQx zp|H^t4)wpVk%%Dy|H0V@Z57`08GR%7^I2oZ+VeSczk~C6>logP1-mTwi$$l3+KVN( z)`N?Wo3Rm$_VY4V}86c&-(4wGsZU_u)lw z@`IpBsiXYM*TJ8Uzpq~g|GfEe2UA9#=!UW4j1zdi_C(~SkrC~CD-4}sJ5Yvz33=xC z8l(JeAl9-KHW3%E#;fFT>?Ug`0bF^a7B>j+USX4laW}f5c4XhR<_{`#Ox?U>rgKP< z3yaeO#+>Bvy;B#%&Gg1J2!g`sJ=FpqI34XyA-SCk|9o9F)ow737>E z<9-!`2|n)Ur&0-Uq6dS>WR-*qIO9F^HR(F3{}~&F5tcIHs1D21oxq^~Q|~M4YTa>? zQJ+wD℞Ebm=6sZM=-nZ)D8!<|L~Zb+wLB9k-=Bg%6|jS=Pw7gVbsER6@B(h3Y#O z)6<-V@p7@&k#`<}r@5^vQu8Adz8$CeM+p`8w^b(tmre_=Q2Ok0 zL~}Ca=JW-C2qBB3HU*(OE5v<-kf$D)M%_CMA?dt+ zWfCwJcGb`Azl}jxB`dtdKoDPBOZ~5XG6Kz1V<3~# zt4|Q)(WU94-%o5=B&M%{G?M{rynGg$d;XU(=s2!J%kfis_REOrykvD0nHS^Mt@S_s zUQ%4g%*se?$~`!To%vxgf+Orn8Tqv?J9$xP9GqUNA(;ZPXG(W0%E-06zn=MX1J z6FVb;kuqkekEx6hAK(Ffu>*K~z4*;vx$$l~iab zGx~zaZn7B1-3aCxs7kZtga=sbb$ISjRq3tUWJ^-;`UmS2{{_PMGY4x@jD<8$)ea!l zr5veTAy@uxz8IRjRRwx#ChL@ph?AmuQRLDtu3ZeIVsipzsFIdpOv;1u3YBfSU}f+_ zscI#>{mO$@ZTI(87|0(H6%iLR@8h04mlKD<1~8iCKN;E5b=Iq} zyxeb4$EUdVMD%`AsLIK0`feVZTjXzLi^iEg(0Bj{su{IRIr%ci!#;lYfz76ZB~|%S z{V5#Z7`{MJbG_9J$JM@}PZS}eaDQF=Nf^j2_YLbTU3-YPRR>3%sj<-D(#%DgNe|ib z^v<2hc$ZLH5=>0MB+IQED1hGrXlo9Yyi^cV5*hpgx6+S()0^7m_xxIhOKPa4K2aMz zL&~gDu7!qomkN;MK{d3P&(a%+!Z)__mjPxLQndBz$CIZo*B9fgzTqd>n%Wa!hFxJx8cjv&I-ueO%$t0{ zmp@xDBrM6U(%Yw+Vt3jqc&|(e02l1+a{1MMNSNhWdh~02Q%}~9(plR*XDmH1m*BY6 zRk@H2$^iy-+xQ!%eZqz)fv6pbKthqi{#K>-w3~LR(ED!lH!_fge$l?Zgd!xxHf3yk zmHvf)Dh!(?3Vrk_R$F8ELUB;qTE$WArgKb6)6TGj%+Ot&AY=!Qz zWKgF0=oj%FXU=8CzL^Vfwi*_tZQ^p#mj1 z`j8nP_XE;uOCRS|r|C^99r_?awkox(krR0p}xlwpg5z?yFTGv8-r?ty-@lq`ZmqU`7R zAhf|{FqNm8^*Me>^`gox@t2H>*gC8fu~iLH=f<9;cz^wydP+Q(9%p-kkgsRj#C}(U zzCwDd94%$}sI_DUxgEu}bYOxDG1h%`S z0<){z@mZUM*iQ&ff z$dZGGr`~*Gj}=E2Zo*XBtQ-!+8}^@?mOC;~>!!ITy&gT!xn*1J6LL-hcKXb&Vjzwm zU|M}A;+cswF);;c;I|iK>8seh2q21TH?K{u-)`%C#xD4h;wz;mf1VrS=h)(Bmcc6) zk%c^=R!S}hN>JAfz7?>P5tLIY8k*ARCa7rt;QMK1(VUt0x45U8So%hl_AWTtrrH<2 z5^^F=BA;o7S%&R!YbdDz5!8fBdxutvQ;Hv~X=^Fnk)!2GwrXDXcU@;0ldtvUDcvTP zmM6p~nJ4^+tHKx1;WTm@?NOr@yGix{AxHdS^~0TV>DjN^p@DL7IAQTt1L6>u_I&Gt zvnW;OLUi5{4nPoxY1#>gkP zXKHAY^_93XbABF4ZPCy7?H~3SwyCnBPfq;gOTIZ3sQb7~9MT^4FnBF@?CK%mk)mnR znjmZUrHR}k)w`TMr&O10?mU`8WzM3#V4_yW_H`txwDaf5B&JgLmrecINuKne7)vJf zbu#XL}8W4x!O*O$qiXDOAZEldIQlwl8=NxS@jF09rYj-EL~p;~C%W%BqKtio7M zWPaOWG`N%n=)5K$D0Q_-T2x5s-n-pogmbi!^S$NJ)t1Ui6;SG@qSMi*_J@ezlACV< z&5lU)!l>};A!Kd5qBN1o;S6raI=Z&r=5pThZIPPOpu;AJL4^(d8ds8$r-px&qz#8G zrh5z~g}I|Ab6C`aX^`ov7(^)W&YF{LTeQqH(~u9DYibx(c%++g4B=B5Z#ZdLm?}q` zmM;yh)m02c0;-jQm8t|q!Bmtn=>1bQL*y_NCP5k56bS^zdY}bl{x$|lLSpm&Fa~h} z*(BohNul43;>z3NKxr{GC}R*5dMH3cMDyDi1SRE$#do!l*(}8O{;?WBBOYg*@Yia< zD;lf`nnb<`&MVHuIse2zRs(F=NtRKo0Soa}z@#t6Nn1{ov;Myj*#5%*7xu~Yzs8y_ zW>}&S7;UC)0OePSKljPnGu;;dX`hVVJmCKV0xJ*5L1gDtwdd3<=G0y1)YIlRNai+~ z!Ho-{}X`?XXlN!=Z!DsO7VsTo+PX^f(ej1wfyI10mFZ-NB(FS)S)Cy2mBNAk&6oyW}oItGWT1Llqx3O&uOwv{uNY!`7wb1DekD%fQ@Z)FS7#ct&|RF3=^cb;?J{wwah{et!OkGL~JM~a~ep&t8pfw@XIOm zJMR3og4_Zh6?ayit?d6?#+EvR{enL5gbVpfIjeB)@ zWM4Vr=f3wI7TeozoccFTp;gpL{tx7{Q;u>9O?Zi;{X#z9{!6D&A1-Ij5eoVIatf*3 zJ076;g?wlnYmVR2`~44`Lie%py#v}Mz1L%vNLKQv2!0m-EAsi=S^NQXyKw#&@)4`o zB%irha_&CJkWqbOVX@-7U3>W{_!9Y!|5FGK-_>g5-;s~_;njaYJ{D+6H@i=S-UXV~ zz2?i7X>pp@+{a3J@4Js&bv&6?J}z~e z)&xaJTF0~5xt$Pjw-EA&TtuDM-JZE(y;cGpebB_WF8!f^9c0(^3~60Dj?_X<3NwCR zGI|}_1fkf$dx5dbS+MTjPetP0do_Ie+K~R6|ED`lrmOSPS9o^hd(KfZb04CSc%=;I zu7ejX^;jp({ZwB-1=t_F`nJ1k{V-@#rkq-1$=_)U0?*b+Iw&_fng4G)h5jERpPq84 zVoCw12tBNh-HAiB+Fln|5gxNl=Dm_@FF%l`YN4#8Z%K&z_vZ`<2m*wneZoIJXF4fnVkwIaN@{xL>LYG0flXDj)qfPGx+>yn zW~8zRx76sD>vmOHjJ4FF@X9PlhFY9{b;sk3Vs`&ihvnD5@ybGNB(EKL?z`M32bFr^ zKC0giqcOPPoJJfqzlp9|MY#{afSAXgq z`$OmOUUd0Q=P!aC@Fuf+;p)VDAiA^Q-cOIb5@10sW97obU zsP={{BemG)x%%%7b2a9ZcrmEp`96DWRxqX`Ys*H_$bleju(V+vNTGinrEWtb@*s7y-J?3~5y zD=Ft&Wh+QWZP+0dJF?sfz@fKHCHC)RZiDTnV_GC=ey#7&4J$9}r7&8~3q_E{=Chfr zP2GDebl7CoLI0+brjx3o#>=G?S3e75r3I(1gm|jyC;_o{b`;aHf<@N{!r>LM89`IS z)+|e{^467#HQdb=IT1ge(l1&{-J3uaa@*O>%!^OKBuK2KI^qS^HVj^pbn8+8AqAHn6qN}!&VSxAU;Z3LuvNe3 zFKDi2c=0rg zR_A(JYJqBScLn8N4|jhpL*DZJJi|e|2JMw%#u$(LGE3?$W2|gU*_igYOP}w&Aie|f zO>wwtSz5c01mg969`$_!5^2! z)gyfTS$UpwkD_crs6<=pm+dp#d06L_a$!-iy>fyY38q=F zg=-J%ba>fc1sXPdYK)>HV{?8vZa+xTR4bSfYi?)CEO)f- zI=DO`V{3p;CuEy%&*=+h`OTjVtUx&yJMS=EChjExSP(v@a;`O(Gy{fqbYw$uH(KIY zdNB<1K9+(1s|+y$u{?YO{ydsT-2P1Pl!4x_?vUkW`Oj&<(4Mhe9;G`Ed6zn}Ba?!2 zVd%iBYv3^M{@n{tTg{)2cWj8K3aL^wdcAi5W`v5xv^uhK9Q8APs_dG&Bf}->TYN#w z{WS)nct%(ab9I&kf_Cgg+?jr)m8RpA#JyE!p)v4R6J^!7hz zO8W#+6^)#84T1;8g01=L!yO`Sx1F#;^cEJy?#w&2Ib`hC7pA1-YyIn0v|*If4HZgv zg=KtcMv(Gc)+Xb&rVQF~3pYtEY$>}+lIQV3UA|2AN40$JcR=W0TZ%@bGNe}IS;Hvj z8-x-)__DuqYqs?>bjY~%HGNk*93724^u)S563O8qqUTai4q z!uMS=H^7@}3=cWeaE-p#74f+g7nt?A`sDRbZEIvPyYw)t$346rhcV_>3}jkU^^@ z;IeQRMh%&{k8d|3TW9J))c@Ai#GvxEe_dv__-eQaNz22ehRuHZYVO?Y5$%wjv~vl2 zL6TZzKc3CwoQKVJyn8L9IHY$OFYh~w;}Dja&9S_aKx-7eW16f*^`e0Ek^MuQN9a+m z>vHwWb-XXy-(mI%XEWpr4PTfr64bB`*ayUS6Px^>F*M^mL%0*@#s z+sr`VbWv{Cw(?|-3&{Ie_DC9bTh+m26n$tPx+30iuauEePlz#be7}*smz!7Ew-*zy z&w#p<$+PZaR7|g43I851DLb^q59Bd(051~Dpp2)l-|>Ax91=}wD((I8Gt&Gie3LsE4{?%$Xf$yv`;c-(yV3)Tr)$@t#Wn!aXCqa?pPQ=gSsv?IT zEM#A0ucyUH)2w*=ogOMvv!sqdBf>7M@WLVIL%z&bf}sOXCF!%#(_+U#s)roy(^(8dHw@hmfy4G3ywaWN!k8zyeEHY~aL<~5e zWK4E#i6deC&u&i(NxFAbv~J$#-ku?}x_6BxZ{|90QI?YKeMhbDOCN79+9taX{U*PE z`hI)aOVWd^XZo>z2YEHD)pN2|9KI=yyq-$#c|O4ObJr~N$=#liW~J4zEm!3CRg%}p ztD(?9Yzb?$FIul}Vxw-)JCQ$+l3)MW)UJs%UHok$$H zr%c#UEiG<_!;xO^eL^{%L$`t0O3vmBF8k3@mM4)0SCPUCN)Ap@O5kYLhGhFJoiu@R$G^7O8aoNdL!@-p~jzFxnUz0fojR{h=hYz8p3Y;aoH| z3Qys~z>hPGlHwFuhOyVv%Kq4KhI)1(;5Z*LKb9081eg;}?db0Z1aLSKGRM|JS<{^) z07qga{;sXYti}UQu3~m390?EyAj%oliExlGw5qy_Ctz`H0jj)$yP)f^jUW<&ohW>; z6J1_OI$xNF7Ms~k5vy!~u*lgk+3!CRl*60_PVOX%3MHzd3F8ScIg!x?%?Q!3P(31j zb^>M9H3n`W%xYnnm=F$}bs^qH78Ia@rTY(4!7SvH2R|e$$x|&rd5VfORX(sDfm4W2 z;)q0&TyA-X4FU~Op=ml^N}jt9z`Hk+mxT2 zk(dcUgN$7>187xFNoZKG>H;2Oobg6P=#$_v87SiywJYW?VG0AMF?qAR>n97Ui5Dca-!Jj`_00A)3|nX5@mfUcNxo4RFDe_3DX*=+}_d|F)`$K-O?r%Kdc++gj%x9GK1#D`I#hnG0 zvFj~g{l!5(aF{kjR^$(yjOHz%cx-F38i`J8DC>*=GzEI|tIzVgm0Ndhq0KC@7-VWi zB@}0sJFNDB?&|&4qnk_kjP0%={83gy0K2XHC@aGRK8iE+OIpJDynumc$q z(Ue8&m)n<|w7rE_ z6b!$%J9G&S1JWSi(B0kL-3nPCFOpv6BgGj&dmm#%m ztW-&X4x39QLSx5rQgGPqOuTX0+ADH`&wYM&2rHVJe&q0jcyV#J^iM({$KPmZw)@ zl*T6q5N%vh2Oul9Z8e>!TI}^0NuQUAyU-ShgFxV!J;`U5SRK>iOyjd+M!vwAX>98_ z*LF7?8N{qwm$0AuJghqeCWJOsrJ)fFd~s~W2$+z@x91fDL`$u1xq zd*=CZr`Xt0bFBU^i#>4$L{DD3R&n~`vckXE53-#D6vnO-UEU|EPhVhTG)?D=#knDB z!f+|A7C4a&j8YM0KL<$qKb3-wJ8d4u?RMsk5Z7t7KL*DZtSgdM%-VJBkC0yau1j3} zslxXv>O$!@@V()b3`f*}C&DCtb$^#tJzgqmxc8=YZ@D}%DZ@_hu(i6SEhu{LAdwsJ zt>EBSP3Kq9Y*-7v9R&bvE;N`lVAA}6r)A#?R}t7Gcux)eT-XCU?KPtYNAiz}5bO)(v*o|aTLRI$Lf#y9_jA`vhm>rP$lvAPlwVfzNmy`tbj1|CUA4y!Vh z5&v``sH6+PqhqdMp-RQ4?`t~}m9VGfNcNuu@Oh1dou4TVLW;ih?Bsr&ITw-#GZ>QD zmk%vF1r2-j;3to9@h7rL>0+xp4_$F~0yRn)-jzvM3BU|%@S`)o>8_xc6Vx=xRKMaH zp?~BW2z>>unERc`ZWRk};bx6s%=w6q&(0D>+$7*nJxJsuAlF0_D`CFAa)hV=qmyA^ zk*LcHN+h5ptEiL9eFbv>UFihxMOJ|CurqG66lP7{#K;#GVbkf+gP&K4$vMw2MN}-)r}klzuTAGtbCN;G`OvkU%H2%8aPteB)8F_= zTpnZ&_nMT}wx!P5&5@cOTIp3WYazcIBE>n-+DAm*UXIYxgHbh@+@0j?5H86PX9zuN z!<2z4;V{H;20PsZ5Rfk8jV`S3?b6A-U$)G&GrYX!Clxqj0ZbX5yyf29kdY&6&um6L z>~$fzjj+fg7k=A^z$bcah^F~*jpcxGD~$O)Ym0@klSPB9^<;d&H!jY(OEKYXrod~? z?iI_@{3nbCor(3@CIxdJsNDK8`c; z;uTO`%sgaS@IlMeXj)T{ig@hh{Jg`)Zw34^gQqt^MZH3V%KH{;m-kA1^_L|>4I07O zjOU-3%MGKI%`NzQqq3tqLn^U58e|q%#hj}g48>=N^@Kx#yBW4*elW5vC0~mY+vG^5 zDQX#cGrv~?-Vv#4h~OOKF?+)1gAT5kEaqE^Z87=!UcC!NCQFi*5XtmGr%3gbwhr8p zS0HM`Sx$~$B}pRc;Y4$X`y0=`d}qj(1dSmWE9r%Hlqhz3Mq|!A?!vBKxU-*T@**3f zzA-|f_trj~Oj%tDWp|Hhwl6NNowvW*YGYoVg?t=S=zDg;cSRuK7IVK}`F)f>PmN#y z^tdnJ-Rp}Q3JA%I1{$_mj%8l76NNsu+maAMv-wmP-A+1o#a1GyMWm%Kk_)j#QukXzhkyO@&Dgm)x5azyr%Q0>ooo$NnVG$x_jRTc#^iy2?Ga%y z(Bx8-lno$=CLVat;T-XWt=1hgmW$e5!B7KL)1~(`n0kFK62(mpPNV+%`1T-^dS+_N zHukpZ1ZBASLs0rj&V*(y?z=mxaOUiz6NOZ!tb{u;T;RCRADaYqc}oFHl)~DJ4{`Fb zdR&A=wGGcHy7oWCBRp1Ity$y^7(Z(-T#L$lnZbU>-FXn@Pl^yQ)B)pYbO|ShE_?hK z%95|YxYWBFBDnI&c^G)kr#gMMdMu@1p>n?P^enD(`F`^bS=;pNjisNpmu9ID?*Q?g zlrotXiwrd_HII#UgzloI19Bu`^gL#bxV-)@X19feD6J)mG-ldxphK@2Mj2&RGz48n zy1T#ypI0D52B^9Rpc+sd)dtt2zCDQ4M%=PTm-0Pz!Mb+As&SDtm_f}MljZ*2~J^ztjVT6xOBa@VXXR?tr72b zq0ycE6qiYcrTxLiaDz%6>WE>WlpYZ74lL5Ax6}$|NJi%H03PrFJC{8TNbIh;2fJA&i5P;UIM}1R6Q1OflO#;-! z$-z`kiEB->1bZbNlj0OTpvjf6p_@*SGeDhoJd<@}qv;0464m2^^xfo3W5m{dJW~&B}GEtXE9F} z#T?wMB9VA=lf;II($)!Zb)IQsW4L*Ka8jE!rRFzKY2xJu<4Na4#HhpNaq?}DLMdtw zSX+7H40$M{iz9qSB(2($Bwxr>M2|MY^l-%7(@)e--`s(Ug6NPqf)<)r^Nb21(zgWf z5UDWM_XF>nSegl9$uk8Id^ND|`H=c04KzLu7LsqeIaH*pn? zD@&9KsI>-Dj#Gtm$w z)Q;RfRgw%h)@_BE$_)q{s5b3;4=eI;dylK6r>oFYsn~|Qgj%Q5=3fWPJilKKlL5DcaW80#m**O3kACh+*W|% zc?Hpu{af)0VDNQ=6jQG9YP0G1%lH8*TjrMNY^K-bKziR~&!i+vs)TgVB8z3VX<0^~ z(PHD@`eG@!qAv?Ld5_jyV5JklQz(S{JBE5jnW6AQMrf1Mca7fhNQ&Kt&c3#@~a9@*sX&f9j9$6iXZ zzWq>kCZ@jc2UN~leY9PD%xirzTMekaWvs&e+{XR90sZ_r{emwgi);N?n$4nQ1Cqi6 z<|vJTTzP4Y;sn3a?W^iAz*STXL6-$a&2vL<8gA6Y-(G0YS(ybKVa%GXX?0X>WAY5`h(5S z9D&*sATObExmC}30E_M#r6E@LALgdJc;8=S)5s>%sDabyxzm{4)34U2ah|3{Ii>~c zzXGv!Z9x)@#xo@AL&%*o6i(yFH!~_1Q@@1E@L6W*sb^4K8_ynXeD`NrObp2rW^Wz~ zX3;s!gCkr#Wxi!eNiSQzj`9ZbPJUz5q+4xp>P6&4R-W7Kokij`4w)f0;`J|*QGAdn z;q05c4ON#Jn16Eo*ePhEpD<5XJ>R!AhoNDJEay`3K%SR1&*HRj?b_5Yxfp}ExIU#WRosUu%)5Ls<9S#1eiZOdKl=w9twU;Xm5 z+C#q9C$ctRvNjaBHj=wG*1a~dzBcu=Hch@hE3!UkvcB+?P8_(N|6dM5tS<*46~w)N zRBw|1kJX#?g@bYbQN77Q`+tJ^T8z;DbP%E&ND_T3z`!u|O`cgL@^Qv2H!N`+>wlcB`VMB#~AB3`Zmm|DR2-ce5Hxk4D zI0yw$E%zgSrKN4=b~rznE)w&isoThmY{%v#%xuXwJNi2d6}(d6(ZAEd)=J%MjYq5* z8!7}7`}-gyWVFormHo!TXyUvDg;;ashCJvc3q`4Rh!LUdi__Hj*%0~V0UP$B&?%5E zVutHU`B1fHxvy2rDTW|_kog|P+%i&#zjprK*bC>!;#dL>Y!471oZM?mQV_7~ zz~uGvN&bjXkS3w^V}t@ag3z|%r&&V_jMY55TG1t(Ek7)@TowSDfdUv{hCekjVJz2= z$rQT!TV)Iqj+n^B1@YbF>y9Nc*Y0Kq8hD9jo4xX1gD0wNnni`hn5fn-1M~ z`s!T(zDu=EaLv$p%Gu8jnf`ZjFRlvmZdw#)2RAx((j4tJcB#Fm(H!@jm8J5JqSv|% z4LC*2m(y4YImivh6J3T3Asxp(A=!ZF2ua?)Y#n#92Vzb*_%FrFMRe;bU{ySUyrTs2 z4!W5$mC}~2B%EW>F5>+{yiS_PMaj*GMELX1*6D0>0nV>Tt`p9NZ^YK8Kdb+KIPatb z9l9?DK0Dp@8(n(xN(f*zaWRYpIpp+u?A-rIaXjtzZpdh@0k)U?rV*?;TF~D~;7a*v z;&*mB!qxd}WzF5W7G&0NG9pza5V@-0&mnDTs?+G6t^5~7v*R`G=GQd3UxDS~)JnXG z*z1PV^2KY-MNJ*a1!iXm4Sc^JO@f_+Tg3UVtyAq+f-3JYM->rMr(>0ui?DZhlFs}F zDCW--Ja6LiPj@d{c%0DmC{FYx%%!P_tQE!h9M)o#o0<_k6N1*`%;O#lxf7sH8UP}B z|0Vp|tF%JwP&{;iSDO?+xeDkfE;{z}=rBL5dl;chz@k92tdI7?ku5l!gt)jZl5?)k z!U~WzSVarGc||X9%!FQISRhT8b*`;mJa>(_DA~UogHM9!Ja&a^*l0)GD?RK>86I= zoFd4%_EXumJauD)9h2nGl-%yg4y}-a63X44t@=BZA7sGc`JNMrvkDo@Ik(0qh>BPo zH|~pzw9-(}U6qq_yz88XWO;5w9?+X0v%uzrZ<)C2gkHgcl4Xeu1~)M--`m>Jx}1HFB2xJKPTb}qf|EiE zVe-v5lKJp>kb2k;eMRjf$3ch3ivw}>#u*Utw~V6-G)V)2u|Bv=q0A&>n6$QP=xyPf z=CWvxH}q7x(`VfKS~$dkJb2X|Y5eEML~;jN6xm1iLD@v%^o!wI6ZkkD`hk_^?{_rA zZ{?`$*Rv3-QCU>i4@DFl)FA#`D6}}&4Z#*TOd&fT`$5P&LD+L<4!X*+En#n{Jj5BQ zY?{evF&pdN#F;TJGIKs}F;){#(%WG{8FHWO)Ghlc7^-Y#5C^Z@B3$LLi5FSDZ;!m1 z8$NlcI4oA&CmRNjQMs8w)?fNlL8t;C(EHnB&L4aBKV1f0q;x6tnhM)QW=RoqzoDW5 zTjk*Fr(QR!1XePm>Cenq=n+|*RmO0YEkm!GsK%Qu_;*qxVn&VFeSFRmRgRB~k~-k0sKfPLYAAwh3`5E?eNRHk9 z1hhV|RUjmOAoS5sDeNZ<6%QFbLP$4&)oc> z>hCdlRb|+?>7(%{sG)wVH#oT6q{xAZ1gS`tx=p@eF^76Ent*qk=viY^`pp;_rw) z@4xyd+l~>mWImRX&02)w|8+Cs?2*z@0UQVaqQ-EvOv%%i|$hj1LN@@3-QAeUjPUa8|vg0+jsYlbq^O@b@QqB`na*E%>GIag;*{ z{pFMF6LPQ^f|h9x90}H5G{JlMBtwIKX8aGIWL7tS`hOTaS#QJGiNZPg!@2dtd40n9 zGsAbAShh>TMQ_7zzB!BkyTLOvLb2^X89ezTwe=%)eIoTU|1Sp554TY+|JmS~8SU2= z9k3J~^kVQNg1&(I|1@|)Goi6B2G1pE;`}WXMile^#^5PWBbmJ&8@6Ka;&HgCzY^TT%JNsZVO z4(Lh$s&hCYB0cg^{WX$!hev%OPnt-D(CGHDK!ZeKT54wCV{#~QXewa-9jqSLUBMiy z4+@JYU_f?Dz_}y7&i{xxDSvqh_S~u2gTg?` z;M=i(PP$_+KG<9&O`JdLDoiht)GzM;YP`xT9&+eLQZ`X>UO03mBapw>88XHj$hutH4}YS@ev`sE*y)QN0Er>M-fH^dCp zE6XJQ-rp`*a9V6z{kr~cyn2uNY~bTnWgBzdC%ClE>gO0*jT}qRE!6eGOkRY?$9He0 z-{dUsEE9|lqGdVa(3g@iEGS5%x!lXVAmH~5l+#wpxYC=_&t-aMVUQd&b13A;5P9U^ zsee}(O)sgJ_7&kK+p^QlSi(YR3$ZE9%cSee^fv+?0pBAHo=dX@0cZ*iETD)<{NMc# zFg(C8>Aw+hrB9a`_>g$XX?IKjEDPy9=Ul2OO;ig-I8~JHws>~tK4H4?-;GzSce0?+ zs-?(9x1ij%X;sv10_sprNda3O**`-E#i=9^TR0BGW+6Uua-Sm0xj`1Wbjz-`RrZ2N z+NL<>hwYx+5{qZXld2}ph^;8Z5gHIQJ7;`-NtIMb@K!6OnOAA6K|}CF z9g)_ql|rIZ_93qldl`boVD;nLEUdy(=`?4yq>}Y>_Z^(PwMv!`$k4ZNG_87-O2k@; zy6$7;`0HwbG~$FnnJfjB3whx490vD#0?rZ*tQkl79OfZ_IWSgp?)if)P{;1jybqi~ zmgkJu@1W-odj9}Z6}+-FmH0{gz|p~@2>LWCd?QQ-K+cYvVIdk1&?_US(?1ULu~_^b zCo1Q(3Lpor{^Z5%IhVb0PBZxny?V}e*jjU%D#LMK@|#JMR$|xH2+KF6 z=>6kwtE11E*Wa10nvA7u0IC|KaPT3g^!dEd(Beh!d-vU?7^VDhN79$nzmb6)kj^`) zPaz=u?Et1k#Wlflf-7P1VrzBCQ0sD#`%CIyUIT@#_30>0{RpQu!{h_IKdpMS^>Wc# zp>;M?;B;EOsiOf%ThkxzngE>X@G$zOKK2!X* zj-1Djp~W-`+CRGa^_MJ$kCD#3RC9O}j;NZzdL1e#tqjb@aamw;_eZW5(`%P6sh3#B zt51UdY0TgHPHw}eh}rt*L>RrYg>=aDXGE4$DhK;bw!GvNFCsQJKZT93CM|kvY_JMr z1V!F+SZ4CkZCJS6oPtTdM^VE31TAjd_a4OtW=ha`te!BI4tOXBb*PR(t2c2SN>lpy z=~uM=i!722)W_R$PCL|)fK-Cl+HUe8!AIE&d4DgY&y_X;2O081vWPNRC0f>eP4yFE zCSYavJc*!+TsjC>QZbB8Bd3FO+!jBb`1mVWH=>w+X7Q~U=WxPo!B$afN$Vh)n(s4} z!b=aGLH4+hCdUOtBS&E7>g*5@I3HQ%&L+KCnRbO=1|H=z6i2{Q2MCx*bml0d=ql!u-~CBOt{bhA z>q;uuoRNKT%Jr1LcTGeZW1kOQ>l4e~lnk@qZ&FUQqqNS{M95HFP#~{+Q<6iZ8pjaH zTg9lK4K)fjocXM|T!`RZ=gbC>X>hd8|f~{<)PS!loccc16q^J z3{8GBn4LsoZ1_+n=?fx&KHON%qAY-a$O0KVLr364c;(~WHZ|$64xHXN3fC44RAX>c zOPo!SdIb-Q7-^TC`t4oD2g4Sk?ALMy0HV^YFz|kNj@{K{`8%$XJ?lJ67h{KDx`KmLb2WOCQ(8zGB7@FjXKRnqw~eSdAF1A__;$3Z zv+-9R)II08W7Bi_QAUqUcP&t+l17M8C`ehKIj+w`p-ecH^Qj8qAX)_x0<$hRe8D{JiDM?KAM3GnQP2 zYR-Dap3*7L%(<=;^Y@cAmK4_wjY9+sV)84KQ`aq>Pd{CpZ~L&ruG&_gPJP&xE9G)- zzC1krYQ*H)L{q!%b1o-$=j+tu?-5e zh7R{i3^vAOE&Uxy%_EBa42>BofC^GkX7kGlP*IXa#8&yl<`TU$<;2z9V$Dj#4p7DB zF7dm<<8t^JEfHdipmDYJvE09v+*2u#>QV9}^gMV7C{byB5SWY2K`$lJW4F*z`FAC9 z@l{)KWKB%p3-yr@Xh#p(J@*)^%@a0#+&7@aYxD$VnTAIaY;jORK57(!bVDv_)X9+V=`)E}#Sz~^nf4CZmqUFP3Sg&DSgJ+*YG#r;J|p`M;4ky|N*~?4 zEtcN0_!0di0tI5sJMO-v7+$%gtjy#}4cKy7{No`pFWpg6IXopV$#K0b;gKJP_`0qVW z|7J99w1?mSdi&{LIv3_XT^vKtG|AcgRIp@ZR<6?D@kzFsmXi*Yn(($@w5$Q8wmN-H z93W{)r;JslipjG=5^T5Hx=jHDHkfF?&~8Fp9ecAh)o2%5Jo5Np{fosKBZb3(BCw<7 zXD)OmOjf=jt$H=eDCz$FR|)Hhnk`x%kvf*MgK0fR)@T5J8wH zy;C5A8goJe6OSIBEH#gpFGSyxRH9wh^fOE9HL+TADqKzk!DS25XuRwSQ_LmhFoWr$cTtM?Lz!G9OOb5GmQZ|N2&d#eFB{iOK|VBl8RLK362Pp1f0}o0d=7|+Llow z91qM*f({%=aRnZ^+;U+jM#h2_Kr~`KHq8@C33&bG$i}kEUS2k(38C_*`cICg$Q*1t zVuut3nBs9PIIz>Uc2%&6!szzsYPBI&7xF{gS#{sW{!wtOHWiV0<+O+M4L!^;@IDe) zZi{WJ9#kamv*Z17&jDmqjHrAj*_hTD>4I&BmQ`ijv7%^Yl{iXXl08zcKgMXLv^m86 z*W3n_{CmK(ZH(yLXYphYy3pKg%hJsJ%qau+Vi%FjRq>@XubFN{mKBqsXVsfuO?0e3 zc@(8_J^@N@)7JHdF;o^+gHY>Ni2w?Z+da+)M#)f{rHpFSn3r zb1B$N-8hw~Wl>1U#uHfjLfI38owN5j!3LJ8FZ6k-!g5SColGyv43O%(5ttPfZ-e_4sPz- zABz^`VTMgEl%t(_;@}XXQ^;3-v!YiLo7^x>NW`0KXncA^_~#3JHAra0_GL|auhhL8 zWp>-Pb5Ma;Xk7_`tkA02<2B3k47+*Q9aiMZEEDjJmTyD<%YBmiFSvzDDiIZ}>&AfG z<0O;)FC>fL%;j-23eKc!bQ6vpyQV+#l;{JDtMzA%&no1S<0`@9i6nbR(yj639OCSd z$)RgXQ;btpbYk1*LcVT2p7W1iM(Ia>r%DL6U%-01j3F&hfh|Y$Tn8mPOW^@cgsE~f z)FeY3rDSeF1`oSB0YZKjO|tH@70qX+_bmCudSCv_-ggDv6{__DG*0mS%s2V4p;tuW#I4qKNw0N8 zsA*Is8#nB}C5ZR(+nAc95MvyJq_nkI|eyJ~*>$%T0al&KQVd2rUNonLc<5wtnSndKGaF_-3Aj;Bz>XwoikCG!(A5R4Vip)voYw}xF%deB9MJZ7fsPdOkb zcCCTUxo5kb8=rsSoCfkb8t^oK&na62Mda-m&;d|0cY?$^D@%_AzD= zfz&e2Zz*{>^Q29qpohEq{p zynUa*mqxzly8gy!_COyvYf~asSlhLS(M@RhRUZ=Nu>WdL8myf)5WN|iEjioa?lNR# zbVTy4!NVQMx)w;8Q#bewxy~bIc(lTj^qbsr4(9pUeI!^j@}`(?iE+#So15|}ro(X= z+yY@P&WuJ-Y0qYSn_5&(Olg+O?LDwY8;EKC+B(F)K@Te=1G$0DzcnM2cDsYsB8SAg`A84VOJz-jj3Kyc30aAnxtm=frZ1`rxS8FLkb zpb{!ldiq8h>&psP1B0D8QBbAAcy{cGTGZT;eZ#kCSZR1a6^LeS+0Y}A2p{m9xx4d$ zJfxa|c$)w`N|f*nOH6bBn@D2J9%Y4Q`h-5En{aaMHcn?Be@s9m_XUTxR~Qm5|4ce% z(E#ur6i7PkPV)?=>!7kmMW9k-N2nhbPYo3vt4I0BhhkiZ@;TF^V@4yp$9YGCr`5_U zgrA)*OjFMzN)}F2!$FK(4`uQW6hc!zo#Vm`^(HH{1{wjR(?#NbwK}6JApzhx!C(5@#M7LipYhLn2=P_W97K zk$}L|;x3p<nL~@Fg=x1aa3VahIKo~MRCZ_r8(TQ7n*c5Y zAheX?#b``Hbdi`b7Z%hgO`J+5bm%O->ujZo%GjFphEuezpXBoaMUG8E^`@&XEzDIS zE`-Vjzuxs*blfT@M_!Q^s~uUxdunk`M^p{k!4!H8PLAVrp6((6#Zk(~B&B`ac=ASb zIv{A&LCv}=GE8yd{b6i;J=TXYuVzp7CRCg_sYVpuNJ%R0#UbECR^fyF6LfodZ{$?&jcdT>0xa1}Z^l66Yo8bArz=iS;C=#i=98wk~N#n%ib@deD06@>MdPfFP zvAIYbC#vF}A-9b(a<47a2Y2#P5O>g?)gYY)@e@WbYeHs$&W-Zdw$G2t8eN(!>j>UU zhpt!BOoSz-!?Th#xVWjU)XVjLS(@28sQ@2uEG&9pjWj5kn>T%q^LGYkGJ{lFF^yYT zymb$TTss?F3v&svaHb$5-^Pr2S6kbFue^YuJWY5JVrF)Z1!=`?YBNWn;!*T+B}Fn; zC)UDI$HXq9B-8f1{mnMiu1Ma&`p`gcLJ3r&gij{{D$d!fdKmB{$P2;?N9W&+KBLH|V(+k{ovW>6a5mw~Tng4+ zGuGZ>mX=Iolx$+W5wHGQk5Y*%xNwMNqz$~Xc#S$PiP2e?Aw_O`fonx zd_7sTX=ARlM*ux*tPTSpAfNR%*6qBaDd!U>9EmeW9Wz%QHJ7s4W)p*^vZ1AbWT8wx zV+RYp7fukotan3Lh5Cwat(P1DCXDe-5qVrXK$Ez(WM~#YA1osg{M&Yo zhxTB_u95-*OyZY5Pf=_H2CW^&%0qsPIyP1!Cf#=^_~Ixg>L@1D7&vF8s5wzTjJgI~ zyH-|v&yN|O=)sw{bno7fXZMBE8XVgfye z(qe1|A}2K4O~1A9Jf2@g+>OxX3=4@4`0>68ReJnKcH>cigZ z_a!4B?4w5LH#vx=DGG69n`lAX`oP$m7Mh*v9_AtG0@VEhfYJ?T2orvz^}|{im1rZ( z2JofF4;Y|j^K^iO2BHwRVi4=cP(yv9G-Hqo5b9r%W!D+}DB!!ULm}@2EeV-?i~~jd z(ELsZtospCbQ3lCNanUh3WOxK04cu2;}+MA;Mb2^xCy)6BqT|J2;@=n1g0#gQJ{m7 z4D^9aTT@lCU+;xYuxL?|QUNi^K}-_;v~vTj5&&e0K9rx}j~vl<5~#n0rk0Io()ehD zI9_DVGb<@jMucwEq(N{3xQ_}SS3Q4PZ^mJFn&P?s3)4E~T!z9IztNwR(+u?hKJvMW zS#xrhIoZHD`P@0h?m6Z4In}2*b@F*lk$G*CdELNy{oHxO?s?<&dDEwPbMggCkp+m! zf=%FpZSI17_k!d4!iT2?7xG0nkwp)aMX$g`pWH>i?!|!h#h|Cf5b~ukk);TerKrFq zXzo&M_fq`&QsUDRjC?s+WI5GjIX!SWGj}C?s;`S;%<-!DzRUk84_&HaAg{rz$M z`=6)p0E$gS(M@F2P1K-G^t?^XFPpD6HgW!J0x7mYqFbL@L5l$(pz;=N)fU;t7KJE# zXqqXtXyZH6ZE(;w^`EU3OGopyZB|n_Rrz)~Xy{&UN5yOBQg=r%afg>xl~Z)i)X>2Y zf7c;R##C@uK4@3*!>;lvoa4_8y(4C$$^OqehQ)hKkhM|SsMVYpY3(`#< zWmg#oUum+;*4=k$!fI=K3bQ*F0a^B}Exyvqrb=Xx92tQ>dd@fp9F_siyodIt4%IGM z#*q=iwjU^vjCQ3}57lrET~(D+PY;4b_buZNv(k<-PxaiSjvg9G3jQ1@>9gIK6yh8wRi1oiJ#LvgX*>m&iXK*t_tcpxFN1c~ zBaf3re=vq^&wkie6aM)*b!$42I?n&cYT}ROKRo~0Wl!?*)%HM~{NG>ZJ}6WFH?i4& zz0CdHHTHiKoBdk@`+urH{2yKR@h!RGDiQw_o5^V6@VmPH-N0T5dbQFxU-O266A=zo zb!mU;8smgFHMF+tREFk>yp}HHKme?M!rhmhd?>F@EcVx$=ssH9-)Vt8Kj{1_5Q*#! z1ptyM6+AJ(Sf>P2-47e{&p#rcTlak9kTiGA)aubg%)^kE;NV_Wv6z5+B)HG_?-xA5 znU~8}IV_)@B%?xMo~X;xMzHPA`1=Cp>k;!h@>>zl*0Oh!XaBdG=Gbhj2k2%+ee`>de9tA}1<^WE}Cb zQgJ`UUPyee#j(9AndGx?c3=sjf;tn_1b?Gu`|09!1sW}bS(eI|o8$VCAp@&Cw5O~Y zws8#lO}8&33S)V>zsq+c-_oA2NaqI`sUzMCpl8c{Darm&8=YivoP@e!2l>3;%y`;; zD=H0wP=^(t{$>8B-zqsb`TU(NDxLAB*T?;nI*B4^wt)@mP6sX%a^(B9n&TB;n~!K? zUK9*YnfjE`k)n@IHH>)NrM*;C?_c{IQOJJpq{A$B>3gX~beEW-#)_~#>lneU-MM4j zh-#U-wMk}bRM$()r{v6=u-93nkc;xM84>62jUOgY z7fdSKt-OhiHsBrPcSpqg`$cu)0n*jA(|=a1^7!};0ZdN7<>gZdRwekj=Q}jhSD@&@ zS?C>Vr9DU_HXzU8=;wOur#@8Yr(pRYg5<3hpN`Q$AmWjsP)>8-L-X8o(9?aH3M;Id z1m!7bc592o5rk>mPB~N!T@KzUU%`7o)z6BVVbG;kAPn7<`Ak7o!qvfLc6ZI&sr@N2 zgveOAj#r~0jvI|C%3{u0wyAV%J;CgGC;qvlm5#-PJv`V~RR);JHb7a1ee9bgv9cM$ zX{$z6Ln&YLTmnSSz<^*iuMR+_iu%0TwgUoYwXV$N2M3g+4E+367z{OH50WgT$<)In z+`f_N(VJ7k+(HoLHR;i})Rd46aPR&cU=B;r2eMUd+x@0zB^9mZs`jxYRpc1qyo6zq zK}S9;5HZkvs_-(}?0bK|NODmxAG-odpy0zG@+O|7G-4h>O++t|=Kv!(q=tZ`ze#p} zQlxBgiGDsl{4`}3qn$HBW9BH2$|jJch_hKR)xxeAhVD+O$%!6yrYC>_9*yv%{>)9< z+N*o~JIiP0Yx)NoHZ0GoUE9eNpJ?`z;ss<&ErO zA%b+iN_0@9x(cQQ{7S-OOmpF*otk-L7m4 z_ng;%7S{X-DPGw~w639qGZsx10lVEQ8>Oq)G{0L@ir>@eTxx`w1}d4Dgg)h z-XF~|ZNejo3#a_2w==QAVDAMFi-!t1VUrO+$h;BR<`uS66KN9XZm1T?$ZPV=R!j2M z+{_woks0}WUge566$)sej!KJDzJpz;DH?oh^}BoN z+0M?WU0Dz_82RQw`$6JNR@8s4kc&45P$Z-grOKa=U(JhDWubzJEq}j2zg&+LF|gxI zQWES$j_!024sf$jo-XQm2Qgezc~>p(YIqvKph$IM*SXC_QpZ#C@i(cNi>7>6I@E%d zWtIJc%V;?aSh4Ms>3u!xi&)UY@Zv2>w)0=T#ZhQu2;2OVlug;64gicr@|X@ewDn)T zW-urD6sj&X^O{eFX(c~0z{r?k9``u;?7Bak1>Hgxaj%k8bVb*jYUbjZ77S@{IZuE6 ze!X*HLgMlhFzYRZ@5=YJ?HDGP;Q6DlsF`Oa>C=LgY{?8AAIj(uJ8FiI34=H+WZ1%{ zdXU)h@TEwn(tyQ7)?L!V0oX5Icy^h-6u_AJMVZqiIfPz*5|YP(TeB;QiI+w_o!z>b>x8&?*c8|L${d+UB8H>W(jpxJpwAX*Cj#N%6 zQ{opK%~43HWq}Ca|J)VN*C?$>-G38%eVTLY@SXHYj|*aUU38)ROsXq^rCSxs{Vni| zs<2oO=k6W&i(c33NVR8!@y`o1MMzA?JposZ#kFb8UgR@^qLR8AT$m78ps^mNskir9 zsUNMB|K>2}{i4So?@(SUguHFat{rJiOVJv2xttKGrUAZTZ%;TZz(X9%F(2jqoHh|X z-Vq-@g$>CAEwK6mm)nz1F3hC3*@a3Ub5YmVb63n#64PB16Q=>wBSe}5orvd_i=qXf z1Pd{#L&oVr*7gB2FTB%Yw}lrXycu>=(~rWkz-k)+A#DN>#ZipaQFYjXh;;z;HVae) z1f&9hj!hI>FFX5)ueLsF)DSYOI}74g0GB=xFcKYkKoj*`2Kq<~e8mpHdf7TR0k7DR ze}GYnDOHc;KokU#@ok{s!(gd8K(0DM^otQ84EWwdHk>cEVMGi40F*@ppn%KvUjpCo z0h8$C;@kY0sZ4NsP%OFMW~;~cw8i7RT+QpF5ZM18*4{I!$#8AcPC^nOL3k2EFNWSB zQ~?D;??~?;U8({CQWO%JbVHSH=tV$!6$}VUu>eX{5D;mCf{F?jCVTI9-r4ibtasL$ z`F@kd^CM;5*L@z>d4Nsp8I zEVl{r?9Noo%A6NXJ+QkYu95t`;Eo#Kos)$-{2JiD>?DW^32IM*N0R6YNr+w&!y<|C zm;`WSp;fXl_F1fvS?vF_Ym8qdTkxN*G10r<4|Lz*2{L3}An4^CDU%AHq zZ<~Pr|8b4|Z;F=bQN8DifBjE!dkEEQ&JB6^Umxmk8^8^F|3gsqZ}pxANmfR3jOfOa z|8c0d+!D5^;wJgAbkzQLdy22AToY6`>|X-mc0Wax&~hlPWp^r%(LdUXd6@;XS_~#? z;Zr!wRt_@GWethpV=@a(Eo%UK~{+vm!JZW8~KTYJV5+atcASdBd1m-5w0)p~KAhPs^{~1;&U(@PPV&(o zc@~bpCbHA4OmUrw7=NN@rTOYwxT`T!r_ZFuUllV4Psn$n9QW)<_PaE^y29_$)iRXb z&j$t!vt8!SSVLdeA7tmwahmIxyNhEL^+t2?`AnHL?fE!ss3A7EIUwPzmS)w!tf3?Q zn1ZKgV0hsx;aHuc3Qv3_hQ%DhB9>SXqvVk7K!S+)R*_s zM^;hlw(tSwJ3gk4uBlboQkkcMqq^;^KJOcPTm_5fTB8HG_g?Gem^G2aT zYlIn@;t|QqPK{Py@wW~QeKj1F&QxFu@_)X3{aYoy1cN=742-(E^({>!Z#e@`VOc|A zkx+jriLRaU?tKIN_$iO~2ti)Fb$Pf`yh7^o{KK7OKYw5HEJdu|?%n;)s&>2{>j+{U zuJWwjh-Ol^M~`mMI>6-n2yIUN`WHWmxymXi3m!_)Gn!mTe>a|oCWX@`9eR<3pimz+CAViKAzi{TK z{zez=dZU`98D94kZr58Lux_Qlv0Ue_NaD%AhMfy8*DYXf;&$#%rXUp#m%{9SiLWf^F6$9H? zvc-UulF(E6WP<>w?7}k=GRNbOGknP9hMZBN9G5nl9^`-1X6$10#LGNMRiVUtX-)DQ z?~}8<7d@S#39nN3$!+-f4jcB#S9i;QQ{(8=oy%svKqr+NJ%h@fG|nE6hE@|UJJbfd zzUnsrgRb@B^AVoh5;TS>&QLTAZm!+Yx zmVt1SKp)MAnTp$-oCk9^B-)D-iJb!Fcu3+PG`EBJl4x!?Jzr$`H=*W6gIS_N2dub@ zY6i(L{A>C}G4?maQn>|Q<~&gkjHi68srw@iy7N$q|n#e3Ed z%TF7h*1xKE_jw7o$=#C;ZZeC5;3R|%MrzLpf15to>~w6`cMa!#{t^FEyc|LPOJYA(;@y9bj2ugoi&tz~{WcND7(>=ci>F_0nBAhV^UE z)}#n%jCA(bg~My5DVw$!>zYZ@4e#K7D~++&`G3B5U0?(kpt0!AQWbw&uKZ!B)wj70 z`p+?taeIQAr43SIG()-lw(LB+hG%x@`G?0k-DaG889$pGKTXg@Vn>SVwMR9dg~?{O zgsLXw5|K`3S(;1c^AGg#Jsg(9x-}q9+SfM(eBPjp6X)+j#5p7a4mmiRJO;l9Xq?_N zm8<)H)zizWbl$P$`lRP8VW4urONwP>KS<^RNtL6QMOOfpD;DzMh(6ebm7#Q4jwSCf zN#=^*WOlB@P4CL|Id%EJ51==M6Ga9TZe9~+E^zl$O2`tse12I%Q@R5+wjP?V8JtKH z+VpXwJQ>OLk2SOVQ2MciID-NT-bTDwBdmIcx?uU(LYRbXYkXxiPQH~NC7($&Rk~;; zTRoablG!gb(H#1$p|t)qU%a#(oEfuRi^N@(7|QZw`)(n-wHi7d4_Sd z^DP`UHsVe)!a#$(0S3**i^8+ zeDIaB<~&t?1iV{aF1jT==8(%fnL{fieqc@a?u?vI>ID4b$5*Os${O%1s?4uUd3qT9 z6(XxZLS~AYVj>@eiEX1J_(;FOx3_fuTq*D7+xir6?*90R-KP(VhvB2A#z;tjGfKUj z>&8czz2}orOIv4eX?2VByJGQ~=SG{{Za}oGZ%i8B>E2U{reHXB&4EuJKoh#CPCY#v zA=O*c@X3UmC7~MGQ$Anx1U7{&XXY5cn|Un5KyfVoFh0V|=}@OxQ=K6fX;!)Uc7MVT z6k=5ZOcv=ew`Rn8JrxOTnu-{M#tKFd`HA>%>uBF~!OkFGMhYUeO%1LP$F~*?WM44z zar>$Zn4N?D3`g-KaP^KPSh+i%!o$Ie5+1Y(Dzd_&I=tC#k)U~dQB9@GU;&|Idu)~l zEbD^XA^Y-t6dgEB=P=$*AYM)*!sCeFX^PFmMkLz`-`+~_KDA?RE5G9L-r;*UZ(Vh4 z_l>}>qo^uZ1q-mtmm8LhK(v{jYLh~8qponyDwjs9anObl*Y{-QY5fO3*fKiRJipjJ zGGl5oV|snWKd32u_2^uzydio`t|{B;MnT+yl7u)Ugq99{ISZr#+-i8@F`KWUHAKHn zq&JRhH$9R+tRFfHAw0ibFRwZ41$222rV9m(kmE-c~VEO77zm#gq+HA z-T_^v&%Xl+&ayKjQu-J9Ps=+Yk}w5&D8JrOrTE_c+L?1*ApJ zljto&nfpEDQ+hlcPT;>#n^gFe54f37akWyp=?n7Z4q)#IoB|kRycIzoh-G7awUa>8 z>bJ1Nl@V$;TO+Mi?(c+$dEsGJWKh~Th=u~9$AM8T<=lwM%}~en8h7REg`(c_)Xe%v zj=r3#qOFA(qegX$bDFQl5`In@Ha8OyA`dG8ysT>T zIK^Qo0LDnDvyMWUpR%X}aq>{NOH2y&-&dIeBI^TpN_zCGf6}6Ueq(O%yjbd?1My=f zeigb@2tt6Mnu0LH)gnhqts}0Onx>kwdf6$%jPS7jB6f2!IBf|PdnCU!a_LFmr7?ux z_=(aSTd-iOu-^ALwjSa0sldqH=%#jQ8WGqp8##;N=v43fIXJK(&OPcx#%qc`U_Rt`8}Ad&hl9|{y_L0`#lIa<_2NYxj4bBS-vVlCN>*2DD!)0^Yrp=*w@I* z{+5XR_lR!5QbyL35m)SmhkM}>ofJgaYV*0iI`R|m--0#Y1sckQ8;~0CA!R+JY@(>D zvvaC1;&iC3(j)5pbY?_&vZY+mHCcL3SDz*j?x8KBU*y`Cnp((oGxa_q5Qm^=e}Lxm z_`X{PC3a$kP*qr)w~vA7h})LsT%URc+z#*ENlrSO!0SQbS7*Q9-Wwh4h~S*0f5*X+ zRmDAlVhN=nI;Id_W=U2^)RlzxGv%EO(+C+y5}SDga;+yk3|TIWQj*K4QI~QG)okb zFFm-IO+(C5AO3bMqjVLt`vzA2hW^ePyB$Ba5isa1ikXp!R=BRan5O%4=TRY)lJfo$ zbPrT@4n516c>JbvAxdjAPxLQ8@K$uFdXj#tsCDQgXu_>8pat>V2m|V+oGIt|S$|Ks z5M;XL(S9r<)Vv3=F& z(cA_N63^7~pTkk|r$O4KSw_D!#uxT54c z=|bB;{awaZwt+Q?ff9L{`kdrw2t%++oP@fbaye)#k~14?dQyBIx6 zX@x1at1&kL>Hd$OgH;=`F&LxPnghhGw-K>!D(CBxb5w=fW-Z(D2hr{d;qRr+9z>(Wmx-}UHD0Ooc@r>yme}$||xU#16cVeB~OE;%$$ zw7;3fyv0(m4+j0aEikf28pSm!6nz+2G#;qNMOHEY}U|ZP^ zvcK*vr;92mcwj|6RlK zQW3>#mn03*zb@9P<$(42Kzw0>O_j2m*6@#x-lF2WgCWr8^$Xerhhlgct2REf3R}-U=#DfuIz)u;0LFb4=#T{xbkkgt8aR` zYXkY+n7l8N|C4qP`XCvK1b)6;ZYoHMn(iWh>_I7J+v=PJKJUWjiTm zJ6WM@J9Th7ePuiI?>32dCtH0d*JUR^W~ZQRr)Y4eWM!x9?+%%Fw?cil%4HX2I$C3@ z|L^H|2q*_63F-MSFVb`po232zd)@WFU8Mcz&iDVgNNcC=t^8N%c(L%y&7XJ_M7+4@0)D(zy%jK;zn-q3naAf{95jX&p(z(yy(56I zdry)u*B8`|;_0!tS{1Yg3LY4x69^#jP_xBAT@ zNueE3h*X%ch{v^IpW0lxHtNndUp3saASBfuQRvNjB5*HRxWQb4X|Q9x^7>{MeO`om z&31KxddEEssKxV=LGn0^)7lwy1~=1beU89&S%9Z1%)>_?WJP8Gd_~; zz2<#ws&Rx7oa=)Roi`I>oazq)rj5?92)JSHvEr=L9WS_29G)H5hhv2a*e|C>zoRYb5gO`5&;tTU_vfB%+;qQOYqj+PPJCP%hU$}rl zWrqY|B>$;-#$_x!bbCd8d@si+E!k%Djtj$1x66;yz|r zLqF)F1Ob<`S;LaVrMwA6{QC{maL6?qvKf=$u{QVJ^{*+B4I)p#yw3ABk)=D&O0cm+jY} zyXMAkTvYhgM0Y+K#tR02VPB1 zz-}L;y1KoHyr~SJzv~M;Fe(_C$%l5%O2-lkM^bs`k~nH=SQU)VJZsU{>($=0+nlV_ zNV3bKO%-)h%hsI9-n@JCb26o9+E_w&O;Sv-B9jE2j15&#Kx=OEOBojne-vpa-t=+( zsde@Yn}VUPi8Q@(dX;$V7cCk@mO!H1ofJf`+8OzT#>KH`s9mvPK3~aZiG|@ z=n2@daG^Lq^4zq(8@fM-Pb?6n_a~hXVIHv|)2)(MJsKphk?=uwx&|bS7IgnB_a=rl z*GP0%NNRe$=0Y*Q{QRDdOXvEu{_gQ<)x7~)oKLSE#{pW?qOXFb?&C0;wIv}^6(c&B zQWu%-ae+o0DHxcNKa*VpeFR*&c+_Jo1%FB}ZAL^I2T>rr6Beb=46L74TBfGmGk!)v zaFE3ve3$FRSh4#oM?Hz>(Gw}+W@~k4T!-Nf6R&G~Ah&*vtU3ISE4AnuW_GEIW2>8j zHS>mnF+L4;&R@=^a#mpi_33_)&M5?id)mI7;Q5p;FDK*5a^Ge<&b%HE79KN(IL6nLhbX62(J@5SJ;9ENy+(l@?e?{23|3G4euUV_gO# znU78d-E1gEOTN`au#ru(l{vMmfZS9p_qkz|JtLf8kQnws_k|$%sj3p4c?fo|rUfdF zD@U|HZ)8(KI)C)U(>!$6?aZVcj`2X>JM3%|KzTJn-9*5AlCEH8pR3n<{T7AC<`Il5AbL3x@sGn#{tx{y zy@wH5q8i@ryrvK>HrG`lV?0*KB-plp3idYBm4S~=3;reAZKeu+;T_9Z3xAvRJ85lI zA30_g5j+%5=L$9?LtZ84^h6at2dgpDq+62`89JJu*!^9{D+J_xT~7fUf#mmAHmkD4 zBID`YW1ZW7=3<0i{E9{zs*nK!0QjQ%v%Q2FhkM=CyAgA3tojAnTlemLk!bN?r-7c1HC*=R65h$4%b0A-UbYg~Z4o$x=I;64 zTR|_G(*adC`0zW!w^uST9J)hr8~sPv-LpC0d6s{ERN8>_G1sh@v(XkrCv=EQ%iPP5ikcmiOS_@HB zzESy=82LV-3QzlKK3-fuVGo}mm7L&E2T0dK>nsr)w4$a}XBm}~F4#qP91xg#;yP@R zjjKsl#}I`riJ=7m1P4yCjj5y&cC9$utB1Hnms~o8u+UFPib&j>Lf9$?UbnmLcuMEM zhy`USgN$%DsCc~f?ReLU_?mS>jRnGLA>Q+6k_6rDYum|n`hXS=ym18)%^qvEkRVEz za636EO&__3h1YKX2i^ltq0 zxPRPOF_)05aU#`#A#v988GN?8&@YDS!sq; zRmo)ngAB--15?P(7DQtUq5+?47747>!e}B*Jc3B(g?Y4K(8pS^Un~86a-Msy@zo*3 zLt&U&H^NON--82&6#+YtVTwDT>y&(Z`kW3ttv`jf{Q$+_dY8aa5T{a*U|*0FS&&>< zklI_2zF3fXTtMO|%vLGPwJ*$%EG#H2Eb1*RSu89&E+lglRj3qI*%$q9(((UALp*p~ zO!>di5bOTGX^4{-of%U3|9!MTgYrS?kjejYwD@Ons&S83<5urjyX+s9c9}YLkUvmY;;BYqTSn(S%GLF!q<+;*WBZL&YDWKPx$0QFuvhrJ@XkL* zi&ug)Hw2Alcz5Sp(lSGSswkN@c{{&Zd0zZ&V+9+iQaAAB+`;=XjkXz|3o1{-8FO2V z$+NvjANk8YuK8YyFcP!Kb~;@#9lZJY@}~XL%!@XUxy>D_QTTFO|D;Jww^i-SM~_ao zx=8CYtUm+MykVz8?C*RK>Yiz8o`QrG{NDoY31QEG;l#`9vJ0!Xb7vv$w^oKm=-GbK zZ>}Xvb|o*zdk?)vhxDdWA;ZTt_!C*-DcASa^;e7= z_f@j4%A|1A&;+AT3S$mF>}*w}e;O&0DiIv1!SB&qz0}M>?@~e_!E5-cl3>l$f=a|# zp$(6B*p&t^#oY#Nm%-E2EW%P?IW*2NAWM)`t$og{#8ZEZa>o<13u2oogz+ZDe=;;| zol^G~3VU7Q$JW{A-OqgU?A)B8MDd82T{8i!1Y;{hdm6biN6_(r(7FAi7{$3XzPhKX zK*J!%_cXqkdU(k!MaR$oV2Ho-%U%#;M{5eyaD?kK)G`RCa}Q~9GnnXEqW?YxGR^M& zNW{G-$aU7@M_DIb_g;wZ#gNT_M~W@+!&NRdd+alU#{GWSJ1TzcD9OwcN9B+Erv5cWBrQL)K3{=%rrea6=3ieo(-Kh znHr|at7y@6Mie{HlC_-C~Maxbd@jHJWrKzup=wX=WxWAk$V2lVAwp8(YOp_PP z-{*W*aBm(WhFkK96El*1jRI?zXsIaItTlATbbrl4VkR_e0NR zE>%iT)8R=T-!$p2VQP$pVBD{xrEsf8{6MVZ6r9l*5YT#y2tAoc)8ya7uU21L{r+-Y zjXNUM_1b9#zC&CmFp6y>TI2m=x_B#VQVDqK%CC6la*Qz9Mqd+=TDS5?cw1b&w}R*N zjs7uK2@oofzO_&DQgDUskvWTm0aGp%X4@k|!zyS=J{|+X@)HggOkETOMvGTE&b?sJ zM$dUr6`Y-d#OsO-NpP{V+F0+t?J7xngjrnM3TxB;pJWqphIOEOp^oC~i9^s)D5@JE zI8j8a(qe&ywgT7Zla&_anT2Vrs*kVwD6rjc4K(Db|9PHeR_Pc213tqTWUxj|POjv? z-f{n3o~P_3U}X>5AoS5pmP&&zEZadg<-^+Vglc@yUfzFbb~;z0d(goKo$BNRp&9 zk85ICOnJA5Ydkx|XlZ>#Cy}N#(M>1>dE@5C)Vwcr4xoc#zNxUbg=!GX!_|~#2MR*M zE*|k38`sA9<6)J(fJQ+>R-YiD4^nrZhK@pLcw$S>YzJYX&P{*AhcVSb@tm7vxJt4H z!?N~+xX}uyDoH$6yQLxFHr{^UZ{D&wNLuWP1g&Da2GZ2ICHX;!L!~Go6zYRd<(LBT zD-ggeQ`asV@p0QK`=0T$(|W_0orwCyE~8^jPs2?CoyZZvDD}3qV)C-8_}*g=o_KaS z1>#vp6>({W)X*df0gO4G{C3n9^R!l3>gGbp2TsGh2Yce{*r%t70cy!cmo?YMLypIc z$pK$)vP)@YKpY$k@NtXA+Z8{9Ucfa%4IR#tz>?TOQu9Yhoa;D4WV2GGD@Tg&3i&o}IbnrV$%&;7}wog$j-$slf! zFD(@hw%D7JnYER%2?)_uG-Qj>dh0)8+`Qy_B*XGix=~5N(J*bNynM{AOim;P^$aa-|!cci! zzYN4O_mp#~-kUi9^orG|Bav7i?ZoHWGj=`uL#{q$QtY(mT7uK z!+B!v{hyN%R|2NS?6Id&_97|GV&It$`D~=LzPb45y;i(a}e_o6ZC+8>}39(1`8E{CHxSIO+1e4K%C_<59maV8E40P>nN4A{yEHd7j*{1B=*r z5)U&k{c&KC^U11z73p(}?l05P;oZ%}6_9xK|9UFk-`rW}jxCPq7BPDtezClEsGP5He6ahp!cY(kJ zGp|*x08MV5uVS68x8m0Yne>6imRpT@Gh*X5BAb7LZ3Q_6`ziJUxy=AQMBbtVfXtWLbA(C{n2W?|* zi;fT zbp@{44B-u!1Z)Rb3@1Mi^>5w|XwgSvD^ogpeE6$z)|iXFKJe-wU!;J3Tu1cax!4!F z>5>bGcJq+Vo^-w}uzd@Bfi0@hEVbGdQL?IXA@r6XH0{AcMhOlUqi4-XGJ0m0$$4mR znPiYS&zNx6jiW2NUoWCd_|BdkQ>W{l@A`;4cF6l!pIom@&@swY)b<6$@In{ayny)VhP+z=D^j`+HwS}zvzUod1{)wc5R{HgAByGgz``rYaK;w+nfh!< zE8M6bu?T-GU{A?|v?6KU z?jndep1pS&%V7f)J~`VTK=|XC7;#LHawN@A0d0BuO^!muA;yz}e7Kt5K}ldF z<+YOwvyTe}_zHyTU{&?>x?;c=P*KAU%0>mQh=F-f!~Nc(j!4u14q0Loif+l%v@0I; zMTNFd|8r5xVsYC+@t8fzSQNqNS~7lIGR09UJVZ;omOT?$dIoiOp||wyV(H3p=_*Ir z`sx4MXu+^VW;`JSoaJcMa*RVcYg9RVQ8{N{IrmaI?@2k9vw~l>LeQZ?II2Rls6xE2 zLUO4>`lJHKSt+Mlso+ql6jiBQRH@omd10wi{iG7lS*593rR`9q8&#!WRAty#WxP~n zdQxS^S#6~c+2TSu|xdMYj?sy3rdKFSZ*bij10L5ffW^#s)si=>neYj6AEJf%ssX?;S*Fwlde zy7V|9#?`vqJ|PG{tje{nuus%@z5d>=NU~ysFMmT#AJ4y!Q2)T3mHv;Iv&H`@o!K;& zQ~J*lDn6TEYeM5bSwH7rtzvoT?A4q9fjNK5b#0k7uXK3)Pt4h#Xd%b=JL+GJyluw( zUOB_{A=D9Svin-LRPk5@F@`fr!PYnI^pL`9~wKv!U=GZSXgJ6~Oud|Gc7yLh#WN$ajw z@#f)X5YW#j+)216%Ed`Ew`|uk&Wc;zjf3q7+XsdP^3gkpcWLT6s5sD3JQy5AJ?uKw z#JqION4*6CjAlM;Xj(*g8A)_uJI2jr8d$3F0~xw&`IcQf!k5pvh=Dy911+kx_7lXW zWN16X&4|%UIo@GM*4rz^rhnqMD;QZO-mz9C99K(e8JN38Aa42Q*3cC8Ot}V#`K@RO z`O!i%($&K-4fTB-t3;jZ(@jFven-}F0y1(IZr4wxILOe&_qAb+K0nws8oL_y+SJ4B zU&_>r6&0yKC zcMflDF%mx2T0!jDrPt}sjCB}>FD3T{gEJ)>UP8=M!vXO6`7dK#cIu=gr&hZ9PeRvN zg*#F;16?AMt(EsaDzdnR_1(-P)OLI&7oujA89_Z%wfp1ltE?Lh9hDKG=bYtT4tKkM43; zW4;;~#fr0YHjJlTVU6bgu_u@qTo~lgbTEal$R$vWZ=avxATbncJq8!1JJ!C(8i!lM zKYCt49;FpBo^s?oTIAR;@~KQy`#Ur^$DytDw%qb2BBZ#pKu?9vKHI_O#>L{os#LEQ zBlr)k5(TJWXjVtX znVw*fNZobzHTHmhQ`pmG$BiS7W^9ZDaW^`}`8;%N#O0*Tg5C$lJlUynLjxfa z`;1MKKt5%)+JsB7Kr`s~vmb~7LiyF$QRSxwfSfTAX(*a31rsO;-fhM-iH=I7=siR! zW*2O~PLnoaS2dq*$iS1fwpJGq?uJC`H{&miyrNJ7e?IxCa=ZRoQOYgLWR~$-9f5Ce z5oF0;ri8WO4gKKf{!xjd3|`fN+a9JOzM}4l3_F&6(3)`33HRByL|RKggR37RHnt z-&%dwadcj!+Bz=owV#Dx5Lao@Y{HzXMPf;kn&#Y|7PmvWF_>ge?7{J?G?tN_^fBG1 zvnj|JmN8b0E5-qS)s*t*8LKkbdeovh57+VhQredpi8cLpFFu-rd{L6`?5EhHEXdSw zQSD~Z701}f`fKj@fpMQR22&XBf@CkQW$~fFnCfa*9@4ykeN(7nNY*l$lYKoTlWd+* z{mE&&6>=ZwbKtQ29?_*+`8rGC$BFHuxdh4hgDu&nz+~QYxogG2sps{~7fOT=EU4YZ zVCH0z+d`=-Rdc?%ImIPmQ#anyczqgH7Uqm=;&)y=Yzt@~{&YFKd*SOh5ioBKNp>q4 z*bJ@76R~V#JQd+ccMlcq$Q{ODg538H^7&ec&$LkIC;ohzzdd?uFRIAsN#>#6DHyL0 z0m6S{QpXK5zN4*pDm8PD%wB|iZ=cHVQrPOXQMN4|Mn;K86z^hZL@$fM&YmMWzO9)r z;8stsxoqrPJ*ro)_({z4f^NrWK|Z?Bn2Esfu933RS@|krYomNy>oXodtQ3Drxavb` z5xyKUgi1Uor~&IIomqeZC}~;AJ2m@wvCWiSlvn_T_1HtMr^#b2p65!-GA0CVq+cES z`Z%QTjMDWt1#dUtgaDm{dD8EU>D*TcH@zUF{fh?t;P3NNlWZhIqusPWZ}jY>^i8)- zHTip%17)ncU1`1;^4v)Xq_6%SGGTgdIe#Sh)(-=IW8LL8Vg@keSID1#nwVa|6z_PY z-$}hPw8^z2Y)$!1$(msnrQq)e1&++d%p)*`EEeh^=4dd%gmZniC<0 z-c&Jh`w#|EPR|nunq}I;&P^zx5gF8?N0yF;th|x6Ietfes6H1lw`V%^F$rl3F~q;* zXKwqLanK(qe&x8e^!XQW+M3=8m+r1Z$M2;#MFi##4T%eJGR!O!Q$i~5G*9Mq4mXdc zgJC|}KTUv@>?cbITw~Cr)RUorlX=@qMphf?34z!84;6gngWU}=HrFO%^J0D9s4;%N zq;cHDUQc#NZsNS79gykN8?}lS^fr1&`^3>s`P21~di1-Tgc2dK(=&V-&&I0r9Yr{J zojNxQfBty_zVwveutCaa<;6HS?x?ATD5_&2+KGe=L5bDW3Mlh8Ptl|;DP41Ak@wd1 z(~O-5rU82PpU-jHgrVw&vG=qigFakJW|nUj9HD%dsqm&11~U}hJOLR*kdVFbS5CUZ>!Oe+)8LfCT()f1W2txM7mqB_0bog(n`N^3O`N;DsU~L_ zku3lfM{UM}^J)JIPxy8v@OCv=SP9150`<}dOY6f}D9~@6U=CS0KM4j+ju+zt-^0kg z4>9B@4;WojF$%>TQN(=AeH3b?^mWxR<=3dz>F3?j$)~}-i~wwOhNBt>d;z2HdIit3 zaybxUjm==j6cCl)G$JHfy8@*PDU4WnXaV}MK;-*49&L{+RbI#=R}2*v)4VSBT~;J8 zULt22I9?|vf0fEhX1(^_Xp_kNRsmi8Bn_egHl6~ROo7VBpgze-A~t|-9_;=?s%Y?8 zX-$!UjHiZ)5P z=|G8nlmlFkQux9%$0~Bp4wzklvY5eUPLq?aZ-WGIfB=<+RL&9xixqv*cpY*(&4cML zURrC~k3Kk;@qkH8;STMPIs>0`XS>Iv1Bb`n7zr`737Ul(wNXJcBo+i20zq9f=oXTA9S1RYwc&@@1M9$2eAmY;%1Sq5_vl_faGc^>8#T&xl0P|3Eh1Z-3Q zW1l;p*BOynoSs^M=U1i*D@_0U^kz%GdJ#aLgYeo8tYic` zb|e|(#z_mK&+6xj5bc=ySKt01yZ#{E-Y*fT!3f-=ONbeC~8qw^R=k4G3|aM?eu>jlevoaK&M2WgCn zXs}biSF#vO%pC=^g$h6PHIAVYfL&*r6-!_YN-svEZQ{f$3V`_qkPRM?TLt-(;Q=@~ ze^Qy>Du{im?ChcL`)*~E9N>=_a0C>Zb5!aQlhJO4K*v8BqY1yr#BbDGi$#nMK%AUd#eT~rhpfcpb*;awCO@0`sq0jsb1&0uVSCORZBQ|JS* zfd46uHiUZoaz&~N1oPu6+$K&FffYu(TFoju(^TYiqh#Y>oAp>|{17zO;LzA6+FoYRxXWzhn5#6os@5uL6~&A5BU)_TmR_fahU7olzs z7>3%B<)ZwH;bLng=h6TlF#tm4EBl}!_L6WGI}!@+*8+dI)Y2T}RYjpUaqM6=Zx!`x zz?1yXy~$P&?nvwd8G)RXKX7rjz{JS#>v&|g-@Ui->JDR_=&bfn+7DRc%7P$f`K*g+jB>@|tK}gQ?Q>S`CR`9cEN~;OxAc`?*~fm$q><^)y;S;#Zo`QW zjRHcK&{Rs^vk-(@O$@B0W;S;%CJ~*h7xO07h>!c3WQ8A|VhT=ju0(#9M=7}(cZLgn z_5TruR&vm|TMQf;F;n*l=m8Mxj&srn5GNTXJqh0jsbA7T(Cfe*{6ltAU@OHyr@8lN z2>aN#bN9Xp-Hj9We$0O?4xY$Y8H;Xzt`7{uQwn^5V^i!YsXO{& z8J)aZL`SDC3Ud}wTubV@W#C00B&C44reE@@*qoJek<{MjiD5V5vu88lX>{#E#R!n8~$h0*`uc@c>k z>BCm&;7or2lPk#QM+OXXBjcxB%=)SM&y5CtPkRS?J7!;ickh8dEFp5z?=MU;Hm$zY z$%8o%V0}w7S9Ji2CcH)CmD!)#mZ%J7{6!&FC!4!ri$jw-LtLY6)8~J@)YXYM2Vjoe z5IbDl*~w?ocE+{?%usSZgR7kj`vh^z_D%U~*Wmk}gn_gBFDuC~gO)jy4DfrWc_!3+ zW(In045V!~Eo%_F+&xPa0$YM!;{&<4|D-ljs)f(IaK|G20Jws_yDi&d^8g0==Hb;j zZv?^fwPUKP+SA+R1nY!Jo+kQ^9gx$mt<@CF5)XS&`WBxxR^9`hHD+70xT8G;F9uQG zXAg9Oc&f-S54EMV(-T{t?YJ4cq6y~}gumE&!+P#ZaT$&Ri9cg$~glo!NUee+fJPMb>$FElS~7<1xC)dOBtaO^V&aat8fcY z81b#B`i68CtYA-{1tO-wVpaL=d8OHm*&w3w)*74o(y$4Vuw2DRD5_foIht;`zCf=; zj5`eTTVPA(WY6AT1yL_E8>n0b4jHVDY{$NR7`)XipjeX$_a$prC(16I~-P)zzUAG`U;*ekQ$geo$E(K8-l;qd*!J1GcA^~VhZ`YZk zowA@Hkl3-@LKi?BzBO4%LHNJe?7&kW2DGh$240j^(#5Z)jMTgA@yOn8s7o|s-~#JW ze|4A!&6qlI``^rvv(o!VQ^+F<@*4&Ddv$-s6j?-wt-eZ%T?ueFaEsAX6{=KYg^e&y+qrYIk1pcZ8w29aY44@cRI|DJ6hnSqIQ-OE(xc{ z=c<8>PoRfbpaaj8`w0~0a=fh0)Npzd#(2{98K9d2aE`~+!+EdzuZL$*7w!NZt{=Ho z0e{lR=10J-sb3SHfmbd&6*z!&4WN1S`}JAWJ10QM`Onftl*j4ca~k!qwTFM!Wl(fj zL3gv){1^W2eg*;L5a`0-$Frw&VDJ(O?0^O5NS>Zt0`?fqK(gMsa9Y?IUhM+2HO-_m zJn9MT=Ih$2EK)8b1?KN{GkMfvpd1z(`q_-=T!ih(O5g_c{U zWoozD(m|_RW)(UaygEfzVxx3MrRs^C*1J{>)=e&>Mb;l}nwRU89W!0xb6QNV{hTm z^xyV;2tfGE2~Uw9xFr=|hp+3*y`6m(H_Q+9fJQ=2xx@O;&v|w=J&S zS30mBpGS)(9c{vrx}Z|$ziQ(a zarTK?$lgwm{`RL|H>?5@X`!zp3)YlWq-V6>hTpROz_Kr&;n2zPROihvBcbs&^UoiO zc+a&#SpoPi54YDwLM!k4I%}T0-Xd}6mqmPj`}SF`<0f27kn`prJfMC~#g)Q64g3s9 zC`eYRl15L4P*7Axy?`5&T6lpw6!c^%C7gA6nPG-8p~P&?Tk*K)@eFE;z}l_E`(CCR zx9(84M~5QrD18Z$g|$QdDK5vT5|lcxQ)L}IXA@{==@uuGD0U9Q= z`oK1QM%iQ=tDG&v9DCgkyz_zxvuwvCprQ_Auyn`hQbRciFnu8+^Df4to$a9Hf!)4E zu@e__zT7c%E}_W(ftm)B1DP~}*LH<>njQ+kq6>-4%%(FcDJpFVah?^Dm(ZD?C&&uJ zN3n)xcqCyKPY>AEDybWlvh^5JpC~8`3@4%j;M#p0heRd}OVbz$dB`(=$ z+?mLPL%8I<{)wIz*XSZs> zRZdTM9kqHsR}rQCSjEx~@_X5K+Vpt37HFl-)32V!S79oDa48p3AG~r&ugcZbn1r@z zO->PIw~mBVF4glj(CptgmG$3%9dL0HiWt9DvcNO zLAE`R7-YSLa2qv;ZY#kpQg*oTS;j^<&|S5=b+S%*|1{KeQ7&ix0beFZ_iPnj6|o`N zT2zVa9DM9nLM(P{KM}Ti^21{CePc8FFLkfqX9`{hu*X|EfK2EJl4yAWFBcx2U#UMSBX!qX$eAY@@c zP-%atC@Mk#hlmjZCuG9D!yB(oId%UOpwmYOmec_n<|N6DO5wLf+*J$At;T6QRG&lgo_HeC(eCc%XUT9s+~nDL5_<0%6{P+zAEG>jK ziZ)D1eTf691GLGEo4%~!&C>;vV_C^q5pnbgzOitD_Do)FS7im-kMX8Q1xS}YG`*)@ zxS>qihiK-yRV=q z8!b+KTMJuLMdlr3j6|(~v5#&f=^%QpG5x&-Cm0vIR+cu2uO2R}4(w)3k{v{bkt1{LB`Z0RCknfz;83HB{^9ekcod>1X~ z!tN*;=uM;P=TO9wm6}LgYqZNE&h!eVRDYZWH@s!9S|NVfI$zZP_gJYH#WMF6;Tp}q zVhf+>j3BrBQIBqB+NAh8Tn&=3Q~BxtR)n+?NAgMcxdpJnILVIe?-kCFHWi2l1lF`Y>x zor6szvtj9u=%;I>njC4YM5_tOff!zg23_J?D-}Zoh5jzw`Htrs#}G731hL` z!?pWKV5G;tx(Z}Kr^&-+TWCl=F@pq?Y-t)j!*U>1qN2my)3))4Zc1`9g*-s%icB4b zDzO+52PE8ldXQeNWuIP?Ua6`(%SRn{bRfFIC1aRBd$91T-4$RH-WttsW3=I8I~o6m zV(Pv&`_Ros6e&t60ux2gVT2LQW?o`$`gxo(@qyH!0Oj1i*hKRXviagNBZ6KD8*Sg) zJowAc|IK*6oB!`yTxMGBM9yFCmc2253%#veefw-XM&5(w^WOlI>LM}57>}Xi)*bX( zG?2=fl}IaLkWpL&rkC_*Cm+u^v|uCX#Z;2Vv*wQ`HH8DqTrf0b){#8JxQpV{``fZl zf-ukbGhb-kNYLG;*M(6;&=N*&@IC0G32Q>V!9Pc`k7Y200+%%`&m=}QNk`1sc=S%rkGuTb+T=9wk8y#vrZPI%W7#dp8X`qU=;Ut0jBSEMj7eMVtz*iLu) z$O$5-0RgiE80sN`Fr3LW?F)TYlLjxi&=pNkxe6H?3>$TARpIZ_7n16NRMb$d^HYK+6&#+(qnC%Rw;C?E_FMPs9Y8E1Q? z_l!SR?70%+c}$2=QLp}J8zOId2SH=z`sDzSla4f^ubIGN&YjgC$DJ5~4_ zH02vKy#371=Eq|?d!bk-1U(XAg;THUjtJ71{})|@f)TwbXc-+8n#b&&Djv`OIQlew2sXr1~bHKY#PNhJh28b=wQW$=fx1^sopQ+BdvqH z(WNA42i~i~8+Fqd;xn0C(k>AhB6$eIO&ud_2461SXFDVS0C1Rw69Ahw=gcOC7={Tr z_&mLh2O&N|^Lr?j0+j_40RoYTb+xRZ#SH4OltxryXn$6FKQV7zrp|IEVMqMBpE8;$ zrdJx_IL-arKE&6|3G1Cgstd=FCcY+w>)j-38Tjk|yh0hu*MR)eME)ZY;aL29x>wy0rpwx&mXTl8-{O?VjQvMZ zs;Isqk-5Ioyk4CVlHyWd-&5bXQvY?nl8DN%`Cdc2c|&J#Lw9~dPfx?^m4>&!8v2UUIH;(5wPWCjuTWS38t8tpSY4%>zoO#niaMMzL(@Ia%+Dg;Lucl4r=IwjU zJLb)M!OaKx%||`W$1BaJznagOUw*&$^3wd}b@0m{`7eLk7#cv$qRtvRk3#~;9eMk#qK?`$l3(IQDo!>3UTdi!etsEAu{XGF( z1+CjhVSKBt>%S-kzP9#?SW$7d&3gmeP;PBgdTycBZ37}!(r%PIU)x#-SXFK)`%vvl zUzv?|ZhZu{b#}D3v_JvFX@!pJU<={K6Dp7VVngcw?Qb-Xf`vMgFmrZ<3| z0<$Z|X#FdON}p`g3FdDaPS=vB(+fDF5bd_V?R2yWF*Fe;p_u$r8P1#k`jn_hwm;1}D?yIj$kZUVBM&b4C=o}|}U%j~J&9{d@rKj_g*>WV`NdC4y zZut4*_YZlujlMkj#Xly|oZ+T&0r{yn~Z?=-enX6WvdgZb!>|N#$Xw0WQsBe2yU=>EW zh}aer-4g3?&QaP+r%Cpxy#Ayaicw-e7~ z&NwnJI}~C9jN%EG>>NKAKbQPH|EX{I5TZ^Ta@Ac^`?P@Ns92a%K3K`Rj8wy&0ZZZ3NRAfpj}2iv?%@ z+D~+S6@+8l3A3>n60i*Ll${9lxNiBQcX$)PDS}BIfSc`I3x1TIPQ--_FcDf`8 zA9`PyI)B-D2u7P=q)SRoUI20J=--|HTzjfl2mOxJ>RBqYiDLX9@-mb(X=-z{wIAY| z929$@ZJmw?i{Rmf#{1kE%v8F252~avwH$Rbmsxt2Clt;Tnpgw+#6J71QJjtDu7aUB zVmu3{RCzG9wNb-{pMZv;_^5gD-Z?|m%+o%+T5NiOv>f|CgrwTpH%$F$>AyhL?Aw@h zkAyBBd^RGDq-LSEGtLQ%s;g7?PB$m1BVs)wBYmckRAF=sDx#K{Oxbd?jzAON!L>}I zYH665$kV|`;@rw4J`@(yDmmTjr^;eqH`D*>mC0>5CVIc)&^6za4M(^jXW~C}mh*IX zD5c2Dgk+O-@q~-(sipzcSTM(n;**ZT0ofG~WfOLab&7Q}`v1h!m-$JElUJsX9J0Io zWgORuZ*-hX`|O`Soe+$OBAeEm{sJCsT}eBOy_vL1T9CjnHVfn)yq+K?DVK^s8pw|Q zHaZ#=#TFZ#TT?NP(_+Q(2z%COxp(omqV1Tb^koF?(j%}@%~ge(S6?L#lX$e&Dy5#6 z!L(I+DrhheNx20dO=g(+KvD)xz+#GyyTL)+8=@O ze?m1DGFZ+G8Jl>bQyj{ZU8ke(&>W6xz_^$n@VW|nBbqk$ae*xd{tH^hA!;JT2d`rs z<91!l7(&vr$venR6m?{m^YysDqdW~W%bh5tXQ{6f^`KtZ*5@-Rv@T_ON`mQvbn_IF z?jWz0(6wVm&D9hRubi^Zq% zaRj8tQwL^`ZVK^TOfhGika{XB@Q)be{nY~gF zfQn$IixcPc`lz5bovhSaC&;IlRbjN-y{}`bhvuiBY-ZneR+Zx7*AHW`i$U)DPmgTG zw7e1(BzD3(YU;Zb7`GXG3K9&=?m$^+(sI;`G|RaMr#oA+>i7pqDG!nx=NXR*&&=JXs41%iC z2~SvEZjG~7C2SbG+t$QYX%+-5v;AWpAl~G~c;U3(rPL{PJ>haZ;7bR$Nef`Vs)B2fHX+Va-Q>?q>S&hCZz551w0p?X;n| za>L&-%?wpy{Q&Rf?EP@-6zsq2K`ESNyFoG({UfzXd8Nxc{EY!wx$hI@dk>9xGIvBt z9)g*SNak5U1J!Zw>NWd+^plTP3mBtT0KU!ex{u&G znu%VQ?-7@%L5Zn@(U*eZT^OMgJ;kGzlB(+RNYlV2dcI70t}E{KWLi+{!urB4;Dy7t zC!(76%wMllOFM7-Iwpx_bdn5)eV=|SkzLAt12Nm-cvY%%lb~?O#VvR~ZTDCEi1y<4 zW7ev)$v+UD0_0SJxW`h6Zo#wN((CshBZXvEqp`c6*-g{OVssCP^5WMc)a5vo1ZvCSW@_{2pw(n_Er9eB$-83f- z3nUOP`S6b|L+yO90(D5XKmE4_43`m)%y)ItZoeI(2NjC~`W*sT(YsjD2&8EQn=>T` zV?_L{PtlkIeo^XC84FI7`{67b0r^DvZhrQOt-NEN-L6w}d=gQBb6imc~ z)%4x(GjKmVh&tP%)bIAG9Etco>MmR>rjJ8qxB29LaeSuCEM#E&?ZOO~bq~WBmC6nw zyRZafZ0+>;u0@^<4ADQs_Llw;XG`g3r_a14Q>1|VMj*}fc?+S&mO)0q-AldA3E7pE3sm3v^yn9ay$Jy5+@y3~%zE@Q z%jPE>_C5J;cgEjV$cx>?@++gbPJ!jxr#Yf34f`xgPU-QAInv)*oERq;E16 zgt7q@`&knt*>THRH#ms&L|l?7m(!u3U@xba5S)E8)-e zwlpy#!k-=34h;f!*g3Ic@!9smc$=U?6RAIA$=zlJcu&e^gtdcNS8Hu5??Oxlu3k#C+)%u z&PnQ%BL;aom-}!gP90G=7|$#B$`L0Ml^PJHUYh5ft{4=70L7?*jcog9=w5hnEC)$Q zC?f1d7&klbli0#rDg>v?z>2f#@AQbDNC!1Y+7qan6&EcHUC-s6T$rcZRUR+Uw9rsB z{A4ruTcoBoNFsnbhnThEli8iPGUXRrFV3sYd0JJ&GnC3X1DbS+39DCq6i~Y!Ommj3 zH4B4H#{m(*zqf8gK9^Sg1Ce~vualC~0NtT>LtF3+&+cGzOgV^s1kda|Rk`S6c0Vwd!I@h-KMb?2C!;wN36^3MZyz#|F$Xbe88!%q#i` z<2>K@<27Nx6mv0SZZY%MuJ9^dVoMb8Q8*KPw$R6x@}yErxSh3#uU0ICmA*pGhZ;Lk z$2Pza%4e_Pk|uIP{NQ66fl!y{`(QK8Hq61Y{dSwhzYD}<+?_`?5*T-U}`8C zK{$eL#q|!oUl~gHo%=a(;Afc-UY4RH2Gb0lGGY!O@9Kb^}96xsDn*z|3nf95+eP4o>J>r4_cO&RSjR!tKYL{;8#XG2_gGAr`VjoNB4fjdPb&RwjNiBGQAo zt8#FbbKzKAj=iYUx8khu3GWF&oRrmjnALludLTt9a3u+$g_|~Mx#RMk@+8c_y4oeW z+KIsaRGCi-J5cR~B6KcXpWEwsD@HxnP^j8$;N$!dR!!Yj1^{RS$io(#1*gI90SDUv zHY9=y1){(bh#WeCLU>7Q4!O-|ta8_!L5AX%Rf_;3@Q|MoPs3hj-x(?jESR&jgNa@!{TQVkSRK6wx!Mm#^4`= z72QQLR!1)}0Y*j_wj#y8nFzh7w;gt9{>BzZJyOuQ{mmQB_(<6KavxeItLnPXW{U{I zCm+CZ;2lAPOB2uz0kXvc%>Z*m^W`Cc|VD z#EU%ytp+fM0of3squYz6cWCpo^>jD@sh0S|V%Yh9agb6{M-VCHdHsuR}7_ny%k-61o znm{p~-w}F$^x;kYgyP!sUT|W}bCamw=9$NcXF#zzg@%UTufetlyWT1ycr8H*^Gu1C z2%Wdo1R;^^H$YGm0KQq9k^rDaoSPv)pj%ZM@{32wKt43$_M>y@t(epAmWk!xv3BqU zj&D82`~9+OZ`wM8$f%+-mx)={^520!bUFPQm@q}F?CTSxBsvmOb(!v8MTWAy2EThP<0NT+){@K5R_5DVWLziLaXThW1YBC zR0mZ&{4^8kSW7AZ^VPtRneAl`vkn6O!%AtVx2nz$824Ov z0-Tp;ISdE&KXkHrd=qB+*g-HkIy5CjG!6 ze{XjXFWa;o4>{6PK!k`rM7QNP*S}aPZqUhH^1H1yr6KnP4&);2;Au!vfM=Y1B{e+0 zloGm9S$fHW_^NO#C;yx^?NU*wj0HNSMLI;P;qfZBd8j{}hYdAbbNGDrRE4*u(z~th zcn14gpzDw0ltAz0_q(V!;0#(on660O)wuIWc9XkHESb80eXCC8L1ZoMJQo?Z6qv=R zD@xDGqs4{cOw`4LBXGDjJ=MD%abyBRmF@bP!X0Dpm^0E-`}BLX)L{2nIXl?8l-Nis zC4I}MIY|=S$HR}p%u$iM{=W_W@Sq@3BLjS2DjIcmX9M7d^@5+9W8PQsZm6W$v%&L& zh5m}Oy|f__PndDnf9evQB$)eFyOC$st@cxdo!=(c&f5jHgvquz(8UNRy3}Mqp5)oq z3xAcDRe~$-`}cpN1)Y&y3SDAf(wyO^st<-VUM_;Om832No|8Pd;G_{{_WzRnF@!bz zw!Xy!-eVamIlkq4k2DN_4<;g4ziMWb3b2H+C7uc1Siv_tNag<=Ek5om2Y3D$xlfXt zIhl<+s(kwlwys`Vlm?sCj_!xNlRUK(A4cABZ?$$ntn>VcK!gs8ZWV;l?|b+m$#DH9lqRa^R7`LIFP|gn}5$S%Pt6!9S(LtAekefvQ)pK)1& z8On&h4WZ1~iXs+t@FC-}9AWJQWmmq zsX;)WHPQ5-yzLoh9Q8EQQlc@s$j}oFpzk$bFcyA6q01Q^fyPQ)Mo_fb5Lxc_SiJtA zK;McT6WS?*KSKo2KX=r&xs47V)DI_$^YHMkS`|I`n~J>Mt_#NAgRdmm)oEWfJq=(@ zJkK_v@5xnWe#A-B{5=ClVLIr$EBiV7O()Xj4W%Hd0(_%hf#PA-*we>Uo0}9}{VwJp zTj2zA)a>E_rI3+*Z$)%;tv^}24Zp_-j=0+2^z{y;B`81y_V^iXA^q;YNxWf83ub9V zSjFM{FEpa_L&T6*(U5_kzy|1BdH1ikKIzPs*(fZmo>fq-6oomn9qWT!|16u|+55ERS4mUf7 z5Ien7A&-V*0KbpSSjF{AKHpN32WJuQo0=t?lHYhdAxfn8ML=R@$R1fr`H_1sMc%na z!5<;#*WWNIcJ0c2*Z_?Sa;ASqz&OX$i|4ED?`JttI%6diZVgw;5sYi(DxjB;|(b9xGV zFH(3c=mYC^V;=ue)jg8nY2MbDyhKccIc@N4mJZ@^N8sVZ#h~3>3cvcVfA);Vf)_g8 zUIl5E^;nXGER8(yZ_QahuDyJvkn-HWvupk2X>16A+X?7dTt5vM3)#4O8}RmK{o4zY z&`pSZ;2^`sS*&X4HeFxfsMN-JYHa8Zr+m<)$;S7bvCut?j|yvbb^GHTLY(uP{@Ibq=UC`E}Rl zf4;@OII5w0@oVw(-gaXEmb9c1MgWD_5}S_MI62MONGXfuUQ3wqt)!KMrVK$?cL zaIobzXO$e;Lo60Fm-a1r0DD!0cHOB~X3_qx#IXTGW!y3D~xT`)2)=SOz&o8Yhjp1`mHlWS? zQd?VHe^lStd34mkC4z^2ZIrD_2Q_u?)$?1nA&1AB`-%CFal`a($1USr4acqTB)=ZF zO{?&qw9gs4opdZYHJo&=`F}m>+Kk~p?cT|DJAHLf-Ei7--1+si_iU8^+w02(w{LHL z>@|FQ`{(-Ww>|)gz*#?-!ToH2l)Le4kWA|MYzUz$a6U|H;(k8D__*Y z@O_*k$Nl>RPfg?ZNkZZI_bJqvz{NZ9MfZ#M()*1UAMW2AUwlN92wqMrF?d|gsBt%4 z&T3u!e)vgORq$%g(8S|v-t=+P)q-Wf$i&)6SNnTFrJ`M4E*E8xd=Jmt;Jmt^?kDJ}~%Ly%`BHvGr# zppnoay5>P8&wlcRnr>z#KXIUPwS9Z=5pEI6uGX-4=l4nXezWYum){=b3ubfA^?pn4 zAVL?Ac3?sYtrr0F+0;{~*B8^OPxAyna8Cy-4{_7>Tsd^Gh10G^mM|eo3apnuSvb`H zb!h9OG(-RQq!O+v;DBdM6CM z?*BBYdRbg|HPr0V57Fry>?}nZ9rgd7)T)V${eBK;e*(Ft|M5cGe^71e^oj|?SQnOtakf+CD!=9=MrAf=}z6P9Pc{T*Od zm(@|&C6{P{S~8wZEMe}3W6%O_dHSd1*w~?Us^nqc+x?-9w66O3lo$N^V{&_8!q(H4fk`ZVVfv{&V%j5 z+b5g@0oV?9ggXTE<2G+6kCd(t{?ZxFt9c0ilBUL0SBaqpY+Bf-5Z5Zz>U_Q!&9neZFIdFsZ!O)IjOd75YjtL(1Hif4);Pq2H;E#!xVtZfD_#C3hUw zndJMrwvx67(0o_mr%p`dp zy2^J3&*MO-EdB5UTIKCP2%$PYb~FilhBff{^`UEZdr8D#d+z!f#zoV{6^@ z1FbV!5GNpPh{Bz*CgX`{%v$R~Pe6HY(;xdUlY~iiMQG{pMAs5^w0XTtgf5OwH_!9c z%Hicy5tf-ugh^F9+Chz+!7}~obeKc!``BG-T{nm)7$KaNZZCc0bWx;WZ49b$a?k!WHnb{FE@741a*Thei!^Rc? z@l@oo`R&Kc&jqR&DLyHF&xq z(cZqX#IEjyK&tPnd5Fc(MhvbaYQ`I;gqwv}Ii1fXB>PdKn;Z#0o0 zgU_Dc9rt8q^kle_3M}2#l(R@lSh)o9Zj2!eU%hl(w6<*&A~;Y|Tbl4+OlfTZzjAyS zpQl)%CEdPh+RE@_b0Q!e?={csCNmVUz;s4GP#PhB<>Kt`8rg5dStx?5c9M+9PBxz* z{sFGBvSW(tJ{VU|t8`Y~gKGcC_Z^ODfoU0mXeM-jN{1^W%^FRsI|B3 z2gp#xjy#E_=>L+kE%qiNlargyGRrNyj#qnx*F@`2>e$;MnBzaOWGb2D?bYl!&#bhZ z%|bQ$w(POZB#Qfi;$P?&Wb$8ej3)B&7nD_VbGE&&b`oC0W^S_Mqe-WCy$6Gm+}6aZ z%n?G*US--#GxT)WV)n|s*b2|E9r^qzn#io+q&ovd4{;v)M#O2M0R4wl?z#wHOinBOz|%1oB+xYQ`h&&L>%a zCbjeISP)0&^44#-+W#&tnXS`g)D*zY%-y8kPhdH$3XzI1S&LyO5n)IfoZMP$xd0m> z`h$=8Y44{-8x=!jy2yJ+&akLUTOqmO!IjeE?GOEW0Z+%?ttzI|O+*~%WpvXr22=v% ziP)!*DS1gY2G^^$TXdq55KXC}=#rVzxs;s3cg4p?xzsd=ef<3Th7yf$U%YK&{W0=b zj?+Lo!Z#xhQ4NQ5A*;02fPmXsOXl3KUaK>=I~mW{xT%#zi?~B2uX4#fq9V2LHJz&B zof#5%L$!EVRYmjM#|ywpY6aO>wv?xP^vr8RB;Pdf71Y(1B2OJEjL%8c{6W+;mEcxO zWhQfwXdLUn91AZbXzDfdsq>u*i^m#!W6x(?TM?pNtuF` zINmwex%-g0~hKAOg?M^Sn3Eub47lGD?ca5`#o(5ZCMk!v(lkSljiy$=$DS-b9I1`taMX^6J|SeRm0$NJ%+?mu0jWzw zeQ!a*WSWulzCNO?E$C?RTaXI{z_h7TnsY!2UekrQuX-A^4t<0>AB!X7t@XKzH@;?^ ziL-3G@Mq-tcp@!6tZMYu|Hl`Nzo?t!`uGRP)P}zDt*0caV!ay441j`K^JZr^O3{N{ z-pU=VWK!9z*Yoy}+pXl`BP?Aty zwW==qRQ2j$BZaASebR{GmrR^-Y+`3D-AvG@NfN_5^h27b<|D(VVU_) zeIm%1*$T~rF11HqM&G5La?&ZdLL|h#m_yG6 zfNdHSSl>GX;b;Z_-!(jbi|hf5l4Ugkn&86LSFFJF9xi-03YwYT=Jz zw%fAZzmUtywjee(X-FJ@p;K2dOc9_KZ~Cizo#Kk&o>z^|o-R9e*Ddd9x|- zHrFC6E?y@yK3LLx!kJGwC-{s=zV;x>YDgg{^ZBu(jX|fl<6LrT9D)-fk@;*6M z)X)9Gs6E17T+Z4?WiI4sqOr%@qH4cFmm1K`+UgY#NwcLsd+~0|4?}NzlBq-~BIlKE zx>uomdoF?B-jwv*$e|zVgCCVB=7Gqt0X1;6=AQiHq7VW(kxN4#lEz#;oaS22JgLw5 zOBx}_8Rj?ReANy46NqSR(J|x6APHCfMwd=e8iu`*SdT_jk|dBhQ39yN%s20h-dN-f zWLC63o18HTBHXPLipA(qr9jgxEMR5j)S21GE|0_h7-<|nE- zm95;K4Dz;Yjv{dyJ@Xj~SqLUBu^LP+6{~xenP6Wu7PdvFa=@kCdjH`~U@P<~NF;|M ztf1N@Pe}j4WSWrito{;-Len<;-(BV0i@>!39iQz> z<*SFLuHZtH#Ubt{lnSyzXh_`j<5P9<a4ozlob^dr|#>8r18-@x%7imF08W1-*fY zX|a+aTJH~gLj3_$Yd(ksMlIcX^It;{2qxH%n@)_4vkqG6GAMkI}qfm_2Xn{VQKL;ssS}A_f{ZcSVDu z4wwk_4x>63=SO==rRp3_pAeW{9dir&<5!~HW>k65jPsw3^VBv_By=#6rA&&G1;oTS z=w`-LBusTz%n=c5B)GMLAaEr5AO^fkbMm-#g`QpbinACU(|NRf$xss;rU{ltD3TV% zn-Pa|;m$#3Z!{cJRTRqh;c3HndGgSY_fZ8aRKE?WERK-;i7$x;@)>1?(-$QNz>jqC z7#MgL@TUwFEK?%7Q-hnQ-YW}-rL|U3<7hBO;PWOCS&{V|ete92U_}H`IqxT9vDCeQ zJ2_HxJycq5Xz+?`7wU!dLi=}W<&PIn1MO^VkDB)g#9E?MU`xkbkh7FxhzxNj#!99Ur^ zIq&OwY{+nb*k8`R_LkQRQVjnPTZ^U}Cb!@fDxJpg#@0U1U{W6rwk1F-4Fk)3Izx9J z6i~l=Y-7aLJKjLoWa>CH4qM{TwYX6Tp1aeb|Mbj@v+a;tu`M~vr)J_Se=xqyNoG|X zVIlo6f+>7uIsJZIxqZXjGtZ+LGesVOR^)6G0Xv{Nu$73DpNtQ&l0dKh2ZlusN zqWQyL@rlJkO4nYA%00Wu%!R6@0bv^?Scn@`8hT!^si2V2@Ja(|QW0e0GaSH_e*A@I zt25cLPL%51kgx*rTtUN=o4k@kfAjlFKru0Pfqd4PR{i^<(!p#$1H8o&BI-M z$|6j%E_AB&eCTWUROZrD-oaEZ<2!teCjWVpEZIbN;k#RU4~9rN+6vojVegHF0P*3tfNCTcB{txEff-BB7UDqw#p&+ecBn`X99bdSJ6r~qJC3+{IeLs3I$hF4@_9n%-xzovn=d&uR+xTr?Umh zO)6e<8e^DHX>&TZZ?q=o3^HT=bKwnj=gp!>sG@Q{c+J~X;!3T|JCH0m@h`a8Hmd0^ ze9T<%__pA=w&4A|;5$}W4_pj<#thJ14E4g)&s>aLTa12Qj3rr$=U+MB?Avn1+H%$Nay7|HE&ocr?n$jEm zwUv(Nl`fLi9{$xn-PHlF)xpfw;cu&>YpdhWtCJ*a)BJ0*x@+@ZYm1p{%iq>k*Vfj- z&ug0`>)ZV6ySnT9Uh9XM>&M^LPuC#Jrt6m^8`u0BKXf;4y*BRu?Xs!&CSumVE}L!@ zv||6iv~0S*WYgHBq_;;zBHizSRb{=WGhT>Wg{8l~7r@?OB*2iS0U0;dvdE%KvY@q& zrZY&xTzcAXs)=@~qFelYU};1?SA1YDvgiHRWmE9~$+BsY_i;(qaaqT4#rkp8%W*a7 zNv*(1z1~Tq_epcsNo&VR`}#@8%SjjMX^+5ZpWf+!_vv8P>2SyC==$mS%jqQP*|fmf ztlrtY_t|3B*>cC(>iXIG%h@LB`L@9MuHN~+_xWMg`LV*P^STAif`wPukSmAS4{uwI~ z={ycRN570+Suk05pdh24k^_Cx1KN%-pnakD?I2~`Xr$`o{Rx)xVM@FdEe-R|MFXXl+=_HF358j(JIe247sfTb z0xtNNpzZ*461n>O5kH}5JXRT%d!?O$a71xjCQAp(!4O8;tUjr@-G8e5d4VNVIsBvY zr|@ASOSwoklY@Fm<#?tTJ<+aR#`RdOn5w~hZ+X^Qqgpoq%bJH;#at42SxX!Rk3p^8 zb!eSSR=q;E(&p#zGlQa)cAM{-5toiDv)+JroWMUSf3hqcHU*==Jo+weKQ39v^SI)1 zb<#Mydr38Y^lUwDPG-mo-hi0S9$f6^vcCby!?XQS z`O^j9x(P2jw$hpu${<`V6-ML>ui(mhRGutCqNu-QNAg;pEJ0##8y5bv@<;yEK^%`n zY_d3zis(w5$S?0gg2a8dMlv7zFEv1z0DnL%H1B_YxR$VKQVjps!}Y((UzSYe|Glfe zSTSEloWbzV!}VJ09M!^CgFn0Km;QdZUV+pA!8g!0Rjonhz8F@gW2@GGAFlPZRJS_2 z|D^`V$w2uxV*0ZNsP_>KQUi1}Q}Ur4-s@w-$wKv;YcE79!;?kG;TrwHy6K`l$OnR$ zbaEHAeJ-riE#*Gy4dVx1lv+~v_E|Jw$0R^(6jw^dkLBQ z`pS#+{OkVaWaHw~t6#9_fUXT+4MSXg2Ur@Z4=%{uki#|ik~*d@P));-9y`i#E0{~FHJwD8j9auV)k3!9`i+>7%W|s*z*cIdbW;o`x+Uw63AnAdRB$P~KN(J| zHCse%EDaz9{^R>%=ASUkb(&9^mDt66TQ=#XrLR_-3 zX{V6Gwd}z-1Tk&yeToggzb#KFe1We}wf8mCEQUcqsYvcXe&hMUzKQ+xvd;-h?l)r6 zN$!(zDs$8!_F=lNCXIn0CiS4m--t;rv5n<7Vq(iJWB40lig0nB5Ne~hoz&Kp;~ZNh z{f(I3oc;K3hzSM37J`_@tO$(WXHX%T7FTi?JXQTOVnRq0UVnxMZ*_h4L}0n!3}nO= z-?|$2yWfs{bAG=QE6MV(o2YL0u$N+9^{}7ee*SQf6T|#-bpCi! z{hj64Y5juTABgGKdHdb@uZu1O)~CxpJo~4sLE5iR*Q0MPo*;CI_4&uFy8ZLdMf0!E zx2x_K&v%<4tS|Sw$v*U9FuC^LZut$_FG8198@gExBZ3)^=$rQ7m#4c6Fc^TE13-}K zf+ke_93q_qQ{vnO&wJ?yjLdPC$nv3o}*h~6&86t$52aHY5@1!7%lXR&G$qp~Uq#?Zu zyD8Oo&5`P7(7FoO7|p|N8tiBBxQZ}9&By;PHNcVPs0GiPPq;8Rz}SgA8gM z&2UjGzKfXry-D~t4!+V%P&>{)`^9?wPY(WZiy7`0;U6M(Fqto#tpK5GZ6;Ob^`>!& zw-Ax~&A}leb@N&qMnmt5Ip^EtQf9kf!G_;R5H(}hoapCMG5-7M3qNagCq?tS5pWFM@kRW3#Q*s zVRMw+PrZAP%HXqTglt;aArG2lxWE?~xjGZ}>1BFi;RWY`+&htTjYoKSDi72ebzo2>mGY<{a4G7r8gGbQ!#0U@=EzZyL5a; zWtnuv#`P~F@m1Jy*1tLUFTC{gft7eH-r>(0O_EW9ax(nN9Ebn)`*@;fW|>BoXS`1$_e>%WTBr7xmf4m952{~%If;rRc9NNx99 za*uB5ik19Bq~t=R`apzNp;B^rSjmHZG`v?~ijjHP#lJ;Li4m$T4;O5d$NU$O(z-A< zlY@v94+&}QKSb&)YI!s{65@ZAA(8{U0V&Y?|8Wb&TblpYLNN?WZ}`_13ML$EVrj*a zt~B^KXx+aHjA@z5a8DXnAys#pSk7GO-~R<=QqJ%KtvIEjn;bTZqE>!Z{QehoyvE4w z4}+u)1GA5;A-vfX0B7&Inf&$7GDIDv>O|%=VyUIkFI74d4)lMPA(rSPK(Dv&UE?A^ zc79&c`!2sM77W@zW#qVH&HKFn(`XYzscGLTPxFSBW5iN+akeaz`Ew(2J!metjZeE$ zkL(YD`LwO0`QA?<_!YhKigdpnbK$3Qwa!z_C-)2Ww#x&!-$t7>)nqeeo1T8>JIw>Y z$Gf+e+BTIs2fp6uPuK6gH{+BxL&$^a^5k`)C~{$cDybU=!8{vJ2v+7SW-y=WSnLS0 zv|6ChmPQ@^78p$>Xc{|L0#7c1`yBoU$CN(Yd=>Z1;7%T2%8;{MtH^iTPFEJ84ImfJvzs@j%&_DY3jb(*3wARvs-L%F zRB?K4!Lggu{kWFMP6O2yr_8am9lZEydDS{;{TO1j8R#R@QG){b8r~wQ81m=7)Ja1Z zK|3zF*&87imo&yI%LKKpSsK+tj5c4zlNeMdX<*J|BpA(J!ZWewYln)wA_xn1eC!(Q zg0yeAAx0Z?zZM#x82{Tz?IyJP5@u!coN~3MIL26Sa7H<$r`+u#Wgk-$vAw!5_RobT zXeFK4L@j_pU6(DcHg&YR(Sm|Iixo9R77J}9XQcu3WQCCQN2%F1m`Xao8AVxu*r44x z0%z-Gi$<*KEephGBMcJ%+237wODjBg^{ZGX{Z@xQ z0{kgbxwl;1(z-VH&GctMxIN@d8}F&!aXk~{?v1N6<2}%FfS}0~t0=|1kF$fmh;W%^ z-70=MfUivN;tY=Eh{dLRk$=4SQ0Sg&jY7N6cd5}3tcd;8fqa=wXIBH~qCZ#oGwxE= zqAF=|O>#|;RExUfxGR}8>6Cyqv#O$TQ#z~l7SbHvIg{J-a(~^_xR1~}WaviYt zx{ic{4N1TK*T~cQccGjL8u7_E3>V_dw0YPfKii1tZ&<#0e(jPT=~rWBu_B4enaBK` zT5~NwX2RuTt!$o&NZ`%yvA9huTzNPLtv|l*_4`>uV?Q6Vy%<%1Q(``Jot4q!%VNCsTr! zp?&-xWbLcrhmE`oSV*m+%O#F@m>Fur8TqCLZ3?ojTAftYQBt%ybLCFk5iNxCr)pQt zN1clLQmcB@>6<8Hsmz#D_D-^`;$ulTv#x}7%MbJ`g1}t+vHm#A;gbOjDl$u5cIJJY z#UiYrEHzYR@_^ZR-t=C%a*eNEdFeRIA2niWx#&bhBY~YFGRO{7%t|%};$IO#^=GRR z*09p6BIXR3R~2=M(4Ug7i;{^nT;Tv=MiZA69Pxc(Gd7fQy6%m=v+3MPrBA*1t{TGm zoM}UNYt|H9a>w<7(?7~FN7lUtWco~MF}S6e5CJZdV#%Z&`az7-Qg#Ufx9@0UEmX;L zqr}vInvSU7mcTI%kORGsQ7b~d22(T&GK<$^1h6yKO_7!7a2iCi#CS3BlWw`+sD*R& zT1Q!g5aL&++`jph5Osc?pZ}}*m0MVpt;q3B_8Iu9oUh7%tcO!{VQhAf>+y*ih}Oea zkJ)e8z9I*`hs8(j&(cD`xb0PcjqAPElWvz}%kJgg9-t8vhGRw9#)+KHTORlBkLtAwr1|!R#>P^_9(zY!NMU7OitzR{i17_w7$z0CWMlbs`gl5+i!e}PjiML3C_wC+|0Or& zYTsAfJ+;1f$uYVDD^?cyNtTuHNvKR!$J1tZqj{MbHI*(lPCg6D|+8-wd_J^71<%IuozK9V+aC&3M7`}UTh`#Hhsh9H!La5d zy$UvsE8e?S)fB!H43~QcfHdEXzZkS+>j-OV;dIGeGGIExHGm5J+Kc+#$GkS@Nwx#d-)P2jaRoP znT{(wcl#B@m%jO{pr(u~-r0uJm;pUcUgvyO+qm~t;Hd?P=!?N@&}fk7J_hm~ZrTir z=mwkl=hp|&1e{nwaD;vJU)_--Nx?6OpoPHOMFA>OYd#)cU~A8KLQq`@V`CL8Qcj0p zq>=JV%`o`spct%CXv9F{Rj8;li^pmVa(52#Fl`_xinorr6{_oI+nra{*`s~`O2ycm z?4-bu*v0Tp!X#V*dtBx1<`!}xKypM~e%6KJVaopzA%Jzzf02Tg$H)?ahjrGEWEftf zLCr!GN6VYb+bRy1&-k@4H&DUY)~lcNtFjJWup?ifJ&Us|o`|U_5KyPa2fc+M52Do@ zq|!^F(8CY@03FN#uTUiv^wxs$mk1?)ikImeVQ+W96_y=Q&cW5Lv>M7!d1TSbz@!pO45hF;18G}2)^wnQQ?aY8zxnuU zEXNxq9R+h=vrFbXHs=Dd3ZrCU zd^RvC^}9b!(|TPrTeiW{o`=3svxrH)4t^8jC6dg-i}UHRm`v3O>J)=gLi$0<7`{HIgSL&3?&fqOjML-lR$f zZ+?{MPHc#eBy@^nu^_puA@<>5P))E#5+~YX~&#Od5fdebwhU2z$en} zSH)@3F8y&a&Y?r|G(_Ec0yE_hCQM ze&qFOrk_%IsUq4aYSb?rYK1)EfyHSRZ;bV7lF$LLBx0C3$sY`7#ckYxHil9iK=a_Z z!ns^*iK|?jvVsW?ng|g|RJwSV=Jfg<{ef5cFpeo=;`ZT%K$16PwPD=R2f*0|Bqt7h z2NR3{@Nv;(EnI{M^)NwFI+oD<7I}1IJgg%_8;%t^dx_h=9O93hYo}y{sdv)s?~x2J zUc|A%xyI4Ftn;+)0o!DtPwqZF`cKr-m?ijH z9h(pSUK)8HBgE8x&6O!4+BEZEN;D#mWGqlz{G* zWt7Jix;-@g%89ukdPXfv#amy33(ZhWOz29`j(JF|kFPz)&8F$w`~U=gBl*$+ah zSi*4f(mZioBEl7QO)YxT6N!`}ptKcmDFFzNzPOapiDPU|LI{N5X0 znrnRs^B&ZI77RrA#U@!GuG6KaKqL{tMUAekSp^~!yY(}1RzNirBmB_xikDT|x*8fY zH^sS;+4)_rk~WU}dujECdMHe+&zPD{rD%@n9(mZNikMZK`2xpHvNIk@W^VIw4!1M$ z_Lxm9P&Ld>Vw7;0y35qX*0mmdsf~&)pR8M^K)i=Dye}o5bwzozs?joW&E&a!(L_!t z?6nQoq59u}w+<+sC~XZ`O&EQ|({+rHf+af<#jFt;_EwJe6`)}RaG?3yTnc?2*a9=! z+;jMZ?UyKU@wn_m9?6h$bFC=8fm$p8X<2%MD5j?DFIt^F(<`rvgnzo+uZ;4#; zNg7;|*qFwtoI^bkn4h~-jf|nh3a#iFD!Y*Jv5d0Ib#l10!fG%NsajD~J2{A%k6u}i z!)TenD{^s&nXn;M8 zC=jq?d0GP>ugZS-(fw_aVRB}ugrm6Y9%xj=Xe88I z*#UF_dapD%B(VFKDEcwkWd`1{R>yxEMg=JuOS5J$$sfxj9LPVrlW1^d{2XDwF2{0{ z7?plK1gAFMgk^Br?!bmWiN!Q|I{0~YwM%`L(iMcj2;xFF?2&|#>`NXt1A7Y8M!fR1#@W|bu1RF`rQo75*glG-%fr z$bMl4Ythzkl6$WGoK}QXx2LtoXom&{?VjiDKhf`l|BW$PvTy(;@#_U*B*zHNMFA1yeC2qNS5cbtYOp^^F==8MjQ_-Y^S(HUo}(@jJ;{QFoc-8LnOJ^t2adYv!6+_fR1iL}7D{f^X|9D?GdE zwa(-yueB_5Rvn@mwSHMi-{}HE4p_VL+Sr34U#^84^4s96fqjWu*rA1Lp;&_Q-pprD z%BM;~T;I&UT1O|{@_^dHs(Qt#y@gz}X0F|i|Ki5B#xbzA1rpe%(%Yu--u^fRpzGLn z69zE7Y%Aw(Bd~vE)7#kpZk9n-@i!jul+N=k3PM)pSw&swX-sxgbc`> zo>Ez@QYf6+HlK1v{crGn$NA~{`T5KFCF#Yrz{L-}i(BuDf~vFo^{~f|i`O@ivQxBAN;wqW&R%20j(A^l>d9)`EO=V&b3^sw;;18L})q9zh_VQWWxSH z2^>QP|1^8@2k+FYtYhoWt@t}iFoJsb6x7yq@lTPu_qO&eH-AG3yqB=^b=Ke0O(49} zpvm`dDB%#v=>0^;voiTP+H&}NaFI2_+6iB1S!bu{7#?-ax{K+(`KBKtO$h`gK)dP( zFrguC1=8)A>k`4(c7?%YI0!=`b-{GokVqY!ku!R;(Y6~#l?G-w3)bCxh{Inp-?eh} zBW9#@L&;8z-xvZ_05^np`X#Uzqzg-TNn|k7tvgY9VJTP^#%+@v3^Oz69qn09xk6am zM40q`>f~7Hep>HZ{GP}Q50Ez9rM5`yccjkT;_2+@Alr9-NINGG*GiKfpWCH4HQxCuX5vlvyp*fi`$gQ3Bb)589POSl9ACAIXiE>-%X1fz+nNi%t zv!>sXI>VjDoe_y`xX*u$)cHh5Ty$7#4PSJUMIm2y5i805B~s^*`7bEJU1t&-E^NDI z09pvUe~>QOn(bR%0VGm~{|m+0V{QC*q)xIvLKJ0Jj-p=RUm|t?j(7g2k-EG7|4Wqc zxg6;??agx<3I&w1y5!?2e{t&bp4%zDJXq68n?y$J|Ph@J=szqHMd{)Kn`Hn+4ztFof>;k6$*@e;$?%pp0So+YKM`BL5!2`@b4AdQB7c4@mgeL8Cuk z_E_t0C&S-gHpI!WKK8FK8{+KYfV^xHg{a?<@MN*hdgE_ShQC9?!V z`<%CD`9{QSB01Bs1s`Yv3CpJ0s7WB3H`YVKvH{G}w6W5GpAI5C>>B$;yv~Q_vnyIa zhq6A{-U0AUAxovZJC5x8tMY94l@!NCeO7xb$yf*|M2z)8-b2 zlM2WU|D>{+^hC)Qg?|;maXIB)%sXhW3X>12KIB=8A-%AqgbnJ8p_a;Jh+3X}-)Gh$iB9 z3Ph}>8cM*HFA@t=GL`*8W*Ds_ePcS7^2U65H7uccJP^eP8AqD4Kq;9&0iBZhD#l)*PC)>>|${ zSI-=VLsN99cKyXh4z1iE+8@zxvic%MVVUcLNpbB^g>N1|=w-&gcmTx=tX9ms`M^vi z#LT4#P$~&)KLAK8TJt+2;1h31^gAjO#fG+8&Mgo*aY6f&P2s?X&`21Lxb7qWWR4IT zO%1s>ww61o7Fe}pE7+~(x{DRLCnS~+MtW;l2nxj64|5i)L@3e-#82e6sgzpR;7lt- z62|Lrn+PL@{F*gjAm6Fj(=*A~P>lN?g~$FqT?7LW^tCcDTzAOUu*R*})! zk>g90WD&uJi&bN(SuzTg5HJJL7Ag_@CqJMM=5{fjN{fhs9a*FU2rDM0g(`L+^tA>= zs;8NExL=S{)1sJ_XvRR5rh+cEuR-7{GanEXZdz=h8UE;-f*E^VT2!qEzTH5mnU~oL zFc)AO&?x$Odmz$?mI89bcxP22O%M< z`aL1L(ub(N8rQ$0Tj4lBEE`z!ohV?nMw~2xxORvV#TelUPS1z|JPG9BUEI3S%yjeH60Y}BI`>uSuTXSzab6@j%C2+s( zN88b~75?U>X)~Tupk>Egbev}|!+8B+FGri@ajQTQLa2-GDnIQN+Mhq1qgF1@uLj2$Qa_oku8W}<%z8nWVCeK_{C4AALcPGIiO1a49gQBGKlk5kKk&9rV z*cZibww{bE3FjQCY4+BCkSFyozR1^n?lH#~d zaqePNR77v3g$1tTBkN6Qs2`+S+L2jh#1QdkIEGt8>FILYN9ei&zc?CPC0#xiG|14$ zs?}3)1jvl=C?k#NZ5R7r?-*&Dyu~#V=<>0ND`aoMhCIU=7E8_%juDWYzSe7Aa84c$ znGlU$u#&7%su@p&s5sDXENMZ`ytlC>_U2PvSO9S(4;)rLbO%GI1A#c#+z|M^&DIBY zgO#nD#fJuDi3xW-6T@hWw}Td0j^sR}D56t5`Qa>6d7ZsON2P@8p+Y*{QW@>x>4csiMOenf`(_ZvE~Y&<;s+! zAkCYcTvfnny_6fMzsbabdz`4*n&+&rpx!+)uE-LuvdC&1R?ZLEnMD>I>$T^iO> zV=EJpdWala${BsdnMv|0M1&9c@^r&AA!niICd^Ee7bvT$t~Xl?c566bdTNeLX*)h zxI&Vbg4#c{AIe|U_BqM^Y+d-KLq15SF(qK~?XE*Tih>BfNAQCZj+k2ig>trfFhcVd zlnb!hAMXjEl_8GYH#<*za?)eYf&cAFoZ719^A`F|btfr$O=yhsIzr;dK01Y(aCIia z>DI*$Y*nU_EpK&7%Rm_yy6jSY&ots(a&r2Lo+^E96I=CDt6WW?DwP_K?`;=a8;4x&o*IG{qAe7#R zaiY~M3j`5l{vGPEkLdNmxAe*G9h$6axb=A}ePTe?$0?lST78C;0kJ#r@fv8(f;pxm z`Ok#fnJjfw7a>RQ(+SxaP=A)Hj~%Ps&5Q?J-RSuq9BYXlOxpYXG?1}9(HoHr!d4*r z>Xj*=x>1OB;QT`i`rT>Hi0K@r{Xru9v_skZQ}eucA~P2c6uozj1; z9x61oE{vVKZBVcHP;fqGo!NyFq_fPEMpPwL;(^xN)&XA=w7t8@=%4t)px*PCxmj3t zaO!MX;WlaCGoLi?5^dw#kM>SDE%y??+abqj8I)AGj+YEsrvcy1fB!IkT``xu!5s5e z$1SuxsS|FGL$IOmBJTu2B|}p9h;c_jT0WmHvkp~#MY3J;k(bQ6 zN%!N7{JNun-fEpg_rv^mQlXjzFJ*4Qwq=TsG4fUX2bSitxTI|E{w~jF_iHWMKS)VB zb~4xaeIij`qV0mUuEu(vcy$Z_c$Kd@=Ce_sc4#+nfyEE1x1otUw6A|OGY*_4Zp0pp z_4LCu7|9kKe&T`zvrOC@*a#4xcb-{(Mb3Qw7*qM}+Mt?tCe3NxwCy0>>S)&UWAnats#xL^%R~<_UwpGo||ZKts%RS0IuCFV8tV zT3=i>BRu75N0bs=Bywu$99B{~Y7P+~s;DbH75=p-&76xb43tmk793)?KS2tCbPkzv zH5}KXAL2GSNpk?uKcL@;5QtB8(B!2_3$(qIhLVz24#JCfQyjPnRKO4Nq6$hp2zY8h z()JA+hVmy`3?e=ZGQbZoRu6EiMKUo6Hfx5{z9i(MgX6jn#&V!j289ThP?#uV_;t&e z>8>&Mk+<|WKK^Um*vJNFVW6pA~-gIn=YSX9Gqdx}^))+0O6glQUCnHqN)FtY!W~M9Mxj8?+oZr?!@%%GGL1v~lpAA0fesUgmRB8p*c|;t z2ZVY6z`cz{lm;TC#-a_y!Xm|?yai%N$6;E=y|RqOD~%%v1CBMj0sw(rDd9|5lm@Wx zZmWa42FW<5;|*tM3lu}JYbmkA@Tx4Lx4=TcTYT)pK;X+gpo|?1v)MkMHqvB z2zOs90Yx|lb}AZUGu-Sd5!x?#I5bh1A{iqG-8eVde<+z$It7+J1;sBVC^ZE!H%6Sm zkNS?#X`5WxAVQW~X6Xk;K`fyDV?=$Te5(a5DP05xEd9oQE_# zlzAT(&6S!xQG)*CJ`+(m`B4-17!V_R6te_OJYP)wJd}b?h&>?Z5+*cSF}F3szAVn{hiYBVUO9ZsF&3GW)>Qaeg2eiQC?oqtOaniA-;K?THc zt#G|kG|R03;$UOAMt<+EpiCwVQ3loV04bIfYRmEf)qedTxb#hivj^qC$M{w$WS!JJ zA$(2|j*7VuTw8Twvul9rB>-Cpu2hEL+^8J7hIU3I+>L=&Ni)AWT&!)`qW~C#!-4dzKJkXM z7+7`jTYwL4s$|W6sK10Ntt!7g=+|*|q!Efm7+poMXfb)qMEMa`3-AW`B1iVnz1dzYkC6qAZ$;cdRoZ>W zWkYOC6>fmgeM$msX{-qR`lf=-{NgKy_LAV7!(iR=8f@8Wt)nE*X=<-&WRppB@Fe-l zeSLDj0y6ksn2E3?Rigv%ns!Ah8w0l8#DHlGiuPM;M6o2i{UF`9(yYeCtl1H+g%#xV zSotyKwmqn(yMWL6G<6w?ZTx*-C-y)(E({;r8t!ihy>BB7W~d8N8dKGQ&aFsHR{0J_ z3T9o`%5hYOf1kk5{ zo#>7d`)-WkAUkLh0M{$zF_5a`B%o>3?Bw4RmR|m&zWjTAH<|^12Oq)E2SjLLM8rYe zCTqq`LWMm7K^)5N`<;lm^qQi6kV|{LGt+BMnf$zFveZvmT|2$r9BGg7K+?}_*@Z3f zHLy0|8fqfEj)jC0vyY_lr(IV!(!XYdFin_pL%R#-vYKFN*+I0v)~%VPA0pbCb(fl- zM7uWY+Ds$8yr&Qinz&yj+DePGpkNObA2`>KbUU;M1f2Gq)VUx5ywN%8MMv`Tngp4ys*lQW_ z93UOXEZI6Xk03_X60ycGOm`;SY$Fs7 zrUJeMi+moH&&Q8k-36Ij1PCMt4JN{7tfJfc*4!Ko%o#U769$h>5!>C*(w700rz=%P zqeQ-iH6c!RAA)=%M&Z2J3^Ym5(S*h@BXzIovDVtd|!bV4gF&dK!6$2Bvdn3TF#4hsik zO`+>r8l6?U5aSCqU!$bTH)~l?%53_rodlN*hH($3e(fo*5P~m{(pM-^DCMa_WH+oz zTbLLj<(oxD`9OiQUAaTZlD8La<$fd)6y zn|Y9S#55MuS5mg(z5x@4)TO{7(B&P_7J`Zm=Lk>2x{XoJf6>=G3xdO=MnOnKSc|<>jbjF`X3Bw=TNr_1lL6_G9c-Th%9zEA zAlIvnr3wkk@NM(XUA}b{SP0pa9L~b2sxjrp zyd(kw#~)7?@0gEL-wKVkHh&e_O8kcVCZjv+g#yF=!jUe^4z)^ZoDq7eQrlLmR)+F> z6nU!c$*3_cr=9zmscc3pAR1*k=36~^=giGnZ~o$0@#(*5<*~Xo#<}aa#rF!6k5zN`rwmfItJF?+n!SQm zLLhiES)Ti)Z22naEfnUKpX|zXlN(eXdWuzm+fUgS>w})$;JHp;vUr<&zYdLi?CvSC zlN$Cl^0$$}=8G?dj64>_3wam23`>T#6!WWF%#b_5c9*q2L5*J6IUE2roQ zy47j`LDm}MVKEA%;(S$xzsPH6*p+GgfC2_00kGFV)WTR%vgrb2t>W=wd17P$DG_)I zMuCo(Q`;i$f$jp)cvb2om1UH)kBw?vD{{C)gH0_{ZV*CxYQlx|F# znm1~VXxR#zY9O#8kw z-_)F$@bTa!`)q&PTcIqUL%ED6DaFXDtEenN3VCZiV3L26#i}q$Em(%WFnZtmh(fzS z(H8^|-A0Z@eDlFN4_mYL``fTlK6VKLa~pcj&XyTd4qZpJD6`ZzQqL}-z>LQz zp54&T(Ss4Q&}I1>C3!V66ZrKbyy~&gF~xZD#$lo%4la{2uQ4A@3p4w~qO)Cd_jF^~CpxJ+^0*Fe5d>3q= zQ@Lw3X__As%r+*qBU`GF1^p^ar*hQv6x=V5>ZSa(sDAq=ln{U3tzT&D+@W=W@w*>G zrfa2Ni@VkZMr$(g>ke=uE|4ldsKD7>O@7hl_+`_LU@!gdH6!WA_ExPmXaEP(i&IIb z{aT<&o`y4)NvyDkZGR_{;MGhJot1GZyl#2B({jP2y~(o9D}s_|v2)^E@0msm=SlYi zFZUwXbw1si&vFJ4&PnrDy0P|N>WqL%r=x{15U4N;;c=|e{dJ))17CDFw0<9gi!x&= zEH{Ndz1wRJYsP(n;rcvspa&4??DO|q?}$WiXB1_uUIG~owe$g7C?{@fG^cQG3i``K zIkQBtU` zI<~9DL8ZMDs@qOq!=xqx)to*|)kF1z9;mP>6wsg)MMRg!bm#*zf(xf$w6BqcLr8D+pS)h?!(S*R=e4k z1e_r?`7PvEeAhX{x?i;kOZA)qmeO|ylaxYiInF7RX~N!tVHi$E;(mHJzV%PZ)EaFuAp zQVF|Y5ZU5dLWMH!`e@}nDG3K05UmJ$V_YA5$*jJ>nVya0$W)u-)mj$#KV%@<0kB7f zluAH_8Ws-Y=HGT!%cwC5rQUJHLm|5K2}Kn|ZjrYtOXWI5Eu>8diS_c7^^F%{0sQUC zQio%ZE0+W^dQylxzC%u?kP<7vp6Y_BwTcU(m@C)s zH!(t#7&@Vjq0f|Evu5h~!0;29Wi35k}* zUzk%(ticzh#LN(@Kb$3pvhmxX8kx|_>o}Z-&ZN-=MX6vMZd=ff3>tw&(u|7#S1+9* zdR32~@1~7ts_+QPDE&|t!T@fR@(t)9+c4locmd_y8lpY5vRpV1E`@p_q7*IUkK~{` zP1!7>w_n>vG(a*+s7x|jgQ9Kt?Vc0i4@3{uX)R7u^^c^MhxP=-VrYf1wL4x8F8B_R z0a3AUL_$*1uP6Jy+$&K(pzN5D%c{TZe{jc%Fr<*|rIg>Sr{ii5^*6_2#3}s|!Mr}m zOiFGN2-E~goQK95gDXsaXkprlm5!0vxH1ZGI4cuEYniiT7sq#$=o82$5S*6q|_f>*biMSi&ID!!nl) z=RM)$n%b#IRFoEkb+Ymj%8bcG6P|xorMI+z{YE?l`=iQ)BW4ruhgEDa6n`j`hb7iFzt0Y$EYs5>-Nm09o+G!c zFQev2*7)v>bU!cmy}aN$_b!Ips8O=Vo++b!%u!WL{FdYszgw@!0XelJ_kiZ9nH=8I zFt%kVEBC8BA6cql68cgxkq*qy9({8^yimf+1wM*LoqDKWC@DvS;sv4#NE-%G+rm~F z8<7H03sl~l;EOe812mZl)83>ET4VBNxurXn9#5T=$7>1a#1+tZo=){TL;l^-87gHi zn%v191cLYY;DpB-mX+ickKSaDPn}q;z}!dJH0Kc!IED(?$%Ofm!?7YYo0PSCEj4K% z&qWM2t7)VMNqU%^-NPB~M$)u(DXR5dj}}n+Ta#ytaT7bj1=EXw$7cEGSfNUbiSo`V zh0?kT*a=dGW#Y<3k(3RBC_lQ7vSEV;&7oI1QTMy>RC6$^3$&v=;b}a}pC>scsjBAKGDvJT%!-VgNaeFNo zL5Chb%@deNZA5c~)nPG!NJ?NFrpXaoGpcR(Eml=UtnH7ZNDk zg9LYXx8Uxs!6irtkl<2y;qLD41PdM{Bsc`uAi*7KIH#vicdyo`*E2Kke21#vTK~Q8 zeO>ewH}zZ%!2Q!2d=l1P3;fYk+769RNvfnVHEBI-s()JAUeR**zJ@=z=IbA)P5BYhbi7?7<`plBQUqC!%M>h*$8Y5FEv zX+Q^G2e9`Q0>C9vG%W_|-9{myE*twk@xwG)>=xK40n9TET$ImHR2-(OWO5`%i&X7S zu|XhZ=$PoivlQ=tTnu)=0aDmAuz(Z0D)8{#!<`l71TBGO8R6?45nP$!Qe`9gnZS7W zNJTFJDk<5LcyyRx`Bz&JZc&YplL4i=klnnls!Ft}(Rh*gxDfF`I)=6gf7oCkT=-Y% zhQ=>RH+U`qGLd@{U76s}+OX}LmzSoaF0VNJ)6j%bxm&*uC_;ckiNGJ`$U7Zhd>RR@ zPkYCv6)~RIt(2%a5$NU5Q#j;Lt+_P=QLM48BC-BsEzeIrCNYlT@bN;W@x~A(|Lh1l z#WWW@HLheQY$|BK$!*#LYkkfJ^>=8O1q&< zB^&S@g19m}!ujG=xhv6dIQ#J=YhzV8_HzN@05#es;7%rxnvEu#^uV-3H$L1R7Z~$w&=*)-yv3!E=pdya@Hm1t}Rl z^ze@e%l$O;lv2z}DxykCH(dM*%yfaVx!`G@@-~*x|V^{FVr7p^lRDZe3sHv) zkH4wvMpYxviyI=aRre0bPl6z{A5OU@0i8)To3_d$2xjWnb+8x5&-Eu!`P1Ib!#28y zLq8sYhh?!ZDg`#UJ|~H3w@-uF0P=5Vz~~J?tx{m3G}uoXm?X_lqdA9E>R;Lk+$q2Z z0pKEs7ebOMLqq1Hdgg-TH5N zERCSQ(_SaMHpgpwAqh(^nq)Tmgm^EPyAA;t+ikHhWU1In|La9m>^9KnXGc|e5>g(P z$a{bOJvHoT~+hB(d9>8FQLDCweHPS2SYb$s)d{{f0&ol+Vo}5a%e>sN2v!1dygB=sj zbOiqV(ZA|be&g1^T!NzjD%jr6;#In#WGUMy&O!wPxp z6WI79{ks8ya7d(QBao41fN^$%>B>xffBmv`_Az3D?I}us56n-u2HoUdi&hPY@HbC3 zU1vSs80|!zB56GwH=R_aymCbDlU_o}XH7^#e%k*ML1&rFW!a6BB(&2NVYBtgeTzRk zyrXq6ufb%`pR>CNs9y@k(6)%#gNyB{qDs_9rZ!3HG2j0>FIgR>A+imI57&HBkbY?b zw$+u3!8xe{b2S5Ld;u!PtJzrcqTj4~+bj)VX39S?bNFKH7XdXS!D^|%fGpt13`2D8 zn;(hb@Z)jf{r9S*;8Y%No`dA6ZpA=*klKHk+XRQBy|&4=Acyrc+Uf|0^uxq!?vl%;4gv!-2gt z03pK^tgkOX`$jQ-XAU~$M*oH0g)jlsjO5!VBCyVeGSB;~P zpBdWN5Q2l2_ggW1_9?RV;WqZsrCcq#2RScE$SiiQhQax47U66^k-*%Ek+8@~bnVGo zmCfLen97NUeAx_)a&%-dSbO?BATxPU^~7>Q?nbzaP2Y}#Ntr-tGBP%{m{AfSpT{7W zfPLwsKkcSX8sKO`S=MR?C@51kmy9Mf1MK(+Fpdd_j=hv6XxvW`nWjUhTC5frI7YL6 zdX}ISos3LEfKB0{M~1>n`-oX{4vrI9V3C<++OflyTE~Moars;hBkA_zV221$K)XX) z{F2_O3hj&94sG?M@zABc)D)KWgkS*{W|^(_-42tg_T~1gD#kEk*dOyNaM$AJ zwQ7he$guvFgwq;%)A(F0g#g>F@`98-Ja-4A`*xp!UdT&jj zQytOe=f<9(&Z9G>bSz0&B%IJuOUH%gWC>cS0?V%K1v#;8sGL@b$F%y49C91=kYj}E zoN6p)Z_}9`6sX?)<)k{wpxQ&00utfE`hZ3=a@f)xcRadhA6^<_r*h?h(Sn`~q(}h{ z5WS(9yFz~HslWk38Fq4Jy!J@ha_@dqR2;|`PCp8AQqHrgiMI`SbNzAm+IO-kK^ESA zN};9M6T8~eZF03O_@!c$V8eYUEUI}w2B+g#v5ndQMw;8{r!CN=I8s`ml`#E#Kb)!QZ;yXEP zZw`UGg4O1H*227B;6i8b!dUN8&%3PdFWD{LZWG>ppS@kMUme+2)gXPTitPi|UxcT{ zdcQuT%1Lb2S&ii}XbJOai@k5Dxo?a8RR3e@6GqJYnVs(4`v`w71G#dfuYueA$ZG@- zgzM}a<@-sgr*St)O(u8AgR-$M4u|}|YCRta_?=hG_|s@VO<~-AD*;B4eRkoY5z|@Q zqxcYh(gXBG{=R`W4Fv}w;l|S1Ll>a$S5_ZakbLWFu+$14n9-4`c7foUjdRV9$v1=c z;}*-F7^fhiA1!;ULr({Dz6Yz2H61H(-O~xL@9L^=3VB#E)r~5>uT5S!FoQZ$C-D>s zS=7!qCii5#mDd8_mt4><7y$IcK*VCQIms1A2I6x#?43}Qg*XD8ylhT4dbJ5ioxE$y zHU~ zF(rQ#Y+;Z$dv|~m5qcmJ4f^(7k8V~s! zzJJfcEO#2eyA+?RGb^ZeyyrPyZudMtJ|aG!UF{3QW_5btJKGvf;dDNJ;J?`WR$~41 z`cdHOaIwYh*YTs^&B?}40;}_r&|SLH_XcO^*Y^9Hv)%7C&QOu3hr8=*<4LHfKa4q& zi7hPAR!#si!=7ru3yRbX8CU91y&&}76mmjTyVi9H=IA$i!5G1<(jj}F1_;9F%Ud_z zQxJJ>NU)7wQ$%tv-b^cksx&Fz@e6QGMT?`ftp=60?M=%;%4GB`5Kj5164gX@U&(07 zdtpO#?AoYP7+4mlQ=w)N{4{A+>Gb$ET=Kl@X^!o;G_Lq4LpvTOE7Y`^Uh38**&pw2 zX>$Wm1WKKxvApT>!_8?kq~G&w(dB*6FD%Ya`YFAul(<7hFRmAIQzn`FvJAV#%Fd3y z+?{Z7$pn!)l->mLtvR8xY|*wY<^Q79sUC$X#n!5gQ>gT;FTEJ?2e z&5B>+JIe_IBg2qJ;*qvrpO8Q6ok#+o1=g~KRiWxV(F`Bhb0Nm_TW+{`(zrP)>K>Mi za0UHrgY-j12hmXc{4wk%^qk$wQEt>E+yaE{WqLyOXg32A$zQ!!c5T(0k2 z;oR!RDzV&6)8=|g^D|o5g_mMdo9~XAWFm!|6HDSh@+`WAWbrIH-W`(Ezjxg7Sn?2j zeXWA~J*-8QYw3}9P5(AHw{5TAu(9{s{1@~Bko7p9aA}?yQSaw z-mdrhAO! z??UW&voQS}Dq@n+`GCx+Vh@F-6YD)xdAEJ!pZ3Fgj5%Lsg6vmMGGM!=3-S~rAf{1n zF{g_Aq)>s;Gk#=Ub7t(2A)^RZ+8jlUVuz_`I*S_x^HyR@pU#+->z)VtZISd!5$26U zUM$ak{)@D-@oa}Yi231g7m-DY8ZOumO1#6f6s%ApTd&VpS7_RoETmrCkgZ1f;{di; z(FYMFOB6e*tu}4cZ}yjj_Gy~1?|NFWak1R+1*PZ_-B+->rXdWY683r1^uD3P}AL$h>7&6}p1T!3gRb8CYxzg7X$pwtkRjTN}=RHLi zNeQpx6xEZ(y=*FDb!E`(Xynn9(aL8anir`kpIKG3$rqvc@ui-KtiXv|6(6g#F_=NL zE*Y96$Tc(aO43zOXrL)b1i{YW+#6pGVY1={MTHWeV(ye0ms9c6xEWH#`~XLDUCc)& z%UAYsz7)Y0$yJqf7!oQDZ(rBO3opruW_;E?+p5YJb~F?^z}YRjpzKt4e9T8MAkE{^ z3MoPpa&ukiz$>iw&a-kvO8s`|s2$3OoMU3I5ide>%{%ad1vA5Ed z01;0P_I}Z>ZYQ0E5aR)nH6$Fxlb{Zr15E+D5grQ6V*lFUv={zUUt>rF^a=C5z-AHbh@b{4z#O7c2K_%(Xs! z%58_Fo_~V(O-JlF)Wal7F)0#|hCy947f@9Cg-O11tB zFXIy#Z)#9*P1Nj;-3Yrs90>msnD;yO$Y2xFvJ>dA`6dD>;%n6b+TQ0pIhY*}FPm7* zdC#}8Ty^?={6!;mFAji`#Ka;28SoV~fEf6__)@1GH0oAA9Sdnsk$?Hl3GP7evv1Sj z9@V%{`IO%Kz86(n5>m$qM_FQ*D33MfJ$WfBy*P09qsPWTo&4xFN)Jvme5H2+|>-CDDr z3i#sYan!c#{ZM4MJISiB=hk>AnB48}RLz-n-ravk&HjXt3qU6y!6f&Dm_XMvq5EWj z<5gIiTsZwPs)3wsM`HxLY?wEu9n7nShUB|HND)HGfidK(AIWq1vJsWZk&Ry>rjw(# z=ORRyB72*n%;vsWAxCc~+QjTfN0-77>A^tETMUs|dttUoNP$6_hrv)x0pc*reOQyp zT{D$4OLHL~?2Ja*$%fI-`v5jU_g%-gO2cnQPJ5>RXH#GnuVdz~6P24`)vpt`uVeMC zlZ={Se_JPg2^8lV2zpo}2+ZRld`XT@NrAVK_BEG+X2aSxk5V5(!cA!>E(4w?qe{oB zCm?P3U_woUHO00;Q~cubW4?JbNxRg5csM2I!YV}?83SIzebd@}Q$CGXJ`-_V? z_RrSJe}EMJ2NT1^$(=5H*)UQ=CVHduki2JZi zTZ_9t=|M6*@a$|fJOdN={xq?L$S~{|CTjof5HFPB=idzRo~@O&gU~;Qc)v|-e;eXK zBA=d-!hdD0%(j(nK%YwcM)Qst_J3}zbT;pOV*FccWhFx%`j<e?6Rlg1 zqr%tHF(rk38yr@?x4Wi3@B)g-f}aNVu)|jpSE#a9PDDW_mTkgCD%D@}vFBLs#adT8 zz1C2@j3Fnb{}L%|v_GMGX#H!%Tgp{G^!j4OZS^vHzv4GqXQZ^u!&FAMs$f6y^u&X0 zi;C!Aq<&)NabgG3a=1UDA~`HZs#pLUn?E%2Um=C7w>_~=fj29meW6jT-cN!CXi9%U z3RBPYO@0DVFfQkTF2ZD`@Y<@MX`SY+hk31M+;NmDI6&+oJ_tR-lr3lH-y(%ulOEzu zqilYob^eAFj-%9LG6t>wQ=~A_83e3YNQwU^q%itIA4Xn@0J#6HLyF}~c#4r{r0_Ss zG$CWbotqK$^s~fL#Ucis5qYV*Ur88o#7u8#zUVG~qiArjs=>nTDS8Y_={zrDBPCD_ zdWcUQ=6b^sTlVFRd})~Q2a+Ac*GgfjQ)%fa)I2RC<4)e^8Ea@Id_!^*uIcBQdx|9j zb0ZV)+RwA*r;3;UV5>iGI5D3OVIJ&{e}4$6bnOcM^&xcoxh%&H`~UPI{3na#_bs`` z|H&fx|DT8O8Cz`mXMJzFL-XJ3dp}(L#u{Lmm;a45u)>N>VYiq6J8R%y9Kv!#Sd3h| z@&GKVsh<_ta?sjxALQ1btbigj6AKp;lIX zNoO>!g40rv>4e8{sI}XQL9Omvy}LJRgGE-9XT)wXS75}^I6TH{>C33Ad!S*j{JaXo z_?GbqX!!-MdA{Kc?x;~5WynBrS@{dBSro@;Gen~P9cWX4ZLqn~ViGO_#d1=V#aaEZ zhnev%R!k9JcyDqp02NR^JsagJ{#xTPQn>p;vSFN0<#BS+!X%1ic2@jLWv$5PPS%PIWKdJ~;b-rkElLJyY!HUrtSB@h+YFsS_(Vo0#WC?rpUvz8h5b;j3EjT) zd-MoYHA#5rR*^dbd$`|KyD@2o)lj{3=Ic{(%XnLi?LvF1c%V)Bz%3-Qp^gL#DUiwI zMSs8o(F)xAW@G@@gu!{mIw~?9KU{q8%c`ZUwnQsNtg~XDn{$e4SQ?mV+essg($qs7 zPeyv}Lo2@JC05|;2ou8>?%z;n`r2hGL#)2>a4~@^c}n@MVJJM*=VyCl>tumvjQ#`` zgx}~=B+nj$&_t$Rm04P`t|OeJSOWCAUB7>#%4an6FwkS;4{dL8>@})?WsbqjD=lk0 z_3|orOSBcYmMr3@_8cXU@c9k+c3(z&Q&GDd?X_Ic)E8HENIwBZYPBW`o87H}-sCYD zD&>!?m&TQvV+6m#9Xc8=dVvdol#bu0sTB`f`s9D3Jl3CnFP%nw*ZCV>jNmHi2 z-c&9Mkn00}=b&JX7A&WKs1#{yVwgzNcC{Uj1$DQotUw`6eRB{4T{Ezl{fJr(wh_0q zDN3sVTZ_C^;S9w3vJ%HOP3?RZL*V)&z^%$%CTqETzZe$LAHK<3a~ zAVU}D5x?#>z1Wv!He7gQy0^ zy5bF(iv)0dQ=d4+8bIP3O@JyR8tPSVhN4OUfMsLx$#*0N*AuO`>OpwpFQ8ql_V(bG ziu8ASkx>Q;gx}6)QH=Ay4zHV!yDg+Jzjt&%89_;dKSKZ@)XtfUBc8>6#PhGxyQ@n$ zTSVwi8J2Q7)cvS%;yyIXp9K za>y+RE?TZNi8x?b{iStg)u;xB&+}Lq^{fF7FrFKhRYORZ%8fCD&rfE0N%<-6x73Qc zC4}E?1fSIS45AzCcq4W8AEM^?#8JOvoe~vV$c>1PINEc3$hWO(<#)PG&_f2;cQ%s; z@WMWF*0B_glJ$fmcSf%vHl$6k0Cg?9*y?K3`%?Dd8AYEWvN7mA2lSCPf^>=W)LnRn z`QJbyK5@eQm_cjeQv&G#Gttyj{l8GN!IY`see5=+UQ6)j&-7`JjTlTw!KI1otB=V< zDa#=~k0`BAa`Z&ba+}df;QNKypU%$+hu^7uZ%2RAJ16m>cKU~X-Wj{$qqfGde-7)~ z`7*`KS?c6*=YV*`ihD+DmTk#kU9kGtW+toBNu4cka#B97;aVURmZsCG=w#y|f4RQqdDPtqF20BsM2-Ur#8JN=|CNNo^c?~*M+(-i9 zZ0T|o=|YYS&q_*ZaV_9L7$$NAxB$fi z407LdYzx`7hQc8F!Nutot_4p>idiLuyvhGy$|)!Dh6xI_U=$vDTO4G67RX`^WR9dU zBX16;&}O}CG;-YwDi9avwh;e3fawVGwF{G?lQBAh)jkqKDS)tJB$;b(VUPt!mPotV z!J4XRfQ@D42K)F78@yza7!!bYZPt8p_`%ljRtVV9#~g~5jpplAq1nBR<)_*R>*z02 z1708js^H}8WMX*TIOX4QCT^n2ZeqwuD#(PDVz5^AR1{;6?!|FmK9$NZZS|cHJPd#z_ zJn>B~f`Oaf*7XSZT>Lh(Iygw;dH%Wc1*I8kNu`E)rP{;! zys4M$2D)Zp`)ScKq97@9e%CjXmAX!d8di6F!LAZpAOp*;+{XdJDkBX2F0ir}U8jkN zLmlJwIo0P4$U-tB9h;}gOMhCIMv~jjn-la}GTAg0{_|!8&UY7JFW+=vRNI**;yX|| zyXr|ksQ)Z8Pc05X{Q0LU`#}q<(K5??Bh?!Um&V2)9sM~}@Z8^279^snE^@2VfsA=i z?c$7UFU3y;^#oOqAlMDXt+esNr_e;qps&A5jsmm)vJA?!;?6Er&c2GBbPZ)q&A|yz zdBS~Pn3uJY!dEm6BFE?JkrPUU%QkU!WcCu0Ptg4?>qStgVl=C?5)WwHP9S=hj@272 zkfO}s<&g#>ggS+Y17x~3HB-_pjE8f@-!UfB2fc3RAzqU-=BL@#<_dh3Oz4@Z#-*`b zLdT7iecHrQ9q3LFAUn*PP)LyuyN&|cLdm^+D=80lAu4edC;=zaZ1D59YSH4F)Abw}LGv}}}7+DQ;V^u!Iw`pykH!q&~ti^D2ZX$DyvkjKVyngR38Yu`78HGDK$#2cx%3w* z&{4ukvepr50Z5|D(-;8CH*fO_%KZ;CGFZT%3eBuSxa_1PKAeb}mGhe1UIh36@BqH} znJ1G0n_Q(k^MEUR5g^DA5cG^3TL>vN>x+*?j$-^?sr)%FEQxm%HiwSNW9}P+Q-1-< zx}r2eMUXzPK)XZ(W-joQSq$p(y4#<5mBT8&Aif@}sFdR^N{^ErM=T!a$4Q#Z3;Fnj zd8W|w#tIa(YCFui)GTcuhxx!d2#iefcT8yukcT&@qaGQ`#(6`Dz>ICr;6nr0DJhxr z(a`bGEEc`0)i-p@Dd2Z3397<_sX)$iVP& z(k`L}uO@*I%KJX(#oSv?s)leXrqpfB*&;_U7+k#0nd2E@0BS~nVd@-ZvTIV(3ClBs z)n@r#D4W3Vqwlewmd)uU(b?eOvX6N?V}~T}z<;Y@Dh_Eo>ObSCD{#5c52(7y~9eqKL&nwZ%8E z88@_JOkRZSfcs&_GCozq+7b(iN+G+>10?RrAJmD#R)+Srp|D56G$a~h4co0xgeWXO1xt$D)8uJ8kH8u-s;ysf`bM zvr+$z2;3CkfCpxYoW`+hC6I)0VyW*%UjNgsx7P?Qfky5Ir*=HOf91Bd)?Bhi5MXGEJ_aeh_bYH zNqkz+Pi>6TCgiT#GR4pFLEqJ%GKr;p=#jTGM3Xsz5$q?{s6VwMzlRITF9zEe5;dEC z;W-`CHzKgS$55qr7X1PDFJ3YuLbfl52 z?MD-IKZn6WB<6vXYsPHtC`3JNh1o4hEj&qCZkUqMLc{(?4+X-@5%*BN;dX-j5C>5G zIe0*6wcc!%yb+`z-*h%U3oAlQcAY`q@|-8G!%?iGiKC1Me?dJaz9tsAQNpSsw+KpE z?>gntsVscCWt{%AA`_*gN>%ifexucl&pW7uE4xr?v5>ENkw@9B1b*{#Z?G?EiTg(( zU(y(nmn7-9TL_lkd!IyoX6%)=II+C9KB+OS2pan^t72}e%p17b-nwH=O=@-#I*@D1;z&EcgWR?tC#E^2%ZRn$!&TGoDKJCoDeO>XIg|{H#y)S7l=O^|g&kW)x&Krrk&&%67ieX;dqYT+5PWvs#hQNLO6dG zz9dBqec##dU;#TE+V!(h8Rz-2@)s%S1n46_S5HLdxVq#_vKl=R&^wLUHv%8G4~gcBw9UscCYl?RTl0bE)5bxt{&YknH&x z_^YK2bpLc|pmuKKd}Y`DlA-&`33}y1cI_&9?QTNnXmZW8e*S(HMURUqxryk$iCVphf!;vKZsSF7Thy)+{cclpZcR4M(w(tAS8vVou5&T4Eky5% z{q9P0?#jFGDp&8Sp?9@p_w}OpjVAZxe&@~3SjHxp9Xa=1WVkud`##Z!ev^kmzlY(R zhtckbvDJqO=)+gC$8VyK(k zpAJ`_j-gK{WY9BF=!FUN$`5*z1HJ2pKCD6kr($bjfe0^NN~NlLKvxPrCY2Mc43g=2kzm!hb+*dCq^5YI6 z()y`cu2p3`kgj#0U2XKq7lBy&P`BP{JX<X~XG+Gorv8%BMW{otY|=p=_i3cgH_I`5}=R zKfFKN9?$vnhO;}2%;f3A-R05hP>u=I_v!Hwiu5Nbs2CiE6q`5#zGbaA5?L^t1Tt-5 ztpqA-ze_dqUuV(q0Azp%?8d*%q9qb@>;68Awvte0vG`ks-apEsfhA)9Yo**j$)cY< zpZ`S`ZRuzBKcHj&e^<)=^DNq02fF-hxcXBTjmWU~TNeFH$D}F$w^=j?gY=*2nE#}d z`-6^I=|naud-=isxNWbv;x~of zL3NE>C*!Zqi`i$-=gm&VudauygJ0bnj>KtA01Z5+USQBWHgij=!xQUxA*KbIP-^ni z0UA5nI%WjSsM8_xFp|WN>Vi~gTQ?j&w@_cfo3yS_$%IzA+%;;KIc{HdwA6?G9enPvNw@i69T-lUVT`fAa z{5J}{HU+As#M|xv+w zJJeHpMS@_{m(p~Y+@BYfAM@OhCjIe=K1_8apkgtF75Y+LhqMi@!u-+ z{;}utuS&URg`VLWsOouOL2(O@fC6}Kx!|8$u9*L*?w5t&(#QO(y8pT5;>QO5)n#Ge zrTD|0_y5XeX~F%s+}(fHa#{I7(Nww~;O2JzId}K}#LKe#8&UhumxVz}=0CqIcnkw# zCCL#cuozU3;ELLE=%NW0MrL|BPUEPZNi~M7#8*66x!!X4_Mfjq)iEFx(&b2U5cs-* zcv^&d19F3}G_Cavkmjkt*Oe8e+Jbv5!Wi@4V)~y`?n<1YmmMLs zH8cR}auvA@CrLkEd|D7D{{r&Ywv$;WKJc#44Jc>RA_pGaOZ5ui{}FCbjXORF;ka z6@1Q2v?n+1g(r9Z@Scp8Z3`Fx)0%$H8e!0C72y8xXTj#qcd^QPh7grl(ToDFESEULTu*Nzy36L3B51J6Ak`{9QrbLL;t zo1xj|-Pl}*aQQ<{LTyO53zI~1<%LbkjxG1glkrW+rUaD1$cY+K&lTUaWCcJz26bfJ`peV>k+Z8K*qgbq4RyDx zxp>U}%oX!bdJfE;umLweUJ#Z@&bhDzS|ZqiI3`iLD}kg7$&Acv^T02pInW& zuC;huiHpT&bWK#u&s2TnLHuff6&%X27I11YGinMacO|{_;Xu{`M+R zw+r#I)wycoy+^0sw$OEhHe~%ndB;it5h7Dj@OY{gm8Bz9E;9#E&4?#Kw;whc@M?$6 zR4yn5HBSdLk6G+pEwEC$)Cb!mfs zF2_B_M-iH2y`Ot6OWkXXifmBZJd`0jSWn)%C?Qy@-4Re5pP#-YL8T?fQLI#H4WDMi zN=80W%^sQMU%w%C!408Cp^7%|f6>@w4S}bV_CBiE8@~ej|EL?aNDVTcgx76|yk&~x z)1t|%1PcXoc^JtjMW3W5l~b*a=X2OE!g*`6Z`DP46dU9K<@nUeyT+5jlos`f-x}|6 zpTCv&%5|Ut_f=&NRm0j2wVLk`eaas*6%)>#1?sdFC_4!Cn;U7~<4gzJTpA+Qz3c!y zgUKei!{z!(hK|#RXWVkwmDfFC$r1zAM;4$&SnsdO z56eyvY8~XXJWBK_yW$bpTtg0v42Dfa5CZE-j#a%;3XRI&c+-Cjn5}X~U~V6F8JCHN z)s18xhf7H|$P=#YY)c~EQq-yCX^wS%6XeW#9>Qoo)8bDzj%{e$@l6lCg`9Dkpxbqp zd(bP2$1ghNCr&;y0G|Baggq{(xJVLfaL$1{fk50#T1PA(szJqw5gKDvjY?CIf|HO# z_)&fQ#{f;1r}VGkWNF#&6imn{tr_;qv?e|m^|&Qxa@F%br6}k27U7LYbaLJ`92~qb zjX$ZL<6!>)J1L+pu55o==L%9Uc$PU`qtS}r zY0k$u>=aY8s=UbvRK{* zdeh;_Lg!mP^M1l6j0DK+U%yiA=<6x6I*+O<7(TN|bdmUiYoWnxYpRTp*mdZVu@t%A7Q+)){MhVRn^ zkA1HfMEtSO@!E#(=VVqEwNNnMYcno}dgw6B8`YpB1gaF>1T`;FR3MtdVY-&<@T-I$ z5gXnfp7I6>oeql4WQ*5kxKFEyk(Xn5HKwKclc$ausj)djflY%ptAYwJ%sX8vn)rj= zgAtTU#>0J9_I}76KO0h#EwI%KM8Pr}$OR1J*DMwZpO(JXU?2CCec*h_xFxn!OxPyj<-tpb!Un@N z?|?POdrfX~s$pKOhVi88L-h<@NfCSf8dL4$Rj(wQ`d1Xx3%kQmJ#0)r;3*4$oPXEs zO#=d_$ZHT{vQy9?5t|L@i?%am3Lw+pj30qJ4PJN-Q9Z-M4E_}L$y5{CBd&kOc2Mxa z;N10}E)q98|AaFbnvbd2KMEB`oL~jHGx(&3)Qvy$FVEL8UT` zx}RCMT@@)d!!r`t2{*%&HZfdUdDf())V?`p!U<}_2@oNAO5kB$_X~`E10mwbzkrX( z9roBy_Hk|yt(`)zcJV}D53PU$So(7xlbg!&n64&suJD+qyP1`}=PnDOPWMnlz?9xT zW79~~?U0O-qvHMI8nC4Wl9QCCvs9OOWzhq6fiDu2#3#Z=WcQb`g^hblJcK}D&B4y8 zy9uYBR>H1ofqJ=ys_O1A@>&}TGS{S36Tvo74fa@_5l3iHCc|cJng8H>!QeOG&^ySu z&BwMMZdL&CDBP4MlqR?Nu>+ss*NF3=Ndhk?XL3V` zc0Dq`obFLWSk!wd(WIE*FvdW4j@2-Z*mD~^OFiTgkmiDV8?HGDf>0zc;TXIgdR#bm zuE>av$d~hEC&CnOx?qX-+<4E(fHO&4TPLlcxKVS9f&NJKR^uLk@bRrI1 zAT}@N$IbXMwFJNkrYL9F$2OrlT@f)o&g_x2?N^E4;X<@25y+Yp;LX^@zN5UjV0hI6 z&Or$JT5nx~73&<7g3C^q@5WZKPE?(%0Sf~`0RZsMgA^B(Py;mdrj>jxsDI_Be0;WA zHHOYN2I~++dpDW3@iG-?vTn@^W1nKOLES-Xmp(bYe8`yo-IOpe5P-)>N=pN12QjBv zga2NdTAn_5N5&WDbGlejVo|EOVS(aj9*!$&#}iK>)BqOye*Mb4Y|l3dje+c`wpec@ zt#o0t09H=*KsGD@ydp3Yo{QHl0iY7@&r5~1d75gXot*NPA@eIDryPsD98;Qg-kYFA zE!Xswi|Fi9PGmM8@o)wQS`q$pwxf6-0?bgvJe+GiB8L=E(N{!u5Wrb7XJ`a;-^R;t zN4*T2g}3kA@{Wn@PN956TRxo+3)j7xN{4_wdoT&K?M1vN$wz$0KMywZiYW2&F2Ua^ zfu0nq$LEYTHH05C#ACn2eTSZmfm8{=QkSE{fR(uU?sKEE`n!27_&sbtf{xKIwb5B zFWr?y)f4?&QE#I{Rg_}}_Vu4srlTbYahx!4@V3_MquUkTK;oM2u{S%mP%>eeG{BIWq-6|**$?zqK7TZ8JSvv7wn zf4!^m2ut2H&(55xRUZY_Kq-~G+!Zi~c=vwFE&inb!4n}ZEjg`M{MnA(Bt_Rmm+@Ae zd4j`KqJc#q4);}+l3s+Jef}fA=~=pO!Zvt!o`C}u zlULy5aR{jAmf)o|X27m4o<-Y%r5mQFh#e)EqP!fnzdRSO<_@-ft?xBZt%Iajr*IHd zz*7UE5C+I%(r(ttL8)x*&oWCQi>B{V&@@@V^ENaZLQ4r8MrD|~cHz(Ua!U{9uxz~H z62m)%H_7%iD}!a8@;f5PAFRPX7h0+@_KwaF z2RjpAju&Le1R8D~4R>V?zwm++FWp@a&7pJOmK9x`#&W?O3gi0-C?*8mfdWx5OFF4& z-P^^^YaTdt>8y1MGfj6qRckZGu-=X-U%AE4$>+Tt@aJp62^fF9QJ3)@-Qatx)-I>c zu4`g4%M`H;qFbzt+AzI4p2B>;Xo6#{0t)rPc?RaLqsA;Gq&#J_5S8IO@FmuAie)$a zsWSQmyEe!i6^QZ@@B3&(A0MEI{Rx-jCSFdtL5mIBAd9G&q>($V=q0KV9ql!0fTv%! zEIXfE1jg6USMY<)*u^go6lH&qyj7yZE}9z|gm`6nq0xgxZ0#eIbVJXlI`?0erqB^f z>561=XFfu{Aaj46LGdXLSitO#byW=-C?oou@ESE;n7^{p2$aGZ&-;Toa+Jp%IYm-7 zFHk6WY*wRQf2k$zT}V2XfvH%KBZ*!o9rczAidr5#%#Rl^ukq-XJH#O`*t;dhc|<)w zC_o*5qD5;>TGI9rUGC4f>S=T(HWCg_5~mEFbRKOdtm>ZnD6G|{>>MAwV7|T z&P*LWPmW51k?4F?iiH%n!P?eyxn*&y(`+)Rne%EbPP3#?^NARCh*90YQE-!}X&$7# zvfc2OL8DpF=i-OW6LCIKrGM_ugZ@|UJa1pof}NkqrJ$M^tp{1VTH}L; zY@Iq~JI?Zh)~*iREbL3JH24)*8)he*AL)>U(>?=dIPkG>lZ4zggeeK?v| zn_pZxT6sEJdwIMuL9z3>Ko!|BQoNMpy>kq5fzW=V}N?biQ@Vi+szD@7G z&5XU84`JG!xF%V=&1SwvQTe^)BD+cH{+pJo+3&tJ=f1uBzH{}y3wqx}_V907F6e%h z-=k{IZ6qAoAEv?QT$Btz4M>3P{s)ZpZUoCkIzMaYg{fCBB-ukQUK5zF8fgpiG65I(I+`UlTHE3~nC~l=K z?i6<^?(R^aSfNN;w8ctsN|EAL$>zRi=AM~nXB`h>N==63@aJ|0T7BZebnM^}d*4SaZud-4P|qH@%aBPf2NI#E!;TYrzzuR)b| z=;nCjG~Z?VHGWa7rzgyr(OvPN5AOvLmx00QgeZHs<9kvcmz8%yq^{@FNSu7FH%c#r zJ!iEPIR(S840O-t4DC&mW{gUF1vRDoIDKV#6YD6u?N|^;Ij@rP+kNF;adv3If+Vg! zC0zts4EkT8ICG1ZJdwabpwbYxmb#@Q`X1g@qbqbMXohc&C z&v0>LNBpWbV7J#J;npL!QZlLT@VNK(ZfVf%`(bB?p6b#2F%7Nd9;|OH+k?MrP*-Gu zr<20pewr??bM>|7EM|dx_PIXWYN8w=y3|+77>H_;q{Gai>99(Z2I< zDjB+4aJt@YK>hl0^$mscHv$5%q8XSW{{eA<9q2UxuY#fY!{I<_OB^g28RAHSaQ>4| z3c&^tieE=`0+Voj%Qu8KC&y8z0Td8a)Srlp3_N0=3;7@s+XKG(m>R~tA=|F&5esfw zSFovsao)A)Ti}(DjVg`s<@`Nyi7%nr{pT8#W4S&@auTC#sZM?68wIh`TW_We7#(@!vHljMRJIzT*C_ z^83K0vx4hM`%JE?koQk-&tBYf*+wtG*0S}{n2lh;(JcN!h7#JaT1*D>}SZ+e1HUob;hWVn~Y%2>Rs)O5&n!g|umMf9pP&PHFy zo)f_zNGNIfsmv8qTvRHlS0gjW=gP${s`-9`((W-yW z!PiwmK8%025_u=5dbvMmGpQ;sul`z{`*ZMjIrTQPtht!^HOcS$ui;D}EZs zF>BOQRqE=v@%1%`I|CV@2)aj&O9~nT>PtXCLQmO4hs(=iROKdVL%V_HxGk zruJ}3hM!b=`r*%&DP~(b^@l@iZX3MTq~E+-XYW#ZXWn^fa{djWdfi2+6~o(ug)rC9 zOFR1)B<}6?^_*8Lg5}2glsM_?SE1_MDBbZf5bGy~yhpQTSF2C8mml`W(mua_D92rT zy&2d=4|(?~G+~L;K;JZZY4@QdWNpexqe~^ie!J6Ft@%#4kYAK}FWEmrdK+?$L#kcgE zufL`8@hJD-ad1*0X%w<(0R>R%2U7gAR9^D03&OJeEG2+|;7j(0(bX1WEBfc0Cm)9+ z)QZ3cN{Fd|_u-Uqa}5i_fjRQwNSq=#uHSDQ{5VPquNd;~&#A1WRt(F0^Dj6!neX4H z@>VSV>~C`F9S8sWR8D*&NpN(M7>rj+ho$^R=I`ayKc}*a(dj==6aW5y zI^v>O;mUqE1pSXtw6ym_{JtS){Dd|8eja^Orcqktd(}tu?dWV)h#THZ6k_ZGTMI@; zS9}hs4f*&<%J_aG4mp8>l0x7$xeZ+?nVp>laGe*i7FL=B-9U%b`%OilyJoG&#%Eu@ z2r_m-gR_>lA~zFCu?;O@R|8mPiNy5j_u}M8Uc%n*bF7@$qx<;>d7d-fU&5cLy;u=-8UjFWiw3+Rx2 zr)S0n{UFA!NLTb#+AZ-Yx~3099*FLszd~R*uoE12;-t1uRaRo)cxTd-R=#^(ke|PE zWAOq#8Ra;|jly=ad-fRUlvpTqw5Y+JTF%Dt5Zui6xysKsr=YAEcAnUB`2*bnh8F7d zUh2IhoonSi{QWw^6Y{j-a8u?RKn2M5RhQ=ZF(<+8!(m6$r>o#x zs&4XvU;@B#aKPSlH00%s(2w^dIJ%Gb&_7x^zwfk{UH_G z)LT)51l>NYC_l3f6EMcP^d;u4CZ#f9>a>Q(KDMsCT}7g8-kpW`b2`S&fl$-R*lm)T^Jj_0z1_Rd@(?7I;4!$>psNt77zs<$Qf0P@@SJyt- zYDd8qjuczXOniQnAv|1%D|gCFLn!xh*}4Fyk_fPZ)Bog{@9|;Vdy=314T2-}-KOz_ z%08|tew1!$o03xs+wiL+TUl40fSv3f7TiaE^Ir?9mfDVtb`laKUj-Q--;7%4br%_k ze!xll+8zv|==qsq4gS1QDbF;>`_}Pw>WAK}VOAo`!zYf(DVbClbn<0f!t1c5o)5GU`O0*|&I{#AmIOsV6+QXx_;-96FZ8`3EbR@=a^waoE$Fut)sDw-$8|h+Z0gj%2Bc zt%|`jP6E6)dd)yL=kDleVlX`{he?mW^*}q&g0>eZ8e(&xg`A~3lu-~~4nDBk1g0HL z&dC@~r)aeoQopD0kwJPl*kyss3!i6}D|dOM*%p1sglq_Lk5s0U%;Y$?pSNpJJF4Xk z?sTaLB~iLsx=Dc_9%qms;-*s+N_onIHlimRv@{&DzY}*0WEFSy;#h*3*IZ6BQ1@j$ z#$NzEQm`M!2q&HFs;cE=f>GW*5?xIXw4HVhx@F&o+8oh+x}6TVBi)ffXNryM$Z$^q z1{`H21z@brVJA@&5KLfvPh2PA93lQ=OS9M{VETe%ynnJNuAEwCBZ^{>g@5r&ZZV_! zH-F~F^I-=m+ND9FQk561hCGsP8#C$caw8hRR5Lk#Lh_~QLaP&Kg`tNr|EzZjH)dL$ zP<(Rc^IO5W>mzl^SRK$sNjap7=&B4Pq41vKZfj)@B z9G2Wwom77e61rz~%xEdt5Z>%9+KcNb4{9BtKVJJ>^2LlM!pmS`2~K~43ioJw2zNSV zRE1!RI%p;{VFMT&S&iCdq&>D4{g4baImNtAu7}0jXL=}VnrX_YqvdQM0GC1iu-kHT5D)_(r6c&(8(yKLjR|m-@+E0LLNYBB78k48 z<_NH{k4_L16|?8MK1njMCNc=)5zxQx(wbPq7@9?-(%D$8N!@-=LTlhxumBflx3j8t z|B7qauszn5d@TSy6O#K8rmf2)4Vf^FBPv#dAq~9XVkF_irE9@5Y5kR`6XgWyyOAmk z7zVkuyj;h@4lWaA7gD=Mvd*Yt2f_R~w6Jl)Qs^xX4j*qSeE4oUCo9;DIO##Z8(iJ> zL!LI8-$ycIQ8q62uY`%DZ=bb+C$XFr+pW?y=a~C*aTU}fazvBNCG?wBNLr+rwdm%V zrO|d5H?-J=6=UaXiEWcYgI`|SSM#vv!u6w}=B+rsK7{f=Z}t?w)#UW1*AfwA$w(6& z1DMqMXHS;lmrrq99P+D(+W=JJ#_H)<*?z4-%~VfV9Y5>O#d@<3ZIC2IiQUZU38Xle z)|&7_H0ZV#U|MxVXTSZ#iAOH1lot|xm9Gn8dXuhW z#t9oF9f_u^El*lY@u`%QNY1$1pNP#U;Dr?X3V>P>FS$9B_LFPe2&27VosEp1G)d_{ zV_0)$stm5(G2#pwayvh?R4%J9hVMyWXYJ#LYk&iDVaLfG9l&BW0P2pS`glFn7WK9PmVELp{ZXb^E<~AjrLl0ExWUY~+iAuH^GB z>u6=aEJvHS{uPdioc@taPxz*<=|W@oRp958i^V|{f&v-$jXGVX9C>-9ICCH8(q4tS zAi5xUsZ591rT59G7bTHi64ph7v^go4bS61@I9ExOb}lohYSi(h9n=tIZ359l4Vj^V z;J>87--Qt6J9hgYp*QF(Xh3H5P~8CosE97){;Bu?-?K(6<}aljGrDXQ8+_?r9O!Sz z$qXRRF95?N_L2zuyikjMq@lk8@B0mc#Mj`3R$+BQ&izn-Y6qw`k`6*DbQNly(#m#L z2H{SjNm(;q-Vx04<;f#ukhMkf=rVCKK)&j!mrT>i$p;d+2Ln946-gh#AQ(10;dqRi zLG*Gq{orlC`&RN`8If?F2tI9pe^puT*Ql0|-V}+6HWMr;SD6oO5+lnUq5~C0P`;*H zkPTfGHu==*(({2l)zd6|Bm|@B3E{DLQz(N-r0tijpxtmTe*SRc6255})3_|CPz8H* zmY14U$c3$DLM8%2Omnlvh907KoGEx>Pd8U-;L6A3el4G)M8Uj?Pq3EY9qqlo?g(&4 zV0Je(sAet~9KhGeN zb#1<42m&jj+%j0A#4mJ6Yp5hqq(U6HPSA!WPoPCWTCPMzE`NngBufUofEmY?v%mi0 ze#t}|f0aTY=<0zHDpm?LCDy`2u?7`~2-dG9U`Q*rmKaqFnp_qO=_3&BSmsKO-0k*{ zL+E|J%JAbWrx2{`X;j7~A#4|IY1f5m&HWNQ&L0;La-B=l#u`9dOI*>Lbfh9oUNl8w z6~!`_(1o7SUJeQqi{2kf%Y3|;8R$sRwibOk#VM?mj^&Zk9&Dj?&cc49ehCVoXS8iA zF;ujAuuwunA^i;9L$#MF^uOThr- z%?QLrhLejzR&F5b2>vV7TK1hW0;A)OQD(0VaPoc)e{vo53Ml?w>@3SQ9$F&2K~ambtsHd)M{U1htDC9HSvQ20XO zvn3R7A`e3RU!X#*&zop^!(NbjqGew z9jnW_tD~-Q^9sw1b0GRvSvma70x$+luS~oRf4mt+!cg5YUL!eW|X=PTFKfz{<9KF>UH<+CNr7{cAg>w4$QhN4-Y@aZVq zgkLuE?fJ>)FoQIZqBx|_XyJ62SLDnT&#~d6ZbE)X?dAJhx@Xdy!SqEr9YG=)4D>p#{qLQ z;#z!v2C@^<#>bX0X((Qj-Gb|p7+WssFX|6-$^qLlO95pEth|1aiYOXE+ow2eW(2xg z8?cfUSY*gj7;by&jEl@MAPMFC zvf0<(YO^I`sX+QXN*&3Rsw3<;+C*x}*N184BBEa}-HV^hD((Z(EB4xeN&(SoHpHPN zM(snkA42>o^xqH_mH;G%j9!uP)G1A%cw zb}hEvEQ&yDtX+F@ZJQz|NF1g};Y0GXIB1vxG&o(Ox#hLY0VIWAe>+!lQO2!gFdcY9 zDLe{RXIJ7@dK8+!5RcKKX+!REo7)E z);RkLYcB36BZJ1rlTojz`Q?qn(X_u<2AtY3hXhRQb}&hvDGN2d3dd6-YMO{Sndm=& zQ7$P!V4eh8Pn%^Jn(;I=wQEJX$bwdk3Hod2IS3)?n#J2qlDD{;L|L-cljh&)hi+io zlam!q9_Lx_IM9Nj4mB@e}+ZcTC-hJU*<91 zYu23j`}l+YZyDxp)L?E#v-u(Kgnqt%0nBrdfosf{v@gwaw=yHC8#!CWe>BZK!}LF( zG9nb94;Fa}EC!(=HCpFhBTVPmLdH!FsiFmV?b_9CPC5G4k{xmqE!uLEK{otP=)`_} z5Uwjg=5(;Ad)pv!`;6+4w;bx9z%H)T9gu}k2^g}FPaWybyUf_GMc}8dTH6nf3Jq6` zmcq8dMNNZ^O$mwfC<09u>3O-@HliYm8DDvGDSTLzXA0MLR3sww$-#PcJKf#*6Drif znd!@UIJE?tRw5_o*U)*TWx4`O&+;`+YwAibzMMqRlws2HJMR9Dp6gHHBG&Y5%Q5&d?vrN`5EvPLFC>#G&^2abok^x zp;qRfi`Z-K?c(WAJd?pRk%4dJ3Ism&G56|a^Ot{xvRL;L{{j$ZR!PI)NqxY21yOqY zWkN^(byt*fcy>nL(@ogmPfOg;)jjQnxn^qu35~BW{p?@Z;38C4tNRS|25FvB@4s5$ zC2-sC?%SV1+wb|c-%oQeD0%Qdpq>7=K>pb=_KRcitK+-L0esXkg!TmXw?O{Y3DxHl z8q^6L?J50(KWnG|5s?4SwbTDAK;HZ&<9F@!Hz5D{rT}$QNPAoS;I`EKUuviS6v+2T z4h{dUc1lY~O!d=(|0gE==lop{*`Ksif&W-LZF#kEo%mz&=T9`Wzp^6EJG03aIQkEV z)HjWPdq~A=YaRTbBl!Qbhtv_5N3H))icD$piLSnNsfM9wHT!yQ&c6JA*lhaetSBEt z(e)o#(VvP;l^^D40V~`8l{48HfOX)qanG3}+lEK?plQ-K+ok2z&zbVZDSb-jwht*_ zsrGiXfx`~VwjncCLJ-=K?N;nKn_QY$#W1=ub}Lu$VR1#jEGqB&B8l*PO@r}!e4B|^ z;mRS?FTddvHA+>Ri8Xi;ToHi=96yOqF@taR9fl_4e@FrFJ>n6sK$dDJdJBVce6kdj ztvnuke8XTFdfM(fDOSx)ewmqqpvB3=zzMVWzbYM%(S=hhPMY!Nb&@)P>;bLs>(uYf zzSC_W=g#MxHSqfI!ef1Z;$;BdrLB!SJp^cPe<@gOY@FFB>q43KNYRhd<}{z37Ip6H z=EVO=d)n36H&I67tP8q0tj?RXNPsPoO!VYIApl+MNL_1%7v~q%7Mye1YL(l!mrdp# z(Ytxh2lr0;SD1wkM72s2?N7T?ScuTRRFk%I&B?!$WPtYS+zUGCI(dHIe~|mzk2pix z%d4~40gc{?kM<2e|HO*aKC!oF=h0UFC@$|1khnfj?KrqSd<=T_BePrfH-i7l`u29$ z)&~W^fT4g{nWxa-SP@<8yNZ6y=k~bDUUx;NhzgYUaVXhjA*S$~0sPSN02;g^Y(=F( zSk9kW(VIb%?&Aoa_`f=nlSTM{!;1bw@b6fW5v<~0up+L&zh^~%DKh;BR&;eu$E;#! z@wtYY_J5xh{kh2WKV(J!g5a0``y$gn2!2asXpofTRR9d~bgAwIptnK_OJxd0#U1%a zOo9L$jDRYDGm!50n8d}V`d59=tnK6fhcW5RFkA6o9yGTAKHU!iI~|JWc`!4axD~32r(am|F?b5Mb;3v zKleSGs>Ell1pP{Pp!cN4pQC>)Q;XO%H=z>v6fg3pzUSy!=7bx>R+1da!y<8o-}|0J z&#h9m6j-;@bpLDL^WUrGX4k5@?srJt>d`w#7EPtqKLpVK5|hmrHYNY2=G5uyf2x)r zG`(T|O)V$+QXqASckY5V4Hl?F&Xe%CwlAxQLpnYO;<~nk&p!Ee z4$j_7VR4>M$^G`wNhwPAY-X4F@cg%jPIqd#f$PO@YWc+n6TdsP+#-tezgNqX53fE4 zV{u)tg_F8nuSc`gUvI<XZb3|roR^`(B{jBg9jNHF@_@cphb5@vEz>@yQbHv!WF0YA< zP%~PAd6o9s#TJLz>bDECbmSqqm~OXh?gvXR{m;IBn&_~dWpoqnWx5ECU*k0S&h}d? zyY*{HpOJj_PM-BacMpXpfBH%-ff`f#g=w4~w5{}Q-GZ!xHl;50`(A~graHa$SAUZ8 ztc6sLB{>aso7VWY$G0%c+o?LHS`j?YfBUlgVt*kOh}+v5@46HF zcCSU^FyvLs#0$+=zs517w!W?m_UH|qY~t9w4=4=+=_zC9q*(-A3jWs04%0Q#boIFE zH>fm?q>@IHoGOy4YduXPiX?BBSC(Qdv{Ht)f7yuZ{$#hr{NQ2dtjTK}n>ZQ3k`;l~ zkDJ{RPLPV_mS)pHxupLm3r!KN~acF2S>n^P^bO2c<|~9PFC>9QZQPE z{X~Y`FFDidyH@sE=~?YSSb20W8>HN0`fHK2$x_%Ce}EKad9V?9Zku~VLT|ZgDe;xw~ZLPRRj zp-uM6?B-9Tg+@jGNbmBe?<8NGM`M=iGK?E8Kd7@fH@uSjQttb}4ii51i({rXlrflx zdN2oQ5SGQjG$6CFq&&do%i`vtqA6~DZ>fNGa`_#KM$tv zYK$lfTySFS?@Mh`1ZG*Qe-Y5<S!YwODLF4{q_6@O#bZ{n6uC(hT;F2~wTMHo$Uvn5p=gkauXnTkNmXZa1M0U_M z1%BX^0??9{DpM3B!WP1!?($w)g9tG-rfL1gQp3r6ruWAuzQE_D^F*6vFHMoLEDGoO zfoi%`sc5{?D}?3k=<~sh@{@X23gFA?P6l z=U^Yr4>m2~YOO|q35K7rp#yM=G00z!nt2XtvM(R2@Ez7tN8ZHf8ZSwEk;w7PTi=su zx2Pn+Z{uR|TGmz1QVgS-E*|8M?j_T2g6Qv;+KSOeILWp!B8hE~WY3-O>FZW~?pdCB z7AZclOG)EJX6QfZCn9P7&@D0LfjLn4;T;1zrt)6B?aKwC3PjQb5w_CT{Y{D|V-+EQ zNuQXoSe%mAA5A?i=?JB;-%_#X>Z5j`PNt#z!A8=N8r5%Hvp9|O4Lh6ZtG!sFhQ1C+ zwvHr@q&@a@siMR{g1I<+o4{4e-LP5t5VDHU%jIxDSWS12)ud&QF6nLXTyyA;ArevE zHD=$mvHYa+uwIiQ=_xR6V?8@S;AN5^;Wg*Bu7+Jd6ZgVb@4Qfsw|U89#g0PTb^0qK z&m*#NE$)AqNry(E<7!L61xB+Cqba?H$Dz#*d$6-N2AdSyMcV1sD5^!va#suvV&O1HpRypPCdgO{{1yBBmO z!Zs6=8LAa98urb^nlgaOP;=$-RttshkG}%57qHTb@D@0u3s@OJToxK>Ik?1@!Bd2^ z>0|xT8m8_frafV4Hgyeb4-*URa47=P0w-s!oS2CvJ^&Yq2?|^2q4a1>3&}*bh=`-D zosv~Prj(aVLqz!0&VtHq5*`{#d7KJK4YeGS6u?S!hHy%l?} zu1hi}+FsHNucKm;CQIXTxOu(}<}a>s`npqDs?gT-_@z|Z&!r&t!pe6FKki?}=Wxc$ z9IeaW^9W)YUxi8>c4{Xp)BVi<=#a&l?i;PqqthF%L}sfksTPyA-2=Xtb_2 zOhA$@plo=+S#4W$vZ8G87z9nW3d_pH2{d|qtJul=ExRc>`XgN|8_QwrZfMVIu6OdE znys+lCf6}!X*j#R|f+;ujJY=N>| z#kiOOJ}4x>564@#76=uyyi|O5dOvQM#>m^*$A|ldm^7y7Nz<$YZWB@<4ZtqT*m6!0 zne07y;%1Pdn76@sw#jKSX!!$+qO_5_Y#VMcXgu|rntzC1`igMO$5KoQLWZEW@SsTH zaSls1!%i2IR`Rg3g)o+5;4w&griu?Y@l6b19*$s6pec|Fgpr0n;=U#i*mf!-rW>|l zO`#X+o3=3>Rev*2gy0u+!-kUhJdnepd@2x#7#8vHeL8W;p@jyhTO+`Pi*mLwY{F>> z)^I8L!i-Qd(W@!O6Qq&xaFDRhGxQT-xD`DCBgyHOuM~^1>j)v`wEI2jCvw)YYG1+` zm{~8hn891{=nY(;OkAG@L2IQsM=L`ISt%y^`io%t{E{ zP>=qZt<)8xQh`7e^|S*#T&Ni)aVeloZx89XBt9C2w=6L5vp9Bi^5X`?jT6T7dME7p zli(a{njj;^im95kxvxVN>!eBfQt0)nh|HGH1^a0yQsEpui@j z9tI@{xmYqWin782Wx$tm$+7_?WQ)(qWvwSe$e@bWhjz^L40;xWLXQ<=DR|ZQQqtXc zA4|7V2t4?nLPc)CJveMax?vJZ6aXcHk@!f287L&t%VEQk z+fE_YgWSwMX6eyI9p>mtLDTcl$BW_dtwZW2qKm8nOg`Kua2uXN~$rX4L%B`yR! zN#%N&;mH^mA0rMH3yv0rAJdCjcL7xU0h5cQ)erNAbhXoEF+TuF9vR&Kb)u@sB91*x zg*)xIF^1r}fiUh`g!ASfjj@tv8yn3Q5C=+=SF_mi04`Y}w1F@Dc+Gn@qBZ#gnwxN* z@iSvZLqra+=KW1zg`F4)l2nm3uYoA~IW^1+t(0mO#ADalV~Sn>uVO#G#vdg2x_ zLolWQa&*Pc$r)&R5EEyzfOag| zI3qC9EV*orJ}zW9O#P!b>1@W_Rwb!6jdOLJQAYVaX<5E2f{+&Kx7~azzWKmH2%N3P z{v;@zo=!8J3aOkbt-`$-Q5{>F?-~|MNe0~>c*t2+1zfN1;DN{x$74gQNiyxSinYI7 z0VY@>^Rab)C&_hMO59$N*$S9%pqci?A|b8jlLOvbH?T+37Flf86dpS0>-A7=*x+1E z@N^U3Oannu9$=X?>r^FZBMHL*c2|e^t4WT2RwZsOpUp#@7_~1iRoXbgY>+z zy0}u!(2x>&RpJNw@jC-KiDT4$etvVMVGdDh0!=tutUO}NkfZ8aa_#I5danm)d5+)7 z&jcIwz{)M5Wpx7Hl-p0dOS!(>!o)Z9?s^Y9^FkWKJxlrh2o*{sD~5&k zVfQr`4W+fKxGNKMX7H=nAhln+VxifGdvFt3iJ@^~EC!Bgkq~U5E)KX6wQd*j39B&= zKjVg=3{P{raSU)tMueXx3!?P9w(#M4 z_vC0Fl)cXptvkk(<)V1TAetW>>i)#$Mz3cU}C zUX*SXF|aQVfh&}eZN~j*;`Br*vP_-aYe?LyW&G64;L34z^=S`fcz?BQCj}M!35gMj zgOMqHFkP{QW1r3dc0Wb5KWcfHk>8YOC*o3GD|W z$sQ&l=efrO{b2lqfJzMYNOU(*ETXcA9-W{Oq3PzH%i2Q4uueo4h74t#@F<5&51hB$ zA#YR`%Ghc}W%YybmqjmE>r2vP__#T0`yUEjpei4l+d7J9nbElv6Z(k z_Jy@<9{7KBJK5CRh0+t|gwj~)xbloB^S^FBcY114yl$gOju2`KqPm9)2z%B65H`A zYHeU6x+w93$oMT6d#1| z;nR|R86Inzu$^YDR#1TJLIx+{0PkI&cwuJA{rxtOtPBO@@nR__u>*^uaVjT>!4dGW ztL*2}!-4T$`SjWo+?DnD#{6X^xLPO%3gZHE`b=-s&3uuQdqGI!tn% z$ZVbD={i}#Iz`_))#^IUuXQ?_4SLB9Mzam(ryGcZ4Ys}wj@1pWUmH9$n|zX+0%n^+ zPd9&~!hM_fS2rbpZA#ryVaY8yvn_?ETS^66Dt%jOt6LhswzO!rk&@fGX50Etw+#!n zjrz7tR=3T5ZClXnSV`{KnC;j--Ek<`aq8P~S>18_wc}2+>nXYGZMN(C^q*+j!=6*z za$oY$p?|CCG6GWWuGftJ4dnZ)rpurL{#R>-clCv1E&tJ4;Uos-vjA$<-|k|m7TQK=5DP}?oj%LMt*hp*M$~>*0N86Nk=rfk5L%-eLp-wJBg1qXg$H-H$Q(K zouhvx>3Ib%gK&7c$NxkDFc*y6fElf3A)}^IYoXy#L~1CW0>aX@&P8rDJX1OvE=|nk zy&OpwiP(saI#Jwkuz(VMjsbNI{>@sU3+w9LT47bp>&?WcuIouj6hKECvoa~Uk>tCz zLL2E74?RW)*U2pgS+)CBwx-l>d$xKYo_=8X{|6et+4$sYlXiTqoy|DJOAZ+{YNqCTrsO@+k#!qVf%{j z{$a;jB>Pe4R)#Z|Ep5Te>in$FhPKvE%Wo{hUMs+5|^MJ19 zt-wnTt+xm-;%)Q?SiPpY4+t4srQ``*wPqwzFEszpuh&zDepQ;3MAx4ieH=yBtH)TA zHVAm0|G#*>zSDGn-F&I|i>CWug|Oc=T>xI;zb{5Dp`^kTHYBF&Lex0vtGc7#ABM#;ADK2&(2>e+ZWercl+h=Q-ZB49Kg1k#K-@T=bMg_W zo*;xG_?*{ubEdt1I*Eg^dp2ofgwy&<_2uQ^@^TZXf!}`im$+!eYB0vgIk6=mcsIrN z$>EN%JxEtE>B%B=nA%$5hSVamlK2i$u`toSehOIILVD-5@xPF{oKrMq&#lEOj0A={ zY$iYj^`v5eZ68ex#F??F?N3GTHslnYGKa(JTu;n_IA0<+({$ z*(ovAxYXhOlPI=v)2IM_6^lZUKvvNs(3gxgm27x8wQp30qg{4;FxW26seqzF!c`09 zv{ySB(>ZT}?#LKo`<0V5$tnVzR$7d5ffsw%B{@}=*15=2)=hngOnsEryu~i9uMOS{ zclTYUX9aNVm3K_gYb;PziS?Z$G3DMC!k;q zDYp-p?(^%lWB>r52sS$08}K>X`Ii@0V@{w0kx_4iy}<0VE^#YkP?a~kdp$YoqZcwa zX(q>gg-L6p!r0^!f^|+0`?Np*1a#7}vyIUyWdoTjd*=OMhbXD@RL()%Qor`aHmJXX z+{5VWj&*y2{tu5*uCFe6!D;-NclUUPR{6+$bj%MP0Wal>VlN}I#gHnlC)-B)-weGs zlzr@YbCPB7OJ2TD=BTT#VaW)PHX8Y$bu@s^_`_Q|?i&!%zdH`Ni9i3ZAfJW3*YUv_%0HG%9#juL~ws2!_2zY)Ha+ zy*ClyTERU*d~P#R0sK%}S+t!^$^%mdK~AzIqQRR}*F8hFrKN>n6xVk~#m;8))w=O3 z-7n5K-Ffl-q``{LSm)5fCY!5CQ}iV;1B{qntV59^Rz!qugMl9hRvS0uSi;&S725`uq?HsAoFs|CVf3aSx6rxIlBZduuqhX= zTPT$U5~KPS=Z$NzNq;CiO5DH6JXrHCzwM0n_LnUU#9I)jaGNs2(gyF$eCheQ5^u2r zUt@S?m3=8yb?2Q?W9D|IU|z_h;b;X*#j_T`#5CQT8HoG5NAl}95JIbusFQ6k#!9ri;KK8ZKBUhFa#)qaq4kU67LW~(9vd#xu>bQ$IEmOiEp zory$Zm*QcIk}Uv&0gOSfUl_S)FUctI*r(fvh9mB{nbb=d_| zmcc6gaWHe7qjYqS*HTMsBQHt9OD6aaFXkH z2NqAYQg_lmK$OlS5>~YxlXqb*krN5{a!QJpvBuABY^2GE2OmDyWl8mfTkqT+;Jad)?EW|Fn_rFlK9iB%(>= zaD)jngCZZ9JzggIoq;+fv5#=WG8!Z{^>T^$jAs_%|IjXWBtX#HBSG6$F;K7)1Y{V27WuCCa4(`{D zaH7Kuf+=b8(;KlJaZhor7fkeA!*`paZ)=X+Y#;@KKhI);V*Kk9Gv*ioYPxx!FaGaZXa($r;_uJ83%oBq_P$=uKQJWoAGE@1cEs zel#XgyPa{~9oauZ*-LgH?p*QY-nx=q`=bIqpDAK#G?~X{&B|WG%Eu?WeLWUrlgnm z0P_aXTT$2eFe?s{m)yZk8TC*?HclD1wj3C56yg^msKd{8Tw)V+B4(E9R4w2~PfU?S z988c*f|sl!XB&n;Z3bM&2L(rh*1+2OfR8&oN9(lMbRaoj<_{iGUc{QX%#d(7%!}hN zP>~U;Kb$dHqf`LCG(g>uERsqToH^& zE{*2r!S;i~unL8Eehtx7+7CK5&Q>-te9>pN4z@E$ol5eQHB)ybHGY^oCtCasIvs>j zmk??|BM8~lu|&62KmHiQI!%I>5h+#~tnVw>yBixT7oNgQ+ujep2a0CHFwC0@$K|C~ z1cs-|2Q)&32-2Re=*I`>(NlkrCr3crbfIEc32Y>Qmre1yQB3Sm48Rmgq70mq-ogV( zP>LjQ-ypa_OJ?`v)ow-XWI9XBO2T&yb9rY%*>QRUE=3)02B&jh2V7kA`?#9-@a0EODl z6||Kxo4qYwVX7sz5pn4FvaUaaT|Nm6Qc0 z3W0Q`s@>pb@1-hVrxsRG+nf?4#iaBXaT8@EZTM0#r)kwfMLDur12TyxXZhM=pejXK zSlax3UWp|cR?P+gy-brxVUVbeh;dRj^-0EZGjn+(0LTmQD^K=~$vk5Q9VXM4l_;SP zhoXp)kGx4tP|;8Ye*1gc38(hI4se-wOI%Clzr{sdT8$;p{dkk&aeGGt33xp^VLR$@q zIn9eO%xpq%IHOZgM)Kxt(lpCtDiP`A&XT^6gN?v5iN8XPhN775xy{i5hry;L*+SA` z5}43p1quP@Q}B;53_J+zG%|;6m@QVnklu>xxh$B)8j|Y{zkg25EeF%_Lj;w`&qvc< z@s<+@;s#--#%hCS6(DR@8~`bm2mTfQITik22~ca`Ya*DcOg_;Ly%*mj4SG<+X%K^d zt};p?L}WOQalnF!gjN&`qqZ@3K%_zl;ekt41vwRJVvt_}P{C#pR?hQH5!xVY_n~q} zYeshWa5wyR5Oll=RDa9?ciGEmJ$3BlPB$fN=>Btdi*q zmSP7|xp>gUj7M2GIlh<4+#Z(IhH>>Q>0&i;GALA~vq7&cc$13h9h9sVPRWfkd1bT1 z7t+Hk=;g0-Oo@2RPwgsvA6f;Bkt!b}hRPY8SlGSakUvH%Z&HSGx6p4n!QT#wT%}YK z&8BQsS2-gL?vBU-;hc;m>0v+}-6|rzad6%MP8p!$Wu!S!3l@opj z<=-|{ug0d+7UhDW3{~k6Xzs(xq9(lcCP`cP_%%e#gE3VhJH>#YbpQj@kAcerz~#XJ zA2%aHo+}Neb(S__`W2d5+5uCU*`jw>OFuIUy*$ zyFHVzsPLeb#6sT1YWp!-AeNGOQ|QE65>7Azyw7=fyEW<8bD?~yP3X`(hcK1snx-p= z=t+k}h-0@HMEw}Xn~N9>rLJ)lZ5Y!VVhR0#6l6wg1;Lq5r!fPd&}WJ!9)SgftdNUf z+Bz0A=2nD28w0Zfr7RsJN|jJYC(2Q#a*l$*O2;pFhBi9WE0cuiF>2z;t`o$`sPZzj zq>6;ea)!{@g206C?svWbPL~QaF-Be%^>$QeFi<~XFp0760$D21dvI1Pw|3S%DTVY9 zN_%{9_6diB><3|DXU%5Dgw*sn#Qdc;GO}koe%xMUM4jX{_QaU$V!-<_hk4}b$No)m zh{Czu}+~@Ga;SFl0!wsk@RQ;9eyBhquPWr9$=~!}_ShtSw>TcWX`)NF>V; zb%ZT(ma_gjf#d)tb|5d0BDk$9)Nhcm5sYO z!CNN8B9=HyoR~Lt1k*#pCMlQ~iYABl2)semF(-Id^zvzs_aqjX?*Ah1Et}eG__g04 zL4qYAxFxtd!D)hfafjj##hn(nmKJw+C=}N!E^R69P^?%BEl?;mveWCjb?)a`>sqt+ zi#@YHKwdDJ|9OT(euwnklGio2_mM?&951GCoJ@d>cPfZJjHj0~RYWjT6m&%m(p3ep zOB&WSc}m7d(~C+_Z+#dy`3cqkOlfMbf@dmWP}W0b_%ucgB=yC+n{hNVJOsHF@sbn* zYGe#Pl{?9%j6`@&6!khaz!WORDZZ4XywKMaO%yNCjGXtatL+d7Lce5YjW?#Wa# zU4WgmFg0(rqN#}@X95w^T@WU@eQL8UIVQpx5QDqpa1K5WH=uELhs17wj#?z%OhQ=( z(MShm3aUc!HnmX3;0*tCW$N%`wlz)n5Y^TDLP754kP^)e+-x0o_dM^H)|P+n2p1mo zm{M{fAvb4w`g9?rFa3udg_ZoGU;k`%zjGtPBYIFO&XMV|Ww8@w*)q0(N~){Rh>2sO ze%{Ae2=3xN>*m8XTAU4B+=*rQ*!OA%T8tjZw=SP$s1lKX?0qQJo;v4x7Q(r{B9ISo zR#KAg%`7*U9e9>Gs3W2;x^!8y>R68IoEBiNdhAm%O2f8J#KYw!?U*jE?el1jg`f!s zGvD{c0$lT@m9cl3GUn;ptMw^$LG{RdT;Kf9)>XPhNXv!|WL-}M>pQaOsy9U1d0y`t zzh)BSq@SebQ$mbQ+n+j;ZVsvNpk)e{@b0Cb)t71#*cv_}^>(>FsvpNbx=OgULk8${ zVF^sM61b{(InDI^O~Eo-Zg?nlMFIoSZDgKqXkX(XG<2v|@~ zwS~8~?R;?FIN8)6uM&84@&z9E7yjH6_^B|r1Fg#341Tb`BP+p~+{Ick8C9|zz$eA* zKSRS1eBiH>OVPm;xOb56B@!)Tm8H8>WWa1wd{}aQXy3bDR$~5-@F-S4I|8Hv+Hns5 z8~qF`lJmE?{U3`P#BjWw1 zNG|zQ+8{+mG=)v8M7vj1+aO2Gql7pV8}SAmM`QIfJHBcB>@1r%E1NkBEtY&qI7BO=R{-hH{SVtbweZ}O&|d%HC#71Y9vKQ0e)ZoThwDRhWA zjmhr2?d6mA#q1R*LS8!Cn-w^2Xpue*-3Y?Vp2;W#&be{fk8;d!m#SSW{$3ATS;wgg|Gfz#vYq%SwLx?4 z!{fJ9#2=GLev9N;hhb?gV<|2-1>WrK8@B?v8N4EDY<{d4t+3{Kb$|PY_lHRS&-JkX z5Xm*tCq5axzW#C4j7#JBxu1xu@$&$w5t=S(oC6K`klPC z4o@fjvmfy<4$~)1OZ?++Oxpk9FntVW$Mz${JT_kUp1)=f7LBx9VU;zP4E5a!;t->Ms~yZ z73$T;Or?jVA~?T(tR3&Xdl6ZMdkqNMvx&l|<_1R)o#yC4F?7F^*D=-a0zj&+c3~i! z;BrSiZz%{L^KXZVJwtp;k3Odd3N}R4{>@=3dd+Q}_zEGVAB(&+TTE6U;Mq;PfkRjH zfL;ZSOAJnoRyU^Q$Zkp|Xr9;I3e#$bZv0{A^7{+;Q8}rq7J57~#H!$GGGgA} zAlRcrS3xMpUTxK#Ue|gcB;}}~u`8_d5o-p9_(NmIf;$!j%Q~#`SYm#bv*0Oi;8EIR z{68F~)vV?Tq$Rk0Qk4(fF*Bp-^{2zsZ87mrhv~mKoSqdLx-(U24X&)#IgznD@s{GazDnE!q}G+_+1TXmt2 zq_#_b`KRp=peI9||8X+d_e~=p1+a|s^1pxItc~g0#r*rG+@YQ#G}pkUtw^K2=1n2? zeKVK8TM5$uR^bPJ^R1n(RL|tKp7>%9Ek}2Q*VQ>{CalF#NfZLQ^y!3c=G-L1uJDE0Tr zEc2KVr;~sL)f)tza*MHRmBljrX)y+TneGx#sE${0CA|*E`>-ctd5>C|tkBbIwQGgr z_WTL5zF{C5dotD>dyjxt6$E#>2-~5bv%gpf$VY)ofdC~ADD(YhSeqK7(l=X-QZlUiou@Acf9h0VR0O8V8Lc$hQ z=8i%*pUrWRXRhzFt?Rkdl7SH&mgsVhxZN8LE`$qg`a;b>lC>D%F>j2y*Obt*Y&|$OG$yS2Bl%P z@E+yNGqihGdnJ~?-t$b-rYfEH+uQc|XHQHXfNozHIDN$B>km23H#V|rEm`&K*?UY3 z0NgaLVT@`3!Qh!6MAuqO^g@YdC(Nv$0%Op`^OKH!r${<9jH}z#@0C|uZPqF4Xk&#V z>l()!VWIiVOk+s3|ExMO6<1pPh3U!y6aZHl>JlORQfTmW4>9&IM@zKNu|Nw{Y9t1n zP5VKG(wuxY5@}?n$bk7`bT^8|qAt_`rA~LZokQ1hk>XO*^XZ;jqie?7k>SJeun$9S zd9^2UM$hwCm0{L;b~ylZ1}z!$NdA*<2`A#JJjud`DbKLWb1O=#ST2dpY+#%qJ6F=c z51S0Vqxfv)yC{+>tMn<7jzVL7oRyv|QR=e&_`PbGZ_k^o)@x5C(?1NPBdi4{emAK!D4R>TE?MCN?< z;@H~Ogdz%i%E&Mx8Io%0PB)6AimdI$ayT{ZKqnfCfTW;a0hO94PKVVBJ?DJ*x{kksP8p*&72kMkPks4Q9X;L%jh9+|OkvfJWy#_YGWyojLKD z`BXm?+A>IHMCnuQI!jX8v>a3v_IAWL2v@NGq+SM7M2=`63(|2j$^abPST;_;E1sKf z;L-rMC{ssW1f)l3T}AtT(Jqne7?IRDZQT77zEtm*JADt*?Noc?)FTICWg9&0Kvqk* zG&RD&7etO(pqI?9_H9fJal(E;>AV-ntQMkHk$hO|0{WvVAcz&8*Kw-YtAMS!p8av` z!F{49-j^7GP8)}7HkP;#t6?o!r#Xc1s}zB;hx3m2TVF z(sj&cZR~!;fo0$UD8?rmZ;}5PZ9pVkA{JNys_t*4w>hXV-_o_03r zBS$o+8!_a13=i=Jl1`v@-D!|rbvJxLdB)H*ld6LFG?Lavd_vqP9%h2cONom*0zJ*1Zxa0Ix<*`MhCLVhU1F~+vuM?0F<+OGoVgwBhIDdxbbnHnSSm= ziC%;X1F3hw&k=>^&_}*o9_*D))KiY!E}#b{Te=KQU#R*3PIY^hWUM%#C$E)=m<=4e zP=%yCqew*(0H4q={l#AOIKSiMtd5S-bcwev;odi8m%^L-B1R`{o&54OlG%QQFpNA5 zGopUexm!kBxYVKRZ#Q0~e$#*dPHb!&lg7Er$q)y!XV}e~CgT8C`z4$Iqe_o^M# zZ1Z|Vn)x8Vnp8!jO2Fjlr6&&eQ;kP=EEZ*subPr*Z-uFcudWVU7tV@}F1mCj+=%T` zsxer#?{UWwxas#pRcEkMb5XO}=J*G~gvUjnJ8tu%XAYdEmTl%xg|S6>uFXf)ebxUv z)Kd2Rd~o+>Sk+9ki-csgaPP%L!^HQeEZ2NdI134M2Va-s4G`ov1lU)3a^mCsvXG#G zSOtP8`Zq-VBi`il#b#98*m@FQyL`6dT0lAE!`|5=BAs{U?Q0ayf)vU^7z4H=$+!U5 zY8CpoA>78RB+Ch(p!08b>GfzrMUheMPZ5&H8jy3EyBF=xdG4#jR|)p}BNAmDQzZPVD9C+4OolzJ?8>xCd| zP_P-NMF)cwNxb-*FH z%RxpOb%)6_ifUoa;|gS|qOdxV=M!J6?w~t@v$7vV{B4v%Rf7!=G0L$-r?I@Mcc>N+ z_lV?ipghl~#8fI6Uj*r+b|{GTg$d7*#}xuUMdNQ9#G{SazKhs3y3m%+Q2xNVvs{k$ z?f^efrj=3$&t2*P9Ki|g;F?NL$0&9WyqMlh#N{T*^!a`KZI+5Wc8m{6nk!dXKjU>w zVtYo+S+Lb6A{3X4s>CFuxz#frO`yO9B{!wn?Y212xapX#$lxL*!NC@v3Gl^%M=d=J zQ@i`KPKJ0mTz#7&Og-iaD+1FW$Jw4Tkj2%pBa_rA(MBYBfuQkAXJO=oBFC(oRl!Ip z<+&Q0$@b6}>gHllqxJ!IemX(zZIU+!86w1)ELSYzy~Y@4w7%DFT2#Ez&bo_a+GpUluEPKNnJRu<+r;O*$x=g2h=~>Yqovo#n6|j-@at&}dm}j+30LjTk0ln!- z4Rx|lYewOmv;lu)bN}%3%d)eKAN%M8v{!pg2$!d6ML+0 zX7WT}x)g{Mf^X!v)darh=2#z!`DBPeTM8e|#;++7e90;t^e^GR1i$e$`NV1fF3-WA zCO03yce^9b%`ee)fLGg$6UNIqqfrc;0?e`^Jje2Idl?xs@b~RGr#Z8gLj;(_9pSCc z4pq^I%i$;6MwBaHsR_H&fJ9}BD%I~41R9(Kp(H<~1%54;bB*0ai6`M(D5Ts4@nSej#pbUO~GjJ{>@0TuGu)>}(DoMS<~rblx}c=&LgeXm~f8A=P`rE2)B}3Fwlt#fF1n zebcC4UEp4eawgvfN+=FINM;`wrKAU7=LM4pgWn!iRirqjiw3?6@e>qfHszqy=0sR% z8gcp-eIlwkjw!H%L98inT4JK`A)m3Ib|97l-(C^!!fSh_Z_}*L0Nb}W_G9@#DZw}0 zuBAqhsHv}O$83ue(Nva6g77ap5}asDD|?@3Jf@%%e6x6;QWQ}X9twlUcb)smJXVBR zex{gb2LMss7xcl=LtVkFS|K5YYRQt#ls$wMVtht0R9Uy%BM28UJEI*N&IhQ18JNZ+ zL1(r!*?@DNp38bi`^T2WbcQ{iuVGG34?lzkT?RE`H6q*tojED7QVTM>+uvrDzrSyG zVi$fZixoKmYt`&~Uh8+^OJX#I`ZmK!GR{q~%r9BP(6zv1Dsm&*DcpdS zDaAG*Weo}^_(R`MOgSTwDFtpnXduAmqmn#jbPv2dARdyjLZ31vIF=b;ekBEIvWUD zA$ENQe+SGf&RoA{>NSQ7i)N-Df~8*~Oy`uhw(mbR<;K3PrcPmBLmqM!!R~oL>3$4` zvB4gsFrW1M87zW`xCSgYQH!42p`3G)hwizgk&LKDm{smAxmGQRGwH_f(}8%2mD2D?yX z*aT2h#3&?5PwEy;n<&$){dz$g0-c$dL?~9m6)zn~z^^L=aVvC^?&E2`Tr8T*s}W4g z^5fwGi&_CrNhc4^NHjF_l35X7GQ5x0-V*m0{3@5dluo_W0M|q7;?kM74&Rcd3i~;_%a4AFi(J};c6^bv!A0$HwC<(H*BhKAhXzATX??~$ILeBDnBZr0`hFA z2}xaajJoH~G(#U&b^kDvL)9TRwLVsdd46><;3rq$(o&#gVlD`(9yD!%NpD!yY?5Z*C$w2?Tb&!c| z9U%X5>p%(0&e2vip7}2{jy_L`shrop1+M>W9XxaOum7)@Ie!RT|6u0)izfV!)`8Ef zngp!C#UDheF@k00)bQez!(zpmOiHjc4wuqG7ThastR|dmsrv|PsJLbzpS*i1?Qb6^wyA z?!CiPqBn9(BUw+{%{W1fIC@a^UF~KWwIS`Y9pw|Sm35@!!yrr6MTa~`a-eg*Yt1)3 zS@*8cSs}vTtpnpO^zRv((2_f0mvl?cYTtPd%HpWq56b6oPNN=3w!?Y*T zbKH%WtW$G>R!jm)uroBj(PHk31ts4Xvm3fJVUHe)*oIN&t-!{euypuEcG z1biP`hB9iDTVb6BByF$vswyhpsPY|mXyRxccR~)2AdO3t6HV$XL9zmM6jzjwdkz#( zCyKASV%++$t%KXDMUx)?2WF1;$6f-iM&Ygxg8wvB7_A1WT^dhE7=u5aj=~f9&&Jqu zJYO=QB7&G6Pf9T^_OGyB54`7e0 z@RuJSi2t;dsI@bqYTn>es80OL<72Koj$N&qUBBT=-DJf-kXsBM3t4cL%^X5YB+qbi z=btbiYY&K92BAS$#INsBuT6P0mw&^2u#XR3U%!jK!?LCBsNec{&*?_BO+S?VJj!TY z#}X`ywUn@atO&^>hf0Dtn#U21eSGu!#LHw9d@WG|Q4(gd28aGB|lzg)KBX>k_{Q7EEaW-np@ zn8DgETeVc+vP^wSh-Xr5#rp@DQCTA00=Cb9;CosM~v~$>t^p{~xT-D}#lc=Og_5F(bBO262t?zepU{#D4fRd138l`B=&vUKX z7!a>s9XE1$PsiJ9{-B|8Whpz{@(YG1tt2NE3!2fmpZgAV87GrgSEc}WZ60zq*{1HZ zR?B=S+jaD@{pb9bef1&Yjx47-vLPz#CV1RlcS+3m!`d$X&hcb{ql5$hDXcyopyf5K z*~RcYcc{sSY3u`@Gw4He-O%;yhX>&qZDlF=bWg3iJ|RE0xXe*&)7a1LY3`xAkNBpB zNvd5b?s4-{QTMrmR(ZybTfTjs;OFB+4Mdu07z~>Lv%Zcn3a4hro)n#73>%2(h*z6S!`b}>m2%XU7RG& z%388{RPWP1-;f}BMlk=X-^SyK(dV)BJ&d0vwwfUmmvy=Jz_IdZZhH^-;!4EJvQtC7 zyv(7yY3fZhQK;5qZf61FxsN{a4hG#%4O1e9IRwX`%wAQSJ>Xt7i+x4L7ilKFt4n0D z zGw)f|v;a-|{6GeIFTD#?z{K2WT%0R?Pok`-E4Xk3_pIZ(`toBdDn}R6{P!Vw_AiFf zV}b2Yx4w03vq7qPadi9lggMHhoUs%a$7tOo)ibKiem!(i*zT3?Ai}<_;Z8gs(J1v< z?F39jvc&;%udfsHv}g$;`s>H;(~))@Q}0b@68#ul@7~gWMi3FRIArGKL45#IlH`it zei3slr004wlg z0>mClBX-`vk6sPw!!i#0=%}(+xa;lPd=d?mOAB8B$FB?m1S+LQK z$WRJwfn<7kx$Gz1p6$Q!t`>MhB5)|fr9H&o_i3G`tL5C>uPl5~iD})(DPb%wLdq+vW2e0YZVz2pURLbB zX)NIW(j@+=raNwoI)8mT=Cq~m#Z37KkM%_MQ`TT{yLc}<$yid>TuTn`VKFLIh_;8mfsVxz;vHH;kije zZ7}oU4JVz@&S;k5iD!Zh?frUp(1|%ItZJq z=f+67Y1&>5IV;^Yxi?O;4WdIyrJeMUi*YehczrxG>*3Zginpw|$Jee1m~xh*4TQI; z-gAf<3xc~PB$2!ra-%NMF}yFHFGHi8vfD-Y_VF1z_YG+<&j$@qhVXVZ00r`id}MHY zW=E_)hF+?BF4{q%T~R9CEsU`e|NfLWWV?s)O=n`%Oxwnq;Qmy z>_M_%;pwH+ZUBj%>4?&I|K9HAb9%WgwEsoI8u@S%)3$yFS?TrG{sz-Y%E>$z^IJC9 zq5fUpp?D75!hgU6SAE6u4P8~60+upAmKOBjc1XpExC$S3UIZ9pXQHbX74Q-Ry%rf%T zv2pd#)MBSjBp}vy^a&y&c;Xt7=bVM-;v-pL=u-S>yXv4MMADV=Zd-Ibn{-$em4pMQ z;5H1D&6{E$q0dd#Qm(U86;cP|;8%yp^ve_Gfp@aKv+U?vg2B;aqP>_l;xn4?;RNu_ z81CqxWNrz95D4(+KpdGO_su-3&?G8bBJ@KOL~5OBpq-pyj2dh!oU}Z&WlXgG6nVS} zVl(2hh~pjG=eRX0{k0={J(|v7A*w+<#SFo!VBkfVX?7&aZYT~3t3lT~a_MEJkW5n< zREK6Gz-!ncphTDCZRYhEo6`=)=ey=*^Xygo3BH{CUq4gSOzDuq!FW;kRYaUj*$f0S zSn?65CmqZ$bB%K|dGVu#=(Zv#aJZw|jPaLv`8mPJdC;-5rPz6t|EyMps=lp}RF^&r z{uYw+T;T1VNU)r=8#ZxJoJRXs67~ds}jj^NW!v1 zak7k5ktm&1w$7Rb;_4MC>x&)3g|9Q%33r(CAgo7${INLDEB*T0urtq8wgA)oWqoRpL-B@!@=&CQ_)gLvgzvQ!4 zT*}c+RVdgAk0ra3;bwkJ@~LZoKr$$&cu6HvBgC}}kwHhSOGA8)gx~t#!rvl~sJ_vH z1Ndm3{mG0os?W!lx}t0V|6;5fMRGW(C0$7e}3%`Stx{xqq99#qeMN4&3AEnJvso*ye9jO}PGU3ty`Rth> z!I7I$BidF65dRgI8a0jc4i8cY9Bood7w!6Bj;BxJk=$tolSV}m-~361wA*+nwE4F%w>b{u8*COQ2__vmZ173GMh zK+o#!ADc72Sa2!ptZ_h~+z+8gi-G+9%`{t0oiNry0Ppv%JSHupd(zn$);7)^iZVZV z+flPfv>^MdIs~_7baHi*$>Ur~X$#CSl|*zJvmISQfpE-1JGl`B1-wJ?75KqrD;H(k z7PRd)hoB~d0)1JV>?w8U_tslkH~KU|*ZJ)Ec6UgA7!4mt7ruumx+lTHz{e?U1^7*b zz9i`f#b6O}?z4^nk2WUF?vNi87HMq;B$T7e9coAJsrw>c{>otnV3rQfsID@0{VqSk zERe6r?by`&ZSL(75E~h!J+ZddlRTZm4(&(v?MvNE5b1|;%`EW`L`^)t;UV(N**rni zhLVj7;%VIav}=j2sjLBrt3p|m0_ffcfq7p(Q$7&zih02D$I{;HY<>l!Gqeyz` zMZ%ll!j^CV2^b%ztn=$j;J12!3r8^z&vRTWXjVn<20=*7j%(UVp#P2?&eh8_XFI-V zUzB=(@aeNp+p)huP&F-}W()Swpkpva-fe4`9@;NJ3ImA>Uk?ZgC%>#Yx7xsAn?i6% zPpjo4h7?;7U0Sywwv?DDAhvEoidFX0@VjiW-W?k>I?<36x>0_+bbwFj9)0T98`okZ z1m^MHuvP_;8)cZmP(ELwDjyOox=XnQpg2W94$TMWjE6G9HblCgpNZtvKVsI9zcSUL z2uaggpzQYTq8Q92)PKRJ&xj+8!|`zh=OwUHd!%r!+BUyquTEf%jrlvboJ%jujI>An zS~XClkAG)E5P`4L1~66wH3LRzdS5AQ*^`P2f8*pOd!+7rI=Cakw}J2YuKSg&p`}YB zL`fLX`0}O36sWibuod?PWhYWXs;!ADm3Yb~v!$BVmvf6SO%&bx+<~O!HIxJn(AkC^ zPXRyw@V@*>nU-mq=O$K%=Nj6s9iIe#Ejle5Jz!t1Q!Q-LN-`r`&Qp5q z{+sUpF#!yAdI{e+4t9ClYVit14--Iw4XM=y+Do7w)4~07-|?#6w`8QxmzJl&p{YYj z(h^W6c#mNOS7l&5kjig$b(fs*yfoyXs zK#V>`=M?$4Zz0DavOAjdMd0e>{dJe}&L4X=_Flqz%W<9XvM%AKic6t5XNukajq6mZ zCk?1w)5`S$&~vvNQM09?e8PFZNYuW(1A9~18$KmIbA01Ua!sf>1L8N<;JE}8K$y2x z^o_iF3bnSqp8IIWg)h>`(1rWOb{{XW+Q2LU8Uyz76lvSHU==Ge6|B5q(|a9PFX{pN>K7OFX0v5MG~T?HFX97l8p*`kSek=h+s z61!GNtITowywmj_M|qG&ESTwgEx!Ifcv{Myd_STD$`tX={RGkkNBPh1C)hwOF!zcq zy}_!y;8gEsLPS&S$(=--L*{Ay;#cXqBz^hM4~xlpk9|~f6pljLTS*>wR1j2>l(0H0 zB~)D>QBC*PDtsWhCV7PSq2~dl7gzR*GFyi>8!;b;2#^xYovzRY^A~-Xn2ddOUxWLs zF9b*S;qbyMo8$AZZ$;Y>ljjs_Rj}2KW4~Z}djLF(A$#wW%tIo4PUucJ@+rBntjVz)(v!1ETscb}=Z?9p;USI`ym zTc;GP^w2cXDfLO}cc&C03BPtvS(};JZk=)7J^TOB#LLjFpCkV|@q+m|#qw+B#;>_s zzZUNPTKaS11@o6DUam?p-(O&UzQX`cQJbh3AQ`iAp5B&X0vVG+9IgJgatf7z%}}2H zj_Ly@`8)V@2D|DR96BY+`3CPba|EoP$I%(?X=71(8$WHa|no-oGhTE4BF*c6q%1B9Z0Rb;S3J<9DN_w=j3E zfBnL+ye^5w7f*T_L&{Fn9}R;g^%F7%fKkL^AfkVc00Yg2TO}L^*C8mV+-^Ot^sa|4v^3Nkvj!!in+ERYQ;Rq6A9=12TaHnA@`tcV1bY5?k&Bqq(-%~)Aiaa-7ouk zZ?eBbYZ{P4c1rcC7<{)!w5^)Xbsc-WnFc%xWjr@qk9a-NYAZ4yTcd&Z_%%mVFOJ$= zkt9uksU!B|79}{Wx@(?!SF7F;93NM{p5t+%pHckiq>plV?B6Ou?n@sO&G$YCX`C2@ z9=(9KqCfXvA%0hal;%FwQb=M~9{`4)r^B@WcL$4Kzef;T2}*oB`M;?IS?f2SRLD;~ z*Qu6ITgC1F6}1*nxNcI3yY(w-BjQ#_wIn)nKXU3F9>lxbGJ)lPv-%)t@$&YE2Sra_ z{vc;8rvTr4`uRUrA8tgPE^&GPGWb_Nh#hbrYbXENm-s6cBMD8~Jovxc$rDA(KD+AC z2Cn~NCpUD-3NW<4zM`TcNa1qF6G7hY!=uZ(}D|#*6R)a%tFa0jC^p)%0zVIvn@ZRqugh z*S>LZohL zC$6iqP#wmE)imZUxbsC)Uk`KGMcvusu_P4e<3$fB2sg@Op3;@a{1oUl!c{j8`_M7B zO>hueBC3*yU#R!hEJFjGIQ3xU`kbU;uY!TKTcS&8gj%bg*QN8z!acfnni4Z`^Fy4G z`m%&Jx0@9sycRxfn2s5c>1o zJxu3l$H$f-4=yZZU#1TDK&LLca+wBU8}rz9b$TVG$^ZQmZu}}8Iz6;DZR6$b*QOqu z@~UO1x3ylcs8xM0a$VvcEe1xXt~_?c1vth(n;B|2a^SN-l*&ERK0a)A!RuEo41C7X zQEKslVXnSIoA{~(bELl(oYg`l@oX>3L-B2G4y(fPGXZ1F!TQ=6jaXHOii~c!?k{jg z_N46x4VckJ-gQ9VK4xoLN-_;)e*HZd7|(dBM( z&Q$xxZ{n{1Qa=k@s8El}#ov987a$GB-B!lMNi&WI#CNR8gRO5&6cDLMPjGy{2Y2&O zhmzCgzK{|&SM^ZwWd}6L;1VDQlecJkg@MUw?d;OiF(pQ!0>|0Mi31ZwWhixwjx{+9wqHK`#_^k>NK?lC{+=f2Aks=ZBMkiwpWgBTHKtIZP6xMHski}$0) zPp^K9E*`H6R&-Nbs_Kh#7DMPFqoO2`VcjfG#XbaEjf0LRbi@9DGCN&}76$5*wtv19Nf^eLo{u3YH2m7(UJ zA4Sxf_7lMuCa-}aE)mO{)?S?@GX)0CsyhYpQ40zW-Q0EKcC9?g2E+t0jJp+<5*v3W z<0=SbPQ2JD_q*zsZLg@|(#a9YK$5^pkdFoZ_gHS-k72&KEaB{4@!*!qLV`h$ zAu%!0z@5Uucg}sS***cZMG3NsU&(p+L{!v6ul?k&zHxDdQmx`^Q03#hs_?Z}S7*|1 z6X4w_t61kr_AiPr-=}u>%`r4?+t_`wc}h%#>GTO2%N%+(Q6tB7y@n%ssq}1;8r^r4 zZF1G|d{Hk^rpc%E4v=+u@_jIzNRJ^tFQ3mPX3i?Vef(*hTosbu5mWItI*-*&9Sk7S z)sI~>Mef*_Q|f$6`8M0Olt5{pA%%}4R$Y;L?ACQFNx}eT?|*O7-(pz5Hpd_>j+7)u zru>c2jkk1euD?{%;D*|@xX7e?(t7JLX{w?LU(Boc=-LQN`Kr9#jUI6{RUpqK(sX7h zOkl+Hi2@ULmq`@uV6`Ra;77}v$JB?Pi8A18qD@-*iZi$%)42LXVaOG8v$?V(ilC(d z@9?cR*Ib@1CI9kjhIaj)I9qY2r1L?jn@XI!ssjOF^&#u~aOys`j%S{acChvu6_-gY zqxWm~@K@VC-BjTHUG8}Lx_s?!>895Ny^F_5xEcAcIif>WSuoq?0*p=?_c@Eu-U;=O z&W@82Y_=cHPy{(W3=6JM7gFvQ zdPhE~u<@BwfH(rT*E7+fZ&5BbRVap(A+Z}ekj7H=iei~m`jonfd|*ylBOE2)haBZ} zeug$%^{LiyReuhLMJJhR>KYKsz$tIv()w2XoQ%UYg;phZBN8Uaa4yqE*Tn3@O6GlW z4rs(!%LXW@n@r&K!kjn~7)R)-?_M*t{33jDQ6j(YXYfrxNS-xR3zszUSJ?A3Tw!jV zoQ-eK^QTL%1+Pw@sDd?rG-;b_fC)L=+A0oBWH+*USQ;>|Usgo9kxVty+TF*wIhL>% zsVcCXwev1!ygK~G4PN*fN!3rOU$Fsg@zdL8IDt{4`qsDL` z4o4nHHP6uY?TCJgmfWC1WWA4o(^B>C^AnnBL?u9;<54r5g$vR`22bfg`26ELK@fDX zl#-P2u*3xlbSoO)@}&{`4!0>Jg6;x9g2GoaqdH}ckz@nLc4$vKgSSR47*82!%432D zZsUrC`HRJqms6k4B*bt7Ej~+ET`C(TQib@3YG6?2_$>)Wr-2u{h&Er=rd&zLfq%cD zYj7T9R863SJCa~p5nqbOR75Eyj>^21izy&tkqucWOkmYYe0xBirP#44ZACB-`oCQj(pm)EQAwUnug| z7h141wv8pWutKL@H@Y4iWf7t(EyaGqMwT%OT+h z4bL`b6g?F!I0Oo%v|lt+_|hg0^d)gLWY!%tGdYM>+Y)PUmFF1^rtCIfsbtPc5`4c+ zG2}-vUO`0B!JjybNL$5OV|mZm3zS=d-u{BhmFcJo*so}@q(mz= zDb5gXr9xb2R7idpFclnKNQN1>2lb`6xB!25aWUMdAUAw)5{mrP8+&%hIqF8iT2}Nb znGK8h1l1QH928^3Mb?a=#W*5V!5Q#=F*6?Iw!JX9NTTu?$w^uv^FiU}Ea;cO{g@BwgP5_;@X4D!i2#aE3AbSts7LxDW*!(WFyGY*bN^UCGu zO5_CB%>%H%Sdp2u4_G5hZ?@_%-FWGW|H(LSQD{X_3fNntR{o5_{xg6MjC-hFEj*3v zN)uGfl;Ne1vdh!4#PC!Gj0JN+X)^5dn5XGk#cIDGL#WS@hS~nllJ#>Wph}cbeHj9M zc-;-V>f@HuqTXs#6*%@6($IzTr!6}0;LWIIC~G^#Swo#k&Iw3Axvl2 z%zP|u-hPDfYhQD1U+*C>PivKJ1p;G)DZbUr+acuf<$oR-X;tNvA6VU)f#Ln&pe=-I zWEh?3=S=Tl4GNNx95y1hbVb?LPWVl{gLaYDR@zVxexQ@#E;|7shmk|2E1{N!IH#mz z7llYCWw~Y(t=VG~2-_wxEW>wb2|kb4UC{(N>47|_K>ky;Yw_K}=z{OW>1hQ83kaa& zc-fDA#qLq&(M2l$hHkWeO-@Dtyq_IM7)0?3i1!kp2nT#~r>KH!3>v9Uoh1=(-UCMW zWjun)vA3B|#I}^f-a5hUjUSG(vwQ|}89K%&Mpsf%M$)5I+0+QGKZA^30<^K*H?Y}r z%%)Hv>$4X>AaN=DUjw*PGYTZxOiucnG@pb3{~y}k!Y%5yZPy+e283bg9=eh4m?4Lh zl9mQ(NfAWp4k=0LPU)5sNl_XBX#}LCLy%d6_jA8be9wB{`&sK-e*)XabzQ$XkMr2~ zVfhW?PO?07+!}!PA;H5M0D3pzEiRxa-ibuf7e}k>oRcs#pOJ=>VXQ6x^J~#a3Cbmy zK&4$9twpu;2tW=5s5%7R#Vp-DU`+`d;?~ZJ2AoRp$Fdx`5uqI|%U~9GHcDNVu|r{d zFBc4O4+PM0B{1oJFAEXo&NRy_d(R7d`w2%$=c3kGqCkb^xh(5Ti;_xgJTOBCfYt8=t~d_{x4g3%k$83!;6YE*u}UM6%9iIDmC8bXBF z;SyxhWLpkJ=eoo}J((u&fUXShRxR+{K2&@JiPf@bv4V0-QX$yl|c~Qth!{6P2 zqm}&dt#Qw~?Rn2&9hEX1k{@~b0AnAi6BCJz+@L73ZUmB)%K0MFVxw&1fE6wxl_8(d ziAt$DL(LHGf?bXEn@^#&YB68PAekf#60S}oqbIT~hhIOxwvfV&q)$vBDy`?RI0ICI zveKUo*A!9Q-i$r#c_W<9hy>|=JO^Y_@Nx{xyL=f3{TlboW7p?|Ju84<#Bw1#>Vi?M zlaobS9VH<&lh&&u&WK!Ej$j6#Bz{YsB(ai#55W6H<6PKoTYk z6l!&E1oDvvIknED-#nf&pdrC!lmTvV=LyG1sdHFP;#Wf@9uZNM%E}nNn|V-+(cG_V z=7_5oWnx&AQuMvr`zI-am(po*R^E+AW&()$fp%YsqY@%@rirU5T;HExpT>x>T`??u zUGP$!R5@4ksXDOIRd(-)B`Wsgpd`bB0GE?k!&dDqLU*n_i(;R*9G_6Lt2=uWY(cnL z2~HADd^g`#MfjwF%|7YDo^R#1_r(JfT=|U)gYW9jGI$@a_MhR>~28YRYwQSIA^Rot}K~hojo?WTOvl|BZen3J41QbYlOg$)D zcail?GEP#ghx>4FmRdW*xWelbIhR}+Rvn7^o1xXX) zfDCewPbwmSsZMg+fCnDilRG!Cowx+TfoK>r!X4|klRmBMx)aybu4mHjVAZlKC`jeM z+$qi8Dev5=T-vF=-KnA7t&`quFx_o>x!aPx+t#_;v9#NHyW35>*DJl(XS&z_a&Itu zZ@6>s)z+r2T`{fU><3cK( z#77*0=#IcLN5p1Fr2a?bIY*RTN7Tzlw1^`J-7$mAF%yD$@8?6Jh@o(VP?Ut`o`S6KTYW^+8rT>+!c`vvDuL0($f`561oc+I_-~To5 z#XrvPkyN7pwt@0{WcauFJ+guF$H?#xD$yU-=D*MHN81|zaej~V!T!tqKIx81gq+`x z-K~({HBkOeCAvd;{n~b4A-xys+91)p`F*K{1;S~YUhmeAZB6zZ`*bDZgEES|C%twdAnLjmbv;HU zR$ey}a}_%QU2r(n>=hJAC3;4LXTPB;2~6HdAWxy!1*<74>n3OqljXvG@hPmldRUhl z5{kuqIT`)vr5&RtQhu@W8ZGOKE~;wz94)K+j3F3_NiPHz-z- z<9lK9roC!W@Qwk&Zz@p<(XDp;{oIuQ+}iwi?}eV@{=e~F{6D4={nZA_|CzPf;XiGl z{1t2S?qVM7J(;c~Y=9uS13Drzc5@Prh5onr4F3)amJYB&<^6s9X#RqZ88(mm{}UAK z5ABTIq{A;(*QEJ7Y5K42r@0}mcZ4J3dYa!x3gK3pe>r|jtqQ{%NGMpedj8*}>9p^N zvA<82A_+(Ta{MTkNB{Zw2@*k&$FJ;o6T=vm!;?&WR+#eE5sT*qlBfq4Ye%31Iy-!l z+dm^dRc9Apo;S=@c%yZ7{z?KeCBCxT?L^GX{9?U}&+Jyz!Gqo_LG#GP)!_P~aO6)b z{6h0k^7E$_VbuA;3gMH=*p{k4V(r!<*)W+cqqy#L%x)x@>oJ1)1|v|X=@uPt@$D~<()1oNWgFGvM`hnq!j7ILCS6byv!rqikuyCnibv|0 zsjCNB)QCi(VP;RB>a7Jlf+Pn-T;WVT&a(Z5%1DJ3yBd&-FUc04A0X^7ofW4D9Ovfe zP8dtW{FPo-h=hWbS)+mqzn9>RD|4u$WdDp$E$?iAmR9v6j5Jf~enY|jNjp=6)G_bX zPBnTk)_wfj@pFD~h9@}DfYi=#$1ObFt*X|0`GYd zmMvvgq@&kX{OCj=bbUP1?rpi-S ziKw9gs?PdCb4npc!RtSjrvGyRY`jx7ek}s);$S`Yg0vc%B%$fE@&8zw{@)hBT4H|u z=yLjXo%7#oXa3^?7+VeC=OIK!5Dvn`<(Egn{PSw~8!yo1Ki~!Ou{?{13=PKrLpO97 z2|wGE!%=qK`FI5l8qN8yWF0QD#>K7>6;iCNlC7rlXR_X=t@4>ky&0SM+FVs9+vLxe znO;?zrrq9rQQh`M?;qu^fWV#Px=^lkb!%GcmjNyIcd{Df%j{$SzAvVTDesSDJv@ln zAeFfHy|HlkA6J72mP?sL%{_MhLZ@|&H zDZ_Y@=`y{8;{Bte;2cq?ahI$Udi#DTqhM8jXHBub`Dsy)^LnH`$z7cG9Wq(}nF_GT zgaZOhOmRXCT)s9=Mg`+fG*eS(l##9=U*de zNB}%#6q=5D_9d%DIf~#$Ha=0AC6bQ4>^odDQtz(ZMV&4H_o+e!NpETPsC-I*$my&91nj2Tih74~@BMdt)S$_V)BST)-B z9ri}mc}vRh{lE|0;cvmntD*N^gt1?V?`s|J2AkHsAnf$35t)-6qqo(UouU<9-RG(Y zT>!+)dfGmI18o`8y;I`0eI_3!*p%YOGAV@Sjm@ja%DFbEs_ayU16)3M{Ay^@u2is_ z*9{8qy=5izhE{f% zaXVsrjm25!i)HnUi@HjSBWpG2a|~nkGbK#v55+L!#K1!LH1FA{qL_4(X>)Mk3CzHEd8GZ> zWnd~ts&}=Gbj?|6$4RH@E7ruBO*>#2mdklG)$+o^z`~Xadxn*1lsgWa=1gRIutwWq zFWIw|?lW#5=MRV#eE-3cmib5w5f(=5P|xsqJ$lUhB*zq24c2)Q%z?OtY{5^TdQfTX zDN5Fty?!bPrz8D#@3|zS_7Zx~ec#qnnl47j*q6z7fovs^u>6FcKKJ)G9|zs|C2>Fq zuwp(|Vjym~m?ecqNFUKdHZJXzptQti^?FmIOvY==FAVg#S!yG=pvkK(y2WYx)O~{8 z!P+(0sPrA1|JeG#6J?1x9T^1`9RD%+j=7^L~-M8&&EeQsac~LObpg08aIXC@` zT?vEQ7Ei9n0y#)pt}mbH13Cy+*l_qg^7tH3zkh=AP7?J(6;Q2)sZJ7GyS0&?LHa@} zheF;!cF&Vc)5t8SZ5b~!9Ewwl2F=k}OD^Q&cgfw*?KIsMwA4G+#uF=sB?lwYYAuRs z0EKDM!@W7Y9QZ0q&jUC`-9S7}-H`eaBCb&!)kiKvtZ`AMFUHW-qFxXd%rrdC_f_l) zsbM z02;)aN~Hn!IVjI;8aM3ujH&OHYZZY7)0HJ(2st_61eQQ4XQHy1xl}!qdpD?=l|t;R zAw|d_R}@qZyse0(~FMQ?Eo5(wtlljW4$)Ji~(a zILz`7gW-XiHg!r=!aBo===PZz3G|nzK9t$TC9Np%c>((paV$du<;(o^7k#MgKTx@3 z9tlNc^*YwLx>fSB98tnP$U)yWsEVbJTKgd7z!8H&D*d>)&xNc$-WJ(glHih@iz|b> zDO(g*6`Z_F+usBuhxu9B+JLRzC7W0;0gn@+a$6;;1-y_R)S+~_K_3lsZZ*mH9i!u) zECOBJTjphlu$ztQ%k|5TxokB738qsUQ!Y{{=p{CQ|0n%ra%sD-hF+mUs2J~_N$7Y zDT;=FeTNcvw*)%%iv>Fu#y$GNz)Jv14R1=YR#yXU)Rggtis7;28E%svMd|Es>rJ`O zf7*z_XrX^ia~I|DL+4WlV7lkhKP_XL!eGuw+mNj7OJy31YOHkjYJNWt>I^mc zNZow6#gB0~-A_cLla&;Jl~^QO@Ay!5_&Q)TjIvq|Bl|&32%P&Ya;mJl+{^2%mn58T zZmsxJrO-e_kUUw`7!83%!;3UV|f(lL^$RjjXDjF7%{7N;ZSf(xq~PdtSI5$7jD=e3-gD#5+0W&#cAa; zB5pYA0mkXQ;>)e7C+k_+oM8}j)*>tQCI%9(34;gYGX`)54BinISbtF48~;wiEr#QL zC`8Rtmr2tPr$Lij@zIwj8;p!1+b}mpnrx7Y6*dXGfm9qJ?4=Uv5{E`kv&wOuylfA8 zngEB2sPnV%t!6Ur@W5y~Z}**&kNA0DiBtydP2O2rlY@TIII4y1dcTz*>Wh|qfANBv zv;cr)h3L{1lhsieU567pcI`j{AqkPMPJ8pWu^<(Muvm-Zmunm$D8IGr*h7Z3x5HUa zpF^osv`jC4Y$sDQGa?gTC4P{O+KHJ9iJT;u+1_K z1S`hRI34Brp%j=Q$D4x}fE-1_m0rFTR8sU_J5vFcQX6qM#Q>p1^{8`bf0Bl{CrHx` zgz0VdNKtvLP#Lx73CZ||YRn+F9>A1K5?*@`g8IbKudo3hyqun{7J z=mv%q+lJ5LH+Hkgbpw!7_YqM5u4WW!9!7B~=~IS~FD;5>Zlc(MJTS1J6uB)ykM}Yu z@34HR%%HhdOXy9$mdLuIW22Zm3>X3ycIL&%x{S<9do}%qRJB&MIo!Y8j_{f6XuJV?7a^~!-h1h*b`YRiF+ z!z$PtO&+MIS14#C#P1puMgW5}BCtd7Y6ZIU{p}gaFbmbgABqz*cxn)0(6>@(K@*J# zN%k!4eS;r0*9H_}xNUklY|922Pk@u^k)|4dw|uSxD5&`mfGj$7@umQSDE2(U;tfE| za7&d#J2A9J1aO)5O))Dk_P{2g19M#eAsUClWIa9ur8Lvodg`(~jiWFLl*ccn_&CNf zxh%fn+3{I&ezwOwi)Sbg z&ARB#V93opQzrJU%^-d+Yd_(NjNDFil9!J|4C|N^OW?+H4^+ay`-!=J9%=bR28;9w zIG0&VYsS$E#+(x}&SYdKOmCeJB917^vGc=lgYrq0_u%`{Aq36@nw{`{y+%**HZ4 zD6jX2M0$K2-O6nh5y?S2dPb3tgX;Lar!c`TzSNCuic^M!5-=t1HG;}|XLj-OTcYv; zaZNu3%v9yl`!JwSF!ybVXW>KnlLV?XBDvWJNiTX*kUYm}I-&VfwTMtoQZiQYIS`b? z!Bs3+e4F?Chmw~`CBbqflTjt-@g)L`54v2VE5(Ttzc~U@@(YuwXOI>qX8KPPP{n%n zf&MD)Ji3mZECLl~H_tL`zRDp_>(wNp&ty5eR^@=_<*1GXw-C@pE~olg#o`WODu2<* zF?(fE8g2`}0xG?_LasMIiw&{t&=nYu!k26igy+LpjFN)pmhyAH096ZD8eaT_g9H#y z?z2O9tj*nqu%ygJ{z|eat#Ocw+@S`T+w)GC$8A^GJm&YBt5q0(ASo}6*Pk9zO5`b6 zf<<4><^VDu(wdp3`CMEN)$)EBd_OQhACQI~Wg~~O9nt;XWlLE^)|-Y$i!usL74J1+ z+G^sHD57j5Dg6a;jM_4O0q$2*vgbRETt`)?-`KU-RZg1}GO?sR^g}xb+w~J_H>)bB$H79I*h~h2W?Q*J7q>j$<#F3*T(H+gxg`}_ zQ-#c7p$Lv6ec=Qn$Bdn;U;*DaqxNO!)}$g&3Yi0i1G6ysa$ika@b&=Ikbxu!s+)^mxXIeMLZJI$1T6uj=IO9t4-Hcc zCsza+7C%e-tZt-}sfKmKCrQu{C72;2oB$Auk_*Vw{v??IFghf7gKdefHEbW@P7sf= z__e(L+L2J=LtHV9Kxr&c7<|uw*qn=JRiQ6A1N;R=b>pLp4k&_T7Q|rmnVS#XY4}XY zn|i5&89hn<*MNXW zA}#ZY_2yTKu_q3|ZO>yvN9o21LS;W+slLxm!~yRGG#Ct_cSx~3k}GGvo(zrhCT?+R zIcAI{00B&(F;;wURk?{ThMWU3SWwg~*-w(>K1|}75L@P{!5$fM_W)}9aE{YFg-vG8 zBhAkVV_0LvmUd10CkI|Gjuc?e6hNqub9WUBn5MR;knzL)ZcL8?J~N|;(HoZdUqq@9 zQ1F~u#m_m|Nj?V~J*Qt08#Resq1+4SdH&UD0LKE+uOu-oa^C5Lpx!znevYR>Uz*;5 zpDjkb{{?ojBc-$Eq}i%}FITN0$3W7TIB<`+|Iwn;q?)=w+woXrAqPEhHRn-OagJE}!r%V(FZQBH*LH-iCE%pzff7V|tG$bSUZ8ZyED| zjA-CtA!NlEq=}~jtb|N|Fo8N-YC2Ox)#aZfg&To?6>7oD!@nZ_Z`j~^(AL*hVQS2#HfnJtS0F0ns3 zhwM>bW2@CVSJAyAhULkFn>1B-rtGEVx04@O=#Ci?$Hv>ed5Ah0*FA=fr8%s;DPFUK zJ}lOhr|>A9{`>5r=!5KQ!GpL=dNXufWR|U{yJohX0wK z*%PzlsD03wso6Q@Dp6A+MB5w};d1WsmXNZY>(#GwPqT$u(~D=H%S3Z7{FX0XA}#{x zE`ww)L(DG2{4XPNE~C0GW0o)D5SQ_ESBWxL$!1q6{#R)^R~cPbZE}QQ^9oE)&b*`Yi#!*Wz_I-A%8|&0i{a zdHlt47XcOQ*Y(AZ#?|S+TJBuYif8TKWa}JA)X#Q5JKt?pbAzJ}xxU~OYZ_Dpe#Xl#cMlOjH|0bgGza1HEzZg#F z3@%89_*qc|=|mwD(j;7DLh9i{C`#W7V;`@VaVn822*T=X|Hp)M8EHqpI5b0zd_X77 zzS_i;eM?c)iJZftri2h{W7t7F57_mG1Mw!B&5#WzHhMd2t}T@yB4k3U2y<%r5`5=v zd3F+esYkV8ft=K=Rz1@WXKrIFuw5QCAa!M!vm=ZXkNaTtik%&$&>VvQM?_<-fyecI zLv?aBc^OJBZO^QaVOqv)TS>0_EyX;HeKYAG#(q56R{B&GW;PMBnqd!|W{~yhN0ur$ z6%2_p$Rh(w%-SiEzvYC`VmwAlk0@aIr*5qCQZb72$zF+iDzBqbvP&NSk&x#0lWafA z42ybPR$N@ZgBFLcyIEd?Wb`?ju;F{r$;o~yM>6`vL+synFHM`(^x+F48GR%adRZv9 zQCzaY(wy8%pN_@5(NNW%6V_Yimvd`OllJXbuYdC0ZYCn6*Ub8sAI*bu(BB^4c04mO zhI+nvl!`yY(Hl7Ywn6Qd7n&-s(&#oozhC>HnW zm^_*D={Wq~OOL#qtL6nXXU#;uHA2mkq{hBfX45o5?NZ-08ie;t#edbzlDJqzoy)p_ z`F6Rg>n*>;;<;S;tBk&XNl4`j)Z_PRn#0cb8%u;aVC@7`&kwq>?%y2#oza(p_Nl|R zT>%kr@|lPP^tYT8X@X$_WFb2>NLK_l0)YD$a#A6e|F&lM@7EMqnW2B-5C%E3HdimU zKT}Wa#a^+f=(szCH%DZ5%_af$Tx88KC5G<);+keuuXZBR1k=%|COeFN;eNNKpo5{p zr7HAiPO8`*n436Vk6cr@r-SliS%wjfRRV+UU=`VHGW$eryBwICshYzhA^x{D1*r=3 z-9_Y@!YfYS8~Kl$lNG<$6vDEXN1hnH?EH0oX}B=*>d~bF;syg*GlT}t>VVKU&-H`w zgd>uOV^Fps+RDTMDTYY|1tqJ$J|O=-DN1Sm-2ui#7? zh!sX?!Dz}4v^H0e`h;br=IkWj9S2{!ut-$v*E5q76-MTy9Nfy^UK`l@B=Co$(Q=aI0@L#kZTIbFNLj{b(*-6 z?NDs+jk@#W?$#7^m9;gqhDlWHGt69ezL(^NIp~(;r#KKjDn7POgH;qe5EuUjWj>Gp z)HVZeD&F`EeR+_v`}S!gaIdC#Q4U!%bPL@3TTc3u7zOr0!LdrYu}!dBw$db8JASF0 zsT)cYCNcS{x>tM>ggOllZ55;e{^*dtI*!ji-HcA|`1w@Oxr^8a_fQRik6dBJoMoDB zxM4wpGUZl*Zcm8nr(8dfSD?H6BPjDThuhyknMq!5BOD7ApfX;9m?w&zGkb@lWJ8tp z@69@IPR6i>RQ~x8Iw#a<>;IQLNh!*8);yg1{EKy}^ZA@z$vcu!hvxnB1=j)Yi?5#l z6DU)|CaaVba0T6=CAr!_wcxperg~_!ZpEQte&0q*z<=HSDy6y&R$4$SZm!tHbG`R} z1Ik?dART|Tv8BKD^ZSBQBlHIu$p89u_6g$G<#DpFiU$#!jt(a(1v^xa}y`HKu@i3qBw|e-!uZV*%~O;DGecqgMfVg%B*| zL0QV<_z1N^2C|_+Me*Z=_?SW_R^=fTqvOQ1kA*BELqi(A{3d94-(d3gAZ^mVWY>TE zP5=R30RmCQ|MDi4oNO}WUs%4w4Q%wvsF}*>iEoDf;ffl}5GsPta?YKuh>^F?FaW}FoRXV;Bbh3L_zC3?Z z=-8uI&z81HmQ_`ALTkFZoG3r)ew8`wMWp9Z~CZg=YYMnlhUg7N|igvTtf*%%DXyf}P~_IAIiXgXpPu@OUYL zn%2$xqD{@;-gwU7B&xenpc{es%*RP=_u9ag5z}O6b;OIY-)_o=$Tf z^<{n|{$g$s)QZ!N_S)VI#wSbsZBW;N)6n9;Md4_eMQY$!MHnOX?F&(yLHb833i{4T zE=}L-V_X#HSYoV{6BuK3U4nLB-*oPsDu}?|98D^X3L7}&*UbSt3jw&*Uf5?H#Yq&2 zy{~=9G{mZtjdhfOuXG3Y<83py;SeWxrNRbJjWdKIaG=Y_W)sb1ihC?Ngm&W-^uF-z zmiG2THo?p^hCPR+G{y~6dsMGjqeis6QsQBq$Jy4l>cRHboX*J;n7h@f$53|TGzv0b zO3TvgWSNCEjj*bzm%>R71R*>NWtnkT<+$wk+B}Q1!b^`2X=kg{ZICN-uJayd{b+q| zTBH@$F^L8Ku>*q#KVxy2|Kg3#)yG zR8bDba-8%K+uB+LP!7%&cVp20tOBU4O1A0GlVellT;~v0Qf&28sFp(>jr7y-}&bW4qe_ic720R5PHV(G78z zTtqueOR77)$Is$m@VtRJ_wuaL{q#Kp3W3;Lf1wcL!0#E;+wNJ=I8L`@zxlZ~I7r*? zK@2F6k?K`af1KMl6li=mQqL^0PFP2i%ud4n{fsl(l~7`Wm6i-+6GB2T6b0}e)r!xQ)O^uS z8|;Z$0BMIwGHXKWKMqL{Ue+uH5X#0)uy$h_%CNg}7I75mpxz>R@_c>51Q7}JxR#Z- z%2W1XL$lw|kEQT6<$=H!R^>FycLK+6wGCg`RI1rg%8&AwN4t{*^c%%j6MHH)4ZcP{ z_|AOtktkv;0!U5Us@IL58VA+;hL zo_xfrN7r(koFyU!XPZmwMn|AqRN>2NXv=3*8dz|sgnk^tg=Lmbo7z^!NSXNH*X6(I z3$4ocqkL6*Lbc%ckRAuGJ4fDw&d;*xHO5huRO#vGkI9KG(JBY9nqmErFQ^=xzVX(2 z@c1v_wSMe2dJ$QMTkUOlATz=!j#C zvgo23C_}!0v#?fsF**3Zh|#*)=MPsABNR1QYpcRGLyN;HD~o;^kOXk4RS}AzGvj=V z!Xr%y@KyI#yH9G}MO4PEkz7|247SS%)Xi*N%gFjD*$>eys`X>j84F=k5H=msFSKQ9 z;@V+qHKB-q(s|Bb4(>yc(7?2&TC6IG)#;Wy_W_CUMHkMG! zTkdIR%{MpEd1gss_&OQ{7qNB_p6eri!=N3g>+uqirp;O1zYVpruWGV?Ql3~yAu1fJ zUS?JKAxv`eHTw{MQGmc3oD=1k7S`8VeK=%zd-aAN64jJZYRVkH<|y9Z7>*GbOg;#s zvqTkAXmFBK9!^vQ0P+@IoHPlt%Ex=6h}e&45F<{JNV6I-Q{+Wp4itQN*4@lcEsULO z)`Z;cDN7&k$t#$V?+O}-a<)D!t(~Z1KA|R~U-=1c>2!zPu$ZVlCWRY-c5PHoq9p1B zBKSlSy9IgRz<5Mafsd&YXqlF}#Wq;vedB3G^u0NDG4v^*KAXk0O>=O1Ib&4&yv}eu34fpMI^Msv(P*e?|x2cB#^my`ki{9j+ z-li-;vMl2ym-U1?;h+yNzT5#2M!rMRER}ILFjkLdQtz?xm@dKCvmz*_e9emm?-$i% z0nbrHjI|y=RhIfll2_RKzx|%<8DCxU51B zm*M`nyy!nK0QrxDd{$}C1;zc785i<6D6}MAyawyKODuR=8Ki2A3qLC%hPW_78plM1 zgDeZjbb0d`3F@^x1r3(5LiNYBCZ>SeU}wDvUNRK!MSc@DLdlg9&H!dI>Odk6EYcV@ zixz~3B2q=KD9X&o??B@fseBk>XdZ6g1G(lCjzJ?$Iu6Q{Bm0`?L>Ugo2vy*EEn=xd zGv(&F!xu~=5a2d9JJ(RZ&(&JYQ> zo;;M~hh{%?E`$@lC|0Aq!Z6@rhx@D%47PV2gkSk&WKj*SRc)RNQFT~0fEgBnYeMkvne3YtS(P8(=?x{ zla+u|U4k@`;90QsSp-zQh>|hfqMw2*gJVKtM4) zzR{8Q2|eW3&fbJIt+;niyBnSn{31=%sl`ZrpWr7-%HqzU)SzrG_!3H{peI09CQ6jV zcVA>16qNihM(z>O7v@jL43D41skuv2_VU=b(4(Ia-0~uIQLclf$#S)HOgOJ%-Yw9x!Vxl#c`eUk_1OXi(PlH(@-blCCtVBBsY;lHOFV>mC-{aR4L0#$Tjk5mb zJ_Jn=!xBRhUol=Oy~w%1MD~2zC?+m6dYs}Oi(-3lf)BSDyYoG*c%T*w4x(E?SC=u` zJ6n;Q`MXc{PGt50j!AIHt06IBqGKduBUxM1bCMlWZ)i3%E;B%$s9+1a7YS-FCR|M+ z+8jy+yid@WdqB{Z(4mux7{lxo$uUvpsjm}GppOF7U>wPT1Vq^etvQ~t=P(RdkyDJ0+A>>?CE|S;E zQT)ylAV79C7xqF(b%gwx(OjZy6j(GB&<&HVFf8qtOT`+G#at!WMI4uC)$%=WWx*(N zRzm^&U<2(#w5UjB0#mbwN(+lp{6w@g`NRo}#4{f3luE-~kn1Qn2^3;OEZwJk-%zNV z2uXjHl{1esgO!sze^w|M^7b0ZcD~MR8zvel<0&x$#T!YzZld26Azev~g;-SHM=K{r zL3ajJZuV9!{j91@EF0h;Ruf|`a$rnI5RfmwKZ}w784mJQDtZD0+vJ67X}g~3q@JOv zVu|QqBOgPRjKcKf^^COOx(A^7K-9I=l;L!J{#c2JH8^fs^jf}bBEMBxP@G*R1=Kb1 ze)N#<*vK!fbZz%KYY+yQirAt}H(S`Kq*=cym)CSwe+n_~#kpI@dKBWu3c6(l;I4R| zO#*bJ&aq^3*Z-U2+&34+5%4kDlIa z`Kuz6I`a_MV(X-5APPW0{%MGIMFB)b>|%(g3Wo+imC>bu_ssK=-A|%yAkz^gk(&sB zSybiBmFXr8U<44w3dHcBDhZk3a<8TN`CaVtxDoe=IrMqP_7>4CD+o0gfWnLE;!Z>e zKrfYONg5&Y*O9@}ihPtLP$BzTx7A?=O?ONXlylw2-17o84;>f)=sXnGpl3RV)^u|c zEB10>3x}!ILMF(~CFq&nq$>6Y6^>pLB6VWeh(i&h8jf}LrbS$$Zz>5p?b61r?eeJR zPpuh58yR#ClKAPA zdOoYQyTp5&;cCTc)p13(=>%4~%J*!r+NVl=64XKp?`6U;NV$upV@0U;w;^ZIeR_M8 zI)-1N^)@l8;d~r; z-rAFb%6*37%nct1iXnf`r`?fc%pn(PiO|6<3uQvX=F{gNO#Dh_p(Wz4({9!z{$vh+ z!=^%!m`2^}Ep5W7Y)FEvc-=5THxRbXQK?oZ%8;=S87O%(B2ydF?LeW< zUwR7>uH+~-GV4 z+2`O{5ZF>oaJ>VIM^0ezrD7(;mmwVJQfDVbxxoi8Ad}Q*GI~idnko7Oz(^@L6GXGi zHKpRLSqPY9hGB{qjHq6p@-XeL)EJ;i(dbGf$U$OjlV;&3wF^ zb{Y*z59~Q*9Cqh!_n?{GiGF)I4}AD_#&6U_EoCU6ig;=RVkZ2h0{o>wfbzw=FJKrG zUIaVy8;W<|>ErGV#Jrfx5Fqp|bv~ZP?}GNH(aaOT(i>044X1%mxaP}g!2TzxgGl5j z;f3DV=b$~3W~YGnSzm)oCVcSbht(G<7)FS0 zzJ9(ZqO897C2Mj1-Qw59#U;eA#TA;RHL0bIM@yS8mbQ_ys&`9!i~mkmCFK!0De!AQ z)?sz|VyKtrdO1ye1+#OR*keM9^c~g=smACEzNrgK)r$N26lwMdbGsc)`G%w+sw;%G;p9h~IoS}{jnbDw zP~N6(nmdz=EodZ4om6kKBpZTgfPU^x?&75gJ|YOYOiMfBny6&#?Mb$mqfs8i9J!9n zez|)LW4ox^X+I!=<4||sb|C0wUniggNhMz?JqnIYzFyTI!)G!mlonA1CLTVpZsnsx z@B4ZzY}hD17s!s)&c`T40rWbM0rw4Ha1qL;^h`n)Zk3EDAHV3OQ;Sr8l7P@xcJj4ox97!Lc&!1vmuLJ zi}w<&RH`l!XV_Y2dN~m7C)r!)M+8Tw76|%ea{bGB7W4Z&_OA}|Ue=L!oVy_yO`lAZ zU*(U7pPTt#tQ?)odDQW$?-;y0#$3G!cuVQ?797-dnQM{r@SrZ~zRYX?E3~D{_^zw= zs>?TY-}Iz+@UN~Q6II(_ef-t8lu_p0^fQGBTJI{lG`H`>-%0XJ#4>EgG7vwTYm*ph z9Dd>prv>dH641#QDENA1uXnCG{Hd-fA@RZN%H}z%)#1>7+UuTV$$KOSMBDY~GG!;i zm`|wkNeMM1P$gW(omO%F^;J=w|DwVA^C_Pb>kdh@uTOjz&HoP z&YkA2&sOMqlF>0ZoLaSu)Dr(1jFX|r=T8`?;}q$q6pMckEV>Y0Ssd2F8d==?eY|q_L^f*V2xQRtDN;NxtW~6X(#NMnk3;*l~XC)CM`JVsW z4;Gzn?@tddGoc#n~+G)MSxM4s}wevkcLvdNQ@A#fiY9wH5OV2Z)j zaMniDwFsuA8DJoD@f}jI{M0O(x1Vi2COcheJ+?P5Vm(fBr^xiKplI#g)RQtB|GS{5 zCj5OPNmG%%$i_$ zo&Ig`ru{$ngUuSeHdCBGiCJX(^ZeZYm-M@4fam#Y{3n;|{gy2at^GCx@t^rNvg}6) zhzEqC?)~K@6FGi0Ud>);B7;u3$xvOZ#JzAM*qvIdLqmN8D@f_+=6Q%zp zf*gBea2F?el}x`i|4r_6dQb#z0)9O;C(_SSAN|{siB8c*GJpI&3%`G}(^1qPN-scqT32?c=6=Tt(WJqSN2x&Zf!> zSy^g(qSt2><{=BGU(!!b1#zbG=r? zl7CafghlvX>+6sprWCt13r136eXwir!^zgCi}DkZU5Q`r1d$+ezqUm+!po#+=LW zuP^#yZRL*xM28t!%!dV_{W=+uL9hvOlmO4j_nN-4C~c5t*64%G#9?CdPc9a6)LS6i^&>YIScqF6t;?#;j7?D(O*%hQO2^Oxj?Sbn34NpPt=`Q-j>U^Y#y z*KVWe9NW$zp&pFRDmSIb#r-j&w~<&c_G8D;lJT7E75>VXw|Lje-IJyrHB5iWEB~2a>r>`_9^PtL7`T zKa1b_N|nCe%6_8Jp=ytzp=njvprt}lBuen>RPF(st6Fe=TP4=5O`!EcVHaME?w?0i zlDWSLSMREBf$z2Ss<`#1oUfOrr>oj+8@#}%mXH6RL}A5x1GE{VRO$!U_nn5(dDy&7c> z%T6}m?~BckqkUD zKea4f34fbJ_!u(!9Du;&4^5PW;@~JlDZGvc8GvDUZvZh*4&_Rd+~7grXdMZDl0j`A zg5WBY**0=ZSg1+3mx^XLCB0Y!xs+>IRfJAHOB0K6{6um$6ZWvA5^ZqhCy2=kKw+jd z04FyAE?fDUcxO|2Sz*_vK-QSI`KnWwwD8_0jEXGfYLJ|e9h<;4KK0n6Oh8KmqH)3~ zvUMeW)wl|&eg>rqV@D*|=8wb2JvB#B(@5FWagt4@SfnB^RA|L*A!F^2*D&4HY_vmS zRp2V<+VbFEc=vSX95bOT5%1RoJ@eQ`(^9)hGOQ?*5{N7qsDd^7S)?${Qh$zCRZ?)< z+te!`tJ*{Ik{aJgnS1dt!#NolMs7s0^^9TB2`!}B@>+X-ox~ZM&24<0n%k1-t*o$q zd%{oX5R{R56@Brf;p#>!8^4XU!EZ~=()ajI4YNFi#B%MnOqD0CI^WYNtkG)64*J4Fxm_FBw>z!p^T0W= zks(Pp%CfP$fCaH1>A3rxwNJi`i3`Qtu=GWa!}a-e;Js4FduRBl_z6|x%45!{LdG|W z6)ajm-D`SAtJ%@?`}@f&3%ckPv~?+Zilm&~_sL_?^W!zp0Vpl=u}`uiGQ975oKz zL*ukOaV~?!;xQrb4^Bb+nN;o(8>^I#?5^wb3nywf#uvB3YS6-+lBv^% z;z)PACw_&osd$B|M_YB5S#Wd>@F)(^cUX|cg9THrdY;(`A_7nVD*9mnN=W*Uw}Z-~ zS6hlAK~9L5m^iW6TI7>KH%%H2^g}T%TY`PZDmbVRfefsD#@Ry*uR=j`#mk@>PAYal zk8)a^yLY#qt0geVGyp&f-PYh_!`{f;j-&D;9OeE1a~RjECdObzOAJgQFzAIgtb8}h zEPjEH{DZr1Mu*qt=?ierxhLzp@dG(B3)2E}ok#bKQ!nWWB;Y5YX42@i`Szu`&yIM{ zJB@1c@w8l;TFBm;Mt+rrNcesv?Q_UB(+Gj}ewyv9X_3Akygh+#4iylHN5PJ{UJfU$ zmHR|I6XqY@mQBh$vN1`3BB4=UQ{lwa=dW+h>2@Isdu%HQteH-0yQg z4=a~j7hZuHjg2DESuu1Dzx%S7KB4rUomZA*&4jx+U?bh=HT|jFX6E*mMi-&UP(HSo z^Dst$&IxnDe0c;HeXoPp)M?N{i1+hQtDxLlr_|Z{%q@Zbw42&2x8|=!ie}}9cQYzi zk-W9TLeGTuT=U^*uXO6NCVHUvy`XexHp2xIF0Hm>5(YWnTzy&cXazCC7E<;g2>5v5 zgHsRd@`33OL&bZO#-{v>NulRmZZHn57!4k<-)UaL{w_Y}RJ2$^n0 znd?N>QKB?0Syn5|4UI1c7f0(=l0e`ML^_O`Yj`pUv-ibp`1$*7#RRz9jXgmWH%Eu` z;~jOdWnBl$90E8TyBN-uX6{(`<)NXC>RR$xkvk$?(fgDxs{&a2)5sFB8h` zl|hI`81o7M0%KDdV61&aR!@T_mPyDvvj-xeA!5A3KBy_ zVz4MUZ?=t9w)zMFYa~5)63A#dbU+TvMTP`_#jj*WdT%oCWCQ6dXqIQj`77wRvsW>G z8CR@wH6ya&4z3PR_Btc9YAVYQdsKlomV6wG_Q%B&bi z^hG{MeHR>JgtZF2_GZ_LrGZ!f#>O>_kuR@I;gS`L=vTmNxbTbe^>*2$C1loG?sZAt zTnrfo>qcM*h;3!6dLs(Ph2ILLqB^OJQ#jfL70XqG*JJZiEMf~Q;>auF>MYtnRdisx zh`?3Mr&26nT`Uwg1K`b(R`Tl^SlB8gZ4GsFaymmsy0BS>}~lcb3^smDz2V*>jaUs+2oh zm%E0QyXTdAc9wfjmHTd&`*BqSs8j@5R|JPugydC(byi%Ms<^aWLFTHARH=-zu8aw* zjLWM`=&Ve-K2>>jyOP3Hm8MdaVO^CKR+W=imDgESFjZB!T}9=pE>@{7wXQA?tFHWj zEy@80kgMyrs~fm#npA39tZQgtHSKvdot-terfR^;qb{!69+lc&>)Hn@Rih!bgL!2G zowbj*Ylpe&o~YD~S=Wt+)lKBpP32|ObnaaqO>@=1QK_G`uAdL9U(hR$OUs$br& zUr{;vi0ekyKdaNgOfoA_1e8EU{&psr^w;(6!Lc0Yzo3!5>61U8k-;>^-=~6XpTx$BP7Mwo$PRW>$suZ3of28_p`IQNT?x3OVT-F;fll%#3 z|Fb&nd9?WL&U3RpH$XIU+GSZ_3={*-#VU&B=k!T1nJKj$J~ofN6fj1x2e&9QW;&9r)P75Kd@Mmv~w$om%}>e*i7>hMkv*^ zu#w7`)4PM!H7$xTuevAEQyJy$8z9T*LWnOl^d4ochwI3+TB#6yN5<3ql_7X z-nYIeHXjv#83Puye1ES8b~kDFd3P?+7Jp8koNc=J*z42nt$!5*{!Moiqi}^^o%sK9 z`sA-@*KcPKd%2Fll&i|kw11f#R>m$`ed`yeeQ2{Hx-V~(VDj^NjKkJeNlXO zi-~Zfhu`gWl<2zM1=oJ*Phg1pxb*k6u~RADdE;(3zHhuZ|LObYbgcA`tv_`)opVF( ze*1GKnUVV6>TZ&`*c)ENc$4`SXMk3y;=>}Q^Z(2w^ZzlEe0BON;pBcD7P#DfsM+TP z`tCOf2lt{mKR8N}_LdxDcm6n@j& z$A`1_I^VnuL%n_?RejzCrlPsw--ROYbjBB`pOZ;Hk?P@|iaS@(Zacy4pWpUN)6!MO zg;!>WOExdmTSlxcPMi`OczpZj`REEXIEe%nJDr`<%x5=x9iR*0h4JTHKY86TqYpnY6+bMLP<~b}T6n%M%WlRiDNSj8wyFgm$w5lCHpXH4A>)+N*Y;Bd?bYLy;Y3YyV{_YsjZG4zTGeE!xx|b-adKp-BCu+E>ft-lSPR0pHGcQaD!hBkc*I z6?z-}$-ALPkJ7OE!)EDD?N^({dQ6b&Qq$X`!-K?UOa^`)cj}*e9yi(ljSNmpl7EoB~yd7nRW@%5ZN@6CO&Z+9~Up)K3$SEces=8x#9Qa$Id9!>GI?m-@uAeOCUEWqfBm{f+USz&~=f_PsY zwniR+`$Pt5CSSRI_*3%t!4~3$Hk99@-)?>gX;)@#=w;(4rtkK6fVZ2iN9rO4#w+hV z`~h+9^>^ax=t+vCub0{#hbN}u=NeH9I-(3va)D2+3(~*f?T^nXXU0+p8!LIk?uRLP z#(tLrJx5`&KF=hvwOQyv_lhNIPrh#c)b*&dA65#0TwG9v6AI71&)2pQ^G zrWWDtg(3#=^zAY_Vm=+Y8lm&;)jjX~no%P%(g$o$uP_t?g6&XemuXE-ospOmjAvso zBE`gB5z42`kpsKL5-y*{Xjr?y+a0~!8-+UAR-9)E$}f0_m**N3TYC0wR8JGXwYSU0 zG)AR574Ur|)!H8VoVs1&WaG&uiG)R1sTcq|*2bvA89l7mB(%8uyZU^shTH>93rH;Q zuF|(WVGYt36une-i!zdE*&0y7Eclh}^AQ4MfnSSLPxhf>XEJkly5o4)#-Ywb&0fn5 z(W=OJwgE2%A>ErNhm!E8DCC_K#Dj(mDj9{ zszk7YSg&)o#50P@x{u1|>sT1}J^Mg;(5g`{lU$O|mpRtQ6V_A9h?(HCr0;>pPKZ^S zc$%SRiado8)V+@FlXxujrg8`GH9vx>1wt}auo<5-XdOW$pZd3D7sk_eA zBh4wmslfacM|bc7tL`}Jm-k$J1__J?NKAhfzB)(T()>&I@Zk8DY87n%+_~m(9`tt4 zU`xubWHOq&Qs*uUbrks!73v|**)q#%rD6BEEmX1^D-JO{q0X?jMwqNLLNwm_zuH%u6 zGM4Sv`i%}Np3dMc3h4jBCwcZ+YhT@Pgx;F(rM9M;?@(GZoOeNEo&zrFtb|lg9KTSb zr;T{k#>(?~F6u_{n+OAcG}AQ(_e9SITaRv!O7mPZ=8Bg!!IC!~ezDJ2Fv!2hD&TQ% zs-H=Eyosf)I++5(4yH)+QmvZ%Zjm4Trr<9V4W1Q0gpb!;LRuj-q~eq5&K$@44X_3Z z?ph%l=P$$MERx*=+<>^O&-U$bf*+$llanO=#D%ui&adM4mTr&`HmO!~#z=#Vp5*%% zYIvBx^qsmdwuR3E1PGso?Q>U2&e=FPK^kd2ol|e$8m-2hUHzh2{D;WC4>#;{?!sl+ z*JYmcp4D3f3kZZob2@aM={4{h#{u}P(~Grch8Jz`KhtJnlWZyqc6!F*@0`dne8xLD zko#Uhb478}YUe%y`bCA0m$VXid?WgTZ-3YnP@z^nwN#4idpalb(x8o5w+^;vdQ*Bc!he+U*2z&o1-Wi zlkC+-moIs|UYPc7o-HAK!g|qwBA(WJ)rR_RL158-HY~Z&g*^_zN7<D)7TfJLd`27jA0UnagrKDJ<`vojOJvPp}Ru9;(?L zysdb4{YqRoZ=tkLYhamM+rAO@(>1Zr9;n1jU!HsYjBEM@m&8sq!}2eagX6m*ccj{m zK2Pwse7Zv?M*xe43FzvR6T~-Xzjv~nUhDnQ*g$#8v=9rH!%!er6sUttXqowC72J8e zLkR4%%q2Hmt*idGsKX0xhwemPy7f!}kA-ky;aq-}x7Upr+L_w`98Li{CV<@x(E7lC z4w>qkPF7k|*RiKFVqO#XGP6=|)}RWX#>+?Qd?u4wO_tPgchY3pOJJO)KGoV1Pn)8i zJz=`~PE8?NTrVUFS_E`xT_$p{5HhhJ-dmdlS!dBxe}AG7Kph! z9NX8MAwKoHsSN0A^vr9+6I>LnwcV%>zdR@6zo4sK(gJ~ZIaIx#yQVo=tjbp-7);3 z>8EGJLun~y!B~oX()wt|yPO~?os3ypl1)RpphH|z5Ygm4D-8-D>Wh^cAet3Q#12eP4CW5+cq>ge@1#l)IwW zhf&I98UPXTaRu`vEfDHoxRlFgV2`agP0OD~i_!pnzdRjN`9taOTp27*54*@oHG#lG z6tG=YSP}&w2tpXU0EiJ{d0NhP!2t=Ovgxsr;DF6E1{}V*Ckolu*i$(aWjEI4W zYHt>66jsh>0}x3l*`NnLHo%PmaY;c*KKs%jh`68?`jil)w#%A|EDKHr3esUX3e4LG z!-G#eA*axOSka$_s+2EXi$?Wr3N zx9fg**5~xs|Gr-f64e91bsz+K|8IxQr2h?3{dZxrKYYoFm;Jfr;pFki-`ep1WsD;6 z5Cm*_SpDGQdH%-hyM}GRpQ~0R(?kh}nqFCCfh`Yz9h3gG<>6g`Xvcu_+{B;4X5g1x zPD-|U@n6R%zR!JJp1#+%yCe=)UQ=HGQgcRn^6c;v-!toN(Gw-O@k2DsFP*xqx z)HucMG#DgD0Zocg`AJ6d^0UFPS(Ui~x%7TT>0ievytFkRd)DZ0yx6N+*_ayRXxRcQ zuYb1T{}wi@)w`hfYuKzVI>4^xBke`-;>Wh>J)$}bj!A=U_`i{nl?USg2a^$6SO*u& zc~T&=+2-?$uaXaYge>DgGSdHHUx@ofjBoCAOgP)WWW^+b46qC3(0|T5Ui3Ha@eXkz z9XYu_uROmuQpe{jr88ux|4Y$;aUy^Es|>yf(SZ`9---sr0`*eW=OMW#Ff{Lu_||{$ zLv-5gi3YlxM}ftRx}T@y<@3?<49P%vT9{0`xM-uwSFydxb*BgXf(%j5TfMkVG7l%8 zSZV*s4>xV~{AAQk@|Y8UEr!P^p)(8`obL@?fegj`+>CGyeJmu-3;8%ePcP1{6C<&* zH`$V+YvD1PdYKO6{qzIr{PN2a$95@A;hlT;4&t{4?Chb0g0^ojQTBxC6K{}heDGH{ z-_Org?QKS=(;p=1dPn5?VRQnF#IswUJU(BRO0tUpCtHe~K6YmVZi)k0y_ak*R5D*F z^MCh}4orw)$=rL9O!xONO&>b{2Ug-ena4RVzi4$&k(4y#D2(nKshmwS*k&n?Z9YQe zc0A(Ux>^l62m;+Q9=?1UY_E8 zoI4LrwoFlyFSmA^ky>5`O+?e;wGfv}gFL`$f{E3ksBb=e(SecRDXBpE&6#_{kZz-= z^0`{>3#I7w4@;j(+ua(gXc-?A&_&kjaU{IG50)>X5gg;Ec93gm^<75I_mmu*+hX&u zYYt$m#ub&$A|Upec+s+H@Qf<#d%AZMhN3@AsiW{B<3?zU^+76v3^|!|x~|Oju|5#Z zi!I;b*~GU@n!a7Ysj#ZdjXO0fJ-4D&q)SZ19MYlrwhy8+AOPW=EsAe#=-9zT@uqgV z?(Omuj1{$V?(3oyaZJW8>4A&FP1*a8Cy^{d>O)gb9>YnA`-9Hw?dpw}r+pUNoXZ)4MZxk|1)8Cz z?T{HdAEITTsEgVJ&*V_v%k4$GA7Fi`rtf@~iOS==ugkY;G~I7uC}n^fm=Fv6+?O3; zg?)QbDg$bjDQuRmxn>(w&DfMHE^P@KR1>cSe5zYdUUyknB_TC*} zS=Vj)P*SEZ!ka45xv)!FZZJ)RPVgx;(w}b&z z?t$(4JxJHkB_ie0PhhpTM81(2)V|N;izoG78&dmV$BG_(6Q`;1SXL(1-kW-l;ccd9 zf1k0<>NJssip{;|k3JKc@dX4IEX76!!3DgQKtty7bMYpCepaEBGesooGbMKv>7wU= zy(9b15iw#xO5?-IC%7=%PQy4ogL{N6aPp-T^5%~(brW#B^BL$vcHDqoWqgxpV5&Z; zb2KJ`XhKLch`SoYeyh$q;)-pK6OVr5b-5*+s$VTLVF<1;^}Qx@I3vFyA^W;DYBmcs zaE)}dPeI-@jb(W?@5X)$J^gEVciW_Ll{ujTH?GnwmuV=y1fT4+F=k;sEZRPSW0#cu zeZ>2XV}YcOL&rH4$zw|Uc>}wwxFY?C1(TX%q`ZJ${-fkj)yctDmX>3Ih_v93G8v@f zd2-jfQq3c)1o`1AnBzS5LEo1n|B=syo-y@T9_5MRL9vQ$PS#5btD}N^gYC=D0O%iq-nRwAs zO}L~dpj6O|tDhG;FHb#CuFGqxA=I&*5k^-6 zR?S7Uhl1L^j{ENpx+&eWV$D9VGD`F{zL9al2lS}PU1?HMHk2fX$!&7ZZki^_dN|55 zvTwpUIHSfR(HtLyw|L5RUYl$sYJGYUS0IrpvAzG~x%ojsKM3o!ht`Y!ZTY-i4Hmr8 zWpQ6$B=B7RY(coo=g>Zecrwp;-swfMbWGT|wOmZEoj^zG-Jn5*4+ogquQr>C%;`_> zL%Nkc(9nHOquS63RX5J5WwjqgJdqP|fWRNGkXZmS2j5!jL@9_U=Jk8ce3`v^PL@WQ zHC!fFvD#X80SX3A6A#&rk4Fx5_zVyM!wJe*1PUY)AVl zU&aOC0@K&tZE90^t3I*5=-DB^4(@J z!otL?Sf*CH(gmI9+GR~|F)bIN_*CQ%qhEkZCalP~nA!grcECSrK-fE@&lD5FA2a{oU`e<*_sgm3trdWnVOb6t%13?a^ZdC;05VW>FoyG6X}{lrDzPf51QMtA$*HT&^ygcs5#g$8 z(ruPHA2KS`KDG4l5R3<@bX{r17?0-yaBhwU{s+2&JT(K*;5c}I)GJNZI4CG3?11f3wN(Ei@>>wM~muce46}CvC=W6 z=S&z=iw#mat~610KG2tKBC8H-tZ+xMT!9W&_8lsp z9dB3x;~Zsexu;@Pacq3uoZ6SL&=)%cmD}ucx@MU;5P>~B&UU=l0XfVQ@`kZo@u6Cntth841tDGnW8R0H|p;=;xE6Z!}03!Gc?wEkyJZ5xq8y z&h1K(;bg`c*%;;kn_F1d-E8a+BlOw|u($#oQN~D!BF5O$wI}iHY%mA~cI;_@wy6wa zCIcRrc1#)DB7<%LNdy+<;Fn=ng=e0=Y9gb0!7|I$Dr=p9Z6RQf=wc)W(yCX|&M0RK zH3A7+nDF-4H~8pqtE{lEmz)~M1tIj6-V$1*pqr3QNdPJ;bYG8Y68d;x6X5VD(T*<`Yfd=HpG|FY=;=v|3ouIzcN?LIPqKJU{Y;}Dy^t#aJaDW=y)&-_#flsoC zjV{D94=fl}rW?uG>YzT#gh5uqt`Xr70^lP8ua!YLG(#8%;~%-Rps2ne(eTk>!^xn$ z2-)0u#drAizz`gU3U48&v1WZ^ zBW#a%Yl$0jk;nvuQwtH!$Qkpl&uWK5t;!X~1$f;#C`2Y#Q0Z8#(eD zxo$S@f8Katr;)(j#HZRMVACWN-XxOWBzCh&;(3$QPLm9Gvz%(Pf=#pH?eJ!${AQJ# z&1%n^kM1-Rxm(m#TQqH2w8L9;@>}$7wirBbG2Ce};%+rjZ8fuLwFqyu%x|^6*=qZ| z)o!QNo|^`4U^&~+T*GPZ`83a)H1Fp$-yNDCcUypJTaZm#aClotep}ehwhPbOF733D zx!WUE+oNpSW5V0x^4k+`wkJJrzq->-;qFLN?Z~j{$O`Ys$?wR!*-`Mkqj0B#%H3J4 z+F5GTSsvc0C!TrI3S0fWlYXYt_-kh*H}4TS?~(v(W9Gwu zN``9bz^{pzy(FF3h^uP(Z(p?KrZ;-GZHs{d!>hE%w^c`5=-be{EFW&)`kJB$a-TCT5A{}--VVibb`vOHw^q3& z%D^OD`nSCmM3(O3;0?Z_vwbAvwy>SL-mRe5#A}D#d3|j}+D4<;%FfS#)p@_);H$e} zEJMo{9M3BtS?(t)OtBHcB;BSN>A?J7R}lY@h;cbNdU|pq!6Lw_>#B9k*KA4HcmDa@ z%U>fw$&g9dDqkrV`L5u6mF}Ko`2Jb}-PhH`!hcP~gmGR^Pz-x2aaB8P^hlaTCrfUY ztJo+Oo-7wrPGu_7tt_oKa{whnmO)}k`JQB`zFVfZCmD(xn6Qw6I@wpA#-4Zfl5}D( zb(R`2>&C-e{r{yAQr8%d|3V^$Q8>rWQ4O18>Y_&JgGShr`vq(mC$2+_Y{`QXXUpVB zk`)(*hv-JU1MC%FgZ9(^`$SA|njL;@W9mhy=;0S5vMQ99(3umPuP$u9{bM4=)NB5Y zxbX7UTgq{%ud^Aae82v^B;8NRuzqLx*5>lgr$1HfK0N%-B;DEX>l6RWB;87%^nWi& zxAywEdN2idwKhsbAr5(pWrF__#D0LO>JplyHKdOW6w{Bsg6&43c+3e8mt{P5x* z)*~&05>+`;tp2-P95I!_=Q4Wbgbhuniu1Q~pV(ZJ`(1PVTLrUekXjdZG>S zl&ROI4dlIG63*9sL(JNQp_OTmWWDXvV@^`g(es&W$&XY2mG`o=9o50(yt)U#)_c20 zc}piE72tZrBMtlBTybxs`2HkWYA?Ai`USPPirPHk@?Hl%`$P;x?2QkHY2UgD*DJg& zDDOW7vyt6Bcx;8{ySOk~bMl52feZr<01TL#gd+&R zMjnSUWF1F{;@QR?(=nsQs4S>E?%?_<&CE3UAXij2m^tC?zJRe4G`d_j@#Jcjt*b6C zr?}8w5-z|j!#tf;^f?6y6wPPiryNrX?oOCi6yOuwUgx{)$;EJ-Ag6WM=XGas%a<(I ziRnc-E~*a~dLmR!&bo~5XbTj8?IOM`da73n|Gt`1{Q%GMh0c1}V`V`1NbHw$P~%)%@h@x{ zU2JvjUx=KhezNyrr7xojN_QtbQW`anVFO0?-}_b@FAmDZr%e1vs8PIvK?3*TQx9}G zJw$QW<810MqD+7ZH;vX<~QC_K9#yBPam0Hp}UZ6qCKDgsr~+i7Fjp+0Q8Y4MU}`TurYk_ zxL(2ydRd;YOD*}mr=TP?KmT7k-${J_WUG_(skcMye0~Eo`Oa{G2AXHZ_&%;LWUlqp z+3#BYf{iy$+!Up(vN6Zrh108I7|AdT9%(yD)v@WpESpZJ#Ba5O19OXqIyy>|6ir!>K$r706S zK6{!>M@5}d!hU0jkMe=M7E+XfbJ=+*!Xl=LkzLoe&0<)5rt?E~x9J4(Jv`#-l%A$2 zJ&logBpR?s}Q@XfsncW`o^kaM zqeTcvrcqwri#f+H!z+dQNu}R4*;<&YYqN&Ex!7g-sE3gZHn-9boS)auH1HJ^?|PDU zq&J3kd4kV=#NgeaHk9|UkTad&hc~2KA(GK%b)I(%l5ILYcC#c`M7$f;IBF)g0L{u( z>Ttq|0L9M_uPk}n-6=4p8tI(uIF~MB^))36>e+I}JDz1sqf$p!5W>k+$|C%LtU2(qZ!VL_uG)`~g>m zWWTXlp|!a|jOLKkWfe-DFD$3GdpvxN{$~DyYdK|q_N3+01OcP>)qXstJ^P>NC$r26 zF=z~WVaqeiuew|Ec%AO5=6cq{#h^Oc`uHvQ zhGsehpY~Ha3RlR!u5)M6+w=Sf&D$M0hYq%KEV;Vv6ie=g&TXlHXB2yeWq>5EGL$M1u|R>jKl|io(;o=02KD)+Gs#MN+;#Hk@(P;3*a} z8`&3lAmZeUH_QMWcEzl{75HZ+(YCID8S|lJbT1JJRUv&C@&I%x8Ms+aun?w9E@ABEbTeB<% z6wd?DV>9E*KXM1?*kq#Uu@MkW8HH`R2j-GfC2Z@JaB&(K!p_eZF3UQnC3ZW_nRyxl zv)?lk0l3nW$bNaQK2PIZ56{IHz~#i|)h4$roaQS=dnoOos-#Y#wI4{CI`GUZ2^!HO zyUIupL>F+iFaK>Q&&-S2c7A16slN2xk@36q#gN1+E`5Rrw)ENj7L2543XPNYnU^2x zRMjnD;TG8(Jbfo!i1`}t^uoVCz(e++02O3a*w1NAb$LKU)XegG(e_b+vv@(uMM&03dr@0u&8<)~qteD$Y0Ibk3-T|0hU+TMo;rh< zn&lA~II7U+_6r~wRCJVaZiFZ@#unB3=HR;f$ID@#q!w5Qp4Of`s$*}6ZxY`Bd_w5v zz4r6jG<&#s31A{Q{VZm?g+H$Rq0_FcZV@8Fp7eF$U}7KVbP%s!cTzo3Fh%Ujj$hb& z2>Ep{2TcaiedwlNube^)1@itBnS(b_>hlFUETFp*-mC4si#zksRBpei)TWW}T_e}P zFPK&$R>z(!K?*f=mH$`{Fw2|;DFCn%PAt~;WRa+ODyVD`5_d(>rTpxEhDenyX@w@d zKG|o57xDuTeq*e6%uKFx6F_B2Fy(l<^XtB*T`>{CEd}E>hW!~Eq$iK75b>hba#8ml zkm}})=_4d+SJ5^~(Vkma30M4>cA)oogphDp&;q)QUpTnZ^N5=YH;ez97*En@fO1Pr zlnArosk84)RSwhQT>ImycSo()jLGGn(dZJCgkD^U@8n?CXaG<~vTerEj`C5da#0DENtgx{ z2zCZ@5;L~|5dO4K;5RLkCHzB6`u7J1;O=xWG2)UPy8_0Qu5yy>pxypZnFJv>EWdox zeL1W~KWZo^X{{f%ri8})1V@O73$t4(xS}vR|7ZiSJ`W2ybV%+^6ZQ@IPJe3_7JMsagg-*%uTRnv23g3q+u>5Hs+a*=7ZE zM+Sw%!a1>UtCgH$3Ottrx1##OBC>Oo^V?~Jsb*x?DRj#)y1D_;^cC1@$Byab_v+$~ z(7{ZwqU*!xW-20E1l3Gsg5omnTU}%3B~%Na{-T2}CLqS*kO{ijv0aaAv+uDJILN^` z7`TRZ#|RTRe9el0=-2`RR)8iMZ08E_bs$ssR3VI)0&}nnH%14^@YTp5D&Jp6apBHo z>(Uj$A9nDYGef}C;)W=C(+ay254xh%1KYsu21H30f_Jk>$QpN>fT&kz#!-=84XE|d zV!0{ot(8KC>b*Y3yUHbMsMOo`Y2T^oM^s9&jR?)3)+19lnvSVrfRbBs3RW4MWrboD_gsng&_{q9d zPE}W1V{5mo%c^<#l>cMv@jp%O{Dou*S=SKa>qnx*mIv!IVfu8uH=v{&EB^t>!j1$w zx;GU3L5mCnDgXks^zVguj>kA3{aZT55haH|Yms4;p$sUb5`;OK_Ttg_&V;&3XE2^{ z@^I1VAzIyY@T1Nmi2ql;=>TKR-bWp2=r19jz1{ksTIBB`p0fd{J(x54tKM|Z5KhjJ2Cu=# zq|EMU?4!P!*srV%|Ijgnb1Nue2p{sE-qcP#A~!zq^t|Hy!YN6lU@`MF|DiW|MqMoU zXJb^}f2T3(e`@XZ20Wm`f7iw%@X-G5vXF5CULs9pu%+tv=A}K0 zSLH|? zL3_yF7)3Cfj>KwPj$Fb2*~a^wJ(gEGdIAKNt^}C_Id(}3mt6E!?~YZz4QyKq;qyC+ z(6zBu_bnx*>L|jU)7bGH2ciwMJ@V2`EI931_8kftPPGUg;LNm($(=}Y%zDq3>snrw zD+$Xyj38}P?%8-B+MTb3JU-{PS8(PQbw{mt{(2OfXJt(7{=LWbR~v78>{!~bHr^m_ zSzhp<=~eXo_wOsg%vpA2d3mRaZLWXW&w{h<%$lZO3(mIL>N+<(aXCNP;~z3-OU=Xo zw&3i4=5hV@&13w9(B!`$9@n$fdh$<)n}I} z-@EBy|Iq!I00~JT2MB=5{yeZee`5+vTu&#BT&jztGmiN~RT`-KaSCxNn+!g_u6zac z`(?qpWm8p#Wd45dDLxnH$TG{{E(;D_26J$(1W|hD@@3dReqRQCJkGh9wYbuo+^!C& z{|OBbsAatCQbZ1zog)Ye&Vc%?exXE1>EKNlo`RQ2mY!z@sTzp~PFTCYPNh41?U4-ai1-C|o$+&@qLy6V5y@^oPdEZr1wq~K z)r`fkIaZ~MU6e+7l5^$$z7{+2kIusOdb%=u2ljFB^u?X^r>F5YwQZK?yWqmq*eT9_ z%Xm<`cd|bbtwTv^7aU25<~3w5Avzbd9`I+Hcv4F2bvcgmRNd2Ot#v79k~m(uTZ)@Q zK68rJq&5{wex!ON9`U4^6cKH<;`VlSbeZ*#YFc`(_%9Xs#CqNCQ(>@kIYRky_3`sD z^{LM9z~7fnP$nU2&8J>gv3C}K`f_3__v6IdE@^NIEG2*OPy)5I7HlNElAOESp-bry zEF$A=V0vDDJ`L{#)Jvz*JPS_W@my*=mj;Upb!Hno4aIvKKR6peb1lz@eSb@)!6sMr zW5ZF_l1;N&iTs6)Orls{^VUV8sIzwj9)Ody9>kUe+^i#Y)9})n^9TvQ$PARG(4A3H z-Uz%YI8Vc#BuczdU?UL!>CTR4&1Yh9z1y@kU97~H^H-sVOQ8*4tD?ZLnMnejjR92? zy7}4d)BTe9ouOmg%$gr4K#IiLaM=K-_;n@`-ewpoV}{6S3nE1p69ba;WgTX>lm|9$ zwKwi~TU$zuIA@>8DKYWJOOr&BTS($Q6q5&qHIseUiIW~5$(7L1-NnPdsM0<5i9R~# zx-k%F42msEa^jj{XiIAV7d{V?F_bGN0jQFOW>NJC z=5G;8QASCQ8UiaBH5m3S%pBp&#MaK$lI@O8g1Hj0D#M{}K?xr(- zs>Wqrr`vG%HhIX;vPvgE?bqW$Z?%uJ97t_kT1m;h`2u?-u6n)9Q>Vuhp7`)MYt4f2 zv5+yar0ZP?zp{@nUH3I&y9^|HLMjR6&Th7()h6GQoa)b?ejjGuC|KvA(;G1MNpV1b zR~G=xz9pO4Y4b-KpdEFuFfgru$w=^5Pd&z1JQr2MWt9mNa}zViZLV>1uge`*+Huu? zfEb*PN}-D~(8&&ddOJ8q2gO{O^I|{Z@Jm5a$*fd+aW#=$Y~lB}S!vjctCs|gatSAt z_F1`VB$NTcCm@M|UK(se>dp3cUMGs4XT2W|Dvb;?a~BI8B&M;9L}rwk(piy|)-Wcv69u0;Q}%9XAQKz;wm$ zRw@op_f=Z%o8Wl#Bqp2FnYnCC=ZtS_LsPl4gi~nsQQRTyWiiiqI$bECN$;5xq;1^6yxpg4lB4fWDry`ze?aSLtl1}3 z6Z|Zq4Y{8n^e&&!}@EuP?G#I!IibSB*&gnQF(z3g4 zp;*s3iCko;aR}A=<(|o-g|KL?7?Gs*$CRw(%H{6HB$dVf2agP7>0XwYUt&CLnn1m; zvVf*v2r)KJjbz|^Xw+Ae3l8Srk z41;|NE2N~}l+_rdV#8o^WL^;>L*5euQ;nM^leSl{B#ev|WL{&vo0d;_=?^05N7#b; zc^B&q9f+w4fMB$TkQk_VZ1TvZtYsV8^qckv7kx{n+ol;(rPO_8u_pUUHTaWP$Z_(= zuVS$PogV;EG$g|%iqdfVjqX-ioA2lrl`-s|4DCP%po8V3X6)F$)Qvn!h54NYVErMt zk;4G5j>JR_uY24_oML&^w*{ZC(LmC-B3>T$2>$By-X3rpy52==OR=m`{{X{ z=at0+$!qzu9ZM*WX069xn#!G=8R!O-eu*Cj5DH*1o-;h!nxwK{+QO2FNqma_E^ExO zQeW+Pop>H#vr?YS03$@+M%J9v0OjZ&V_28cHqe7w&4r#nNfcIwB1kl8bw=Z5g zbc=UHcTLq%y!^}8sVikXpDlET)tbn>Ar~N zWulRE)R?rri{s?_+0I;^@cz#&UAZ&6U;2)v&mNy`Bp`9#+0$gfZ?86cPFb3hi}mE! zPZ;ya-JKrzWtRf$et{UdAWZ_`#%I?b$Yf~h$}}Sj-Y`!Z2e3B5_2eVuTP`1kp8K91 zF{pqAl(6*;p|W64R_eL5KA0`>uyHG|hn%=TBeJ_k$bCdgZcK`ofVHAVC{5sP$(I}z zvHQ9Li4(xO#bNHIqaTe_+_GTK4aRipDANXJ6hU5I0Agu$ML8szd*otO1asQ6=#+Q< zn?aIvO|Hd!QaB>2Eaq|oNz1!ZMvv%c$q~zv8jg2kCiVkrr_K)dINxdJY}sJ;dV?-X z6EdunQFVwz0T3o?oJE#g!0uKYON6&{Hz3dtEDOT~XS{+lYzngkR_^h(Yw~i;3N1Gr z2$DgGQ4y5(1f~f2(r5Th?ThHHBa%;aQd)#F-|4WXu{F2x)>4HG-(Xs0(BWMP4>)iL zguC=i_=;N~au_ARo;=;d%VdPPYl5MyVagE4TJ4ix6(`p<&^H6IeU?|3`NL!&7sk&Y zbemDTm#*v_AoC-@IKUZQ+qFj?zb*hZT`4VHsP$pYJsq>WI-eNv$y^FoM+rx^yxao{ki{d~`q>Z)!XrdB!lyDe3J(L_jwa=mW@U+PTd7#CR0Z*}7S%^h?GD)k#`MOl2Ou z)PP!)K`(ZpzUO2vP6Ml5DNtGTDuLeJFYS14mIUNN$OK3tdUiOR`LtoK$a({U*n!HZ%681nWNJXWcwC7R zjcqSaQ;UFhF-<08>4jOXI`~>clIUve6oX(74R4 zekPE9GIXQAb)gpY|&w&;(`l!Q5-8K@1ZW&d85Vthmnh0n0~$@KPYS70PQisu`=&Mi;6FnI^QIipneQ zQ^uIdL-dIdcCHdU4vr!^oom!tG=P+40({4(88|&0uOYMN3n=E53XaxYTD@A`r8ub>3Yq-(cd=zU+8Zw(mn^9OS7BHTbe7U zo3Cv&SBtgO>b5YQS{i~|8nauPTUuJDTiQ2TSYoYRx~)AwB zhsE0N>$Z(LwT%b2O=h<}Xla|7ZhN%RHk&Wj{#3X9xl{XGaQl3A`(jJ`@^t&_jrO-< z9jm$>KRI=*1$TVR?pSZ>_%z+|d7}d&&VuT(V9qQ=2#Yg^g=}SU&#=&+Sb%sZpI)bc zbEjZPr*KZEXltkVOy|x|omlZMDZMV7a~D3OOD?BNp|wkCrfb)yE>-bvb-iv4=WflA zZmpbdoz`x>neKf#SL-~yAD#w?&OL@9JtaSPeoJFJeIwSC{^Qu21S?_hJjLVd5)`N^+bzUiq8fTv@zd|$G z-|PL-yppLlle;}5KtnhV64CfHqx{(WR8Re(AG79*_P^=}6ycInlmfa(e99HHnkgN@ z_yUE=4|T47nGs-2WnL@X6!EBJh8jg0r;TqXI~SMiHa~48JJW9xYJN#}f|RY9nQ*np z(DzmSq(^qL(u2T3*~&-Jio5i=%hk7&o&F5p%I&Vaietj7Upuc(_?~&a^ri#Cq4Wn` zdH=feN>8*hr&bSWG_BX84?*uO({5{3giNTguPD*)q9Hs?8-oviKi%cnae;X!ME>@7 zGXkDf|4CP#21wbaPm$@fH0fIlPomg`Dv1d~qd`x9Yxtd53wp_fE1nz9KfmLb@F%Fs zN`t>E5m45j`&|LUpF+P^=DshxvZQl`exqMfGljpw)xSST_XDnccaYE~Pah6`Rpxf; z1tGT&Qm8OQGAqKI*WYpbAn`qP{T7iPmn$f6O{h}Ei-HHqH^uJ=NWa9&t3X`6lwRt7 zq6ozbnD% zNngsYem;EnZpY@`et6i+$DlF?;%e*LF%%zY{Ya`Hr?J*>(B#9w)Wdup!VmGsyui{) zz}1T{0{hRht9@fm+vRayxI13YyaevMTL#`xayPrM2eFVF!QmhWDs%X2ZnY{-G9 z@I%|>ab%1$I27Ob~QJ| z&CV>3rV017e$Q=KY!Cw5!qw3xo<($WBe@vdIONy}{E(Cnk=6co_7uYD<-s|M$4M$jD>vCj3|IcClv>fM{&cyRJPhM_+rV)wNXBNDVD!nLn=|$5+vi< z^it@B@UMT9KjO0-$FW%!PANTKPY*xZ0&Ced7GtwgL*qz3Hpl8-CO;jH}|31W4<%x1J7elZy`-8(2D+2YGeKyCRmqiur z%$TW`SlRlUd?UR34Rt2vhS#k-pCrp3k931;Hk&i61T0+U;Y|yAoBn9)n+E*W>A881 zO$(C3DvkV%CRN8N7voHZz2Kd)K*(F$z{lV<^f5hDrbcj{5L(!Sp1Xv_a|AQ(ER);#5*5I@9hF`$LDVH5*Zl3A{Vg?ebx3ZkbNO zvjsAAoOg-`BdKB1X1>7FM{XGJ)VnZWv^T}j-l1wV)-}F}ogOCR{5dLxmX=ks6c78cbmg0!N8i?jE)NsjPtzS(beq8jW-^dOWeR~VL0f*T! zM2oBWoLRSs^}Wbq_=%0rXI9#N-s$e8n|)ZozfbRjIL=ktcwwd6hO>ujYlPw@-X`DE z?k04K->-Mg-F$fO?u_OqclLpwJ(g#72*NMS?4fv=|l^(;bLik?#Tr9 zj+u9;+v~_pu@@6Gj@PMq=-I3i0IhDSA#?Xnhy$(LgPqu(k12G9t1TQ0L;HhyYwp)t#vFuq+^W!{wd=IP9R0rGU6FItY}r6CDE#zR#0q*w|2RC6vfrEf&bVpTw|(HVa0e~ z%Y^UJ!a=ww;eoI9YwRNLN;YWO>|J&R6SoBI+;W~La-{AL_1?RW%NaF`pVZ*+%eUwy zI}=d|(rIi*4TApq6<8eP8#uv+xfG>%7 ze$j&ZB=xy}K#_GLba%VXB|ff3?1?Ei1${OG^rupj0*EBn`I$nj#X;fe7gxCv1-ad@ zLRd8J4h~6&zW2f@TD)h@G!}E^F~uS+;0XAFDHvJ92A7frw=WPnfKsj;&5zNUD8f^WY(I$R@3C zn3EbbJ>JG`l%(18F28c|fJ5m*!+5U}xS3yt_f)ubcaMa%9?;;__I3}J5bBXP8Eg9{t;8H)QkIMJ7&c5_kts=^&w3L!mg9*m zb;eA`XXLKkU}Y`p3%sSm#*UF>iAfI4Ue|8iAFP}IG_Mw%8WpC*);Jk;M@%+Yo5K+8 zFKhMUhmW|dF8dgV=qpaWLD>)2qHjseO&25CMg6s^ATzt#Hh3h=r zg?AL08S@QNH!I)kLyX77e(Vj#_#67TJ4ZB@NMR2QqN1$ZWGDr#rr2)h*WTt$>k(~Q zNwprY0|B!IfqnbOV-rgWaHOiF>p4-2%2^-kMTADwrTa8O7xsnbiKxvq(Xi`h*=?V; zM;n7Hv-&$26t)TmUfo%lTD^R;%jRz->HY@->}nH}OUJXM-BwPsXAVQ8T6bxPF_2mC zTPej znriZQj;fkMn8SgMhi2X<2&T7@2^ zcQ?W^F0suDlC9J(h6@BNHWEJ$S2p2 z-ttTm=vOFyfWdU>`#sy+e=<#=)oIupZ2_De`83bEr%ky>o|&GRH;-2DyZvC;k)t|` zM7q0vWG4fVRC4K4%}It>KC7~P)hi?_wN9`zbgF8}RVgzjZT>_RDO4(HuxxfvjJL}y z@A&&0g(nSWPY=-Vhqr0&BI}*@!ilQ=xNhzv)CU6#+gMKfWVCMgLn%9{WWjsypowHC z>B+t9Di0{KqjgbsmCU<4Chz`Di7eNrAyny54g%p5q)|ZUB?O#K&%p06gq<5YDF4|Ve=G8@3@n0? z4+nSM9IIdKHbTGl;Z@aX-7rfl1n;YD5KyEh$mxlTm0@ zR5_NT1xy3Kjc|+Qzf$kBY#nI|=JNM4c+2r4=12 z#~*nMa^xxuLW5P&R4BLu4Cq125`ybyBQk)*3&K`3Aue4GI0tZ0KgQ(9@xxdUay|r- zrd<$zoaL@|)S9t-@rm%D+M$f6Km!nKC@0^ zjY-(B5Hx|!46x^Z9)!YqS!L)`y`t)>(GFS>oJ3ThSB#@ez_LAEY~{G@9<~WYb@8r!F`u;ner*)LHZXpaE?%Z5+-TCM<|S?iY|f&r<{|y_fNS5*iLvBeS(vo5 z%2!WOkya=UB5H6m6Hs1&y#AQ7j|(F?3y}n%4m1daew^zG?<KnlH*wqRM>$q6#Tdp!@l*8eON#`wq*yp~{=k&-+OZF!snu@diZmJt{%T6wpC< zo>UD~@hiLdPBj^X&hJ>L4Hw22Mv9(2o641b4-bs(z?$|N3)mo4WK5LgBIsJE3e`+B zmbX(o2W*;a)Phgcr(SQ$;SAd`L_}56;eM)7^QFjg0O=r{P@9ih#iGu79U2n3jM`K~ zSWKZRv4~~Wq+nr0fqV`+jQ&(4kNqA8n#IvdK{--T>XT8AymQ&)^B`ml=#W-YP~~7l zUQjMub3TTc*TzB}rSMW45dp%;nErg>MWEH?^7>SE7Cp6vULX|@tWBXbwHzJjpje7J zpj{{}8Z9;uQHh0bj!lkCb-=w7Tz_g^opEebB@tnU+OMZ`j?&cAGB|iOr zigi0BUC_`T{|D`OX5V%LZd|ts4*jR8_~r4sEk1o?s7hyWFYj)PPwQ%B_e*UOcD-9U zNRlrH_eQ=j)H6$$y$5Ycgq8@@b6HyrZO(uQ>>u)1U_EB zM?W5ySb66&`TxEFt$!9HdaPr!$>x&)>-;wQ3EdGh8~(ihRGJF+_7v+^Q?bCLtFL$P%!jfHGEF2Pb@FDDI(x*5kjtkX-N_gx{fKRoAa?QtJKm+xW?-0=_ORad@Icw z{CiNuz@1AVL;Wn^#vJ8)fzln@LO({z>%-S)qL=O|!*PnkI`AQbgvMn-7rgNjQs6|( zvJdf1+b*8zCE~l;|06@KTpdvQGp3@1e-0di2SyGEv6$9Y27Bpamb}#Z@q=fon1>4l zfwf8Ys8?xI$4Zoe2flylS(^xMk@2!8>O09!0k!u7JUHreto|;qW1mX2wrC; lj*?g?P(r$?;J6Z>LChsECz%l^R}v0$7ZDqSy1<)V_aEf`_. + +Setup +--------------- +The simultaneous trajectory execution feature can be enabled or disabled through the dynamic reconfigure parameter `/move_group/trajectory_execution/enable_simultaneous_execution`. +Optionally, an extra layer of collision checking, done right before execution of trajectories, can be enabled through the dynamic reconfigure parameter `/move_group/trajectory_execution/enable_collision_checking`. + +Running the code +---------------- +Open two shells. In the first shell start RViz and wait for everything to finish loading: :: + + roslaunch moveit_resources_dual_panda_moveit_config demo.launch + +In the second shell, run the launch file for this demo: :: + + roslaunch moveit_tutorials simultaneous_trajectory_execution_tutorial.launch + +Expected Output +--------------- +Though, two independent trajectories for two different joint groups have been planned, both can be simultaneously executed. + +The entire code +--------------- +The entire code can be seen :codedir:`here in the MoveIt GitHub project`. + +.. tutorial-formatter:: ./src/simultaneous_trajectory_execution_tutorial.cpp + +The launch file +--------------- +The entire launch file is :codedir:`here ` on GitHub. All the code in this tutorial can be compiled and run from the moveit_tutorials package. diff --git a/doc/simultaneous_trajectory_execution/src/simultaneous_trajectory_execution_tutorial.cpp b/doc/simultaneous_trajectory_execution/src/simultaneous_trajectory_execution_tutorial.cpp new file mode 100644 index 000000000..6db21e9ea --- /dev/null +++ b/doc/simultaneous_trajectory_execution/src/simultaneous_trajectory_execution_tutorial.cpp @@ -0,0 +1,87 @@ +/* Author: Cristian C. Beltran-Hernandez */ + +#include + +#include + +#include +#include +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "simultaneous_trajectory_execution_move_group"); + + // ROS spinning must be running for the MoveGroupInterface to get information + // about the robot's state. One way to do this is to start an AsyncSpinner + // beforehand. + ros::AsyncSpinner spinner(1); + spinner.start(); + + // BEGIN_TUTORIAL + // + // Setup + // ^^^^^ + // Let's start by creating planning groups for each robot arm. + // The panda dual arm environment has two planning groups defined as `panda_1` and `panda_2` + moveit::planning_interface::MoveGroupInterface panda_1_group("panda_1"); + moveit::planning_interface::MoveGroupInterface panda_2_group("panda_2"); + + // Now, let's define a target pose for `panda_1` + geometry_msgs::PoseStamped panda_1_target_pose; + panda_1_target_pose.header.frame_id = "base"; + panda_1_target_pose.pose.position.x = 0.450; + panda_1_target_pose.pose.position.y = -0.50; + panda_1_target_pose.pose.position.z = 1.600; + panda_1_target_pose.pose.orientation.x = 0.993436; + panda_1_target_pose.pose.orientation.y = 3.5161e-05; + panda_1_target_pose.pose.orientation.z = 0.114386; + panda_1_target_pose.pose.orientation.w = 2.77577e-05; + + // And one for `panda_2` + geometry_msgs::PoseStamped panda_2_target_pose; + panda_2_target_pose.header.frame_id = "base"; + panda_2_target_pose.pose.position.x = 0.450; + panda_2_target_pose.pose.position.y = 0.40; + panda_2_target_pose.pose.position.z = 1.600; + panda_2_target_pose.pose.orientation.x = 0.993434; + panda_2_target_pose.pose.orientation.y = -7.54803e-06; + panda_2_target_pose.pose.orientation.z = 0.114403; + panda_2_target_pose.pose.orientation.w = 3.67256e-05; + + // Planning + // ^^^^^^^^ + // Let's plan a trajectory for `panda_1` using the previously defined target pose. + panda_1_group.clearPoseTargets(); + panda_1_group.setStartStateToCurrentState(); + panda_1_group.setPoseTarget(panda_1_target_pose); + + moveit::planning_interface::MoveGroupInterface::Plan panda_1_plan; + bool success1 = (panda_1_group.plan(panda_1_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); + if (!success1) + { + ROS_INFO("Plan with Panda 1 did not succeeded"); + } + + // Same for `panda_2`. + panda_2_group.clearPoseTargets(); + panda_2_group.setStartStateToCurrentState(); + panda_2_group.setPoseTarget(panda_2_target_pose); + + moveit::planning_interface::MoveGroupInterface::Plan panda_2_plan; + bool success2 = (panda_2_group.plan(panda_2_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); + if (!success2) + { + ROS_INFO("Plan with Panda 2 did not succeeded"); + } + + // Simultaneous Execution + // ^^^^^^^^^^^^^^^^^^^^^^ + // Finally, let's execute both plans asynchronously to have them run simultaneously. + panda_1_group.asyncExecute(panda_1_plan); + panda_2_group.asyncExecute(panda_2_plan); + // END_TUTORIAL + + ros::shutdown(); + return 0; +} From f868e50cea50418f54b5a8dc3a125dd844b3e202 Mon Sep 17 00:00:00 2001 From: Cristian Beltran Date: Thu, 27 Oct 2022 11:13:16 +0900 Subject: [PATCH 3/3] Fix tutorial --- .../src/moveit_controller_manager_example.cpp | 6 +++++- .../CMakeLists.txt | 2 +- .../simultaneous-execution-rviz.gif | Bin ...ultaneous_trajectory_execution_tutorial.rst | 17 ++++++++--------- index.rst | 1 + 5 files changed, 15 insertions(+), 11 deletions(-) rename doc/simultaneous_trajectory_execution/{ => images}/simultaneous-execution-rviz.gif (100%) diff --git a/doc/controller_configuration/src/moveit_controller_manager_example.cpp b/doc/controller_configuration/src/moveit_controller_manager_example.cpp index 0941368a9..da76836a9 100644 --- a/doc/controller_configuration/src/moveit_controller_manager_example.cpp +++ b/doc/controller_configuration/src/moveit_controller_manager_example.cpp @@ -49,9 +49,13 @@ class ExampleControllerHandle : public moveit_controller_manager::MoveItControll { } - bool sendTrajectory(const moveit_msgs::RobotTrajectory& /*t*/, const ExecutionCompleteCallback& /*cb*/) override + bool sendTrajectory(const moveit_msgs::RobotTrajectory& /*t*/, const ExecutionCompleteCallback& cb) override { // do whatever is needed to actually execute this trajectory + + // then if there is a callback, return the status of the execution. For example, signal success + if (cb) + cb(moveit_controller_manager::ExecutionStatus::SUCCEEDED); return true; } diff --git a/doc/simultaneous_trajectory_execution/CMakeLists.txt b/doc/simultaneous_trajectory_execution/CMakeLists.txt index a64a8e7b7..7c923f824 100644 --- a/doc/simultaneous_trajectory_execution/CMakeLists.txt +++ b/doc/simultaneous_trajectory_execution/CMakeLists.txt @@ -1,5 +1,5 @@ add_executable(simultaneous_trajectory_execution_tutorial src/simultaneous_trajectory_execution_tutorial.cpp) -target_link_libraries(simultaneous_trajectory_execution_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(simultaneous_trajectory_execution_tutorial ${catkin_LIBRARIES}) install(TARGETS simultaneous_trajectory_execution_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/simultaneous_trajectory_execution/simultaneous-execution-rviz.gif b/doc/simultaneous_trajectory_execution/images/simultaneous-execution-rviz.gif similarity index 100% rename from doc/simultaneous_trajectory_execution/simultaneous-execution-rviz.gif rename to doc/simultaneous_trajectory_execution/images/simultaneous-execution-rviz.gif diff --git a/doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial.rst b/doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial.rst index 479e1642c..03c9e7a68 100644 --- a/doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial.rst +++ b/doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial.rst @@ -3,24 +3,23 @@ Simultaneous Trajectory Execution Introduction ------------ -MoveIt now allows simultaneous execution of trajectories, as long as, each trajectory uses a different set of controllers. For example, in a dual arm environment, each arm can execute a different set of trajectories without needing to wait for the other arm to finish moving or manually synchronizing the motion of both arm into a single trajectory. Optionally, a collision check is performed right before execution of new trajectories to prevent collisions with active trajectories. +MoveIt allows simultaneous execution of trajectories, as long as each trajectory uses a different set of controllers. For example, in a dual arm environment, each arm can execute a different set of trajectories without needing to wait for the other arm to finish moving or manually synchronizing the motion of both arm into a single trajectory. Optionally, a collision check is performed right before execution of new trajectories to prevent collisions with active trajectories. -.. only:: html +The following GIF shows a simple example of simultaneous execution of trajectories through the **Rviz Motion Planning** plugin. - .. figure:: simultaneous-execution-rviz.gif - - Simultaneous execution of several trajectories through Rviz plugin. +.. figure:: images/simultaneous-execution-rviz.gif +This tutorial presents how to use the Simultaneous Trajectory Execution feature through the `Move Group C++ Interface <../move_group_interface/move_group_interface_tutorial.html>`_ but it can be similarly used through the `Move Group Python Interface <../move_group_python_interface/move_group_python_interface_tutorial.html>`_ or `MoveIt Cpp <../moveit_cpp/moveitcpp_tutorial.html>`_. Getting Started --------------- If you haven't already done so, make sure you've completed the steps in `Getting Started <../getting_started/getting_started.html>`_. -Setup +(Optional) Setup --------------- -The simultaneous trajectory execution feature can be enabled or disabled through the dynamic reconfigure parameter `/move_group/trajectory_execution/enable_simultaneous_execution`. -Optionally, an extra layer of collision checking, done right before execution of trajectories, can be enabled through the dynamic reconfigure parameter `/move_group/trajectory_execution/enable_collision_checking`. +The simultaneous execution feature is active by default. However, through the following dynamic reconfigure parameter, it can be disabled, **/move_group/trajectory_execution/enable_simultaneous_execution**. +Similarly, an extra layer of collision checking, performed right before execution of trajectories has been added to the `TrajectoryExecutionManager`, which can also be disabled through the dynamic reconfigure parameter **/move_group/trajectory_execution/enable_collision_checking**. Running the code ---------------- @@ -34,7 +33,7 @@ In the second shell, run the launch file for this demo: :: Expected Output --------------- -Though, two independent trajectories for two different joint groups have been planned, both can be simultaneously executed. +In a robotic environment with two Franka Panda robot arms, two different trajectories are planned, one for each robot arm. Then both trajectory are simultaneously executed. The entire code --------------- diff --git a/index.rst b/index.rst index f10a6cbc1..be7244485 100644 --- a/index.rst +++ b/index.rst @@ -97,6 +97,7 @@ Miscellaneous doc/benchmarking/benchmarking_tutorial doc/tests/tests_tutorial doc/test_debugging/test_debugging_tutorial + doc/simultaneous_trajectory_execution/simultaneous_trajectory_execution_tutorial Attribution -----------