From 0d255bbae12b73fb01b395f2a1d1be674b0dd392 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 1 Jul 2024 09:08:41 +0900 Subject: [PATCH] feat(ekf_localizer): add covariance ellipse diagnostics (#7708) * Added ellipse diagnostics to ekf Signed-off-by: Shintaro Sakoda * Removed an unnecessary parenthesis Signed-off-by: Shintaro Sakoda * Fixed to ellipse_scale Signed-off-by: Shintaro Sakoda * Fixed to ellipse_scale Signed-off-by: Shintaro Sakoda * Updated ekf_diagnostics.png Signed-off-by: Shintaro Sakoda * Added condition Signed-off-by: Shintaro Sakoda * Fixed "and" to "or" Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- localization/ekf_localizer/README.md | 2 ++ .../config/ekf_localizer.param.yaml | 5 +++ .../include/ekf_localizer/diagnostics.hpp | 3 ++ .../include/ekf_localizer/ekf_localizer.hpp | 3 +- .../ekf_localizer/hyper_parameters.hpp | 13 +++++++ .../ekf_localizer/media/ekf_diagnostics.png | Bin 104312 -> 142232 bytes localization/ekf_localizer/package.xml | 1 + .../schema/sub/diagnostics.sub_schema.json | 25 +++++++++++++ .../ekf_localizer/src/diagnostics.cpp | 33 ++++++++++++++++++ .../ekf_localizer/src/ekf_localizer.cpp | 20 +++++++++-- 10 files changed, 101 insertions(+), 4 deletions(-) diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index b91282015732e..3b417b12bc6e9 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -186,10 +186,12 @@ Note that, although the dimension gets larger since the analytical expansion can - The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`. - The timestamp of the Pose/Twist topic is beyond the delay compensation range. - The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation. +- The covariance ellipse is bigger than threshold `warn_ellipse_size` for long axis or `warn_ellipse_size_lateral_direction` for lateral_direction. ### The conditions that result in an ERROR state - The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_error`/`twist_no_update_count_threshold_error`. +- The covariance ellipse is bigger than threshold `error_ellipse_size` for long axis or `error_ellipse_size_lateral_direction` for lateral_direction. ## Known issues diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 19bfd2d498b68..4a7696ec9e65e 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -39,6 +39,11 @@ pose_no_update_count_threshold_error: 100 twist_no_update_count_threshold_warn: 50 twist_no_update_count_threshold_error: 100 + ellipse_scale: 3.0 + error_ellipse_size: 1.5 + warn_ellipse_size: 1.2 + error_ellipse_size_lateral_direction: 0.3 + warn_ellipse_size_lateral_direction: 0.25 misc: # for velocity measurement limitation (Set 0.0 if you want to ignore) diff --git a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp index 4c92b2947642b..8815a1758de01 100644 --- a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp @@ -33,6 +33,9 @@ diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( const std::string & measurement_type, const bool is_passed_mahalanobis_gate, const double mahalanobis_distance, const double mahalanobis_distance_threshold); +diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( + const std::string & name, const double curr_size, const double warn_threshold, + const double error_threshold); diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( const std::vector & stat_array); diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 65003f5fe9864..ada9024faceee 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -216,7 +216,8 @@ class EKFLocalizer : public rclcpp::Node /** * @brief publish diagnostics message */ - void publish_diagnostics(const rclcpp::Time & current_time); + void publish_diagnostics( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time); /** * @brief update simple 1d filter diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index 8d76102e5d64d..7c3c03c83b778 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -57,6 +57,13 @@ class HyperParameters node->declare_parameter("diagnostics.twist_no_update_count_threshold_warn")), twist_no_update_count_threshold_error( node->declare_parameter("diagnostics.twist_no_update_count_threshold_error")), + ellipse_scale(node->declare_parameter("diagnostics.ellipse_scale")), + error_ellipse_size(node->declare_parameter("diagnostics.error_ellipse_size")), + warn_ellipse_size(node->declare_parameter("diagnostics.warn_ellipse_size")), + error_ellipse_size_lateral_direction( + node->declare_parameter("diagnostics.error_ellipse_size_lateral_direction")), + warn_ellipse_size_lateral_direction( + node->declare_parameter("diagnostics.warn_ellipse_size_lateral_direction")), threshold_observable_velocity_mps( node->declare_parameter("misc.threshold_observable_velocity_mps")) { @@ -86,6 +93,12 @@ class HyperParameters const size_t pose_no_update_count_threshold_error; const size_t twist_no_update_count_threshold_warn; const size_t twist_no_update_count_threshold_error; + double ellipse_scale; + double error_ellipse_size; + double warn_ellipse_size; + double error_ellipse_size_lateral_direction; + double warn_ellipse_size_lateral_direction; + const double threshold_observable_velocity_mps; }; diff --git a/localization/ekf_localizer/media/ekf_diagnostics.png b/localization/ekf_localizer/media/ekf_diagnostics.png index 16de42ac2d85a3d175aee06f3cd381d1ed5cb452..234b2f1e19b6dd701dd1253b853580ab759f725d 100644 GIT binary patch literal 142232 zcmd?QWmhFJyDf^-&^R>iPUF6CcXxMpcc&Y7T{txE?$WrsySuyFq2GJ=J!g!w_b<5l zvQinTC&{WLH8ba|FnL)qcvx&$5D*Y}32|XX5D?G_5D>7jZ%|()HUo;}Uq28|f)dK# zzLNJhm1`96og9U&PnYbN#e2V*nfTHY$a1=&G{sH*$l_v{<^K%3LDni>=$OS9Pr3}yA3xv%G|H{OF|7rj8D;CydkHk-1Lw{$Iqv<)$6>1-zEA z%!x#1TXZ{CO4;Hf$T}YX+RMr|uh@CiWu{X#^vgE)K_-HHEk5>2p}b-O6w%$wm>YXu ziSXPt4*NpfgQh?0=GrAl0$HkKs&+SMKJf=Uod)MEpY~Pzs>7W#oP_>h1?ji<7a=o; z?u6wZ$ijnY6L5b-aX$@l>qb`17BV1%_T6CUUZG*R7;R6 zq&2&b*TcH@W|a1GYr7D1`cBTonHJb>`!>&9LMb_6>?ITXee_tZiYnW-Ib~nVnzQJk z()8t6Kg;8h4ByXO=B>zS+mXjokCdg|3SsXt?Q@i~Jn@t#owef==)$dUfur8YmPsK7 zm*a!iDMpNhC76CQA71F^#*DVlxBq}&M0&ldh4<76kAZAOl=itv!-mh@`}}+NOoKHk zj$|`8&ToK>?0$-7!%ig(?5}G%J`q~kE$n7FUpAI?P@f3FRJ|n?ER>f4b9&7yMy}?d z0Gvk=SrV~#wFVCi?FWlbAs+Gj3)>~?tFQxcV0(2cZSylmj^HeB&mht0mpZKh1}2WHcQ;Sl)9bJd^%OsQGCITxuz}V zH;}J8wv0xPF?(T+*>yJyM5>EKf8Bcm3oTM^9`%F3XBIofG(P3ABRNBUB-qQ`kciRD~&U$s_7lXRrd)?*b7vX;&^exuv;EVk(oVx%tCfkA?;)uh-w{csO_ z(6iav!87!H>5+w4$ueF-#v{#|cCj%}bDfPT(WhSkfDCH#mSc<99}Ee(x1hsmqWH~D z>A#FD4%v+@O+4HoW}s5wY({sh-r=$7oQ95iEcmS_VF!WR*LfhRmNMFX)W(!8BJzXX zzAWSkI^%n<)238p{Z2L?(qcw1^X1h(!_!UQ@*ja)iTAnGrL#4>8+D;dnuKP5)DK@c z?WgzKFenH3@NKdq^w!P%Mtabjwab84N!ZOJ%}3Er#iZf*5W5Bb$gGl05b8BmZW1|Yr{((+zyT#cGKp3zbR|`CmV;p20zVTBD}LsLD9}fhS!IY+iF{#!XMB1LnTno|bZ`3qFz1)4pM8R8T#yb+gQ0?R}8EddKOlw{g6m-H1 zQJF46-zdNM1UlrFn>v;{B6IZXQ4HGY>1oCM0siGJBnh2Gy^*Kjq1ily@Y{u5+|SIp zhLwW-xiOM6PGTc$sBn%ms^iyPZjE;R_Vz`>PIYgqkt?6*u}9n_0&K`Ij{MekUdvz_ z&31lYJZ2R(9Ta4Tkv|0qCJXWNwZ7+uSetF(PpKpYi)oQY$((sn?wVG^>=Z7@$P!vp z3Si|b#zzLgPypHWk?nGeQ_eVCKX>ss~i7je(XDRwd(Wzvh zW#fY)4u{-2N+n}Clr^QfiRh4#7m2WLeyg-w{-t2{)%z)RAQvAX0~^|Z?(poLtt6aL zYo;y(b5lhL&dz1~DbM*hy4djES7!{3#b_2)uE(V6$$LP(kn3aOa}sp}&PAWdvPhM> z&MLY_l9ePO#yr{z(8XRYS9H3188fQU+M#Q`xWcfnnBZY5&QR&m(;+{O?|n~nUViqI z3k6pAvz&eAjcK&2AIRX7I6W9A+PgdoKAUVXX|(w^jD0pnB)T?9^vgYjGPg~R_g~K} znIXS}Q`V$}bO62Q) zyQNWJQ~^zrnW`dzL8EFTGc8WWy{TSjow;w&>*xSHzjmr1nQsH_Gd3D8cx+O@dmq>c z7@0AV*3n!iy12476LT8^#+)#>x-duCPUQBnB;F*x%+@|ROS%sz;kt!5JGs-`LAgY; zH~2u)q!%L;VW3vi*VEG??~u|E=_UM_lmX_ymTHmud?I7K zMa%4U>v{!7*Ih$LK`e(f=h$D$mj-qnU79N46tYRF2vQN@nZ^4!N~e@|28vOy3sRf7 zc1+8p!4O=){B&bRek$?h)^Y@tkwKBikp%` z6U4-5U4c)IhT%(jQsQY6+0Y(3s3F})rM1J*c)k)kS%Uo?GrANzBZ_I$#0XR^-5TJ(XNOz6bs(;qdR-2cJaM> z%E)DUT&X_yypMVcAHQq~O6Th%y}k;1t&fYIc4P7YjEYaG2+EJ_{vF@Wv#SEJwnqkB z&RT6qWk_-iO<>dc??~h6PR&1ll;D~`Ot;v72sUa2Kz)|BzX*zq9g*5>bY&kuDzT@K z{8S$%8y_DRF2KA<|R!VObt!82SeSGJ&hi>evJC5<#c_5fh`%7vz-?Y=QzCNx|1 zb1uEy+|SYT1};FOKH;Pat*me?J+DCjaR&{&gcK3&V94t5He;rTNih5RppVF`Jb3KL zM1_|)-!%{Xn|12oU=*=k1qshHDFr>Z<>T>>{Yxh;$5=)^BG?qx4{46xQj<3EDg~%f z9oV7P#_%<(KR+UVP=j#NVdQ93tF!P=-E--nvzDt$iRMh*rw8&^o-EL)SERbMI76t3 z;xKG|s(ZCAz>PZgF8aIedoLH_TA@>8$+-SG1zTxADs&pu84AOtQ6y8BAwaNxD<9@9q39m7H^`|8qJ)BY`uX?=(cqiGoypH~BCOO{C@5Dp(P^dbU}q z*Uf66)Y)4*JlEkFWi(5RBBy%8QLa3EOrN0 z1QzZQ)!dY0`VTzL8HaDNzM)vm?7RHE72+_&;|52Fxwb<1l0by+<`;kj3@6!2r_d=S zJIf5fixkvLST~Ym89aggFFq8&FL}LfXS!@p#EH{Bb&SI^l4$q)uYlNEli|~}o*5OO zdu4#y0DZz@owE<@N5g3Brg@iqEh$kY7L7)#a5|I*$*+X>^rkr63YAT2CGuiau( zL)&s(e#F{2qpH#$$Ha%$t~3)Zi83v!-S3H{wT{Q=cSDtlH_v4p$)v*BJrlbD zcNKftGF9Alw2)d%o{HbSvn*u?3;+D4c~7C}xa{yz0deA)W{O$mTJi=AZ2zE}kketq~Ap^Y=uk6o?dUyfrK3 z89sinAS~FQy@zvdgF-+6a~F3=`*h=N?O4gS=yjp-v^I+b?R9U0legwK>4^)$>dzOx z@r}RvpEO<>$NZhUS+vK;9d%;-cnX5pJv|UGfA*!38#NFb-!IWw$M{8B*X*Tmvo|Tl zKUDYTd3>SKkR}EK>I$817HQUd%rX|!A-TC?A?;rB<5EVuZ=}DIp<0IGuatKrFOQWz zIE{*K!DGU3y~v^as+3986`r!MPtymog#2gB%BXC7utXf$eKYkah3 zj9TM@ee`mrqw$m5y;Lg-B-uSxBz6~VWsa`rS$y?s0!5g8w<7c!H`&4hh??>B#-8HS zih`#e8Z`PgFU1SGfgpZSzg3h{TTZzvGtP?Cz;*o^01myHv+bWTV;Zf21-BH;7SAwn z(`2F3jZC&zF>fD(s*N_QJs)-K5BCd`oSE=`8T=!zNUCaojwhJhHuwFRdGQaP^KEE^+Dsuc3=dK`U)Zihb ztj(D7GVmW;%8qM|Yj+E8|Dh#%$oUb_w}u``XqiYit)QTqV??a$<(9g| z#rctLB!0`+TO!?bDI@6@^p<`-6an`-U2mZm~YTv=CZX%1bYI3;I|?gm4r zDd#D>M5b1GuFW+i$Gc}s5e8zeO2N0cGxW2K zZZyjE$SPOU{M#aeG=a^5g5gt}-jf3#NJWMft?Gnjg;`YQ{GgPRGC<*RjgM}aLM1E`VG&qRocuiGJN8e zrmq*R;Sel2r|Y`u99M>xvLP6zh)47_6S=Xl)tN|tm-noY#c=qb`czvcPBR4#LSM!!BTr9$5Lf(y4=gEeuNx+s$Rv=&avI=nAh7OC zQvlA!F@{*ZI38zBQkq{Vn(a+TLI${m04n9KPSA>!fOn&2`%iH~wHJAV{iQ_7KZW+I zrTScUv`TghVW9jhxXER4i5)Ej%a>{)Ca9e_#bZGkgPVYKOXUhw@=r2b1X42_Z zzQQ-)HVjKj=lQ@+;4!+Nfur&E9J-3xea(P02Zo0;abR;b_Ie|NGvC_a-4&Xcs{C9F zH@(o{n`Qr=JD#=!ZnTp@WU1Wlj;(og6kKs^wqi}kldF#4fTUa@6N@EgK&r9tCAyGs zf$Cj)^RN6d71_!QY^lY;-m5!U;&y)0n2xq&7SI;QRAbP?3mI#vA1qobnoUE%aYtR* zhtHZgVLa`@!5Pvi|H5S|9(`tn-}QMR9I1H?EDafzys6ztvPqs~H8!vDYA=)f&1uG> z{}!>ESL8H(d`kW=(}C5+?3sJLf`KXElh4UxMwjq5d+Y4f<^UT#JZVq_#w@?vHVVH} zo^lyJOXL_6bDQZO;Yj52eGj`~%iLh!0X4p{y_jVo508(k@)r-(-E`>NxvO~^dY<2t zV$nt$161B?w&=5L<7T_D_M)9jQ3ULOA*D;amnPZ(mtK3_4@Vw4QWC7g7qG=;+MA5- z{gKeff%XQE8XYq4y7oy-&7dwX?i8cwaH9BS>kX6`U5-l|_K?{|JL8a9$!TK9=D&{v z-_m?o<6=(#3hqvfmpB}Fp?^Ga2VFEWHUH-Ux@r-y*aSGkGJJ#b^Dxj&3nd+1!|3S) z$z3iRsTQI`KIFyHo~F@{J0Xb<8*LHdrL;k3kTl<|GG6T;Yx6%2a|F;iY0wOMaCjV8 z4s_1$?6rwvJ>u|Wr&E>06Pw9pjcT7zX*|GH605>9q90L}Rno*`2*C#)&`!#ZHXo+` zDI-ejh`h`2(^eD_ z76$GmgzPJiR6rBqOz@cuq1qbK&8Zw@c9>|hyTo`uCuXMzW+zx2I=B2S*Ep!v{^AMS ziklMetHlEvmG+*_ts<$u+V>P!p7HXYYeGi?Dl?EB! z8ni}uJvCk0bABst(!KoQ| zo|cnZ(C4MqANP{(48s^9W-macS(+&Pq9rVZ+JsHA7rNUVS$Rl>otEOAyH}&>Qs7#G z#AphWkxMa@Aq&}8?y#!)dokgcBHO4~61On80CRY{UNyuQQZtWC+_0Jz>7()ro{uN| zlyuWRWpsI5ym2npIDi0C z7Lmh9>cmjl^$Bk+PV7abh(FRE4-Xl2!Wj1VgQgQaE>j)%rlac&j){{m<;W;Yxmimw zMy=&Q;KeHSKQPuU6pFA_tXQ|7IfEEM)B3|jz^zS=oAfz0AFYK`?dkVsIO3h{h)2*U z=G@Pb|%`kKB6Nv>Z0w8gf5wWBm_)}lBC=i zV13}eaof>|w@b-oa< ze|i>~R}%#^Pxu~jU29T)ubpY2kT;_aNAGYSS|6rtS!L9fn!rB{D9Fr*0vG8N0-gIvccd;I3xc)p%0S;`Hr^3SnxQPHKQVor;f9koH!;SpE6fN(;L5&QDI`=XG2SFa%lylHTAGh`OU*%at z$r_!t?wkD~H=&XLrJuzzrYD?EQJ#eSo_>0boVWiP{>N}_YS{yWo^nmD1vzZ{U(Qj; z#o=VP2%`lS8WUdQLq9-c0sWb9j)G9#{O)TVSo6}o2p%!m8Y2!ICY7T;qP-z8Q1K8tz%vR6;VVBr@_=z`S)Yg&dXVSQ~_606Yno zQbjDEYXlBaf!FQpz7=>7r-Pnqujv%S58s4)1b)8mp)@wQg_B4?Avl6+r!G>0X;;OD zTZY4#p>c$x@R!WRs%3vm&tGtG$;eJuH(5?#ve0HzqC^+3FNb4VhCw8<%Cs#ks^O;h zo9j@z;I;0;niv>Q@8G?T=uCSKGwk*B$I6X7YvL$#!=>AL>ttiNeY%+&@_pUmJEib_ zDRL$Y{=R&W8?*x;Z`Y40f zZl49%&p;TSr=BOei!L_&u~?DeD-7&V-vtprJZcB6_ikqpz<2c~`FXo`SSH@=TB^v- zxYL52ICdD5-XEyNkL*b&IsE=X{iTq0>zz4ZGwN}OXxC=Of_>y?^NjqNM?G5QPHOim zy0X^CUM=z&tr}IDmbQI*X-!B@3FheGx09Lz-y*l_3KhleZ5jm|vYi9%Ngv7BBSLfMB!c4wGV5s?@a!j1;tdBce+K4-G||80@bx zSmD>qMl>Fbzd&=oFxzlTP)DQ3Jm-D#;E>?78=&VWaoDz+i^S^(4T;Jb3UnvOHSSMY zEcO#O>)lxl{hMu@+a1N7q^G|(d2LO7kAOq>Ht?In%zTwKv`yx`C_78AsED(+X2#2# zw+;%_?11^I!M5+jW9j*Q)_wEM^uRf$;Bex^yUCk@^_@i=tolpefDLB1hlXV+} zHk6YtFOZjqn({L=q_oE}>*%w?o2SgaSZUd#Wx+R|pM}maE8Tal2ADGsHSRCi(s+LQ zqN8u>m89DWGijsmYXA1JRnsaLym%rxb=!0rp3}+u;dv2ZH%<|^Lh+pv07tD?eEoNJ z*kJzSb_N+?y3syzHqbmYPos+bh|sKL;t~t3{SFjz&;;R*dVUmbVn>hG`s;ZJA%AD> zSn{1E(n~Z}n6#MsELROhplgCX37F{cqEAb{P6o}SyJcWY2HZ-*G-lB(S>+rlhtpZ; znckFAcq-C3J~b*`xcG|Q4A~N)`QI5^*?|?x=tMM!J$>X0tpeI3N>C^WE1hRLT@2(9 z>mwXmawMk~fm({w6N+Q2e7AgsF3Px$#UZ@p?uos`b@0(J*3Hpc!1D`C-2YY!R-S7l z^#@^?KBH=Peys3|UQE=skN%gg)RH2)(IN(wR44gVHp;Z(=FwP>$RZ`3-Qd_^%p*YF z^bN`B+RY?Fh}1`iAdD$w_`4I`2+slthJ+R=eX!>KH4$__8L{V^o8qD+Fj-0Ia>ew$ z2jy6yk32xmj~W`6I5#`d?zA~VFJjp7L$lz;1B>94?%~B~uiQ8Lwd$YM!tL0>(i{pr zxSV}hSZuNGF7b|;=A)Q-J(zB9i)=B9H!*o^pL+SRm?Z-KbbsBNZwpKavq5W)vtZZ6tkGEKudB z1eQN5b+}@|)v?#y=SKL;;Dj-&ZoQXoG;NB_qpH8}uX972c21bXbXRLdL`0dxMXuBlTYlNnDkV=EFN08#(*%ffPTK!@DT|A9Zc z%vTRhyOV@NlH; zLLFti6hN;RE**2a0c0vKn+Od_+t&dH4^%F*HFMShXiwQ@x?c$St-vdTGb{uluJ{*K zDOQJ9V-cno2lt&$Azs^Hp=|+`-dx`q?P1F6H~>NUQc#)ALNZx$5-HseqSr0bECUL; zioMXNVHWPgf!K(m**-0Nrrd){I^SuJAD0epuVOKiH?!1`H+^hLH#Okac1=o=ZJ@8* z#v-F54T$ceTbS4cii-ho#3sI3-z18!zdh4=0KfeE0@;?S|IJ49a3J9E$Yz;JmlGS^ zW;fK#;3U}0NuJ58sxXiii>CyVSB|yFXjWb@*>@~q<1t&P%p&KM6D;L>QeOQcHou=IKTuF(J$ zIFd+Kg^a7kS18+ZGUw6C%!fbJ4W2cS>wK}8W}kq>_bL(&84_F7b^Dg#F2y&f7>6$N zU4JSQFf8;QY;s+)@VnKQQ?^L|=RzPlnT&tZ&VGc^w02*VrEDt2seI?WJlnppA+`}? zYx``VeZs`?@;Vjjo|JtkAO6J$nvVzhp%Vv*ztbtmh)0`&%lCZsclK0YO8D_2V!O!K zK=Kc4x5-jg#qwPomIrmo%_UiHUJs&CH5!A7r|n1`x8p|Lod1j3K7)kP1AAjdQI#<{ zsJw0FKD`yKa?E(DrM2P99Etz&9c#6TjHeLCV(F1=B&ADnU&WIzb*y=!=F8v!6`@9B zwq35A^*<5(5~D(8 z8|On!Rt)3W@39WI$u)+{-sCa3<2y>0ClFs`O#JGFr>-0VlceyZiblK!Zf%QSO(aB$ z)v$nPyfyxN?i>vY4Zi6wbI}NQh&|wrO4>*)-wavXUJj1p{?%Gc{y3@v%8@O4-Z0$; zQBc10_yd#YVbpKj!v|2sk>8lNe`z9=goWdcJ#qXP%~d^!nU{ryg%ux$_cq}3jq&Mg zFj*K=*8Aw~kW1FKcr=^^CfPWSf>}72{9@}XG}QySX$)DG`zY)fOQzq|I1b`h*RpWG z-ZQ-?Qr#fzj25A$3}Nfk>cpcwWRo2nlF0<4n%PPZaAi~iA3sdC4pvcPgoP{5o;6G>oFVS3}XxC@mWmHR58n2)9kUv*y;ZdRQ5TPf?c;BkUZhWT? z%O{9S^}&%GmPcg7i8OS0OsE#z&wp>uOFg94XpA%`A`A51JHFhtv%PJ&b+%GWt4MwG zCcD)hf92Oyqoe$AtxK`~8($?Yh1I~tOd>@FO%;B_SEwrXkMvE{emWdeDf{OLi~;!p z_`Jt0KSd2XPEK{Ne8&XmWa4|jw9WfkPUKJPkl_v)NjoK4Io(rD}CRR!mQR z!d6V@=~|7%IaP~Q5-(EV?g`5$}z|APwM&Zpn0Rm-2aR=&f9ImyH??&gFfI{m+WoNL$kMK}IrgV%%ME@uGq!kdUm`JNXycJY7bTY|?6heGSE1ZV~OHJO~`-cYt3%2yEWKnDAy5B2>*=3Xse82A^? zfx|(xwRqG5Dg!B@ygiCd(pdS#r&77;J=~mM>@pBXVtli5ekUGuBuaN z+#!(fjkS2SeAz}DIbp0icM3TBVeabgA1{)++8^>jxsXt zVctXFw$}rcIO^|xB-2<~oT#9z-At|bR)#}NXw0Fg<={AeGuxu*;8RN%H{sPSN87nu zU_YewZIrP$Jw3F7;AW_^q#S04_D$OMlK|4NGsUVOw3A8fUD#1|%cQ3D-Dn;_!rQOD z7kx}zwB}MGh6PnCs+8zpq*4mi%Ik8fvP7<(3KsNak z-)TE1eK*1}sN?J1J9X>VetWhcv-Z$6IKG#)Q#ZgE-ZJ{2cT;7#}zgpIiM~Im1;y)?8?5Y6XU4&1oKHR zig&w2%Yy%%zi+2_drZHS1O}Ck7?33^o9(!Lo~J`E!t9BRjujqKXn=St+}4ns8)c4p z&&c(7vHvI{=24|g6sk3L>6M}XQ!Wn*Ii-CezM39%oIYcyOA42-_LoPmF5v`8a0Nkf zhm?-sPS0X77FRep0**i&i&pf8-i2SI}omq05I@l zK0pNxlF)`AqNu8S?i$*(ek^8R5(S^E!u~`T2UbGLQ>m%n`R4H@QZM-6@TT-n`$i{~ zPM|A8hfa#8@($6^JEJS!;np;Zuv6X&bZ5;&4DA`8Q-*^Kw_|lp*bR7-)AkrB8=YR? z2rJ(-+ghlv0i;wDfS<1?=F(^U0xc>BO0Sk@o7-$ccWdoIfIG{@xR)f^&h^Y_^KXYW z-VIvvYAKaS!a!V#eXYrdUB;Y?>^ob`I6}8JQ}Td<=#@=xy;Im1xzfASZ>4e5ZKN(? z_F0>RyLhPxJOwf0#q1Rbi5lcv9;yNN;_%cbt_WnMtH2*`wvoNt?Y!ErqHwSvVj=MJ zuQQu)bag<4{ixVo`zH=z4nMlnxRmioL_xuqAZ7d-t;sk5e!j*z!FTH4h}je?9K&Eg z;*Ue$D?a<&2u_sIA0moefESg(MPZBTlc#RB^&=^i{CFq7AUs~M)pPxKnxRZK=RCLq{sjU%N&6W}VlYN=vJ@#k z&;m11laWIgS`9a3R~ztXYbMv4vs^mWE&(9#GOjZm8D>=c+VxNe@f**iw|634e=plC zS+iL`FmO(Egx}u5OcZaggb+UpHKbw4!Rw9R%m_Vs?*R^MGI|EjO&M)wz1a}T!VY!V zWOSEeTnWZWHag(&c>SU{iOf<~st9JIVZd_QrXcxy&Bw?`%ryt9%a0!0vn_uvr zTWPehV3x|Kf0|>quar?H(x^7~nG5ZBdK%?Q^~s`s)g7+wG9qR635AHyb)(HkZt$$m zwz?RNKp9&EdP$7*rSS6&wofMjQsS>`ZxvC7!JzE)+TjVQUY8sQ^O%ZyQ+-?pFjrhF zgK^X}Ual!y*T)A4OTPlIUGelM1Gu!M zWke{I*7{0pUWu53Q&MpFrjb9IHX9W`C>#j@v#K*y+LRweacI=__KmurF$Wg?<34umY zcOxCFJ@>^PT0J2%1ZT;xumHe&Sllb3g0Xg?3AHF*m^+5)aV70vuiTph^rNn!rbpaLX=g% z2xd2flC|H#-O$gCUUH)2nq##l5gIjI*8{~sBE$;MCX&s{ZWg}>p@DI&fpC-CRBlI> z2)Po6l@PMU0Ht`MYGF8D3yNo_Lt9x1{GTkBlaofRC=M|*<#KRai*~yCrjZ!HhjPQ~ zc$tiv-%4*`p31Q7AW%J;F(&(wp!Fq+-}rieOi;93QKLoPmm=6UVBU=)WmTa?7oCC? zp|A$>z-hM%#mL^;2v1Hhrm(((##VVvow8t!F zl_^&-l*0+|rHbM*O+}QFuI(qc&-H)$($KGD%RISNsyNYTXC4 z5;-`Mb!kr&UylzxPG8AzTZ@Am@zG`W4vOC9TOGf!MN3{~`s1Mjk1e8oyc*rg7wVl;!xPu0K_ZJgN8Pg1n35Y^F zZ%V!MMXVJ5he)4`6zZ7&p&m)PwVJ^e!~XD)WrQyPB9_%^`@z1(Xium2_l=0{%Y(5$ zT~wL=3GW7%5u@o@{e_M<_Z57~cP?Gen|Unfc>V``>z;#3Ncl+re#e$vwLJ1spUb^i zs5s!=^3~!9U-XH?2gwm`_8n}LrgQ!yyH#`SY)hJsngpOeGjp(VF&w+1Wgr_r~7Ykpb8Rl4k z^N0?AZm({GR>*KxaBGtE08!rZHin@CPIR`C960X8``zRJ{M6(W6Xlc3^F1AY z9l(o^b^Y#osSlfIJD|o@RZ+0B)tB4N z{V7c9>q`CQ$C*3g4s1AdWMXcQZT{~+Gckdola-}=jzpM;Mcp#(r_EuQ=ky+kPgt%z zbZpxj<~CZKk`6lRSO7ixj~AuTpybW(%q_sz`X|q+TCTV|2)-&a`XhgCX}v+$7G!#(3eU_uKhc$cZiRgD?`G-}X}%34c~Os?iyWM?vq$Sk4w7hN zLjFMby7`1^6!;?^k4>3D82ytkS3^W3_8*|}=4SOl0QvlbHe^QDC4QYgp0Sp}HG?2I)^l<7nT-%o~$mA(vL zj=tTaC??Yo<8%T+hNRg|5-cp&rM%J)9CkMQ721x*O9_UcUmC#<0rpQ{wqNFi1MQi{ zy79(yH4JqKEH&=W5sM9eVr~hWsP|qf#E$!B7N$ZBqLNjt$L#Y~m3Jj?$7l}Lo?_u? zOff?GDZii8g~7X#Xrg=p#B|7Uqttu%DUpk;5kLq?uZZ~^7{X+V;2|PlXs8g|9WD6= zs0UfCy#dT5&EVFiHhJc}h_(Y$d#MONs+T@!Safvqk)e#qo^Mfev|J*(f#@_#p8M|~ z$vp=6hI2?lSIkV;`KKGN$J~^gtlvL8WdHveiMZl=Q*SnqWikjt&yq|2@o(i!^`o!x?y>Uba> z7bo8?QbSNrGoQCN)i#1XCR7`4{$aZ^#Z|Dd?l}Ju4vnKKlUb@b-Xo3!8y1>6gu(S4t;fX-l#6=0TJrq zvpxd2VK8O@ziSqy)gXR^2^ZU#+0cJo^88_!#6T1cK9<^Xd$7?YMzeXgH2BxYYngM8 zil(JZKmngq?agARA2_AI8ifHb@EgiP8-Q0ODueIv=nyk2y8W?jXW_gZl~kQO*wo{M3D6(X4u#cj;n{ z>GWDg`D1+3qHuQX|0DpKn4ibL{C9P8m?&RU@FlTC*Hd$1ZAm({DKc zXWPtavpq~si$bXiBDN^DopsSaz}nt$aFD{Jre7ntQ&l#m&H z4o;g776G4{hOD=Orsj#_B8woWKND+QA3BIAd51ccGMmR8Z5O3RVM31BAE-`-%J1wGR>fGTiD zgqs0aF3rIXFQL=j?BEw4F544dGsb%YrUW_y{4VT7?nurP%tjzYFR_e?DvoVdbx#eIFxmb*=CduSUEF@*;pMJ$jC z(H9n%oT8fkz~jaKg5Thq1!6^&?Q=OGZlBnOx$>#;?v`I+0~D+#%LySP(H#VnPm7u?Y{ znIwu$RIu}0rr<*4rt*-Hatm|IU`ep*vi?ncmqm`Fu6;OHG@OiQFl09egMzW(l#Om- ziWdl1KSM!6CLxm&ld9H1WvNSaw<`nmkrfrz$6bv%GNYKj^{tnOogWjBZfALLHBn@T z8s)X?^pWZ(1@n=G)3s)#uZqB?HH--t;S38L1nL-XwBV9L536WwkSI!H=UT8`!;ex6 z;FC|+N_h&PCV1uS!QUfC1m`U0-?ib8sR)z0M8K7vrN+S-RY&+`;p}TmAxP@nx1zoI zJxp+Mm+n|~U9O!U`y|BvmKPM1L1OTSL=&J2EDrtg9hTVD&ljCWyoLx}z8V8f1Og2r z?x%Q_qA&~+3~LmUq~OTK#_fAtjsV!QFk0@TPnHk<(poBq)4^E=7qgkE^tTbB>0!Kl zC*Z>j13zk_P-VIz4Kcn1!E6n;_~1{0X$O=aXcXXw$)R4WfMXQR4bwE8zzk%RJ%$MM z897rl52f+>8*8i0+8lBd{N9R!-e}+@U*hX3 zR0Qp{fQIv3d6>t<^(7*LB6==%-ygh@qB)9SHum+Y>xzbIj0J zapdG9G*2G3FaqATAa!`|NVasLT~oWxU+uq3sd$VyBL&$jO+zFjtImIO8m8CphD)WRBtE z`S6?n%L@Q?$W4yD_RcXI(qM3S+B9`uD)zkb$wuz|N{sh5(P$0j_k+xF2jMp1B8fV4 z)W5m19f&I4iIwU-)0>jXhj-y3ByRi4-I>yQJ^hiohHi+H5f6S6%xjIQ6$c!t+4@xk~xEN>IpMQ&ryLsaCP`kMV`nY3jk5^=lw3$E!Gg z!e#q!vt$+gWMd2F-yGR%g7prCi2(rt0tIsjgH&S6owQN)l1&CFj0BXtBoq#bdnVPi zwD4*se)a78N1ep=v*Uj{R>h^txQz!-#;V@>ySu&;$kl*@X4{o*a){d}sDW%)1$#EZ z{PUX~ZJ%%g(J3X~&7vb?6ZSCr;t(^*%w~WilfEn?_(UTv)K_XiGZLKm7o;l(JHxTB z#r=B6PZ0qe9Q>DN%(UGHJD^}!yWV`7k23gQFV6>$*gtVHW*in8uk`;_suQtUS9NIQ zsBBsZt{Je<|Ci+9;RgTjoaG?sw@*+>X7+0HWjSkViyj&FLKN$axyL5?w1zklsl~bu zK-j6BWr&&>TDFl1hE4Whz6SMjWzkKSkdD1-vfMVEDy?pJAs+e)LVNJRfJ7=3lo^~+ zpNDKt-QlfQbL}J^Hc_`>am$wB0tBYYrI)IzQ&wUCLP-G6Y32z%~m>iv3Xb*1^`#}As2hpTWx3AXmZ zxrM00gJra2cFM$vP(in=RLdGV-BH7_$g;`_<5FCE51%dn6}mj-JkEdzjhe-mP>bo% zx4gZ&B9Qrk2QJmXhG0@*?86ey*9FOf^ST-Fckk3e!M&H*8|g^0Uj06VgM6Lgx%QUF zhgcBp-MD9L8lBnCke;9{rdY`{?2#+5^-*(3h<&*2qi{vBkWl==fv`C?zkC_j>$BD# zl=Sd4ZzvIa&0vv$$HfasOQGNuks7_Mq=8g484zZ$Knm8?paWWV{AGXNBA|Qu&bZP2 z=LSz8L|frBJ1aC_8hDv4J0#lr;G}J%q7p&bbjA#ZgYpmO7wbj8qZ!MWc|M#^fr}cA%V-<^b2hewAvI-9&w`>7ZUna^q3oOB+nf zlhcS-rhF2?q%|MgyPCx>Ar=l8U>iCk1fSuf$}uN+I_PrErRaH8pm+(K&H0=-NaoD$ zm!o{hqrK9J8_dNeBqWxKguNcU>jOuzu1T>B&bB&S&+-;_RWJXvoimVo&=~g9?rgL^ zTvcsNuxVyF5xEXww~UlPN`%tTE94Tr^yR_>gpbyEwQHRbVg=M6Z`?teZymm7F^eoD zRK?TBBEpxO9PH<@m!VL^<;Ehz1KnzmpA~M#_5>RQm6Cjk9|(;VC~4yl1eh z?cvUrb>6jYLbWVM=~>{z(NXc_Xh|MP#_gfnS9mL=CXd|0oZJe%M*ptOo&2tsPIlq33IpY zM21&rjDts@V3XqT@Pn1nZe(NisHGL2h&6BO4G|}hSR!7;pnXeZ z^z2?&v8d8x%?Bx>u`tzK>k*rDYF`s;~K(oP#i399TjpzJN%oOgEG{y*ftknbc!xL(F z`lg*Ob4m40s#VW*!-IDoxH>Qj2dqTu1(&4cZw)zt-604imE_1U`V#?{1dD;~i{A|x1bg+XVrBR|`P$v*9x@|45kukf z42(Kwx)hE>sg?>}Ql7N)AmDhd0z0!MHC|zYz)v!rwPb0R`OoukmVKe|OePx9i()?W zF7wo>1JNVAdx>gD9&ZMym97~VTGyf`b;idkjc?qM{E(bw1JK6HJ_OCrTvkg7BFmLo z7&Aj~Lyw6~z-4V?p6D^(P*c-={CSgAHcvDN$GSl-z!1PEc2ihWRaMro>5PQQ5i**E zji~a}i_7pjG|v{O6R}aBP@(C&TQrqXsiHz-v^|V&U#CGItIO(x^5w}n{ZP{CX{*3OKwYW3`S$P?Hn*GK zYeXSieib^~+zrRvgoZABBe}nrD$FykgUYmGbo_&XBCo$ZAtYqP9v3fu2L%1-@ug$= z4qH2OFyD0py#RlYs!~Pwr@_|l1>`yT$V|= z_zcCb!pCYgHON!lhaQ@?2Gn|?ZHYeGev|nDSt{lC9zUu*{CX#^*N?@S{Y^JC=Fe!1 z2l{D{f2e8P?k$VB{OmDlvg@w=!V~`3;~9$%5;b$uK4R&Jh4kdc55%sx(V5;pWK^&7 zK*M!{9dD0sMGdU&WpeZROo;1Ja9&FI@JD)idUxkQ&)g9L&N+(G@c@3DVL$IKO5{^N?Vx8QvewO?F%!>r=k$e?MYxro(SF2Y61>D3R zEjWI#f3&66Y{iNGu{oWIb2-pAUiB_o^zieg=NMiWNOC_uEGkOQt|90COoeqfyzVxx z(Dsg`Mu#;Pv~d@wYM0DIwVu;t$q3fE-oxf@j7g~(^zKN6@jPh(#sUR9UA|cU=R$m&PPfsaE6~jSWmD*LG2Jb1Ti|E%CLCg8;jhWn*vbwr? z=FV-|HRPccEBN;(NPcFNK*Z9y5lhTe1^hnbB)2TNr4u!jUs1H#QB-C10gB+>s6KoF zK0T(frz>$QI_|${W7VZF7z0Y$0=F^wGNUV1Pi(l|xIba$oZ1-wDVRc8k7E9^(y#p3 zc;o3KQFgOLxzZ})p`d21g6vo62~Qp_@D;wp1INO7TDcxcTa-Pa!aYY7<>x+IVlBBb zb5%szpK_LX_s$Kc!pheumMYhq+>`CuNs$6ToP@1@6())gcn7W1#oDT}*S*B25h$?c zmp;)!cMJ0HqR!!1=Yq|R$TC_eAqU>wF0OSwdwz1X^=Cq`6^NSKp5PCQlaI6nZ^_!b zvsve?xg!`|M?(J#YZZgBI75f05d3ZcN6He4)vTb53N0mJ*mpx<4~H~Ms_207(YJsX z62+9H!_SV~W0=qS=2M9(ygw*(Mgt(tk@Mo)Hjzw>-2P}q&sTKIpZOalklJroPpDt6 zsH}G|qVKK`MA)h*9Ig0W$Bp8X>|lrIOyu>TGZ=g&%JdF+b6p#7mLC6kQI&^c9Zy64 z`l*iZEwzKz?liNT?D}ddAz^10xpbAtCW@F-0Bp#3thSy~q?lGh^7D@+c4tz}wQO*< z9CI8h$O?t;lYbgqzHIx9mgPGxa3p7r^W%&{s$LKJH#xlC@^H|V3pkp;eT7Jsb6ae1 zhYALt)Nam)rJ#sShKJohVg}xd2SuZIg&@c}`o4c&UF%q<&=zzjF<-0&fBT_j$+vxK z>~2h?M6q|Vg?PT)s^P)OqM=9s8&hmbh1Htw`n!$lT)aDrwCj^p$CM>Q3kRyk21}SZ z->Fd#6q-R^01i{9aUL7&m?RcU+K7hS#OhF`0X>_gbgec)U$~p^i$~Oa?{l%3hn6D( zEG)zIw)xKT%FJmYuaoT5;`^MamoM@c&ikz}y+G3qSRXD@J@X+N+4YgJ1>Ff0>DP#w zI8}h<&}snG^0)Z=?Jqu@Z(tPa6MhAc0fmiZQ;X+zHrM;Y6N=v;ev^j-h5ALpfGyN| z1e07ux#?n$#v#aBOz z_`c9l-=4>*L$rT~jWeu0c>89c5~AP&`N8tP^VJm(`{~FT+`%Lz7vtAZel<=46fKC= zgos^wU@Xl8smTQ##mqAJt~hY9mD+a*N^Aw>U_)ij@H5)#lY%~{W@9_70Spi>#h#L* zcKJC~Aj6{Ki?i7=*qek_SNg@1Ca+j$P7rq@V(^32>tlQv^9Iu_DicjLpA*4ZD8e6t zxkyGgNVl4N$@)G5u!b9>V^X}`LqY|@jSUQ1ObG#-H1)!wZg)oVapG*DYsjSLWO~Tf z9hfEM4-+=UjJqM(fWN=g^o8$8LA^ku@==3Z)GCTO0-ve3d0aX*j6g-M9LRAX zX?@A;vbzh>lCq8=D?oH77}Rss;~&{q2oDhV>M_ihDUMDCGotZu#+N_ zI&hm_uDmR3eq{%WZ45yOqakqIG^}FhKuRD1TdjAdX)_9>)3uRFLp$yvC@N0w)uL2S zb)Yy(Hf~N559#2Nnt-V^P-rxOlq_C4wuTSc{mCgKQB^z60uNb**GqmM&bHB>pY3kN zN@{4;`6Hu&;3-U8Dee2)CcZI2DL?jdj+cbDfth2Eq}TJV9-`Ez&U!4~B#x?e{@|eB z&C$sEp)xrOhVc(ub($e_f3|<*>NAmf+`;;+r}K-eF|OgggwVawfiq#sd-H+@Fo>FW zL0`Ko`gV44dO%hJZQtIIGh!dHgw5`o9`v8+D`g`GigvyibY9kX=%dg0x`o^5Wcco7 z_Y79K``V#la*ZLInA)p>BQ2Eks5)7w;F{<}{r`?bDJci07M6WcMDa)v_->miBsau6 z&1$O;oXr_)kiG1K01LS<9baE6uGp^g;=JP282FYg&>g}EF?pE~IO^WOmw_3a2WuLq ztVhb+36ACrOb*h)Z7NFdXsPi0o?08bT!tl|8YVBRgD+L4yCoO^LwC%pJQU|#~k z?y1{)yj0rDCudc--PTHPjK<2((NZbH+e13RK#X(}z+fm>pKPmYr4ua}sP#%m2LIK> z=t>-JdvauEONT9Br*YysyaWsHG;7G3p#N*)?=B$DHt%?4t!sYF0f}TyWi7M`cQFAH2QRf9^ zr&n1p&>0x$>Efj>>GQPhX}eo%zCV){4UWh5MV)!yHK7=$j0QO+f?pc6Mk_>W`&h0< zLvCEN)1i|UM}O7Ph)S3I+Ys^*Ll__Y>w^nf*bO7>gZjeX#W|oqngx#t@Nr`k5al?P zEBu~~{tsir%iDOdwUZc7U+MOT`RFu`+Tg6&x3t&1Zh_U0S@c2HKG+%yJ@&u9D#n4p ze}Nz$Tm6%3%vV#956QNcEKzN*u(2UvJ}-hwqdjp4BCZ6M;OOAUdqpK^*L&l}n^YLJ zWe$VEId`e6^9Hu5HMoJNxu}_OU0|kSkr`v6r!zz#>~s7c&zv~l8s>Gq7<@3^@$`g_ z+edFX#9C^9UfiHuTM{JaX;0Ffx8DBQ5EaC!%$f13yFQTMeYTmymK1Xzo%z+daCm;` z&4%5T?*_U`YW>fa;?DLuW0X&ajou$aq(wEYnc9y}O4(zV-hko_XX^~xw^R+|>Qhs6 zGCt~yQ2=#b;A4h8#u=&CS7P(R>wgFh{RS)HBC}Ol_(sg#3X&agZ(VwRt<#z#{J|HD zCqJZmy}J5J_L8`J@NFH-jsZr%>jKhT>_Z)7q}atr1?(C^kE)v|bmM-);K;jA@7wMt zVky>_p80s({5M3Jk9P$=^_GrActsi9CvwzcyNnN0n4(}Yr-qJ1>p=2u1ymQulxDwGdER7{$2 zz-PhhN!iJJ=w6QP3#Xkb0y1@l*P=`4oRA@Vb@jZA;qWE)R@{cPSF``hS(4d3CGw?(L`tfdO|VnYo0ENMUDrs^t;9mp zrWGgU9feEllab3XI?HnIrRqp5^c~ygQ4E2sH@t=+(A5@a9!_E6(PSG#cBMuJIUo z6N`wmMTZ)gO|5W#cNkX@9)dhPTr`2SadrMG=-*pO!Jm>pej9I;B`P$LL9Plx#h*gb z+~pp(Oevl#&^oyC?2Ir)Vta=#UQNl*L7b}}*9)F1oI{+weOx>DYD)1wipMriRTmu~ zA}k)FjRbBGc1TwTE2)mLk(Bfs(eh{USL}CJkY0+XT-DR^xgXt*1(#pRZ|?T;n*fLC z4X5{KnEPSEx2-8e3?me9zdZmI-zo(zLTq06Zccvfc>>E%!t~z;Gk{M99eVZooD|b1Z=sxC)J*b<30n$Cgjk0jKpxq_=B%-& zVIJAB!VPwci)2JHaxOsHFJlX2OHoI5!m~RgsLa;V>=VmI3xf(nviFBw+~NQ^SOCzH z3H|aGbAaM&I85lHzlC_R9pjSMC^>X)T@p%zFV+3!6y&-~7FXn{Pc`t221v&4Ld4yp zy9-${R*6Mp%o0qWwG9h7z@7T=z3>gqj9L8?u--gu{KwRd@Gt?WO5xr~WArz}*xZymxuAYe*1X!RFDTb~rh0ZXu{Q;LnQ-BCI|FlR zKB@QBhiPkim*~F>y>X_DqV`UL#A*lL46YujC!R0K&KJsSnW?(nP3)v46c`&rzsBGc zVAint@IUMaDM z*6T&$rXT+b$90TD%W5Vc@wDrxn!0=yDJD02R(U#i6z=+;YF32?9UjlcSb0BkJWg)5 z;N7zMIvPtjq{=HU{&K}cZ9%NLd#|D7s=F=uSgq$n7l&Gh!4zM<+cJB8>#ch_CI@+5 z%0@gz7o&^gJ7^W|l^=Cn{-NiiAi2PjAJ>mWYDoz_U4CAu>l+u*=2XWh?HwOQ0tCT# zWIBIurduqA{QwmXrR?nBZXHzGJJop7J#&Olvm0;LlckMf+ldG(CEqb2AYer87{yh1 zvd5%EuIvzVf}+XlL&OM~(Uwx&O&fuX#i%T5+x7qNaGd2!?rr(%fk1x9ZZum@C9;N) zE~)YH=2D++TPfa?L8z@{nip5oC(BSvFK+HR8^?AJ0!8py+l6Pu6VA#RHaon>J^3E9jglj8II z3&wD`XE{nob2MKrnzofS7t9{}Vx^vub&)wa)LY)wiY|gPuu0hNC*pgJ$;)uCbPncL zQYolJ?9 zO9ebT52|>3n385oi9aiF11@LdLfz=Oai>ugH(SyORWS%!|Hx*mxj%Y8?-<3C1r8VP zmxx)LCWf84Q(zNO|@-oauNv%Bp$ce=KnXq z+7Z7#&%bH`{v*g1T_mMgm^^~Mc;4&XTUZPQxxj9Ix`b6)pYTpu_&qnBo{Xu@FVbUh zXjoWS2q7osdvw^Jogq>t(co6&`NDmp*fLE!ks!?24AWSP1D*dJ`0USf(SL`}sMANoJq!t#Whr@GG4cjYh+ujbyizXBSWNK|yG>~9M73DPSg+Ga0;!wl^A5Hc^4|u8{`IvRq3S-GPhb`X2;w=^#?@dRk;`uNHNd$+fl&eRNDC z-bz*Ml5ialn3*@{B4vU&PG#xHLkD*p=z4td{Ok}V0G`l}YBNMnnz&<~?Wq#;l-{MXG%z%SC+4zfWTS#^3b!!p5c zP<+0yL@qmygdD2*+o&uEG5RFSE3Y?kUlWxciLeuus6Ya2gDf5;Ehc1o5?ts1yjmYb-H#npR1VmJLaR!HD07sXv}MOguvCfg&qELtq$_{+1uKOnI9o4r}^ z6~%36&KL~c%rae8;SmqlkWvl=K~OV)J*91F$B*vVly!u>3b7ue3C14cpc;^=7XY>NTCaI&e{ej z_^_v$mjyQ~jtKD7KXVtPFZI4f)9UX0mf{af1l)V=(l$F`R!q+5(?^lgs=L#gD#74K zX)ym$)fD4;b}SNZMg_i$~2sIyP99gggt{Q_`_8IdQ!skzbC~c8_b4vG#Rn(*KrX5Ny z3ADj-oH+MV5zVat^AA`+gL*itbB$-7lqgo_s}I5U`KgEl4xZMdJ9b@P41BpFzH-wC zZ*}7I;$*lQnOaT93MwP?=R6;!O`KXcA!WUkQMSomZUy;iMTLwoh+wS)|!CObL53yKSkNEv? z!npBIE!FiA$o!26Dc(bUY!7$N)#IR;)jM||2IuX(SEd%4-fBBAe_yVC?{t>D#-j?C zuT=@-`@W}Vh9>$23~t2GsiSOg%q0e=m6Y81KyRE5oehD4GX2K!2px{ZvnZg_;F9Q7 zve!NdcU}2aHL+wG!RX@-YVO3`)KBZAcPqVv(Lb9J3S8Jl*v9XT%+r)>LHhk(*$)xe zJgRX?U5)k3l#$!je+6R(+kpQo2Ge~E@8J;qw;`ky8n)|Qw$`ZO&fmbg(-AdodHG7O zA2&2YLP-VZ3k#VB?( zI-M8UVg0`%uw#a&vG;F9PU+#OG*1wH^dGJG75#P3*I$uyd>Iwj>Z6lgV{yd_Md+Wcsvc%!^1h)DY5_A!-U2(L%p%h_Ye9U1M7kWVb*zWo|J;iE_ zueUK}!_##l@AvO6^}LVh@XX>!wmXlCl5cz_dtRPvyp*N*SAvYJcXv2H)Fjt>4@$o= z%eQa)#80smqnPj96H%$Xdx8R9O?5P}T`9Ro2>(yXPshW3#9%sKTxZE;0DC$6myB7- zmQ*%2JU*S}zIAsxhih<{@AiuqA5!R{3`2FFKhG_Lpc`8ZmlR^-Mcw*}1H0Bw@_*<881GcT{|muC0ZPa_-HKa29eds*=Yu$oOoPD~hA zB^8+`{RbfBr>N=14Vs(9jaeoxLm+f?8jCEkzWk5dqUhHv*P%opZTJVdbe{TOh{y7p z^tXLfj~uGlhx`%Q2S&M?}ht;Gy0K zI+4$HdUm!Js;yRpRAf&iXS?WH?pupeTn2^gUQvl5J}T{w3sCEm{$zi61=CtSwr*@Y z5n?Wm_C13|^}YC{J>#r0;rpwX@B0I}kb~`JN{*=}u0NAF%RIaP!L$0e=UT^y z$J0#qgz$)opv(0tTw+f~BAxe80hDeOL$-KF{OGm1Z_|T2`WpcKh?Px|2?nw;09X`_YK@vw@Oj{kDHTTgguREx&wGI7|O6F;o*U@AdAF=VK_SZR^c8vG8N;pL% zT%GFp4WHM@jZQ2n!HVRubKpdD!p7MRL?+M4AUQt(4kt6M=Sul_DX}3KQuR^!syby4 z&UfJNrn+_4GtE;4)*3aDFi3-LZ)fDEE96|uv{Y}JaIB1bIePwk_FmYF=wNJw$7iyB}Ka*DE z{t*9UXRR@`Eb#fBE~1nEQvvetjCG@6h?|#;lhG>Bot&d&%}#iO*K(h~=%-ylhmGgMsqF6d^4e+clG5AHaG4I# zCUxqvkANYi#ApDrqCyGqqcq6B?VQ-4{_dR2%mBtj0OTYkpWlsV6pqzglE%cJ2BG?8z9D!I*2zKmXJdZOqG|5iGa8A2SbBd9HReZ;%*$P zB_lc2mDIwm0==_}DNT4W*MlI2gqb z1P;D9|I5Ak`PQ2&9By{P@_;@bPKOQ#5bm5TpmCSKPVCg!_o$b$x8vCW&jDWFTQZT z_9pQUd1&YbN}a$T>d@#a)T9tM#(v5DU$v&AJ_v|NIMgoEkd%LeVroLdGwbbqNi%nE zmbR}PM8t#os5JRmqvVJPQ@eivSiL0#=vqNLZ9)cX<`m_%m5AHoZkJon%bG|*o-P&Viov*M3}UR zBycR`Wo3J0@-Rpw3^gY+H>pj=!OwKV1|LBJ3E6ELiv26GEL)v;&pS=hw699JW9H1! zDR%!ei_HI?{Iq)w^u8He#Gx*?MD(6axiAEWMU|}o1yYe)L#ylMC^%J}H-Z$CTPpa%9hhqQkYHWR=?6fDyr`Ok92d?kHh57q;` zt6vVljn2e~Xev(XXo#W}-ctW%amf{uQ48gM)M=S+fetwy_T>0|lNLKf#$z!O^(-iL zfYDd6(JJoc#lZ)h>}NmyFbr(kcKxe~0ajOmGwZ#fEjlGI0fuMnUjoydMk@xFD(}n@ z+l)V*!{59#(7iX_fA23Z&@(RnbqZ|S7Pzp>a16g$o9Ck_ow1KWgi%G?@QB75F69>$ z$RE;Tozkl(bmIRL7p6lgow8SGyRnV*w7vhLFY297n}|O0(y0*Qze$r90s_VJfquIn zwn00fed9l2B7O1a{!{XQR?cs8n*gHmzHqenc!$5E&3Z)mTm!o(aP~ibZEySxf7c}o zzJJNM)-?t~V10B-r?EJ0467Tn@0eqaV3GNkG_4-{zrT{>g8fNfjL9*2SHM^Ml*IGZ z8B^>&XpT>`gxL`+Jn^-+F^+WA$&j*3XO&&$e@?BMuPT`6>0Qw6>oS67m!9Wvm|-AE z4-+Sr3bL%-$G=n>w@*G(+H~%#7oHXmZJly@@&bdYo>#kwwv)EjUgtTNHemM8f-|=g zhOpSR%5KgI@g1>_eTRCT8-*D@B4y0V%Qu3?v6sw95m_@kja4h`<**pe z(E9fcD_ATtY|M1=8}Eo?BS8w~#{uM?O+1N-M!+}U-@Zdi75`Ik+pzlu&A%>aV4EL0 z*!;pZJJ4~i?Ak1@3XIdU6MYmXYkn)`P}V*cT#ogK7%Pc=*5to*5e&*q816oJ9!xVM z^0oPIdX(IFyKo-%0ZoPey@_B+`^^>2bH8J742>DTSHEW>Wst-*%J}iK?cTf7owV=o zB9Z95Lj=Xai%$+Q35MsJpa6QWa+jB$Z8Mi8yF?V#6pW`c3hqUgg#H@+hb3w??;i2y z3y~n7x{TayxE5a%tt=I0yKj1RYL}1|qDKuA^o|Sm1?iog1&6xVZWG7`Urraj{6Zzz zv)+)H*mYL^qs-+XUhtA6Z`r__cyLe-dpWOAA$Rv`-rV)q0gUgHk7Z2!F ztjwGi;T&oT?xvD<=6g(B+1hMouB7&sv{KD>fc6IPPX*3Laj2#0#TUq`6~LV;tiDU- zCxN#U(ZfmNM0h+ZRLxKF(zJ$~E0!ELWGD%vXR^(Oa>FwFuC+0k^Gkm=;mU=`bfpHO za1Ix1!1h1RO=J?DJOM=+Z#bKY`g!9R+O`Iu+UGo|RXhZ+>~*;h48HG3oJ3hBE4gvg z!I{$)7*sjJLHXk4C&n>Yk}ova3I$~OZ$31x-V7r;Sk5Vk)9n9$r2S8vO(GtnQD8Uy zH9G}g@F=MzQCe?~N|j?BG_pr|jrcF>{$s@dRo#D?KXMTMg(P2w#~gr8m*YZ`-P^Q{ zE?!mInd#)dZGb0FUK2QAt02$O22ESZha>O;GH6sA13yhip-a<&-%#Oaa6^I zK64x2dN-8?n0=Q(%9<2|yk$rlK__(`r7dZV6Ga;l6gR$AnEw=N_bp6X@k_|9-&EY$ z$AN)#SN#QDxjDVq=w#wB86de3#)bIb8+eEvh#lb}gI$o*RODj0ASB|N--=$$B;;kx zo*o&^T2#AJU*ogO9lFX6KO748jY%YPe&m*(7#%%|ft#&H(#K@ZW5(`5EEY8TY*mUT zo{5c&7M>~aeRa>0PT7heOi~GfdSEh&ABD_WrYb%mt@^!^B7?t~kNh8y+udH zic*jLH%XvvxNyGM^!g!%42*oD3Zp@|=1qBYelQTR9=-)MR-r(QJCx$x#LP&PoHiKa zOlxn8OG-oYJ(2ZlwcpU#y-gd0ieO(fG-6$m3lLleKGY$9)YH8#&^n*}>WJj-P*E0U z@zMgeVEn$46bjRuZdXOko}YxKs?2Nra>j1`k99NODO#$dqBHrY)Gcld-pFg*$|-{E zrT)-zhhpQHk6dah!tMb{7EavELX%VMDw-)Gpvnm&iJ*XxuvJpa*cX5jO&S6zE#T2k z*QP}X8jfkAy+$f1cbGcn>f3%2&os9|rI+kpt0P$;A`~qeitHM;97y3i)PPh9`Efv8 z^{PQkNV~+C+n`3tKJI608~+`Kp>LgXW9Nuaffy^O5fMt_#X}b0|3raZ)ZBMEUvOg< zb+VK~OBK|FmL^b+)=3Ikv(fMhi5T%>~8PEat`b1(NO4L46aZ_sg#g(&6Wj~k1slb#8 z4`2x+xH3!9ve46BN7!VgQEA3Q#nuW>Veq&;R!tR%I+Y~8#Oda8sab%gnh7i1ThP%= zFV@rXN<$lME0x4wRik&FMMl`sizqnZSw%Jlo#}0<-li%FTVXUBNg?zAfq}S>lbsXpa<(l5JXRa!bp7fSvA6=1lX$IMnpw z<%>7FcV+Fj?EcmA6u? z%jWImASNyrP` zH~hG8PtZjTC{OM>IpIbf*Wrgm)zFzqqja6ZUKwoFT@67U-(}O{cPmhKskuIWpQ7M} zf4|`DU9cVMsJog%_z{JgzIQgCy6~~s<8|Fa9kZd?9~}D#ah)ulx|~Froh7?NyYA`K zLO;KV7OUIEnDm(_<7XcmugMv|EDmKjbyh7{onBG<#skfRz* zDf`dTrbo-?YS$J#+_;}2CtaEtH>VGNKuux(w%(px)O_*31C(JU6M zCKz?SQo*9TU5dN05WAK>3bsd?m|2d9gJ)c<+V*0$6Y0$2 zLp}*bT~I&J-%qAWuq*7gkPGZ90uMolN$ts_#R9oqA4u@ww2U>9Ym;^MR~XC0x9=EO zXw{rcutD^cs!siC4XkrGC_B^NOva^l5Gly zOdSajVW-5BsMZ7%C6xB^-(s{B>iiFHUff8flK%uGWfg4v+H#8O^nRvIDdNCeO_k58 z+TYv)zk!|0D$GBcgk)MFau%IFG!RHu<7mJ$y5nFrq~NmT9};>g8Xc2Ts8Dckrjthh8xlze zG~@$@F-wTuVF=BV3qyW{k?74G@85LVV1S?N0bR*ieU>~V%2$B46=R4`SV>9yqxkSJ z`3MG70Ev`Lzr`W~cQ}yk19PePM{kg>J~h3!M)KDyIz;>xd|%2Fn8>BjeWjD7TB4=b z_uB+Fub;UJ`x&c|8y5L!#D|pdb z@Q9ilY@P^Q?Y8OiILDl5E*u+Nn}bg)IXo}1V0r@GeJg5y;lcl3+4PMW4D&pF5(_VoynuPhzdDjy-Gh2O*04&1dT3I(+&2ks>CmbrA@Tw1qqCQ zHps_)j7eHGSSa?55y6GA@jP_nP6!*p@Wd6X{5TiXd)FpZS8b4vxqOe&ZU*OLX>AB>BWIShnqOK^$WDQjx29WnAM#RI)?tzED=pIgGn7WG`=GZ)s-4;5 zsk%2zgB%AZVPyH~L-K@N?UcGSnq-j2i6iN7MMFpN z1!F7+K5E-a5nlmN!mhOb+yi=`wvN7O+hD{T2)o>I%Q7{N0y>!CHhr!ve+K#>R=RQH zS2iBVso!fyGLOSP#T3DdZTsXc>vLud2HzZYLb`rM{gPpNFdzD0c<8^Q4-pR!m(X8x zOBBZg(^oPhk!v#qLZKM!Sk3X;;4%ja3=A_L^gdUy)dIM&I^c{)IAaoGBZq*P)&sP9 zm(7^TQ;LU&whu=ss7jYZyOV`1h-$IR(zw~}+Z7{a!0)`uxposg;-F0L^f-JF zSCsMiJ{aW8Z(aj>D7JB9r=sNm&!a)kc-?*F?Ge2pgr8l&*CJwSOxb&g;cXkfk&;=- zRtvD;V)T{X2Mn> zR1R;@DWzEYH3^WD`#@yJo}|a8+ws}&_QIDpq<_$*vJM?F7IHZGhanp)G^M+LOFoFq zZsr6fR7!bMW>&bB%7R1x;w@&9t-q#lXnhxP3b@N0>kq7A`ly70>s3vG)5?r51V>IP zMGC&E!DRfla#M~K#c}G2s8VG*!J*o1cr?R44~L@{;vKs*12LW5PL?i9N;3hbY6yFW z2v8T?*6nHFc-OpuwT7lbUn{_XV>=#9&cZHUBS-b+`Q;~CS5p4?CTt+<)5ny7n=_Qh z<91osfZgd+mCz3yxJ|5gt6F~NWpkUec=2ECH9?A96=bXkOgcc0@9k_=l-N5@k52Vb zf-TU+ecc_JqFWAWf}MKgrX8t$2ajc84$G;JN zn72*;ea*~lthZdtr;N#9gxw7gTc?0Jm2Xo2Y#sFjqQw{6_j(xJ;8mMooud(VR~VFWUvTo z1#Rv~_L)pDyvt1u=n3GG%}W*P=8=14jIp}`azujdsrht-fJxAeopZ>11E^l^jR$Z? ztND-6#XADM*J&-RwM7y~vhjznKh?RhN7)}mri>2IPFn3)@Q!Qn+!_>N1Xf3rwZD`s z9|`ZFA>1tZ?5Ub`Ob46Hjew5jWA}Yp%x_NLu~WC&_ZMqc!fjs8PRXuz%Ve*+0TXVO zi8X`Fm>>V4c=F<@>;5W+jquz%j;P+xoRLhtMW)9LR_$s+S0^;>*Ea*$Rg59`dp;B8 z3z~-O7vHp>rM3?eN~*Zy*u1+O$3SM>EG3v!pM!kF1Sv7ksJtz7o-_Rn@x^qu;l> z?V#K&EF|{r!*?bVnx|Mf8a(`*D%C}}sYPm zzxWA7ZQ2kUDWCs*!I9c<3%`#L(D zN_0xI@XcsG7&a-Oov=G?>27HMHC4jPD8`K)Q`pui@s~x#?&Et0fh=<*s0mX;Ew`Sde;Sl#{1-L3(qBn$E`qXWRYOk+L0#Vbit zw;6Xj!B$YXq`d6ySU8w{>fYiWSgC3JTujcu?%aX-iObYKqF6x(6XsE9zH>u`nk|5* zek9bKhM2lBzMauGlUs91ODsAxq&V*CkjTL01mCf)lGpSY3Z)nOG1satZ1K%a&>|Vk z_#$p5!pb@%L%pVb2smm$_Dh$>IH83CtB}urvzTeF;ex8#QJI`#FvmAT^p2ZQI)V_)en|4s7AQhXS zO-)OMMMfruqsYhFEs`Qy=DHgLZqWTvBB*74^{9`7&QD0biK9--PXELN2v_-Xg|Eo= z=JyVaRltUemql&R@(hF)gU3()r4#v=I2x6yUFtInO9Oec4N9{7NHpdju5gHxp4y94 z-{q1F{y{y7(wKQR6xSuQx>* z(Waf_%t}bDpPOe_=E!FhD--I=LZzBcJ!mxO_p+0tct}azc;1ywom}YYIIP8Ga*EqM zLYCsI&^1O3-7iTDbdV10H;a?<7(RFzk%75Hx!{MqkTk}CTw+Z$W0B_6Y< zZvq8b(g%;%R3$mh&VY9h!Bs0!0pHXDdI(W^vTyI>$proYT34PoD2y7S-5X7zgV+U; zjj%Nyze~kvLZCR7P|%H#qUHW1Xz>B?bhLxA;)goEFmyRqiV;5-bA8pfFJe_;oAC^f zpa@6EP*i)NMH)7A&)Qha7T=br*v03kYDw%oXN5oY7$MYLVR|srvg&CfY< zS2Y7$cLDYg&L4nTtg29JWvd>!%+qPl(O#+N%k}&tOFN@KPAJB4HzYT4N#A73GW%+7 zB3TdoL_5d!mSLp<3IELAI~LDmg6M+B8KGHkTPrPiy@Z^aa4uNt-(EWWDqg()+VuK) zoi=DMS2OiW1V`gOw9xG!_ts%EHEgjs?MA_79aD*ajqPa8FSW~7x)H{kwL#NV#}DU^ z?#-a;6r^LE{7F+hmP!I4lbq>QTcZzO8@#`qt!#U<`v;5&YjPwX*aTO~eNfVQIsCdN z*z}eh)2ie!%yuP?8w(nP&7vM4 zpMJI$Z7jKWTKAsFLQ6f!99%Ub(mz?-H$?qRqY>ZbA3bPn-}3kwRf99xc#KU6wT{t@ zHEO6pYo*zY2Byx>c;H!1%rLo$!1}VfN=}Cs><(cP&>l=?!qAH?g%5~B+}ZNt z&}z9m7!Qd|a#v)s=dPh(dZuF}?*yvjw)&3<%hVR$ zozYHnzPp^w7I2Hs##o1L!JaZTOwp%%mojC@`cl0r9?U!B`|i~7qSx7#8wU+JN;!D& zK@w4v348?p`6_&Znpvvi@ztJM5;!Nc$^d>F`_yUpsY~X|2u;e*SHbY~!6UVv{5+z4 z(u+DLTLXW>^AB{Vi|Xz2O-%dva|LCd+pF(co3pVF5AyrUnnstZw_e*2xJU#O`4juo z`_mcxg6HHLXny8C3mrx|8N-Ce>e=bPR4O`b{)Sr6q_aGto@JASc`rG@%c|y)@l#JwV4z= zOyTD{mN(1GJ3fmn!BojvW+QnFyN%^CdWpXV_?)FDkc;MS0!#OcplrTKk9_^66Peof z9b^JEq%7Wvh1=7t)ER9nu_gzE0j&lCSNFXG2;^DC`OVpU%-yv8!(d))svHx z6QAXhc%uT-oDjkt&tMc;cyMTZd)a(-v*^^}Ip7$;SbzYf+tvT<+0A0EMv8SNQRe0! zc}#(0kGp>9xG3yJ`*L5D18#g&t6huto>p6ytAejS0dM0xH|%0JshUstXXw-YjU-PT zo=EDL&^0y^Qk2MHz==|EWYUTaCm>fBLGRN`oNI+FAZI@{mDDm1;3k)2+PxswU7wZK zNvFrz{6VaN=6+7W)Pjks0G)!N2|8Bqb2>JTpS9InZjb0gQ&8(SPpJH>{{oTc;>-=W zC7qp4kx6=0>fRW?uORu{3JLfn^gs|;GX&eNs1Ql>q*iIh+HCU)BKKFK=dLK49emYY z$TZjFPtZ~tOJ6yN*z(EA1JkFolX}hs7si(NRX55)$`z_fKfwy^ILN_6yllaGbeZEo z2@}eAZ!~8~)8x;g!f$M~_!LB{#U&^qeozzMR1S{8AxhIe=3?JxaC}H zi_en9JFGia-)J-Q82638{_?i*BsZL@GMHZ?)nHF#AG%*9!XQSScBNEw5SQKR@RtH( zorMRxuzA4M{l%dBf$Xb=eHdd2Uj7#`lVoRGY|U(96r$HoeW%-!?L7)&-saroz6CT;Y21XW1&oAa~ifx}K5!)y}4- zk5^u6ovHZT&&>`dH}C}>6p?o1)chYw^!zhNL&FeO8oZghtI`J(s_99n>foY!5nBYN zf9ni3%Hcl~3fZppWmS%OSU#@VGA|Zc32?l*5~z07TZ7$HXHPDD6s zf55kdB^iB9O`9vdj z{XzC=vD5a6BjQwk#|jrq*7kJIkU@f;$$IA?Gw1Kt8(VVc8W8C4Wv)Sj9>v8oaH}tS zcTJp0c?0%2bbDO?75-{ytJt#dSk3>?Nsu3PYAoV_xxuGPom~TOln^_7KTb`zD(xSXi!dMT#kUU)|I^zo-6AiRd-)3A~6uPzLX-+ZUs@z=?jbNm zA552h!`~V%-pCU)GV{z}Zg*>(M!yHgct%t=6(nC~b;o!e(Mvv@?@H}A9uTeEE9Tp2 zyZeA7YCz)xh}?EllxLTW_xMv?_ie5S4(_&Nrh!8&AAj_tjb2a$*8Dt>$wK&t$}bpp zzMoGVKPs%ogD(XCq>q|ydJ4VQ=&H@l-$O3DeZEV$KPw36w0zkU*xFO-_U-YC#!9Fj zFO8XAM~CM8C*c?n(}E?W9Act` zk$B>dZ1+fc6THry!5p4$|HTKUg8X9C6_0O7y~jhIP=dDmcFpy`%F@|vK`rZ8Df^IE zkzdzWI9+dIr<%yH$Zp{ikN^l*vY4f*nb}tD(&z6{*3@7$WY6SPu(Rn$YDk%69->Pp zG5>4{skFvqf_AJxAkx2*rslmbjTQEm)@=fE4 z{yIxslYaMhLm*%y@HfH%labFM5~rM%f*&_LG|UIQX4J2@&s!)C6FEfdR(v%m4v3Xf zY16Rl2z8@tPn2hT3Y5h=Vixl7+lLh_k>}H>V?{_ET6+dZrR|Y=k|H7j9oM6DnoP_0 zBbG5-$t|JZuN>LKdv@vHG4Z6gnl;C+Iz+fur-t`qzKr$F_<_utLcO)*kNEB5@JCzY z!n{lLWQ5=Hwe)-`Ds=cf{hJ&AUU&jb7Q{R&?6t3IQu{}m1K3Zw)cvIE4Vggl zHPY9sVY7`EB`s<4APhBa+Q(yPL^K{ihMu3y{V!(FOaYsdHQ&IKnji1@`8 z^=V7O`w|MP;ChtA2hSS5k=T&b?MrzhKx+CwPjAP^QkiV9=;R^6?n|0Ww9%TZQDr~a z&|bv}gSLNQbk1l)mNh0Hd^`m6&yef*5XhTc!6xtuY{khRS?9VZP~xE_P=29ybzw_xHgVVTDo5r189zZ5&~x(1{T&NfpQj3Na1mu`CTb} ztih$^sL)#vsNXKQy$P@^0k4Tq6I2DSJ%$b ziH9qsq{mMi*LU@m6qLi_;})85;Z_V&ex16LSZY&9u0D8n(xN-8T!#}K4A&yi`JZpK zY15!nZ2h}vI3}uQ&okKa4BWfl{*srP0#YWoEc99}*4PY8oitDt8%E!0P{PX{ z@ScwQ8+la(I<=l9e#^YzWb6ipFo5PhBwJT07)L-^=b*dCYmp^*(}cGR_ODwlSY~}I zCxsZOBk|_Gul?9h9kz_q?(sJf{JK5Vzo7gQBgFSTo$X7SRlq~;O?ZGx|LH!{uP#Ot zwXYcYzaO;eY05%}#aFIXfZUjR?pFY;2nAG(&d;uybW~@g)~obZ7rC(E!u+EH(v`=` zXn$AK1bGU>LurrbzR3QTM#X@+Vj!Z(wf~~5)Ze(>Ubm&;BYf@FNzw?!fDlKV6a-xu zqjvUkj86KQB)h=RN8}w2@YDpT!Mc3w3^;t{9j-`lqgizf*VCC%gxq)~Z}2G)``i{P zEIb`DnzNv7!UrzG$3sO_W(8!ZgOgfsc|qK?p(NMhD;mJ$PFrrw1dm_|88fp2HJ={= zw)Nj~=Mg#)5;C$My|u)Y;Um*bzPTHs)KZ84Gzj=o5sLsgYgZmOKqJItG_Vj?q6g=e zG)8D7I?97pQDL$j|DiL(GH1K_P(g@P;fLerAooH$ZmCMHhcJ2gB;lE`l?C074SLY} zF`cw#M9K+h^cPxzC`M+)@4@-_$59dx=12Nzt#nux!=lh$rvzahlro|MXnQ+#i_#@) zb~jM0R%Rx+o*aCQPM&dnvmQYp3{y3yz!M);E0m zT|A>BiE8(Lv$#S7qcaYJH%HlS0q|aYR0rUa;Y`l? zxe)15H0FL*lkF+nl`E=Zm6SQ5?+`D-g8p~T$l46^nJt++Fdw^zJ=!i;s@xwpE*9tX z_P$Ih*@Ew}XIMRYzKGpG84{j1Y9b*$?!%@eJ5@vDZJM6^0rq(FXP2T$7Vt(hN=DpUl}d;>2*J4IEEM|L(D zoLY$zph&~GBK|W4xXYVN`D7RrxrI;%jM$5(lvii?iT$nf4! z35(Jv>K;&$bvMA#E1mYr$Sjx&zMeG{NPCwcA#MJ1i^_Q{9acpDs7* z3*vEynH2s;drK%|LquS*Hq^9LS988OejgEFV)eb+AWmy~d#;7cuJ_J}Z+y|t>X0;j zuC0zN+?B7oKP6Wu!!osrhha-=?{zR)UqcMA%wEU(OLCYDy}&$j*04 z#bXo{{+$$MzI=_S_PYW>J5(@UL4SvZM&q7Ad-PX@p;oOR`bJmWWCxNS zd7lWh1rmDGNcrLjBL=h}TmLjG;~lr2)DXPJO7_yux?J*Ayn!3uDRc3!Nr3h%3(Acu zW}*b07^%bQIK13R20vM^ayAh%f}&Ci7_5H0&T$L%_G?$G_-;{yeCe^}Cw~jvvYxPF z_`Ld7tIzYm$-RISX>V~x`|LHDWRHC$y1afiB@C{c>0;(E4gI}9=W*jrsAv$<=Bn%_+zk082h7m}#wtyL@ENM<1tl#ODGc(k~CdOd*sbN9CWeoW-Pk6-X# z*p+ocFYk(8pp%V1B`8zc=W>9wiP1BpN62SrkcaQFt(2hsQ#jc|8^81zAV`vpvP>+= zD8}H|r`A?aE@|*f9L)5#dNCIi9`rZsNZxhpkZ(_zB&E*SGY`zp2(tfi0R%YBJe3`m zGx(L4zzweW`}!AfG|w5?JPE`f_z@?;4})$ut%GVRin^S<@W#+r6ul{jTWpK z*RqyV-P$Z^%rrmC_Wct}?q5+LML$nmDO9_kV5#-8AtSh62Ncd75Yja)Q8z#pm$}SUveliP zZsG9i{^XN{7_Z6*@#Kra5j9sDASo_n5A0UDv}aB)gvqAZ*`;B1J?FM1lt{AgRxM8c z;Ao@qezWaTEbUFuFUL^%D>8^;SigJAa$4#8RQI>cdaO@^j^7_|j7fJ$xiWT;%S+<= zaxVM&d0)wkQLpzGR=LuqSuc5-8L)kI$yL}KcJUxC-VIs(LiQ(7g`5HnyQn4AoeOTb z!>6u?5y7Z6W+3e%Kb{e(=?@8D(sYy!P@Lr{mCdRPQ&jfW*;=}M1_mml-Ox{J{S zF%3?yNCc`XmXw|?@pF_U5BmjKGIEAOd(O$+XH@i^nD+y8v!YV9BZ2fP)M)D6`1HhJ zQ7vY#Iu>jU47J&WXn?`-U$_6N_`GxaZSqEQRbwkm2e}v39)H#sDCi}ceZflQ^XiY_$QwJE=E3gFfhsKiG4gq`*`yI z5{EnDpDACa`l`)GsJJ0G>o&eUwgv8z*jBSs?s?kqYqI*w)!wb+pIHClpf{#y{Q3Y( zIB=LH!SX+IxQqvafk;V5ZhK3On_D`BkxH(xuG*kGLqgr;O4580!*of#dW&DW?TX9l zd?#hX2`*iD)2Z%If<}F7c3~~0xayyvp_#=ra`U#?n(PDuI+ZcJ{v@}gh_%x>nfuP* zba>`8!6f+Wj9s*%sE#4-z7MWuvt5>HrVPKBXAj;*WO2D7Ln=oyf`~v&jKMxba7!UY zqYxRPQpvWs>hk#TJTN?m7!a9{%^5U9XHN>)nDWRVf^QV+rlbQ?!l)SeYB&$=S_6#5 z`>rXm0X~=s<&V#v;R(v9WBG$X{kW@8c=Jxg?F1C%^(E6?*;WTLbEYNna)bAJ>39^aIwb*^;9^G$LzM z=+57Wy8Z*dsQI>~Y09VE=auR2%tmw3yr9ahSc~&De?din`-grBE7pWb%k-o>AVxWA zyp0dt9X%F?$P-0fB8=Drf2zWze&-c)I-!we3=2&svB`==s}J}|Dq-nxbpt?6n55>| zlIiF<`YUk?@UZTK9AZjnfeDuR>0QEKOWO?VDK_apCqYmA9C~2xten-OIjRrT`yb^l zGy&b~`;o*i_L{&zet}GQVBmT|Poi%;73uMcLt(w7U;AA9LUI^iC55#tE^bik%*X&` zh@dU$`95IQY4)M+eu!yzWR=h)8lMCXORWDr#b=I3Ydt?Zxe*KObMg55G~3E+QL=3j z(npPQhnmjsT-(jMR!%f&8bok}DQ52t@ZFbk@xtuczsMP+^Q$ITD8&9&N7&u5#FLGk z(LV0d|EpA7H2Qk}%jD8a$pF|a?YH%s*`c+iN}ptqD8KULsrP)RUV45=um0jkKDNl1 zghEtJub{wT-aDE1=HgJjDFZ`6q(vtIIU1D5mm-{H%6zr4X>!yoI`VPo^#53*LL09- z8bjJ`N2>Rz_2oAQ0;FXXhK}*Y%zV%Z!^RBBrX>+Awg+1y&($&<6$!L0ug6q4x)77` zArRGk_YsN&4PxrfzW_UYoLp=s5}zFA>g~Dr8@8miIV~PIkqnM3nV}a()&w2^bSiyA1Rn(p;bBDQh-1~%I zaUeCNav2^sEYW;0ntOOE41j?@t zod+H`l`f}J32Oa0iJ~8{K>5j%jvBGV;=4>H=1pg2PV*=s)LV0OqQy^&OP1r&U^zRk z+)x3E3EV*6`tBPB9$p43XH@N{ZNJ6DP#tY#@vnmW8n}1@(`2^_gnP1N<6b{@AIRu* z4IL!<7NI=eUR1@9GRGX&x^kSCT}4|u0$)9`MaDw5dLm;S-`C;Xd|zmNb-8k-%LO}{ zR3sxtgs$J}XP(%Y!coqIv?r-DZ|U)8Q+1+(Yv#>AIVVRKM~nI~?zha)10OKVn>s}f z_VuwpYlfkyW#O^kjx3(C9ZFU6a6S(kcZ83b-b>sN=& zAsnfevl(V1nlB%Bc6`L{bSBGzSs-KXz|OzYP*OC`Q3nUVrX}|n<2Q~$mai-xgb`Wc zT`(|p2sCUu=mN)FiKpz776@H-hI<2FQlg47`?6h%CfZ-9XR+pAnG>2j6cIw&sjpp^ z-8y>6IxPWpB|XKH8I0ML2McWvBUZ%!utSO*7i@*rKc!G%4jI`(5uX5YCFx`nX%8M zK=kTn`;y5&dne+u3&H$DRgt3B{uYrJjn=vWh$YT(rq~@sg{WUy|EvA zC%7T6YM=J%df-1|)H!A$xMOMOKA9Q-QNip8_PV zq$pwh-^1+ufqy!$&>N`zAEuN=CY=vckZjl75mQ3G%$4;L4CfTpnf8b*o(V?#7hm0$ zd2wZw$UGCl*{;V8r{yHy+TrKv>;sY)riOM-2qnf)?!Wnx&g&0JXk0`1y^uY9gzI-K39S0QhfaNNAFJ#^ZG9wE|vg3tVN zWFEEn$88Uyel@f-)5NP}k+nQK;R~iiTeY|y_iqcGPgqg@2%@eMa^6_li3+yelaJI7 zI>a?=XQ39%A0Ih4xo3$BVwNR8N5gnTk6v8A?tF_W>_Sx<|ExX-NtI|3PUN)u@%Khh zzQlk8R*?!_q8uK+bm~KMpJt<0(AbBehGvqiQw-e>kY|K?)Xm#?rub8ry8@}qZ#4yZ#gRC~I-C)4Wcd4udfHN433xm}x?&+F?~cg{vMzK0gITm4FIU4d9=?@qbO! zXn9-aZgoS8;VSvroR1@U0nhH?gJz>>AXHfacy5PKyK?UV9g07FfqFEPv=H8~tiR7Z z@Hol5ihKhozRw?S{jmA8@^Zk|@s(KT@9Pr3C(ATK4S%6YFq zUrauO;!FTTm?c!QmAh13Kn9XOW0a~`4ON-Kcfcr&89Zwwao1ix`TPVie0U3|kLLYa zc*KxhN`d=H1YEz?34?S)n4TVwQh-Zno^#xEst%eVk5~uDFhO8opW=TbUTE_xI1GRH z1Zv{L*MbEsX%j5eTB78UyN!M}YCT%9;II^NRHgpXZ8aV}Jv&q&J5=uqC*A+ zFY)hGS(V+132q|}rb6EuSTI;xy~0lR{3Vf-)GZMX5)7Fp1^qzA8rRu-Yrl9fwkw_4?WJ5KrUx>!W9vWWe3hGxykJC{xP zNNWathuYzFYjt7c0ClZsS27X0U%cyB@@Uf>C(nzyEQ{{y7_h?Tf(r&Yxv`a$v<#@r zCP&Ntd9=^eVx)~hXbdDxP*AZVyXxc0YRHvDYH#51(cOyF=cygHCk1L)1Qm;7n7XFb zOi>;m;mpp8qk^I5Y2aHtnVYmeixe&PSHv0Cea-Ua`^Xe6vH%uvZhQpMU*~E)G*pf|-J|1Tbny0GA&sdfdJf#`Ja^LQEP>dh!6U2A);&AnV^rC6 z5(BR#<5HU9*9yY{Lu28DVnpwWuWCjqww&$DOy;9UJJJB70oYQr?-(JR*AqPd3~Oj+ z9wi1!z=9)5NeV?VvBq$YkC?irC)k;M^r__R5ti~$t(eged7!wmoXW=rd9AL0ijz7b zoqfgDX?;QERhO8T27t z15Dy!itxKA<=^Yy6?DgvkQ9T%2*o3lvQrEvBSKx-^CB1B>`Gu4kboOT8(gM|*5R^T<=+d(y{X#mBWj;G(*7qgt>)m=bV-=+@b$-RDe5NgAG5)V_8Vv} zQ7L&);2kj!aB5r>v8R6tRwN`gGiy>jcbRqT5mzs)S``i|Crf%e(hJ7(Q%SM*jSe2E zK;{)Zy{Jdw`8dBZOzUtEscFOUWvO}wtUxG3RH6$ez|Z`qieKzN^k!%c)%LUL4@oZ$ zS4pbY*RCfn0K!tpKqMja=jL2f0ZEM7TK}ncQpos^sHUPU(8HFZv7};9lYZ%uiW(`M z^p=q14l|dYPXH_(-dN2ZP6@0wR-HXg$YPr}0v{v%^1Bg0Kodi}r}7F0zb-I6PD~}Z ziCO2k=Do+k8^HbG%LGY4uSNfj9{Ja;esUDU6O)3?T%&sspEL4o8gs@q)x8==_YG!Y zUA2=I^ODi}YIc~1B^r@WZD^(Jrtu}pR;|+{a+kgJ5aUmfR3oF}Y@J^2n}2v1t#WfW zkrEM0qIgE2r~j~=(hx8xV#uFdZLMz1u5|VizWAi zL=XISUi!l`YGvIEXu5 z4YAyM+40aQ)bhV~7ymf+Pk%BUtohrrKJQ3P>HPkJ_L9VzKIQts*z|0>ySHaUmRWUp zG0x{;(`!DHNb3Dn>KI?*);9)8+h88=o>Fn%)$#*tirL9^aG{PC`l0N&aX|U(N!Joa*UA zI3y^OlvgxT7V)}jyM_m!$xn=RHa)EOYu^u0@{XLcPIyDc;7<>o|e`Ug=oJ5J~;HApD&L~ zzrBfa@`aO17QaljJslOiXE;;$0TZ28%+x{o0!~SIn02EG^(YRX&B2gQn;?ubeg9&G z%5KU&K{JOwu{y1HexCy9!La7J+O|$r(eW9y(0)pV;zX|d2U~V(rtfg3k#2&P2aC0y zcb$KI8lp+m`;iRhPxL~WNePCedOf7|zvS^a3GSa$sA+hp_>tQg$^`gb?!@GDdDl1L z7b}Fk*$=>_MblmRQ<@2rqlclatmz+TY>;|h)$+hVu_PEjvR(!8`S%x<{Wuiq2AY;d zB9Sd_sBlBeLB#6tK;Yicw)*AWeV$x|6@Japr2|Jg$pX@{n|zUU30BuOW~oLwjp-6l zR2}hm5?!EyVHiX{AF7Fxv;iwn%Mj)DwbRkHEkoTTIW_4O<#CMAsBks9MjTUuliYM;)k1DN6U8nY$?^2 zea}RxFEcKSz}bDPi*FQM!0@=AfZW4L^VkDyIiKcct>-f((%Vl8^PYB?bj7!Y!k%2V z2hPl22B-H2S}Q(^s7QEgbT?=WS5P?izIs34Q!KUPGDwUYO(L*hPoqv-eGy_v`#uFj zcFCeoDjSPv zG}GM!a{=v-zqhy7l)MNM$!|2`pSK3$-_wcr!l+gHgOLUTsPpn*O~h-7sY9vZA!&c3 z=^V~_I~)aJNVPtkcL<>o8xg}1e_h^sxDwp5aGzXhb)E#WdJl$;&pW3=TF<@RwT}Dm z5RM;~UaiN-`FF8#yaBi|IunN*hhlTA*{zonM<+G?4d1jc%e675fODr?tr^%fqHhM( zH*?LRr6o|lhmL-_0vVd#T%^mok`^jilQs+0KPhBC1^vu2MCWjzf6LGqoQo5Y6XCS5 zfpyh!EmB_j0O>{KZ9N4KPbXPUA8cK!tugydzzb^l1Jk=km{fyjipuzoyfx}wRxChr zd$10xalw1xFIDh@nL?HWueG;!TBrv=7l1zPY{{0^e)S_zK@i@Eyg=JBeW@%oh9se7 zncd}m0X(lOt88+oqU=NOu0eJsjt&1*fVvQ~*Wb4W`_1r|=i7qZYGe%P{E<-5Op;k<(u1PQFRYO$&-0eQ+9yq^ytFgkes zdS|x`izbhb__tmRR$aY9Q@XVWw{`t-hc^25W<>B=;~h8`)GK{UQ>!i`}S zaP96_gQN0i-;zkZ6mQw`B4r;L8<)e%qK4y27a)FOdme|D!lhRYW?<|{6SGN$KH%MR@H=8i}?EURn17FhRb`v#; z-x=NF6^G*Np_V8`u{~nk+9HDo&!mnVf$_rQzur!nZs(w&f(uU3KEE#WI3Is{c{sp$ z)=c1Nj8#OI!E^89ONI~spD<5NPzm-stMU(v ztd9T8bHk`Qh?rM}w!+l2s#$EnYKJG~M%3fz^xL)DU95-B+9M74NJf36nylFA?^pUC zQL0OUQKduVX~8z;L$`NabP2LRP>MD$d^08T^-_Gwpu)ii5Z@TlDF6aBed;ii+*wU*ltc~Yc?TW(>smsjyeCn?h(%7+-&xazw61;`X z^IatrUz^B(D%|DC7E7E;6BRJ0P-{5`5#PX80mhW}Q0zmVDfxqy=E^RJM@}c&4bSub z+18^@se1^`aj9+r=Kl5tCBKnd$FlR{6+L^`qD}R;B`>UhtY=A~*-*X5eA(M@0$dgA z3}HRpDQyoKeIq|OtVS%|mN*=C4ML%(NJ6@B|8u;ac2ONGb2-YYhNdBJW;7?`!IS26 zRV~v_)oto6k%d39JTji*J=aplG-*NAK|6o&YX*VaKq=HKeo7}p8DkG5| zjA3DO?~qn-bhlb1)w6{3Em)0aQ}}5qFqd%3j{_$yMJ{uQu)n%ww*;9Fd8Q~Gw-6~Q zUzG^-zJxq`JmKKU_lk(H=@$l}-_v#^nvPXxo?mofI+N&*15Ts!O~GRF>HA4C*3JmA zUR5?f0iI|kkN6U`f_J7ZZ(BbYW}p4X9kLhtj+QSXJwZ-wyPs=bG89@eg2sXHx1Qc# zE*=qz^91)6uHLXQY9fZI==LWX$O9V?1zaT=K_~CRo=X^HT_o;`Dgk+xz-R%Vmmhq` z>NJ7P5pek{QGbr@JZ*bb6bxA5r7hkPsScIMK50gv8}uL@u~`U))HA`7x*hS|T4|v= zP@yXjY6OsZU9U{u$cAz%h({mf7Lj=Hr8zYQ&v;!Hi&0@x@s!7+J$)0s}_{%3(wLTxBndMZnC@H2PDEO9kOI8aKeNX05aodUeaO-ryN+;KCGLA z?8>pVC!iu$l78YoT#uu)bL*<$i0An-{Ko}=uDt+7Y~I1vwwZFKJKn<;8CP>@dH87^ zEcZ3^Jj~X3i9`CXGvhIMBzK1xn10jeyrz>mI2bWIl6?RRs&G_O@a(4_5OnC*ch+me z^U4>jPaAPQgqhW8_3f!wE-==gTTEEn|Ef08P8evZb^Hd!j}9_@nX9WqQJ}PhBsDOS zmgs?*sy)re^8CoJ?RbBi?3i(68BJ&)IHxvP$As4zfwumsayzF!M# zET>}=PxV?P=0{pyO`*gM6+&5)lyZ#kYIZN&s?7zMQt&zP*l##7?yywT6Omvp8*9N- z!>rsQm@(f{UTX&$lOC(R{Ybr#yxZSo6n*q~rnV+{N{`v6z=}^4p|H4*;JDjrcZM>#_e=I@RM;rSZpZ{)_*$Ktu|43bVGM}d$v*huzZG;9M4!Q}L z7fhCSQ9PRrsa6}##`{b+EgivbZqs>tDz=C`1%)~ZbqAa)8EI%}C~=+}(rDW^4*0IX z7XGQ_q#Gw%lY7`$Vt+0cT5uSG$b6B}B>i6%co#oY!ZMb3(%D{|~0;nfQRSPLDMMby@Y+7Ry4W~sK zFb27t(e0;%z6Q{Sr>?&Z99vB$7?+STRZK9ZMFzAA5QLbUIHO!KqSLGQ(uT+U0~`w% zr~u1OrIYgKi;%qT$&^IrV^bSi4Ub4kzc6A#^_Lr6&#+%f{*r2@M@8Sn%C(b?kmv&e`o$plCb|?s8sOysXe%$a}O(@ zqB-;$kc^o0i6HNAqfjo184jVG7Ilg#4j*;o{e%VXx<=+{)EEtSm+}j=u%Q8A%s72N zCFH0f=V(cp1e_1Q3IHBGk5>#6wbm|aW_$nj-sy?K(|34f1tqkw#-~Socv$ED zcOqMILWp13$cZEXWpt==gWT~CzjUXbnnK=bs(_w#t7d$UKlx~okmXduho^_sL-qae z$S%DThNQ4&PQ(5VeGg$Vm9HQF;L+n}H{TV^a+96q7}F=OYN)X6zLpVP9&l3iYA%zU zoWj{;hPmvJ0Ql}oZ)jVeKS;3uqv&TY^3;1%@Lk3OT0%`|&o6jx+$gqnpdogWWzUcI3fjB+TW^FBAJIEEsetZvM z8wnqSx3rAJ-m6R-?Kbvwa|ez=IYtu~!>v@r&gwVv-=KsB1= zNv0f+%fE_Oj@1nn++sI{2>dUq4&aJ|sl z3!~NIxPp=|B4DA{Lxf)X%K7lXwK47o%b4@oU?RcGa+Xe=TttQfv|biQ~hq> zFh_an`UpZMS#Z+WgF!qe!xW`S=o-r}i*L}9<0AW&Q_y$RbDNLA4Q=@MOd(@$6ILg< zQgS>05Xv@i?gZDJDEd(gJPqRa@;#7vrqHi<_|n=djJCPbLu%{EqQmf(d{~_1MF-Zi zLU?+=667dCpZK1K#yx>G=hs_hO@1c+AC`S|3r>LRVvTMh7UY-oD}5iP;iPf=$X{8u z9<7X+J{wn+i)ktQgtV`j=So#1+`}SCzZ7Q|6hoHX>#wrqZ21;zk1BGsbgnP^jKSL9 zk{j^`IGPh04~_~u6uHQ^X<-YuLw8uL{(fdZb+gbWruMVKU#oi~SnAtMe(yikq#uIg z(V9I@K(ZlO+`7EKYdNUuh{V>oRyefbicq*g$HHnV398D!oZE}o8l=D4pT8#}Am?5k z{s4R?XA2y2MxlfMtClf{%1B*8PC=feHR!oJ?j?9c^s76A3Suv?6tHFHwkA9;$2y65 z9Saf;q~u`!WG#XpMmsS3BreT6{*5fBuh`Xr_wzBhqE+9U4WTqMZE%ARJqHV9`B11L zg+S;tCcQ_qdEkDek-yC+o*epVDmPf;>gp0QTm zF{laY!pGa@9b32Ts?YBGNeh~5*=_YLO@E0q;p(L!Ak-)3EQ~kSDOd>hy**4kS=1hbyRU<)%!c9 z%WOZML(bn9$@w70d@p^e)P`0>@DnG%IRbCm`R=+Glj1@^yzuX512jL-iZD?<>s*M1 zVw9y8y5ha>1OJ71kwGCfx`lHW61SR|Ypi7#yw{s~o6-jq_^E3%tqXOf2{vS>zFgx) zrAz4r{8gXO8GhfL_`Wxtn9JYXg(-BAB}L_K^axAnS4v}-<&&g9;GdUbxtaOxLy7cN zH0;NGI`1)I?~q?_-jeR@RDKRW)OpVY&h-;{6T|tigLCtx-;GIy+y+FV(O{{`SR<6k z@o}rzAnzZgxJ&CQY#WZetoi`6YO}$}H?#cs7F%9_eCMAesouv=xy!1dW0f)=we?!= zW<;tN4){-dR7~OpkKQ1`|10|hN z2a@(h4UDxux^8XMOU;D5oXoHhJ>$xvRq=W3p#VHym)yuMpWS@Y<6`de9jYl48H|PW z=rcb~N^OzfxPzd>Xv1@P?@n62k!lY|D)!Xh!3w@OqYUL45U&%P*=J0F`ozcUfMhMj zZ4lz}CfkWP_^+C=D#m)9{FxzGguJm8zNg%&SUBd*D^5Vc{y1mIL0&|UI~u~{wUlTM zy$HSIw$CX#^QG3GIKsqLEuE<8F6smXqUtA`|4?$AW4oB+&9wwXA<1ew`#lUenemLp z@Xq9D_cH((Iqx0T#O+s@MW!V0XwT>EH1H0_P4VUFD|`>2ceiVdo%O8Xkft#OW4l#p z{7zEXEgq1}#D5}Kn(mC$(6u!C1qiz$Q9r|Yo*l(#3;OZ-3+bbOurMyG&JC-$e!lfc zqB_Q@ambWvrzDEQR{KS)NaFW_qc-q;AQt}cjsyGJ+M(;{1D)!_Bc1oX8gyX(*H(r$ z`hE)l*v^04JTx3oO7d#dS2CG<+N*8Df5}5*lwRYJgp)uYh|Og(479d~=TmjRwm(Vc zu8st~d-t-ub*1eX-sepUp(e5cE$WeEX45fjW_Y{*7h`W7)n*i~`J$zGaVYK%#T`m< zcemm$!JQV@P@oVTin|5Z;_mM5?hZFSGqdK*y64V4`RiK=i@g)V{`ULq-}AhUcg~@F z=vpQrdtwRI#CnR?fgMT z$HVh}{yROS-9^U43O{UFBIunHHQjEnP;i!}_^n``6<@m3P=_yK8h(-Rr=GeTV{Vq4 zYHhI_TFv~*>J}Vaz>|vDGJw3(7iXmcVa~AW4z!%3oc&9;pqpr$);5>j(FU0q0R&S& zl7M>ZbwQCp(OEl`%9NoOo_=uo78$O`y@ZMq2iS-*b7?lMiI8Tppo;ATwO_pLt{jkc zi#Xnn*JW!^`W>h@403!E)m-?vq&~B~@XoOvFrKHI@yT~|vB%*#L+0GR3p{;ad#?_K z;1l2t5~;COrCmVwdotGazbBdA67wp#7xL(}!;)qH7xESQTgrnbQGdT?=KNk5+2222 zS?C9H%(`LMmQ0Y9&LXUjH*R0{$L2P{G#nAM>~u6DZY72=J(X?rYTJD_XJ6at$3^Rx z8&$Xuu5fpmeI+7&Y}pcY{sngN3FF4KnuUOH!g)_CB@9QyB&ou&y%>Ze6-mCqzTG%+ z;(|pa35un0d|!dlR6GUNRe7jSvn3Tvh0A@Q zy*v4C6d&=+0@m|gp5j6^O3a2`B0vb$oH=a-$x?!A|mxW$2iX5q&N%hiEY_X^`w*` zOYYOF!V^zvbOTGm4kyA|VtMj7;M!hw8||CYz&1Epq+VEx7Cl?-KJMl8?jr|obfI~B z0`}l@R+^w&;OlPA?%vdWUC>UcataIpo}p8sa+ zaJ*j4eZVzI;aDjfjSO_tXu#wdfG;Fan>#I5$xd6xmb?ExDxgrgDLn{CZeC+TA*M=V@k!wH%+F!~TESZIkUoYBx`lbsNOPjw z#NUN2Q{bXV`|RvLZKpBcYEk7M(FI|;{^D4sGip_|rriE}h3?ksb#Jv3huBhGeMX@S z@=HS{52cQI&e19kc;)mwtNsmB4pECV0i}GE4O5}@{r|(Hssh9LUtIl*!)l0hp*1k43k^(x3ZoSITkQwf3Z*}nt^|S; zsbYd`HLC&RGJ?x!xi03XzO>3RYgoNUqt7x7(;=ev!>c_QCov4morAOBYd^)z`Aic}kuYBqaw~N<+-6Cv9 z5qMt5+aW{)O@p+@3v<_^m1i%G4}>q?e+?gm{<|vEd`ANK1(}@Z6x*ksh^%;qSl*15 z;|}WmB%!Ve$yS-jbc|GNw{^WzQY74)0v?Kfd zG_$piYA@a!k2%*h_y4VDJ)WZv@yu*5R?<*j#}{8O1U=v+7LOSBljlz#^Ae%STF-Jh zkXiC{NZq%KVD76=ES#RCPb8deyLcWX!222ucP7z~U)nVwOq3h-%5fnbr-nq|phTCi zoA2g54-9`T+Q3$(?x56y6vyOe0jFf;YcEL+-Q!gory%?ZoU%0Gye8yd1ieMi2<+WH zbfhmU1oy;77gt3UD6Z>Wq_G-bX%S!UJS{Wz4KqN(8FFemy}@{-g)a5z%LQ)TQa@Mh zw+|O>DRkP_O!tDFiP9cFR|-!c%iYKtR#*p{4A9*Un2SqD45m4@dtClG7z zrZOD+7rRBBtxHI7Bbt{!zdk%>b%5ac+LAf|%{CnLYZ>s2KR ze_4ayyLHBjV|)Kg$z$Q_J(H0Z)Jpqqt18pVL<3P5DauKn#ph`FSt?D)i{e{%6b{!~ zli;3PA{M`Yit-4r^>j`5eUNpuR_+uVq0vGt0%Wy59Fq_78SR>Km^R3DOZ9noU4h)28c}&ACqRW$!7$ z!p?=$KnAg&;Z}S827P#40~LApo8Nm5b|cqZSD2suK2)j$9ckjRrKb0`$R~69`TwCR z?tP?JHS6Awm5KV~SdE|2qg!6`n~gqjOzXpIA|(X@JGe#SD{G=rbkYjN(6A1>I*jYb z^!LJWx%H-a=90XZ$DG8KV6qBOz-&d9X9Hd+h?I=jh ztU`qn!NK_4tU4lhmPi*jUN?hSfoSEPj(0^S;gDX&SOr-I7DiC)c-zjI8QxvJ<~L zcFVA(BqzOFR_T`jh6ma>Y(8+(zdF+Jao~FCI%CH`o*LpiWo4uWTKZR&Esvg&5``Zl z4To+rmuE-{3VuIP?vzQ>E}e^{n=rGb6%Xb zmfyvgG{(jn)LW0#@st#c0YWsQB%1U_eDdFdR(i6@4u*%f<5EHv#Irs1TyuUL3=7jl zP5rZDfVbcgJ%*+u#2~}08R|h9OFhDGo8^tZ+ z4MvuyR!E-uo2H`S)iQmK#}%fC5l{7l2t!m&WX1gKvM$>Y3(y{Ck9QXC(f+H>Bx86^ za_{gFtwZ07yC)C7;3sF7-y$$FP?`vY$v}e-jPHbs#)P zRX^F*?3(_B(9Z*{~$U8n`+EyA$$?2PH_7GgwTPsVddEBHa$+ zVa5dX-n>VY@VUhD_m{hIyjv!kY$XNI)uhIgfy7?VNWF`i47O%7jRA`#Hvu$5HpU})byE8+zG zs=kvecvVX_JS7rwMQJ&>IOk5;J?5@@l@|1&WuWo6`nDf#ynEG#?F$x6 z3nzEzhfCGLCSpTQX%NPn$(8rnc5%0)fADw09zKvLgMFbr~2m7~ooe+VkNfk9`?d~sA{LX0>xBYF=+>&rQIo2}Q3 zu8}j-gI8918=>t;@B0HcaU2#z)kFQO>V|+}HSy;R8qoimDpv{h`%#PigBBJff5?l{ z^6s58h3|O^5S}qIjldU2Bdy5Y6vBL2dbp52M2?JrWjKa>|Kp=~M_cgpqevK~aFXXG z#e_}ML-bhI*MN|j1y5&)&MTdrL!VlD$H#v;lek6Oq}Up}({cs8sBvW${6Yrk?nC z!Btb4iP`I6^9$3#g{{CZhfeP*Qj6|Bao0chlUyqVz4Z}1$6DF$4f~Ha1}2%9;5Xw} zcR~ss@mQpO2#xsi{6)YJz8?U@PKCO%fzXIn;yAG3sgk;(kz3P0B>#ASN}SnISKnBv zI7G3>3{Gni*$ou4668-Mf*u^%xSENNgyEen00bi=F~}gwP$vOM_`sP;Pf{D_doo`i zzn84=q^!Ds;!22i2@%ZmoXD0zMfs8XNh(LS+SOkr9u3_4@!-OGH4W`2WY(thYhCWg zqnu}JDNt>nL|RxAzv*5K2wd|fYedIHl&#u{96)6xy02&@Aazi&9m=VCP^*9v!zSTL^y=Go;t76MW?7TRR9G z6oESL^0x5%*d4Gwe%Z*$j&)!2T^*;sZ90gA^dxVgn-?1CQE1F)XgNU(>3w_ljQ-+1 ziZZv>#lBONAIl;E2Bsu+J{W0wnEEHie^=Z5q`{^FKH@^rQLwlYCQt+LUhO2yBas!A zAOVBq3GS$-xtHjsFEtEFm9eh-VhP>`y@>{JFijbgM`(Wg5;!ZcpV&c?iC9PZezXt4 zM*9@gCOT7iS@v+c!-k0DedkV7hEln9lVEc-#J6GLYl1;KKytG}`sr5)9xFt|5`KzL zk(>MSddoGEA(E76YgkxO{P7WLVSw3nKp$U=l~rHmYE5lMj^AJAA;J>DZ)8ZGG*yTz z(^x@p@qYEX6)(j*F-Jam^pSf*8DsWm>iWR#)3ECw!wv-o*>-siX7&+o>DOz7w{QVqZmG!nzLCah(?S#Jd4Qqi zX(&&T!JWUb_GC&!yds9jTyVq4e&=UO-ua!(m%mwzrZ;H0uP#Q{W6f7652xs8t@;Ti zb6;N))lIg+KVL#iXfQ!!o*G~iP5r75jg-fx;aY#>+g-*YV`&vGX(w!YSSLu^C^Hw} za2R%0fAMJZn4n&W7T(iNAVryOBiBkHAOa%j-hMtD-$)EM8hf|9{oWu}w`+3$Ds3PH z8qh|-XTUTZ#W5|HoN>|ob&@!eT%Bd7jtNrOk2OX60_UP6B!caO1ZdJY6miEr2A-H6 zy&BTpO~0@?3N^9R73s}F#fx<{)!dNqB>}ek*c?WX1-W;uNy^?x;okXyE*DlTIgL}k z1B@ug>mdJf2Ann`9aVx4VupDo+t^aTr9 zTXpU*|MadvahzV|j3+mJA^#1P`^Vu=y1y-iz2f!jCaz;wv^YW%lU=~8*U-L-5}x8`TL z9P^Pn*N@bmoMJHV??jKq%*;NW{o^_rViH4=1E}Xe87G4``zI+^iF+S89>tpQoKy1x% zh?OKpRd4gOMc$phuDp*)w2jd*y_K<+A+}nXC#3p;Kpp6-51{6n7;F8`zR>(qzK-o} z-kS7XsSK+LCKyV|BW~Ltj}y*Gq(bXS(>iT-lt5VpE25(Aa#0SO>X>|$eJz~e;3D%A zWeTgMzwjut)`sns!T*Z|SQ?1h(HLIveq#is2WZ#R;ADj=eB@BBjTZPh%p+8ZPXw2P zze<&@|D%!MDiCo+FMz@ez@38mDr*m5_$0rPrv~SWIbj-_?z96xsLsI`;n-WE%19w! zrWl!xpT9?_*Gq#Ikuq&Gv^%UJf41d#i;I^_k)*gTV-h!+jt46mjk*qcb;szBP|8n4 z?9?_|Teigm5P@R#lHsDKzP|`p3n&iF039It!krxIpBvh=mS)jDwFTl+uEi7Ib;0;J z@0@q~L+r`tQn<42Y-UCDBEvz3UgwZD98~A_!$}6`Ym^r7D)RoSZ8|-!uf`;YF0P(hH;64o z=#A#I1oZ-#`qlhFVK4s-+4D%Z`3hlosvWHo*f*+Y#W?YL;R@mQ39YK5WZ#om)(gWK z(D+`}Na+(uiE<%Z+R_dXFCSMNI{IS8G>wGadvsE2U+X^ent6WuteQXxmHI!dp+xy~tgl*)Ehq?X=mR4um8) z^;VYsz69XD8W3stK;PDEkYNDwh~mm2T^`QYqZ6e*>-6rZC>d%K1(0tESgu+XZxfSc z6cAyzgzwnBNJ=WDlLv@P%FM(!vG0b|tM(l*Cgw&y{~5iUP>|E-InwI3wUzgYe0O`e)q_}oEN*h z{)_VQ7{EO<+?6deTioHDH~-wTV!mD4YP&WfzFT5Ez&tlPe0A-BDh zPHph|Q7EE2wAfb(wtD_7e6kS$=)f3UPZ(J?looM`KNacd&8|4L@_5f}ZPS+8j|jMa zMxMRy=$OO0dSKd%Egzp8gguz?qY7vd>WYTnw)XM|43;xv;rfq56^00|w_%|NI0uHF zkL-t$KZ5mpWzQ>duMYiEYCeu?XQ(b-*nJYE;=!qKak zUC13{=IW;}yPFUZ?39iIbf*8pSgC)88Jg4)TZtv;`4FpJ;4xWd^p8a((-j`G&HX#vaaB zmGznu;-LzGGbwU$xhhEc@WwY^pXqPpPz*i;w4UDf6ve?Zs4*=`ImCsePGen+o6UFqw^~kBZx0CLkVV z%Tx?~Lv37VRxbav%La$MHm2H$-QhQfCHgx%zOPdmB@F$15T?X(KfV__h6G@;BymH$%WG>0 zw!2R#Z-+Z>7I>2rjWYiQ9;rAvZoP7cZCX6{vl~EJz(%vwE}U_hIjpQFB-&4rP_|O! zd=5k8PUK8`EbGLpetM!6qZ&LkS&R;Nw?(kN-D_wi_78=3?CALcDSdCqN6&xxj(ITl zt_!;mS*WUEMdo}jxN_!D2H$ra+II_AIwUT@>1m2_3`itna z`Tal*f~hURf1tgwGk9R}_MpDW?%+3bp%&(J2;k--T4sGey2l?xU!F$hg+>4j_fJxhw80*;g#+bS<+c-a1O_z4tI69A-Zo;xlxhIdUJsAlT zxSCV97ZA?&nb%5byQH#=A!*DI=-KR%BMux}72RqV$3AxsR=*(Qu|SBT5g7{Fe*d#U zQJ>>cD4!^35b~kv4_V%eP$0K~q4{33cCvpls{d`d$^cd~Iy= z0gNx`2T)7kt9oI~Ja~f%$j58d>KtTEhJ37DCF(s=a;T+%w4BUHny2JA$y2?J%m4+W zCRF=Cuy%(9qXh7s%fUACoY!sFbEhx^BCx~?4IAaQcP1uf=x&u1QQ7N{lj{+cYMykW zE!>yW@RNi5CJCig+&t?J#j%EWVM1zirKD9wN!fo{s~j&hUc+5Z=6;+vDqq>^(9JJ= z+vz#h<~ePZg^E_-N5O=X{l1p~DL_Gt2*eD`&eSYj*|^bg^If&$ydw(wY>k1~ZH;iG$)q}5O#Qvy+7$peRw3u0CCd<`81xxtesrWEbwC+H(j(XTb+%kk` zV{SY77o{XsS7Bz)qsb5WDl*G8aj#9)Co75Jk(pI2ZAHfgKTP`U+Ff=19Ohj^xe>cY zSF@Zu$vH`g6@Wj?ESzSslXc#!{991tm~x~-OjWR5-~5t^D+9NArH~ZLbfCCG59-3I zOv!53!8d4Q$8a|l4!klbgxo~kz)S{o!EcPD#Jn1&8)BnhD9jvm`zvf;=womQRYar_ zY(8Hi_GUEwi#A>%ip=bw-xmPj+}2Rb_f}G_rt)3x$D_VH{t=k8Ty64rL8fYbqhZ`v zr0|ntX>`l+5kRNw!8sJmGFxk|@#Wt%ZO;Tp<{Jr**BIemKR!talDO_V%SD>7o2o(q zvP-;f>FjzNs4ls@{nqTHoNET@?_7{9!1R@NTp|n99Ta?gS|7vQh|GqnXjAGZB~yTv zS5H4ulX?6{E|liBzh0Tsd6|f}-CX0${uG1iOD#{l&G$-kP| zuMK}o1ERl7y~#_yLO>5ZQpWg=Y*A!b$p(3ca5w*3U$AH3ife@HEKS9+2mNtXyNRCO z_z5aSn}KsbkCcM%aTs3KQ-e9U`s$L-+ud~@Ksh-TtoVMcu>X;mtwVnM9L33TJq>6W z;wUexOLS=7ay8Vz$m{9J0y})Hl8~E>ml&;IzH;27U5as=jzi@`&0%puOPJVWKK;0z z42#maqBdTs-0zJcG)Knh4S&)yUn5-iG4}g#FU{98WB;rMctWHk8!kk)4=N3cpS(|q zQm^5W74d4WH+jc8bDP4qWUt99zmx?SJ=K+nciMmdPs|i;w*xo`Qrc^B{n+{CRKe6H z1vFo21Vj^F!^EO`r6QE#u{lh^W2gu~38A6AT;T*{j(MClS?BG-O=gS2-|+H2EZ>*O zYm(cNa#&P!h6c*5hR%HXt*oR~7Di}D;*Cv21Tj=`LaP&UGjmICb4zH|v&AqjEL6F2 z5j@TlNhN__im*^qCG@BKxn#+m2~<>6uJ+O#4O_EmhLqZT#SwDwSE#am2`=xvzFOq( zzVqGb9qyETq}!Tth)j20FduKZ566JZXt+s9peP9s=iNEj*)xG*Z_K^iyj>=WVDJZ>rn_a!mXZ%B?$_@Qa{U z)=0(l)?sM^$0$0a9DIhs3u;RU7ybOFa!1%G11cvOa!_UW!!sEhIw&}1iH^HpCS_?- z0UMjmGgNlF{$93a2|7pXlWC7$O*adLC8fEiSKAK?{{K`n6aNq4fZ*z=IC-Ua{fL=G zQi3U?Jwd$g;J)_sU4F@He|~&}LReGevZ`_5by}^*-?#au>ga07?Fy5WCzp;aQqA6r znjhTbJp@LE0Ne3eB?NFIQ@hXDD!t@kBG%L_kT4I-@$4(i10BOq=0W-=c!;qE=KYAL zmnBTtkv4Ph(;?TUhtA!-$CW%KD_fWlqY6PoS!x6E`<&ik_5nfR)^JePOHVQh1{}Y6 z0)AR3{Q%Cb{91g9$!RBLM%yI4#b@_p@oYt!mVOC7-v{O@bt6H@qi}_hPI|K6-uBHC zc`x~L+5F?*zX^h62GuW6kN<{~zL}}|pksd}W&drYIkvN#d0V^@FJ@xL&OOf_JnPus z=Jq;yICOO|v)Fq1RcMHgcCk?~z6f^lA#6?TSd;5Q6>7h}_4-9=!2V3-bM7+dxT}ZEmMN`NW9rWah)r9IGk1)5*dkA0edy+!HM>{nDGiC z+Vh3WM1d~cO+lE)hYU*vQ&o;BmtAe@*BnmV!kI1=Z@i0RHpZ`?8|b~ikz_$!g13D9 zUQij$u{(|pQpwfd1(^*T-Bvj(@F3A13iQmCD>2`87y8RT`nYpVUHG||`$aJ5eky_> zMG{6TdWI|8(zv zaTIrxZ6j^fTT}a2_v#eSj=VToxh_0LjS`S!o6Gy!Ze)w_&panFX< z!hgjTYTgW=qG?ntpT+w_2XoI#kPZO@xI!)*7)hxa$FcQc_ON3k^nd*5YDm(N%D-|; zEEi56(AVU=JCvq_{x7*o^?zC2BqbzPd;TL^|F{4DtkS@>AqckrZb=NX$Cfw^sn_0& z_EtXsGoXqZvLycts)EFF{qL*n8NYt7{cSSqaam2rH6_`m3c;o3Xzu1m*8dY)a@_L@ z=P9w{`Z?+nVEPEeg1aFZ?yf^}9BYC!57TW)gyoxkGfKf3z#-ZF1~*8KOsyTlC(;!frJ|MeuQdS{_&vo$9Qwv zir=ORyE|pHjUD%7hRHQawxcHyCmtX!hj@R{=-~KR&PkkAc->EkI6A{13a^Is76k$K zZS?M&s?rS9dA8^cf&(W6dN*C#TnKcbNBJA__L7?!BMC@MoXCr?TrgjUhBXb1(Pe0og zhRAC5St;JlaWB>lOFOG8YdWo3lft#@n+))2sM&$jjHD=X6^qgPWw z($SN9!Nam8uv^~7=9>yO3Qnf6xg=Hh(1D68%Zi8)0kktnL`J7AGrJ!Y4=eq`Yh;@tx*})(3soZnhf+1Cl3WtXC!i5Uy z(hPEL>nt)}0tRi?r&P3uUm6kcxWcn$b4p%;Xk0K(b-bH6E5C$I_gr|NhvHdH_Om88 z@p0hgAbl{Cq+CE>IKRf`Tw82(5q*`8AQEdR*i^sq=r`fqJi(HGC82yY_VI?M-5_&# z^nBtf`%%~%ZM(SF3f`OosmG3+NN+R1dGi``@^5Oe1hR~eo1B}MCdJ>u8ZaY8=5*Js zJMKVz|1WFE>(nJh7UP${Nx_dT-`SfsjOv&jE5~5So-cg+ZmgxNKv)*@P&Tfff%L}- z*P!I6;=+8>!$pd~iJCW0{b^z^KgcmqF8aR2P`1Kb0#ZwlZ zE8<{0bgI5YWX!_S_gm`3`zm!he+REB(Q>=)qSGjMs*kI1rCV%vbQ%HJlDb)8QR;He zP8}F9g&C#Tsk}=)w+wZQZB$#G&C#$mjm7ZYbkrsB3mt#DfWJce&Zk#J1RJfJ-dVGr zog*cyYiRj!*?|UV!j=HvBm}+rf}Bc5i(L3|_Bt;M66wuaWSd zE^|IIkbTU7kyZNi?VS1dgv>{Ba>Tr`5uNqeA20>-P@NlISz)AR7I(Tn8E$t==BI76 zRm>-dZ#-Ub)fqnQS5fbmo(D9-#2tZGEYb%n+Ue-&kp%1ERyn!3#TW#^rNhKMwYQRq zzTB0ovgBxJRAsxh1po^_m}g?;DmP+1WO%MBShj|gcU7~qDbV5bjk+c&168)7m<@b) zu^l|C8ol$dyj@jX?UALX1K;04y9<o?05jY+NDgA<&e*ue-&uo}U3WVKB6X#gf%k`t z+c*~Xyo$g<U=9PLJ2))ZSnkSvf>s{Fn0H+TJFa+dFr zgMyRSI{u^WH!Vmk&>9gyAWgF*&dX4GU1Lw^8M%5akcPkc!{!=DzBat?(S>`ZZFGm) zal6pte7imN4qE}Vcn`h^;LvW~{c?z=GxdQghwVei&ykKKu1p7kmI%jnE zznKpLh=s^9^4dzF1zXb<$joJ0xO8U3!aW42C~-l_pBs`;A;$%&7np9S`GaolHnW-f zJ=F=tL@x}uq#D~NHIHS22=V-B)ufKpQkT>gFN%s;GW!c%#xq}dc^|t8ed|x3yvwTx ztuTSq3GOC*Qcygs^sjIb5Un&r1oAo0R*9PBz9 znKZf2EuK6pIMcm8nzYwL%C1P`Y`^98FfU7%^7=;hO-;^pyRec&M5kN(SO%9=X*QWJB8U?~5A{l|A($9Z0d!A6O1BTV( zj^Jcl0HxZ`Zp;rOD#{c$M#% z2~CCGfaxFVVP@9I#XueCo}UFchbrklNwg6?-|0T{ON$D_E50jsny}#w&aqIn=qu-C zX9ttiZ$l-7qFNq(AWSqdG@c2%t+IOv?iVo#gKbg{RaK9+0x1nzqY=T-RdC{8V6RfJ z5}eUl9L+M>_7rS3Drc7@t@Jm~I5>x3R1PUdK7QL5ogn%gcojxyv+Md{cbqh7lHloj zF}y&<#xQk{E>)3Ba&lW<5NYIpu>gl}GcB%xfAM8ZdEmvI=-Y`m(@#n-Cq)eByI?9D zMl5mwu@&OJH*B<;il#N@BC>6kp11Xmo^Q*&^64pxB^G&-4QDfK-^OyZ2p;ynsjhxz zd+4A%#P*FOHS|kt>d$-081E3g*Q1Iqa!|MNW<6I}>8~juz3e`Jyg9;^mj1+~DATr+ z;pX(D{#o|>$DdDorvaSiA|$zZ!eaMR^VjQRs+o%7ey;QH+0 z*Vlt3WooZ6b$TUdi)@1udd-CSfX*9EzK zA%y@McA{~^VrRKRQ3`1_cn@bZ2+x80iN8jv%4@+htTvoY65;1<1Gs}|wyxv_2jwX<_F zqa~_7(Tdy7ykfG%^U?DU%w3ScVgka(UyGLd%;aiC(<43XiK&6B*0ea&K6dvLZNq>~ z3=#t2Uj-!Q5A|5=>DMZ-lCWP{`q2t=jHyaw!~`{}>{G`qOQ$mQms^Qkz`{M6+~3zP zQKxyV)z21!$b|$pEcJ$K9q&zeB&S;(VWX|gsHo%q{A4TP85b4`_c=QhH4SK+Wlce5 zj;iMNSlbkPD%rJTZoE+G#7(Lcjxqw{iXTf&zvR*{cPlhZ{wYT<*{QMlS%1 z+%tovgY!67(&MRGCe}{#C{$B+YwqX%Yt>+?9>HkxC zh(#c6<;k3>tADW{8^dKi^%qs5Cgs}6RM$29&vNoG_$=CO$wjLO+D;FDx(qY18}{SD z3qk*He!(YMk*=7}^dhm@D%t3wo&Jq2k1EfXkBViYsn&d3@Ml*VRp;-4nHs*A=x9C5 zrI_erd`i<8xd#||-AG5lmgdB9ANx~u zGhiKQWneH4eO4HW$qwx6)0<-r91XB(A*P3iZL~*Prt95o)iS(khW|~eBb+)6As5XERDHSQbg_&c zznfQZF~UtoxK;n-V^FpH+a`}@U!~b*!}%A_4XG2vvr(b)@*jl6QYeLQ)e$IuCYZ=t zOdH_-Q1(M{%FtM=u;bA=qeAr|wDd@kSCNdt14C3qz#uI%HL^>QfUbp#ktX6%??y#? zQDlfkwZTUf)S2*82|ui&&NhOT-ooI}Zv$>o*?`8l=^=jIi}tdwLTivBCw0Z8HrL zAc>waEaqTNIWm;`lMDxy=YIUMpOBduMPI}{N+~qpLg5cd!s={&aP<5G8Oz7UtT0Oq zwM6CzIU%(P*?QmTR_{V+aH=!k{sm3R=%+qr!>+W^)gk*r)iQ-TVE* zV>>JA|`VDsmg2KKTKw(V3Tm11^h z9C*sg1jPV^`TR_txX6lk1&D?y!q4Bp`@S{nL;UZNaiz8u&LJ%PCVBKHH#b*pb8>k! z0D=0$SYu-&VNoa$2vqEqa^!g@{*BMesOwz?d17odC&!_*aZ$fkPeROSduHR> zE>$2FM*xVia*q08j`hurMSf9oCAIv7wP^J9o{MpF3LY|LOF)Uj+!Y6JjV)nVO~tM{ zMhuoqsB-^&SStG1MiG`}oe^mhPK*nacQIodf>1AlTzp0=t}NXMe`n_CGoMRo>QJ1V z?v%Sb$uRSC3&?oicgVl~M5gH_^wTo`+WB(AGwHjC|3W|;s}gI_G4*nL467u{es6=Y zcUY{9c2w{KJBl$J91!sv&<#7G?5YsEaBOWOX(j5fFm+aO;b1Y z=u>gWUxzwM-t(_x|7={K3+na<746R(0@~6tusUK2EMGsZ7_1;#Po&L*sEqd3ogE0@ z371l(jkNUrN~iZA-xa`H-%;hYRysa_--)+ED$2CrwaB{l`2^g0J&JF_#3Osw@gJJv zP(4IbJS`c^_@^mO6-++%=a|!84g0`auiXf@uYuk{4KtXvEI z&wfu=>lt`mrRf%HrUnFWQ6WD45-MLb z{UaY-S z4gtsuHTZq?fxH%Y)jw<3OGy^kOuS~M;13aLTH_ji+>)YZ8zfj!1o}F0q&Zzi?TjJ3 z50})+(FoVM&M9~YD!K&%8k#rM>Ih&Z-^HhlUR&@_?7YfZXe2t9c1v>(C%dRoP`R^< z+EH|sp*|AGNn!a|8kE3!n{cH7ZcAmS4acuX?@r_be*~#9uI;W_Bwp6*I-%S4>K(II z=DE9mh~=&n4F@69Bp?fKq8{Fjpxha<+0yH*Pjr`L(=nXgkL4cl+Y!wvZ4gbrI~JbJY59QXS>X%~Fu74W`VmFr0+mgpDQi zt5ZbOS`I3CeA(yJpN+cumr-_|evYi0J-ve%mcA{Vi%zq`x}FcThNp|aWJz$D)@H*q zeru0KwG3aRV4iM~`MgqP9?VAa8w)q4Dl|T67W5{=+5O&S%+6=oe+_E^NV(Fju~>|p zL5sUR|6awpGPH}?(HXy-xqs|Yd;`YSRp|GR86Os6E#Th4y{8EVE{q8gJodhO3c6xt z0a=@i*5Wub(DyS7uLagG_Fg?)?qMCTSM`VoA$PrYK4+mb>bWMH9i*+TEwhniwt%Imu1 z_&=Cs6p@{3471@$2M4KB7b(=LWT|=YPmSU!IHG{KzeiluUBh%pk)HLh+L)*2vufgU zDYQW)$>L4Q=<8$w01s;l$J6?#?FWx3o*78vfg+Z*t$o0zk3+-Y0cw+$W#KQ8Q?rjg z+PD@G;oC*NQ%g+Q;c{R9$%aV>{B1knS96UGrNcEK%h6AYl3u+) z7@?j#GCG#2lhsudkesUoMo?5N+=EXz*9Eyw@_peu9j-{RF1X}D2V1mSHb~`|T50IQ z-qK89J2#*@KRi7O^ghFhCxih0f2e!Q;5foAJ6N_X$&v*YGcz+YGcz+wBWAM2%xJ;b zVrE8*S+ba!nWYhD{BGXOw_lRYR+368{i~~Irk?JZr|#T)?z!g_eS-Fi5Lf^7^(LE8 zMkS;3EO;{6Dor-0zy!tP9Xx92matEV_ff1QXtJZd*G? z;e5ZM<;32U7#H{Q_ySZwob@^9SQ`n~qIh1shM1}TE|o@IN{39P zsH&ylPD#Ecl{@zA=WCqw8{8XHsO$PK>&O zr{POZ-xv+w6N5Nt>DQNrY9M{Moi}-*KT(@iy#*eb&(BPxUgd$#!x0)rUVWPcvu{c6j5nFx773Oz7*w_htVL6hx6lcOU?5p%p3M z9~6a=GD#8W2567f$exvYy1bvFDHNHzoF7`cjiT_ zD}&3rJyS6=tcbH25-)SsL^gf2yUAGFH;j~K~w5+U_Es|Y#+Bq{_@;zq5 zKA5cCE*Y_7h^tCB1-)EaPqR!WaXcIN(%N8D=c?o$$Ev9)h$=~KlF#`66Z*3O>!{_M zaDGC@0UdD8{xd3^3k?=6)9M@!ZHwa^=ov4U z;p+P_2jfVUQ-3mr5oh90xX6&2x=wQsiF%}0fRRn`9==Ce=|K`NBUHy5&hl+>MoNC6 z`b=wd08hB4(RlN>ReABJdO|Tfb;!jetuEp-hn7L*JKOOjq_tSE`t&&NqGo!}gub;E zR`~gR+5iC@6$V}EsA1Ep{tVVK2^!L*P*0h}^h?7hxKFz;+%g>k%nn~p8dts!lWrBX zYN121J3`c{ush=IDb=L07zC!u_5280WJYnjn7J*}nPtIQ<#$Xlo39cK#D`>mf-kH9 z!Z9>p-3rOdeLmoVBZ>P#(vp0Yt{h2LYke^|fHy3%T zHCTxE;h8|d?kFOc%CiCZTNuX563GQbw|8@9VrG~fx6Iw_$I1P%kfP&Iw->HhtGqA~ z_mZ|n2FR>a(SKpDN~aa0c|r?aKCkm}= zi9#1s8R&FsbHv~8$cP7%CN2aJN z+|#7`y}^$j&{=G^hVWtN)UICVrqidR3*lMmBoOpJ8hRy4!H4Gl3PRge-Mqa(qr-4X zusai}9fcBygOia0v$Tw+tGDFVjPg{*XrsNW2~rV&m!P5(M~{r|7Q}w_;7eei5}2b~v$Lph|6q{mNy}C^WIIN>B6C8C?lJjsGI13TXbNp z_F{~k{YwxSV}(<&Utk@ZJ0@w0#-DSp2yO;_j!s~6S7rK?w!MNpG2Dqm_`2gpPq$f$ zQeL%WDO1E|_^4_8nT+f+Mp3@O^#l)>9}NOIQ?SsSkdPD+v?L965qq)T?VELxVnSiY zXSn;B2agT0k;aaxFN7ZG^)sjI>bLRz09qLirNE>4B6J3`+RYQMd~Mx7dvE@(_Qi>O zmNZ@2kdv{m;nc>14QAOSyyY;A0WFD;(k|F&#zL}jrv7?7DnC|j`_$eMe>Brb`SZ;b zU62yS)bGuJ9>XD{)mtj0g|P8?|DVR+C}N8Lx8iS=COj89euZ3Wmc9iq{Tf!$4J|i_ zgwvYzmbTp?UFdekkH>W&c3a_kWIlj{v|nQl-TC%upd$}}n>RUh)vIk~d`5pTVwZ?s z-s1ia6?!t-y6!dvLbW_bKq07Sh5JjXr)f zWmp)I`$d_SS=X1WU4q|Qt0=L#EYj$6+F;sV3U!ki0|gBBn^v?3-jkHh4`exyAs862 zsfz)M0f2}hjm)6ASR7WYyQ6Tlh6R;M3{R3mT5>W*8-l$vP0p^>m1`BS z7w_fc5j!z&Sz99vmA-juujN12!`BdIQ*8M`t6r`no0IL$Cf@-8HK)YxExMY>Lf&f|!x zNbmb`>R{RrXA&h9q?dlwlDxjLEAL)~dDd^Or z`6h)}>zYu4PE2};A|vli&A=@scFozvAg{Mp@D@L5)_rYgw!PW9z3<)@z2@Fs)u4L) z%1>+pcSe_INuN@{YM6xB4Hnw?t;eljGp0(?1aOYuR(w~qWNFnD716tvmL2ZFJC04& zo=sB^^k!}@V=OiKrEP~Pq6W!s;-kFr$;QzE+T)7a_?BX~Rs0Xvs?@;N+9_9jjAX?< zd?r&`)3WwxvX6c9)XO+I9RX)B$6QCX<$*Drz0_$`ofdfhE0~uVCimY#*N*7^_o8b% zGkPmG^ACjALUoROc$U%=N}ruIhcQy({Z+N^ZnOyO@WsDz18;BjO~0o!*;KEUAG( zec&)@tCHaC*yAi3%N0etyNk*4TzB0Vd#&w5hKZ~jc#GI;;dJ%1FOinC8^ga|5d6l? zB=x!vYiXbTt#=DW9`2un$@F%9BZoU51BmmJ^?!(<1C?Wbc+xqL7e{XK{U!V#Ld%+J zjs9C`*;pT~-hj)vWcAO*WOY*IxJiq*p=C7?m)6vY_S9V$>}vdjq~rlcQ4f^Duspf- zhCt+aq-GtL`tcjQWk?pO*So-dHe;tSN6zrOZe!W1BaJsdZR;E7ciii@!^72WwdUW} zHm|Ufr@)sE5xS0aCk4|1cJy2o^IaM^2?NUPH^fR=eg~5OFT!?PA;j~KWAA4lxEl6- ziJ29Zl$0#$$!p4dN0foja&mIwR6_WRr$xrC1KxP4m>o6hZ;k$5$OLooG@R;MtePT2 zI|oX@AR8EFL%jX{@114AW$E}sOS;?dD9txy(d0UrOnf~CJt^IEW8=APm*1a|K43_& zXg&F=e(WgwW8cFN*^(>=z9Gp29#!|vv5a2+H?YR_Vp>F7)gFf&ZyN?9(Ul#=Gv>>{ zeXY*p3B?1(Ktf+6)QZ$7&%m`f?$GQrCJ)a$7aZdI?>slYaBu&L^_C8C$L%407{tLl ztAz1-LiQMsjy4PJyQ?#a$~xU$Zf6HsLachWr&rp9c{? zOWoI8Of_KhV(BJ88Q>kJOz1ykYZ|Z_4jB(WA44c|LKUDluEF<_q$1`6PUxbe?eXJ6s1~zR*L}E5?!ml^=T^6`6D zY-DRGmClrW&kpI-(7cVg6!^Su&=c_ma-Qs>j;|hc8V)2sZujTBV20nzw)?SjlFc2Me`=%q>W?*hLMb;GJ5Zd~L$=VpA9Alh zA0kNjb)aUthda^JgE@fxf~@lE%RxIo+`xc@6XL&xKW=%w0pwYNyZX#KxCSW@m`b8S zj&3bM>5c1h841Jt4Z75Lu3(Mjd1sv&qrYS({P5-0*ou%qoZ0W`D`VA<*CZ}!opKvR zMTyZcTX(o9W{Uetje%*fZ_U;qnHKZdQZRccXS;H7a>?*BMI1!n3mjLHb3A>~MD2a^ z0BJ*3i6g^5NIHx3yFXrwRp`@Cdr#82X;S&UuF8FG+z-6*?>nL|+%Vs@6C#e$749xS z#sXdwJfQ7J{kkVF*54^Wu!c`G0FUPXU zC@5+z`^(taTW1PoaaYk}SaIi_{@r%oJMpdIkv|41>c!j(FmNi{@G^4-1wp$ zhU6pxDY{Ek2(~)toiNR(XcyBLwRRr;GxLvyOVAJ+QZZOhrSdiqR&*o=aNzQI7 z!5)t!%+wZ!l5CmnORo>6q&YcFKio3!6Memj&PAAEum*ra02*kGb8HVogN6VVH!2QNeCW<4$&c*+9{6V>}5!s zN_^G}dGrMRF9Oy2bo3qSr!W-LEi&{x{NS+}MLkmzrFDyW0Hc_iU@Jd!x>Z^k?Lea` zex~!MQy)-u0cB+F=A8dWuqtvk|JYXDgcvsO^MV7JDCFRk^)0-TG8!gM>{2wsugxK1 zh13LnyYSXb0ylkSJ6!CUdKLr|pz-xGo6Ktle*`rWe_t959%%KB!G-dcNUOyiBpc@Z zPcDGI>)#_Qqg0*YKI3mGrSTsurD#L`2aE{xFvzgaMgum~C5Asum>@nwJwo*xx|efD zT13St-+HzR-Z98qut-cV%6|y@0Qrp`7>MHP$`vWV6zpcS_}c=cHx0!eTu=71yfSJJ zyvH7Gas{5g!5WTRzD^QefpWQD1YA%zZry12VIJ*#-i33tU7;I}g$jK+6TRn8@}t0A zkJwn$?=y!Xacyu%U{(PwdWAVw;MxIw1M0`8Tz8(GcQE_o(6hZivVJjnqu1uOD6Pqtg*Qu2$sg^sQS|p@uoB;DxOD zQoFj@>f8rIAL5W@@@sWNksy7gAqwj=okaXQ*pAv|HyqWC-0F6s7`n+e?8ocuPgvav ze!)9XTWVJjl1k)(@Q$^PxLpohiW?jO><(%>Po7jh!*Ys)tJlm1ZM^VbL;%;wwZ3I2 zYV&%r{6VTA>@62D*sFraSgKDPW{ZrJk6v#)aLQ8x@s=`Q&Ea*wVikb#a_sCpz9}WHO{05( zF+QN}Ywg&3w6Nmd(40SQc$_j1D*nSlBPOvP_`2lb!0I1l|1Ula;*i)i!p=R zo^ok0e)PK&i?J(_He%k%|Ac<9aKr?nU<`%mHGRej!yV>o2M>4DUKP*f7^CiAYw+4; zILi(QRlJYw4{|!CXA=wiUW#C~R)L_b z0rlU@3NJ*0+2;=)msq`+8;MiOAM*>$j2=Gc?VsUCSfi+!>DihZyt2nqD|!?uH&Z71 zh0={j(Zn31m{9p-&l=wpdan`H&jy_?dj)@dhj#VzreQU-0xcvo?NGrWVv>B@EpYPO z5V+R|rMdDTwMhI+G!Q~g7}Ximy*6m+5r>C8o0zTZgxB^=WHcS))FlO{N4nvzK9j>qT!rgq?erQ2+u{{u-M&8mO`KIIVi$P=jH zl*?*6*4U4s3uT-dFKY>P@*?v-0eL+r?7VbW3~99cYQyq!<|4vO0%>bcAR&N1*x+x< zhw-}vxhNIbouI$MmFz}ebZwQD&Kk_qDKP8n2rZe-g?v!DD+3J{4FDT|pts5|s=q|= zHF4dq0hyWZ4MID)vd1M897A3i3^CgD`m2pZ2|V))Ow`eo}@R| zB8QATmUyr}`mFT7l$kb-wJhkR2HfIZ_}xP1b*^i(sb|(j9g*@VQ!e7y^&@mu|ETwM zCq6Q7Oob{ZTu9?UAcehm@3(XA=4~g|4^=d=U+y24+B&V8oGEnY>a4Vo!%!5l@i1CE z$b7>)OQqL=mgVN%$gFmkaIHdO+k%E3Uj;56*9Syvbf*T$QN zcxDhdSqL5?Qlz6`t@Ky7o_~1Pa=aaRT3WnRk&gxsLjcAW^<&G*>tbUw{yc-PY-x2ft)^~Az2#X^=G==9 z2CU^NIY#}2L9-&Uba2J-UlV@K@hAHl)jxPDs&l50Zk=SUb1WVI4oPvwhY~ z;|;ey8BfN}urp{&=@IsDVlt*LVn>*#tlpUVUR-gqs6$mOj33@I4xh=$$l`G{dJ7J3 z!=7Iax`>7E%@ECLJu^1rxa(;5Qhh#ITi)TpM5QH_uw0)8V%q<*PtX-;&%rc*DAL4Z-dtpc`Yz&Q zBCss~{aAeODdvhla|k?7#a&=eJm-X@j!?N9T_lqq?|(~$yC1uka|_{4M=0DN z>*@wuED~IW9j$&@$E9k?PpyAILoH>t)Xt6-=G!0lN^2?r4Ds>%LY8(XN^JXB=X%Z= zH!|t_`+-n>fAxa!3aH%S$>s=i108y-OAh$t3YV03vU}qut@eY*hA8M zRg-QVd?Jbh({Vbe+u#(3EYIk2zfsL2UVAxzxAUv0#8U3Rcq1g&#d8MjXqZ4Vv->FC zFR@F%wFhYlMJp?gT+7LeiJfxjVmps+XZbG7&=|!ZPm)Xh+8ti~0G5xE`O{IiS1&5o zN6eAALo+f>=5w<$y{w9i#(DJ8FHKD|!Qehl!ELE9k|3&UE}}`O%q&xp#u-_m_GrHN zyHjz!tCucvn}mLSjr@@$H~Y=t999L&)ZWWHNghvfP*%5$q_}(fV#U-1HK84ppfdi= z=!|&7ELDBbSNmRzTv@qq+AO(za$c-n^;(=V>YH+|;W7~ib#lX`WW)z`-!}P#JPza< z{DcVnRdMC9>EoT=ZBSGNgVGQCQ=i?l6}eoa#88J*w6?4yuZPF*K;cqBA8BmzO)h3_ zo)((GV@m!`J{k_N@ezkcIZ~>pI)Y7X#Mq0oykhLp;K%=bBKhtlRkbM}` znyFRZVZQ%38sGryr-nxEj!E&QOO9)2e%dK7Sm~?e{k# z$u67Co!KF*dFg8)BSH@g+2?OVvHPlGxhC2$G!O4@D*$s{X>q06op*%_Z+j3(;$>&h z1RygetEaUYv^o>hhsmz$_ZJ+0{frQ-(y6*h z`{V{VvyF}j`$zC9Gfcqdy{RYLbP^)2zU zyO3818c)YaZw9{yw`$esRA}joVAm31`i#IT9L+Rv2G)_b-fQltjAj6FTu3TilP^{9Dr-!GKRswOZ}Jf^Y*QGcGrkI3 zC-T3e!pR)f&B2Z;DDEQu5t@}VJR>SV{MJrL5A;nlrf-*iImTYs_MYc{ELbA?^H+T! z1sXCZS9h13mlU1#&IV@_6!I=h45iujupe0R1x{w<)@9QXq8P+Z*!RahO#!CFa}8Pf z^j2x9QMqLP;)BlHhK`0EaPVOR&vMur!SrtZwrxCO7xv6VCGNT?(;zfE<^pj)Wa*iC z_ON#m(_6K|h}t10YXs1|nHcb<(Ka?!SvkSOqZt=yqoiDIOnaq|AqF3elr<4}fU7tE zjdmWQ^fs`?*=Iv-6M93ppIcL?%yfS=Bm2*sDq9LXOIQ2OT=k_(|U z!!Cu_E8Lf-i*Z=M?J&Vax5(3Kg7%j^8AP&ibEV)9^!$ITKPfOQ5#lJo4tdcg!D2i` z5ZlKutDooSzoJN|;OswU#9069Lu|5PdK(Xta`bGuChFdX1>{)exs zgV}<%daW-i_L~~O0rnUosH_Quyp0Ges#Cr$@TtMD*7;rP@OUA-_YXX=L8Gi zGwSq>A4VoTYe0vs)RxR^#Xr1Udi+PgTU6z?WXs?O9?iiNm!^OWm-%Tk3qwJ$CtP0G zCrLFF!!7|9(vzM+YC{=J4{;&nG{mIc;9drw^-g&?qT)^#Bll1=`8LCrfus0d!UmMO ze#su&*`!c6nuxa2&!LW9zS;)hnrnZgp|S2-U(tivCsgLH6`{buoROI-{CGvtq9Cn- z$gze_Oqp&QABW;YWhoVrjgnzT!s*xH7iEIaYEa_n4GbnbDYffI=RP4O18>0Gm0EjO zKW4BdgSZIvc+wb)y{Z^sRaM-!mMF5JAe#4Z_xKk$b>!1)kfKO?r`6f1AFXV1K#dBd z+J`7vtIcx-=<2?xeUkOba8*G?4kPnh)>uXR)K9nm3mIh_pSU*_jY}CEXhHVKdkQO3JmaGUfcMThkdTogyi)yAYG4>dM3(yz~p{wTPW)F-FEBlFW~W zBb$!>Pb!^g-frJrDe`>S!P3RR`eeGXU*}dC;;-KSPLWI~gXNHTf+4))NQxciQMV(+ zLC~TDX+@cxE{~ z-Ci>Pq)b8ol;|U(c6r?0Ot^l~jiFwXZ%+<5l5w~2R%tM%UFL)np;s3uSb_NOH+Uc- zDed3e0{eFe3jHb|lFQK)vN^Xk3j``!8w*=e2hXrc!dNKZcnwb1l1Bhg`33o=E>&W# zGl;GLyl^+%hYXW({kPMu+OsuH;y8UhNKuBdUD~E9b@_ARw$YV~((*GAgD~tQ?}2{P4pJUomkuDo@a- z^o1`!5=*JCVP!#_)EPe;_uD$a03Ur0fc{r$p|I(Q&x(gKN;l`9wZG%JT5Rp;Q^=w1 z^gW@_7E6w;Kp+%%|DD7?S=1ZBcRa*yHb^#I?NH>LG0}R&)dwf-ivxE(2Z)IR7mBBY zZBd2`jjp@B4G!_l?E*oVnP8eix91xgCF}K9Q7*_(_d!KLb{TLX?eOzoJ4&$_xTm#T z>UQ6npK57*Hfm@T9qgbGkE2$6Hx8GdR5(+8khIKmElP79>KxWEIW> z9sAyfV`$4v2_Ez@tvO+387;DA(w*w=Kwl(qy3i(v(`24j{{^0~!S0vSn)r57o&iQA z6|4_+r~U#UuC61(5u_6!5D2#r=#Y4$t6OZ5f_MiPL z6hcBpJ-w`TKx$HydzsatZPwqn^6=~lA^q29KYPx0+G)t5Aj>psj3=GiSCH~--6$u9 zrxfa}&-pY?xg;FBII*_Z@`Wl#Hw5n&ShKE#_hV42<0t>zW0TEsZ<)nN0LY*Vc|X0 zFS&~eB;jhpkwoQ4vnA0$?`1@n=1ak_$#JU{-)kaK+>EB2sAF{|eTvEtm+4E?2b~L`F8WK)Ck>UTt zG@4RmBKBtBW2>i^aIXre*&?cJg|c@2QwbLzl?x*jT@Vh^;%GOG!0vK+7FVGZagcToZ9g#nm=h4JY#~* z+|;AV2uvn2@kKfI)PZDpH_nKdq;Oy&^6OcC|rf-g_@G#s*fon#X}zwhjt z^jQxA0?_D9a=TYpGq{||2;W&^3%Lv1yw#jB81#i4(BH28BAekS=mdR@^ z%vin0R6Vbr-A>_j$9T=-Sg%49e7&~k%e7Ug@^tUaBuq>Na+-pH&`&kyuD0H9c;Dfu zEQqPu1+xbyO&&)=e3yEY@KM{Q55ioUQ2M?kbalwxXfEtLkJxdXEsvcNciMT^vHMx- z?|(=V*w;T-NOM;Fk(S>wz3!};xViZY<;P{(Ez%#@$e{WxWZKg3{7PK9M^~OJ!fFW> zF|n8zndg8MOrZyPS|2^Eg6A}$;R6W7~R5_ZExMGmnD{g|W{d_8etiTX*Nl_$aMLvL#6)p#R-Zl*?5W(=WVm}Y$t2-u#C4VS zsjnHJVMl9i0U%fA*fxrm@^V*~4#U!0g44||3HHhxH>@*r)Y7n_3_Cu}%)?+*>UUYu zovoHZK%qUjM#b*$dZ^WH6zX%g%T;4;lWJS4dFXU#X%Y0wgJ)C~J4Sj_nD?90pxfVP zd9^7_oaPw4478xWITw)b@;h6Wvo^1hI?-Mb7fUI|rtcrtlNaE2TA|WQE8u_WQ!|M^ zRY>!Z-e9~)VUN(<5G3z)E*we(Fql+6r(|_ybFTQy2vh(tssw1s*`r7Zir20`x5SmI z%XxkZ`-*}hQq$APrByanUx~{jZ9LiNmv2nTXNNmgDsvjkq_9lvw&8wX0LudmWvei2 zEgH(SUC-^kJhJ0X3iT+tPQDBp`UIu9Z6$}VAn?!N-@742S zAVlc0M?cXIGFh&mM}H5wl;iImuKP_H6J?aYO86$_B6m{EDBp85kl8U~1$Eyk6ob~5`xdla6_o)kZw*-4~M2dxsZun_cfLTt#TZgejoVMc5_ z&)R=6G9A<ehG*hAcVNYDL}Y&qzoQnW{j$h= znX$A1VmvO{TrWm%z(cbeY(#OlKs|9U+Sxr1CALS(?3t)`ljU;n4|%FM+0N>}@H=k$ zRhWsW3sU=mMkTx>Y*>B1-39+iMxf`rBk!TF^a66X%-$3idsLTI{U=KP;I;~;=Zw- zK@>lSHlLjapNw0Re5U(uvYwAP6jxF5Fd%^fK>sxWJODxck_$6nqc!{J$3v;9a1fU_ z9M|OiPV7veP1}^ICJq*1$o1qbke8>WeP8Y#QPlt3wk47jK^o!jgNKXhr_htb<_J(& z39XD5Z#DCqBBooy7}8AY+#P(()OudCE!VC7QL>`R#6;xN(n6YDUvC!}rN-<20S#uv z%|9hIgcZRF9o0P2vSadQptR-|t1FOd5bpNL6)WbIM4QW(Hx8l!XS6x{^A{3r=3$ zt{UWlvU#y=Zj;{L!rP?MpY6tVXE?t4gQXsW?us=LhqQrIB8;l00QW(nekM9Qol&GeNR zQ7z{r^!iK}$lB6)n*&6k9#UVAQ1S=;0niS9Zt<>uO!%z}z08B5(Aj0Yl|1pgJ9zMu zT2M6wg1Hr3t-i^O7hwd%0ulvslg!aTrth$*>sxc3uh@&ZL@itxBBG+Cn1>(BRQUsV zc;^8WSM%)88F%G^wgocd*I4g+uiD04zVV{Wh-k2|FVFfMpEQcRg^9PvyzH<_wCdpY zRZp}7?(bhzK4vbQ^%)dH&%M?;!+_f-xJF8)M+vEIb^!YGUrt7ihB29 zGw_qnXmIl?n3ChnyGc@VYVp>SJzm3X?=7T2!9u|KSMVq=Alq^9rXE*Vo$3Z_*pC=j zFI7{Yvz@Ibm%kRu^xaON-CmP$<vX;d>Lg=~I}?c)4u3L* zDDZv#%m6}hVZHE}PRrd$kNt$LR{6r53@307dh*)dJ(M06mSwqT!;VyGZN?T?Spw;Z z>%4n@sDeX>ofUoRjI(;t)5qZq$T-^axI?qGhwjuvOd>-87MpzbO2~O&xU`7)r3QHn zbx7>TxKp}M8W7L9F5kKJLaOb{rhGCt#dfJyo&7_)X*F+VZtz(lG5w zJW1>2oXKCWEvy%&vG%ez!Pn(?3bZ_pu}Jqp2=Xo5a_?Y=1hdPXw?A+;)7V9|L@<{S z9l=PDISz?Z!Sw1_i6f-aWPMlI_1O~>FwQ$OB>%yb8fP9{S`XkxXVgW!hCLuZjq0}F zjf%hEvgNu0_+H*2z&}%el!EI1wL#l8NLMwy1tpI9H|(8vD7&Wb%2Zhh3{St@9LM<8 z!V&d+A-;Lc&l_9Cs{QjNKG&^6QzrBv_`YoZp6<&}S+Z3v5t;eBsfqx$j0lXD=czr_uB^wrdl^K||yC5%V6Ox}e?& z<11V)q@DB>p1~uwC=W-W{|+Mj>l4KHSBqM}Q0?ohXL|zPJ3d+hug9vb*B${u+ghwa)y~sE!mJ%zhUt0s+Q4x-Jd@o zLy5XfBuNANCcdV#fyQUjAGcX4cY3W8Q4@mpo3A*Erk$GEEgwW6-4$A zhuonXEBBivBHcl39Gs_5bAL^9ho1lQrHqB1Aa?LNIT&7Uy8Sa?*7zQKJ-fo+IvODc z=3n(Bk-qJ7{e2r78^JfernsA5@t!?Rb|wc?Uz*vmgrZ1Vh9Gk#>U^e5<_Y=Y3N)F@gZ+n*!V_@;;!)XzE(hvYFq^3c44Q{KpjQN|SvuYAbbEK_a7n_xdRp3qjM!vW{dU@@$)ch~E29ct8*O4> zYi^X=|BQz+t!i6HVg5Z~c$_!CA|OO0r#l(I^xZxquD$_i@p}E**9Wv*8_CuSkST(* zC+ba7CR&AQIgmFIj?$_0;ionDFSe! zbb?rD9ZNklV3A3_{U) zvvoA1U$*(q#!nyH%e6b|hVu!#Dv8S*S$Zt=^>pc*BBdGc#HBpLU#g>O^JhQ$ZV;h! za2vAl`DZ}S2y%kmaef9CPTwumI%t6lF>8b~jiYuX6&|=>h?$9zO*`TiL0+tQ5K7fg z=+A@Li;S1gf9B!!jwDvzIv%a0V6R~?`_D9#t)D5UJ9{n3JV5E(Nr7CPmUN~Dhu_HU zNF7qWBv713^n*h~N1B~>-df_>G?#V1f)0QJp2fiwFXXR~u7TS`^p<^*G$bV_(6R#A z3NJ9_324a5qyfnk7~+30leaRH_D*+oz>suY%mhsK|GvcA3+(g*PKhz{)O}^q(tIhz|9D9Q1yvo^k|{9Xp0rx$sL0MS zlDMAGl3M+WhUT$+27s!XvVw-$KbvLa%&D9FlSp(a*%E6X`TM7=zUJjMp_M!)`qmQ5 zoZ4iKoo&*u#c>`0a6kha*ZTi zGBSOsY>APg6B~Bl;U;}QEC5I!w+?0RCXs~vh-7^qpN&+IOdq~UpJVPyx9l1&j7fK7palA7|8 z6Klef-p~HC9A2LQNZX;JNT157o08kEEe#H7*zUV@(D@LZzQ28q6Jvm7)(#=lUSH9SCeAZkv9C*S zSC_zGl@aPvcP1TWsXNGVA0^!tDAi!zLdFx3lKR{a_q=UXAu-bmI3x?rZEfGFygT&w*ui&9WEM??ZUZWa!9f|`!$Y4@i5ID4Yj7- z+LAklUD{OTgWL}j+7ur(P48>H?>J)hq=XLkW4>r|*I3ZxZKRJyl16A{-I3`pk8VG- zU5>0$eNtk4lbLMI1|2@U>bZ<4`lpG-R=q`b%0DqZIG z8gaX8Pd?^58%;gXedZr}^z0s9L)O)!(O?YAx>K3F)CZ=4%$9^r#-XTm3yCIRF{K(k z*J|eDJM4%7cV)A-ZxpPY*(6hk(acw9nHHVWH_*M>F7$26u7IaRa1<@Z?ETDZnXi+# z+`QUa$fyE*f=XKIG~eKNg0tyy+pgK(I=Xyd_p6Cac9Gc~>UMdM3zC`rxc=tJ*)Qok z6!kr0{o^yX|1oPk{&?YyYMcnx1-2u_SMcOV(i=2#+D=OmZ4qGqWY{>qF+&r0)4xVa zSda;CKG5A4oltp(rQ6iMrCfxJ?l6g?lapsm&uP+RzqeagQ+f}vqU-H29Z?}t=5*pLOD4{2CNysmV&!T)SiH!I&kn|^6!GC{yu>MP=Ii!k4zUK5 z-&T$s(%Qg;=s^S=uDtc@>+b%~qBEkIE*;SoYE7a}>!< zyIKpp*}P z!Xd2~|J3i_MT1?7ga3=@&WoA!{~z5cADxX#e5idD;vpFhj$w!qSN`+py5B^Feu|tm z%(6uJQ=-=07gvNY>k@uQv0H_aZaC;%N5+O_ZG)?PqkO4rTGyWsW-PM5p zP-~L!w5BR`19WVkEz-q6*~P2u$L8 zMUAXuL{m`0&HBXMEugi(`ku4R4*&9fzhRENBM>272w;%C6_Mx)NNh|RP}wNVSwY`mw_TvJghX1k1A_C?QIXvmxm7T@rLl>0$ z{O>L<%N(vy=h^GinD{-3_TPQkk7WI`x*{4jItE&y$}(F0pdcY@(=vIdrAGlW@(re# zLQX&R4m7Q`xn{mu)*nHL)OUnHUB}q!-D2NhokhtsqfK>T^aq6`Ztfo zgDMzj2E&!ZZZ5>n93Bb_mQ&<)TLOO4qNHDLJKsQ53(Y7gADa%$X0b@}pdL^W(&&39F7qK2U`=N%9{H5?!?$k-c-@Ytpy!8+!ATR1Z zGwsZ)&!vXOXn3CbWmfR67wAz$Ioy8!H5E?y=%~xIhWXw-%sHymXVyb@rPua0iCa0E z1{CtcQD$CHz7qgF_Z-tIXV`tqJ{-bABMk7(Ng#D|t}N_E_n^ctp2FkKn$r3UP3iv+ zp{a2T8`=NM$P{TC((kcDy)~z~?_`7rMxFz=h4in;^f-st%AM_m-oYTO6c+wLCjXvK z6mp(nn$P!^Mp1!Ft&M}FhLyK6#1zX?1^!7|?H6>wwymPjwolvvi7$HARuw55EIHWxC%?HTUPwA7b4kYNqE)}}-r#JEeCS(<{14u#Ny z>OfEjs7RBTy9>I%Opa5mr&pzsmHL+d6K(Gp9a-1#c}E>}Y}>YNyJK{cj@7Y~jykq& z+qP}nwpDrSdfxkX6nYcnxtB6QoOjOKp3d=!^6Sj(XOi1T1)74tg^M}Xg!PfI4r|Qw8lR1)- zYS+#B%7fT!lVolUiLMUj!a=WP`_eK}1J0;N7T(mAfkP;6c-hU^*x(a^Jw-+ITzYB`TbPUHuZ>$=8y(csOvR)+&*o&#MpD> zbwru`=4*V%{VLt7v3yA&pi!y|e^uxXJF{SjQgVQTBu`?z4-=D*zA*n@r^078w-s;IwzuhN4{F4R} zJA~IWFklykE7`o~Pc`PPp|@<5!*xEB&!sP!( zu%(_WQ{GoD$MZ7JEnTI>vQJ5G)9Laq*^?dO}^XQ&2F;Esv<&BJ5w+Xokh7w@09 zK|Lw1w$#RR7gP(_yoY=FQXHptYWRe+XBv4uG^Gl)>*ZkB*3Gs52FyhTO0vn8F!F>9 zru!Pp4O^l;%*3L3MzRG9jj2yXlXGK=5XAd%pOSO-w9DCVs4&{^%^)+#3edQ^rMJ$% zsS;_Zio#~m7u6Y_LOGRcg9I-?%;9}ksyv6H+hj^SYMwe_UG|PP5V#O4B*H{PWc+w+ zJ(b15(aJ5p=`qlH6E>MrxKg-p%GW&H2-g~?P&ro;DPj>6{y5c|55p4V^dxWZ=XeD$^_7-xslAt~cGuGtu#d>v(%2%zQ@~SCjBE@7d za%z45%M4J=4cTbT*BhsOzFE0+dGNqr=8P&Z%^$^cyq>U=^eN0=u5bKZm3v!}yE++6 zTHU0Rl^)x42?(L!H?yZMM^ehf%=BIBd1ucWIz{KyT55;(US5$3k0c+xlB?w0F5I*! zrq)RPa^TB&tiz|mZPhe-SpX(pSudc%wKQ)SHzNF6{h(4Ad=YcryB|1mG!va_kWB&i1 z{i%{-ZiM_C9Vji2;Z-vg4zxl`W)6$53qrzr8)=4@u#>G)D7Q>90FUt9DA zbU&@`g;yde%MDys>`)xvK!T^Xz1Gsq%|E8&>i0Wp|1jw5qtR{ql}Z98bFDZKs`aOC zt(Li4y?#u&qYbyn(K}3#p`&!-Hp;X z`IScU-O{V1CLikqkvv~{N%BjPA23|84p5BvYvgambl}nm?g7v-6}1VV>WB`7w445w zx6ZTB7GROK|FA1M#?CiOhK!y_yqvy9J2M~zjE{2_HG^oWx^%L}g zXx9^eSN9q_>9BZz#gWlh1x@_!7(8>F?A6i!U}K35Iw;rWph$`wG?Y*B+$;Pv?*-_9 z0cJcN_$Ee%T4BW~0t-nC7AMM~W14)R{XFlrTbOumw{^rwBy&~ltZe32Vc;9mdT!$mNc@E`9l&;|h zr?NLN7k*?grQ+Yh(J4&E(zc}K2T7X@ALEy(b}{+bBBVs9Z}^YRdyO<(hqv-C)9JoD zqB+Yz?(Y8VGk59j{v`_O)%>143tXBWuRxya>axZrXE8O7S5p7|J#Jz9tdD&4bP8poAKmcND1hAh@YJHL62m>KgZH~zuJsAmNf zrn6ekTFg1<9Ct5n50s!(X-+7-BwF^BcjFyB6%^sz(teg<_HQqS&6*GLm+;XWyeAqz zr<*k3AEif4E3YhntDg-FFcU6waZ5f#Zsz&>Ni}a^E3z2(?dI8O$hu(%LpK!Rx{`=Q zbvt%Ibi$_-9vw`tMpGB2V&?C%86nASmO$*l8Yd0%iRIu~Qg#`mPv6jqj!kw~JfVc| zz(KSGGdo?r$(+L1)XCBzj8o%Jm*2zP=IC!z+>#9H6g>okN7axsElwZ|rlb^-h+yFw zxu-MRT;*T|C{KpQW9T=1qrjG!1JPOS%~UiTZ;jW}3p_o%fV`X(8kXJP5@u2e1{3Ry zY9uR*{)60q<|g$`hWsEVX9XPOfKwa!%{J#!oo0j|u&p`s?@Dbhn-NydWvUBx!PRYx z`PMa*2o$IY`s7$$M-mX46VCW1Grx;AdV+O-u z@Pj590cCn@|1jp#$H8%IGLy=2O&j7t<=~M?I^JoOzbOF=UCbUjX6{Fs)T+O}%E6+N z^f>eM^JN{{tk%Y$V2>=`BQUmciN$WDC@`X31#m$NTGfT3OC}Zu$rUavJOee}!!Aw2 zJ<@H58$zS;g-0eXAC{vzSS)1^nfY_?s-5B5ia5h&)Y-${5>oQ(wu z$!VRV6Se&#Y(n2)m~>3KG#XN-8PqGgHac*=o!lso{W;&B6BrmMB~|KjHz}RI!Z;Bd z1?r)U*2(n^E#3%J0az=TdHtQ`IF8@!lkIAp-{s!U+QG{RotfJ?agaKd!Qe|=TPH%r z@P@ID#wotSpi9n0VvWpJLY7%)ZG5AE*VhgKi|kxQTuiOC>j|CO6h216_;}>)Qs>uc z0cJtWs_NQA2bue&wCT3(myN?U*JIFOV`ZvdB#nkyGb-jcW_2va;CY5I&PO|JNm1pe!k!y0HOkY-XK~p#hRn*);unzvBEoyoi1E&$=Xe;ac!8yiNUOy4} z)*AWgb7HnA?ux<)<)U03m3k@jZB0Q)2oAqu+she*s5Evxuigc+fwW#Y$;n5-{>6P9 z1IZ|Eur%>!0PocLH2K*w!d|H;nxpY6AdJRx0nfcxm6FQTf`eXS0q@+ac>bMR9lfesop=u(udgWVwFn)xpwu!NHH{dGoOKibm=b%O~6~f}LjVcJ`MYmOe3wbS7 z2t!VHMOSJop2lehk+RqYO1no58Y>Z2*!W52>GPP(_r%;@4`KU+q3w+E7bewt^35bi z#d?DeeH>mY|0z{%#qby>Wa*Sm2|8EcU=~eL7nA7hlSvOQVhsuNtKSNNRK+eRdJPkHDWSS)(2B~HtZBS6l+cwx_I1b{XP-L9QXVCIUChZSiP$NELvF) zEp1gU2^l#B@qb+oWdA|(g=#qLaseVa4>70`k6;tP1Oge3-7i{wN#pjTRDu~i1V_;; zFKkaM$Wr`~h-SG;Uv#o|$~CbBWXVB|@jAp`#@dOF=J)-L+}kpA&+1@sj(<=oKmn^1 zEG|LH#p1^yu$-<#lYr2S^TYqUO2z80s1>0FG88-0ThhTq8g>~&kcAT|BQ;#grpq0m zJ6T5WRBskr+&))jdMbhQ4^DkNelhE`<2jQ~#2j|y2jHvX0G!caQ3*y{dJ_h-9R%TAJ`<1SS`#8 zB2Fo}w&}ofkN-q2q3L6&s$+Z-I)md{0iK9p6&Q3F-!ZH}ypy&ETnYB6Ilg-*i8}H{$ORvO3PEA^@&!E?7O3(fu zQQ-Sesu$PPQI2UGxwk#uqmRa*R69Gv**V0OmO~qwG=c^`R8z;H=f5R1DE!I0-d(?p z<0#n;Qb+#a*y4S?vJ2=t(!1VWFGC8rT!2v_B%FWH(0@0B6;zf>psou3-V899lk!&c zw39PsF=|%3c!JZShzEnVtUAj;2kOpX4qdRHes|$B1)lQGk1jjG*|{lSbJ-}DmJc4k+b zUXvH*P|(j`p<0wU^TB%CL|9BwDO!t;@W&Mbc$H=c^~(e4LKcjJj{#g&3-75=X5)jEj1=#D$m>VnBYdjFk}MzrX0%aoyLU@C%(?=;HKE-WFaqJ zEmvJLh3%@r59>mLfKRLs!k+0gD*1ZnbAr5QtTy(5*Z%@MTc%xn{mb=iKYCaI6p24O zNQFRG%UVA-PL_Nyb3%@Y1$gpvc3|Hiwf;x8FYz}%_Z|B`L!zO0dkXVY@}p~ZWnyyIa>9&^ z{-R?lr2tyGjuQW^V3BWnN>{Yc!Xd}ee#9?sNBQQdVGACol2NO|$GR~hU9F!}O{lj& zj6d$a?HUx&cI(yU-&;(^FnnV|FOzZyex;ShzZ%Qf%;)@0Q<6i`@0R^x$e}fU!yJ|aOCM72-R2Ado9sRU?Sdh|5{+`6 zk|!Q?ugV||Bdf`=6SriumKnD{AH`EDM`RF(G5cm6{8FNiPeCxF+NNS57nT`v&7+j7 zZk*-}@ZUt_nsc#c37c)yRkpP~{yYP?xqrL)kZhM$)-8P;g2vgfADeYPdZrSq>1HH< zrzci{gXn%i_>?i-wN&9`e&Y7!`-D|3^McowUz1LwO8Jg9HQRdb-+t%O42E?`}Ls|X9oL%G-CgoQey?5T$q zT^6m>keu&P?RBxF*bMXB+dU3%4?qPZ4xyyI{k$x`ePQ}xB`dqF>LuvJwN0-#{ukbA z)s1W(DuID8Q}T)EGO{kEk})gzl_iO5!90Y(vd|r8n-9Hf2*+@5>@#>YV0D! z0@I^<)!Ds2VBG6}OTs%m!eIwB?mDKrNEvy}hvFu%%KJTe<<;>U z7N6gNS3>1CG)+YGCC+UbZjj~k{(9p4$zC=1@{(8A4QksmRS35!A&?0CK56^@ZG1UT z_?v;#b0Y9s0Ko^~7uTOg!#Gvzq1mazYE*9xoan@z1!YQO2-)Xe6`yN;x*Omm+(?9W zi~NcModz>0UCiSUCm6Q(eB-q z?BtI(?Gztp@zJ~_c!5ZvVmIPoHLw!KzE)ERsx+Bga+DH+DP#A_B0*?f*w&2Om0iB? zr5sLkbX(au>bp17D21}9CL68&TOu-DKG`r0VlTQs{Anhi<#SiZ&=d5z4?FO!BVMz<3WexEe8fGY~nAO^)C<$EBDSfr6e9 z=amjyT}5Z#qhf{oQ;%{@P9W|Pr?V9~+vfdG3$e**<61~{Ht*j8DTYCE(l;WWXS<-{ zBQ|z60P6wwFg0gBm-ik7vKCLf8%h28@J)=#q5Cj(sIGv!KdP3k2Gh?F`B{Z1cd!C| z{^3zn$~py}pVZ=c`~<2>KgJ;Nb~h5k$<8;aG#kHV8sJW^s1qP!xE1E+-f9AMi1V87 zvQw*FUJfSgGDm}wB$w2Nw!_t-G~EI={8<(c33%)Lu^#|_?TP+h zT0o+8Cp?ht&ntur9JV~`}x!c-? zZF9%prlC@x8WK1T5c8;iI<|q_4|E3apZ09v3&CTKpX>$b=SUEd+DsUCsRvKzD&Isi z5908;{%)&VQ|eZZ)gVXK^IbpG+TZiFbJ*_pP~#^WTuE_TO$oX$6zHugo-BE1$k9tT zW0spbzI6X{P~UXjNUp^Mt||Pj>C_ir$DxR^!EfGFhr0^5SKTPF;q_~TksFeJV~6gd z7K^orq+MGRi@`D?IVg<|eBhEDns_n;}N`yl-#~$ z^F7*8!$)SsXg2vQMbh*#XySWQ%|19|WVISsqIQJgV5stlZZi3_ujAP@sN%o=a!wsi8NCsdWGJ${ zT)B+ylSwtdd6J`Os}!x|P5GDCkli6%=RG>rz6q&aPlvhVY=0X3KIiVjg*VR`CX&x@ zY?V+yZ*k@KSycMa%iOXS2LQgU8FE`MTV?!~_(~Dh#Hl=M;_hUc@?Lw#;RbgLZ!;~6 z!Sf~G&c`V_4=&X7wg&@F%OH-kOMBqHE>yZ2u|PbG^1ZmZSJkiK6V+mSmo<*pYa&Bh zI3t}kiJ8%<2c;>N6Xhn!DTI|1crP63G>7hUF6$$y&L{I^708k!b`xpuNJ*@q3@UI@{C(_Za@4`afu7k9s~nJ>Q4<>C@uNxpl)f>{ zEo{*ogR+{4dT|GQHO`B$)xy=vi<7$U^FB(Y+DQ4#NY*cK0ezZfwHjHFcCk02Y2{q10sZK|H*&5hgP7`*s_xI^wN;W60!3z+!oA6QFxv9=hw*J4;zyf3!QpFZk;&7dk@HfKy%#6F?w`Tu2DgtQEcl{ zO&qpGYvAC7mK+y8&aP>2YtDeo`x%ScLTKh)s+Q$-aMKc__>aS!%LNN}vdc36e<36q z5{}jmQ-7zjID-v(iQ1MIDL;qHgYtk=Zhi=4WNH3-v7rWPN>Bv~=GLQRm7q;=C?gL5 zE4R(GOqSGH>ENAdxkKFaARR?{`U`p~owsQ=dV9fmRRN6d z+MPW{d@q%HG?>a^kn6A2%dpj`k!f#S*+i7r!RdZ!Imr4JNPbGjj`ol1HZ#7y^E$gB zXp0{LO1hJf%W%GI;oSec{|HT+RmqrGJcwT(60I7aBk(bzVU}$@BJ88X^ArNS?NIGdS!kh-dNaOo~2{tFDGBPu{&BjvsyI#1DW8HRu&7kX<_Um^bO4B})*-#!# zKD!7C$2_}LvOs_LH1<{-{`JL3SCfz=?65JTu>)&dd`)uU^<%+(3qD%oAF|Tz`wLRL zn%~3R&{e{fVFCwPqkShD{zSi0ak1tB$Xj0)j4emjkO<&H-mpDUw^I& zs7&TAR48LSkDHCS+_jr33Lj%g1=TS1_0b^jnSf+|=awFBHGd#&@M2=nP^k63h46U( z@<*lF;gWs0W49J`NMmcK^%0<`%Gey-yN$kip_Kfdl;RNbY5d+N(l?85h63#KmR^jq#FZ>M!X|x%w$c1E zr;vyw+W)b4X+h1k-og`O1+ku+2R{4Aro_>Cai)}^GTl8Er!&>}XYjFs@F;vSLm=S( z+3{cm8KDwi);j=qa-DNnUK!|}PUO-d!Ck`dLs*Hn{w3=`AlYP1D!;h9S;rrlSv9TH zg68Y5hW>E)&df@acKNOt-(Ui__}EO-d=RaEwThmhz&Cl9n|lIkoawp}n=o){A_}wk z{b@ytM3D;w{E^~#vQ|3qfWlyz>I}M7UGNpqvv|vEZrCarR$*%|BEQB{ToQi>susMu=-Nlja7S6G)P468c zO`hoO2003Eb(k~yE%#*Xwy%v%C2F|F@R29a*UQfma(AprDvuR*`&9hey_hT6Ev*n- zCO?_>;=_X6Of6<%u!Gh9d$N7;s7^X}c9NKi2hXj6QxCfZF>28Tv8+L&a_nsemzO_k zH(aqlL-418_uyY0YaNS?Y_2#IDHJ=f${@7tDUlp;Vt(S&zkZgrr{v)S1F}?0L=`~| zP2ubyh|+sraUM{2HL+NHSVf(2!jDhnL0cA1D{Dr zdgf<^{RF&`!6M}|Pp8qLe4fR@bOZ}_YWSo%`fXBwsalrpq@2NXiel5M{L@C#ZuOw= z?fW@P;7rQ-r!rU(V(3`HB8*{%X8tZ9&iSPY%gAv2Bn1p7o1>qFw)-;W9$MaCggL1N zPDD(k4|Q}n{NxbDf!e(?BrdRa$LXvM(ghuz$QhZ*n`$)2y9)D{aWH}{^T@JUS1^)P zEF}1}*ewS?rg`wJqm~Gqz@NoyDUy-rN=5I9T;u0eSp@<9uOVc$*AAZ33dkLwF;F$( zcj$G)HMT_I z4^6EP7aCnO=x&TrMh6?)Ka=D*Y0>cW1qHYuvByWyimT=ANsH}UVu7%8$D*NIdvc&; z5>qMAV{_yo3-Exj+S*cBzcQfUx;SRzE@%%3A5l1_e9fSF!fs0BckH+S<@k)s#?BF zK||9%ea-jBOihv7m9#6!zpFSnwaLt6%rSe4jrd6zOGXI9?vFs~H)SJB-L% zJ>sEkifl=D?wJs^jgE z$0(Yy$iRaCEQl&eLQlx{#}&Rf`Q?lKoEnqb#Z)-y+ibh5+1bmc{`cP*;rj#VpvE?D z9Zz(MPgnBombS|g{cwLj*v;9AvsAhN03)z&-9z>y>U*nM9&Wezmhv_#lUb`JF~!8h zuphWW^jN|lG1W!{`ZCPlA;Jb69F|)U%GK-K?_Lu570B60?fgAnu#n5j^?jG_kwTD|7aH-3S(n5^r`fDWaByo*7 z!CZbP<53Cn?svh%Rb3qsYZ;W>xRNs5{Qi4%!i{ON=}nP^{=o`L8Hcgr+~Ok)Bu)5t zmgoV0w0NduP#^cA?+U~zsd(&ZRSmS8Y)Btvc|-m6MY8lLfd{X5X$d?53N{P(!s{5` zBfM6p^nfitZa)$vDhcA28o|V>iH2_M>!$S+jxDMx@D3Px&~8t=bsfY8>@Ay|>dzq1 zX1P7XtJ{^)kOo_mI@-v$9bcZk(Bj=76XJ*%>#2xNJ_`H4@G;vrG?Q$OtyBgN=zMY$ z3r*cpG&9kKnPnn5pQUQ23b@-3H~(I}I-Fz-a<(LBZouVjjFoekCBh*vg{3!Us8#-u z9ee*rFPRJ_nCKQ9V)Klv(x0-ul;I^K9kM8E+1Vxf)TN;~0h^cdQD`~Oai%T_dmFuqL(O~m5pwxQiIuTQ_PA&r38~5Te@M#wl7N{D57E^pomOWGRostdu`(&3d(CN2V11Wr z$EJksIKCDlu*~z?=2eOiMjX}ou0DSDYA1CLk`E!+su}lP*U!-iT$NsFMB zQ*9>U-&z2mU|RHjjpaPkwx*@N2ITx6QW%r~cEU(f6G3ZL&9y0WU2147y#!cT+xL!C0Te|?%# zTy=QRb*?f8HV$ljUc9L2X+3|x&PXhYU6IYAi9AwVnj@+7r52l+Q82#!5r`Z&QdkvT zICH+}J`rBMF>NTb5r<0A=@@Lj77*z~LPR4J1dA+mI~)Jjv6|1&JBHm+~93dSOy-Y_revhl>i>%eB@r22U;$AWs(-&k#H(kS5Ydqq3 zO_g;-%v1#o^OmH*l60-H;;$s~G=oHf`7tt|!${W9d8DLoydeJZUiPr1+ z5GhUL#%~;^;J|&~aDv?WK-V<-ObGrXJA_B3Cyuem%0Zt;Eet7EeJfdw;L=ttUuZB$WYc>pMQ>@XLEa|?84V= z`gwYTaFDBc%5Kb^Es!yKk&A!IWzE2ySyb!g!TIt1t)g|xicaeV%%rJ%k`z&JjJJL4 zelKq@qSSeRH1vxmY@{*WP+OP#A9L}#=zO|wlxO4CRV%v1`_!{r$u`~;I{VD>>+Olg zIo9%vz^ljLrU*mL@0oy(*4C3u1>?`!inPt(oc94`As{~l>}9cLIFN_#OGZ1CN%gyj z4v?(B<=t$d?Qk=rOM=`hr)`{Rd8dAzX3yTX_AXp}bVRZo+!z3`-;~cffLJ zJ_ItlnU?S7;THeA3f5QSK{@Yyw{>9a;&%+Kh7g|mKS(|0n%n&o_`fOA#e7M)1{LIRkJcD0*x;O68>Bw z$UZmkw}_10c3ud2AFiD@ReH_T(<<_PQiMl+_HXO7iJI_6O`A=yGBVqqIYb?9UGM`x zB?ZCh`k61@hu5Hw$r1SD0=2>!T7om{)6sRi{HZQC)lSyDQ0nx@Qg7l>^ai6_du-eI zv>N#Zzpg$K7bzKI+w8Ed0HEYPo`0zA~B`Vy}klnApd_wMo zn7UpxGhQp47vppp0h#r*+j&-#LK_*I&=rfB_T8D?MS7Uo!=3WLyDdH!o~wv#s`=xa zHHC+GUX$Bjm*rrgul2D-Dr)`BZ8LQ*ZWj+1Be8()FVWX#ovi*{p{r2}VlF(I=YkU) z-_(lC>-olKU6jn~?Q|p-7q5wY{;%QI5CEK)1&%Ropivh!VS;DAWvG)5;+m7ioav9-`D7o3Jccg{QGcL)n*`si5NO|S zjh&XNQK0k_)sT$}DGB|eMC7LS@2ZGcN%1yjGJo_J^Sw)8E8n4=lBjQa4U%e9zaA;N z&`C(w&<&ZzTjgm@=F=?BgYe)92a??BIpn(&T*A?ouE_%b==c=fkAl5`{)6<+)b8zi zcM;rDtsxEFNJ!?kH`$;f#WAS!I9RX&0P={o{S$I{aePX~XF(r0_(6T82Do#1+|#)1 zolv66-la8Kz^EQrSwkFg_H~TY;~JljuMe_)Mh0a7j(P$JA|*3c#z46m{V9_}7Ty@m z%X_IfOPMigsXm94*XE=VQ>*mP$0rs`fMKi3NooCl(pY-5m{dtJaCns}jg#{%{5*|9 z01@H*M~qUn{0KMR^g;TPBq#iKIfWy=c=h`j^D*ct83gL&X` zzZL^Ib^}%Ru#usWY-Ey*Vwy#zvZMLL7JWop%wa!igf`Psx+YjlZb~0TDYpwQ1(y+_ zcC>1_Jk+nxrjM?&TMB8h$)M=5g7lE?%7_JPaFtSx#G`|FyhkMh?3|%*4!q!z{A`1H2v!@P{a_P2pyyfFDhJ3$} z(k1=Eoe{=SgGE!M%*WFEED#AUb?DItYqeb*mQiX73Gr~x_IfumgF$q`tX~!N@8=y4 z-@b|;Kbu^O3<=RgA=yseLM|Mfw?z} zZWR}>+9v}9sE;j{{h0SnBtDdtZnoPi5F^g1Umg#^K`%IDHIO8ULD~V$(&u>Y^9fQ(9kI_xYeuE4t9kZ&Nr!b1nB#WFN zn6o$SyY{&J(6}7jEKT+D>LVset^1%Z$LiNlI>{(^ut~zC#U?kukr|DPJ5cuO{9LDQ z-Bpv@Q{|EC>+35R3qbwVepyH7z9H$P%bwuE&D7O|B^# zF3}&`Xc+==jwF7}P}q+v^?63Tr{mjk(Y#%@u}45HdgSbkq9k^FKo6>}$V~lhOlCH; zKDyg24GmNr?uS7lzB>sC$ErY4n%i4q++8A#bV%|)@=ZI%R|c)bJ_*D@qADNIz5R-D zMbs5VpRwkMxchSY4<`F$OSpTjDIGs#tPS%V#4oP5Ur}R&AaTr=Vbj(Z= zDvDCT5JRmrabW@0;H01w7~j2#YQ&F&#LCyrNqf_*2e`R#e-a)u##?93qhk9?N;{ir z&g$;t01^*MyV|$*!|~#j!lRYTI8sg;A$F52r)PDDL87h0bE$x~MDm&9N-ul;M59qn zMp9bL5z9NI@I}=L9`TmMT_?QcQp6UZe%JJisT5OLhejLhpjI54BnYl}ie8B(Fi2Wc z6W-lYIIJXU|4x}z@fL=GHnC4+aGCn+v#sexEQ+@v#!qSBz%Y?0yd4W2Vo)5%*G=rs zK)mU~y*t#63ObC$R54t$0~qBNN*+h7RreUlvsXqGwyH6v&OqB`Dz21Kuynpo*51u(My0UeE8v~G&Vq3z1rQg5jL$*5SNl6^nm+lPm&C7 zF!@t&Dl)G$bU1VxjcLJjAWq(T(>>*Wlokt3^Fw=l5Iy^Dau%2pGkDM`O-5c+_nz6d z;UK(Z|FS8}#@>9v_(9KW}hkDp} zrN#q)Ra*A4%sYr(Dg&!bBAh%EZ^iDXyNQQx(lEoj+I90%xEjMC1|{5{-AO) zLs6E5nm_Y}k!L5ZAqGbEDWdh;g%P+syD@~4UMUve< zX#qRc3&4agG}NsD{BdNx_Y2UDCGHkuR%>#}aVJ9J=I{XLqm4WIT)nt6^R9RL)Z3MQ z_FdfdzUx>@hDf>trU65xiRZf?M$khbnZy62&xtH^VsP0b+yoGK`-OA1p ze>_e}u=93+Z8(eYf6^o@+h8q8tcF~PCx+p-b6658pST>SxPKkqzWYKdZ8Zz<4dt zjgrlJ(nR>2BEr3$R^0UZuDyPzsw;n^_1^Wzai#KcDpRrIgq+>={|%P67LKwn6sZm? zMf|#5zZnbUa7(DYf3h#d;-$xIz8l@&)!gWWrqWB2K~&t$!55n(+m}I3EOA4bZNY&Q zl2;%T|F)hLDP{&8rYie4(mXI4p(i3e9cI0&@?rv|hHx*xh=3~0->iH(#PLrWfuh$N z{zj)7U&(ffP}2gLN_d4ezkeo5TKjPed8QW&{wre zpf=1yk5c_(eYUWawfmzf(m>$hr)&}wqP$n^!Sc50=iaF9RwC5Z<>}fQY8Vs#TUfsq zj$W7|rTpO+hV9Qu%>0lKL-hHks-K!OljEIwa!3BLRsDY8N^+)huzzyOVj3Ojyoala zMjJUk1-<;5Ktt(pc#{T;504P=!%Bsaq07qhD5lK@{*+csKNOzUqhhbEgp+PZ?0qht za$-*Wi`chE?zmLndSv6IG%FsSDmLxyn3~Y0Oi-Xf{BYKdFRIy(NazWdxN{gq6`IYZ zwS+dQ8cvT*FL}8o6L>eJUiSf{6#KsVMc%vK*(jdVzxQ2FQZPP4GWMl!9|)(HriZ|O zg&-DB8xH=%?Vl+zu0MkCRSASz(@M2hW{0MtLO-!PZ?N8E_*0nLcn=*k?ytVHazl%= z^9uD^bL4{L@%)C);kko?2t)XML@YXL#)U&a<=aEHM9bpB9#b7|E$sq+I3%@)7q@9My69uRQ?=5LMya|JoGzQIUeKQ2|OY zvUE>YiljSpTpu6TQlJUlfOCu3kmCxxb5w|=en7ki$dWFB7&v)+_fywQ{9ktj#ETgP zq6Jk8zgWV2ApjrGc4P=zSPFC`I7KvYmlBlsjBg(O3*e#~1nM8oBD@ z%|>r^@~RGBKLNw_bnz&wps}pxj~mV0>s;;DemJ%dwP3-$o*P?=@D)3N3{xBJ-y;o1 zng$q{oa}eHSBSUjFq-K{GlYbMu$at{Uwhp!$w@L|CY7vjW&_MH7WNXfq+C?SkmTSsIoE zj_y9SkrzC6{34?>1`8P4d#>EwK>!E&01{Q7!DRxjhvaMtl{>7k(RWJ6>pGp;_8Cs) z=JM{}8H`ZFNbxr%1`p=yb!)Sz-g%Z)jYF$MeKM>~Fb!WL+CmC47%|I#1~w27 zYNvc6!=9&%jk~^NeQ<^lv_GJ|G{lQK%Z5iPamE(egVzk)u+YHWHsO%49agSljs$aV zkz^~RV6F(2p*AP{?{_9_l@I>M&V*^s3m*U+%?>}}(R{NHH}hBRQEM4QGIfwakMYNE zY$4*DdD4d8-`Y3*RPz-Y8r5@DleMufTrPnAZUP(Ec*cQ}jI>uOlg|$-eD!z_`fQU~ zE%XPBvBXEAR+Cm&6#S$$XR1P|^{i)eo#t;g>xf3C7nc_7qOClE?fhFPr_FKqg0mYj@|Sc)GOSoW5^Z15tG+teBTCfMettPPy&rKQWC~smbqS%)M{=(} z`-q*-b!m>N=c)%Zb#xt(lo=5Qy~d<6Qy-D$Kwsgo90W-jbT3&mMahHfxi1}dDd{FKA)N2eUvvm&hK(D zhZ7vqLjmYQ?>=V3H{d>D9X`f1KgyrIK+f%kx5QMjCf_YusHMZQLo` z-QC@3+@W!IDBNLr=AGI7VrSls`L+KlG9$AxGBUHWu5+FHoY3f}=E#i42bGzC_zrbP zonHR=v;4wx`N~nL1;p~ze?@%MFYu_ZL~2?(ds%f$Yr5`TV6x2VteC0(pKTTtQv3Ho~YVEEmz;$BVpF*H0|i}DKaI)eDB>o^;Q#xQVuS5q49J%PRd@h4Gut;8oM1H zNR?R`ZJQuk{Dt??HfXCga5_m9pG(Vbvk?r(NKqm7HRo3LE6^?xYOX#4QpF9=vdu0D z)@h*FYu4(9*Dr%Lm~#=_u~~0lv^day=q30$MZD;Qn(NN`u=5E;?G4eCg2HiVGO&T+ ztS0M1H6pPhRZtx*N)7jVUc1}pfwcUE#?+ivvs`en!Jzt}1XYa%EW+KLa?&$7h6BvO z?a2^!u7F7>n0RS=FZuGGW-ndlM?a*EU0?8`{iK*H{b%?=drw5&5{{ql8!bm{x8$Ql z^vOq`bh@neRAqP3jL3(1wBpaL0`9vc;s-*ZE|r`o8sDE=_h#ztj}}w);p{!921lC_ z(&HAhBc413?ad`uR3(reGKT2c&W8 zS?6#<2$Q1u>l*(Ju%NS{f}e>|dm>dEvfv7B-?64()b)R=p~QBsxp$9U&PO|*ABoBvoTyL8vn7k;)CxkSmqe#!Lj>L^cu+$L$n=-0?s zQx>^@8QxP4^SDPZ_h+BdJpV+;UV5^3dHOr34B%p7-Xll+qk}tM6`V}I24&z)c~1&x z{$qvPIo1$Ww65t^wRj`i#{Q=&&N+kdpQ^ZRF7AKTSGKeHMzkngNrjp^#F!1Zxf zu`0+LoUhTAF8SnyYut}@ZnvIOovuN~{WXWGxv~FtKfBC2zW#G4>>p}x(B_%6(mhcY zE2CV`4n_z7)n1|jz%=4fvU?B7jmyW8?zyD-Oj9QIhpPn8`m|?HhB0RE7WZ~SCMu&n z)1>VaDeaPg*1{i0n1k4!_VGDJ#ouJ*(SNVwD`5BO>V}v(lY-3osHRfTGkn2!T+{j7 z?}cQ2qkrm`+Bi>wU%bh zHXukivlR~-2+?9P628QT5Ae>`DwAw3eZ1+Gu4I~Qv6b7Jz3F9LQ*Q(a65H>H=3N(? z4g&qfh;ln);TZ)ne+r)CKj=l{o~}&uHOWy&I1Nm%yL=718V0@T3HLw3JKPG;czjI5 zG>FN{&cc}$e%*f9iVat(@P%vq4CcQ%R1P1JEztaNa z|7ilm{QkY-)=jB~2y^(rdK*alji>&;fapfJ%E|cN1*@P>nqOuyAuK12Q73`02atu| zBCda;DibI$VeIsf5CC^?*1PV}mcIL^ZiuznTMzb{IdYXjvAoG!-h5aWt?6lmRg5HvhT;xVVP;OBBIuh z2`$(RN!S$`Mg1~5>yO?kck@W7BT@wzjIW)rdZ<#QLQTh(xK4jp1m@xl zZ7j?DlTCI^(fSC+bEHUdzgE3lO~N~_QqM0Vz8~?%%Pj12JXkZWJVq@qy7r~b&*`{O z8w2SXlIb*uv_vq(v~b&R@=N{yI+%}kR?C0ojAeFGFpnze{*z%b#UU{sI{qb!Fscwc zphAA1_%Kpt%5PR}gcvo6yeV?aOrz=wyvwKda)d7@PYzuFl5lvfk<;9(Jt%aOc3i$z z3k2Qe=l-5rmGRk#{+iTVeZOCIp-~7F7GY`qZEu+S#C;+TIt##~ri1e;dw=?rhW6L{ zxP?$nenC|mv{Hwdm~&Luz7E}R)D^Tkq!H{hD^k`hed0Y>j<$|e*l!gRx2a?8s){|H zkvS>xOL!_(QeG_lN(AWe@%~Ht9r0(qI%2#bVgB)Yk&6d-nSp?~&si+s{b4t_ZfvS< zaj=vmLMBc%_IKP@D_3Fvtx|%9xWJ(;4jp1e@E5C34OWB0iVb|Us$|#Bzg2Amp3N)I z7Q#d{Xws^t%w*gHxluoD#bS z>1z?tJ!>;-s3XSQ#vHO(mr!V$e;@R*=8i{mCw^GpyL9S$Ccp!56OQqS-EM zWP8W?kS(dAN#J4mOH?*&FcP06oZx}})AeO9|38iD@Ne$Cn1o!FomiA60``Ie zIZjuThEhY{w7YGwt+~t%s}`e=N*KSfo>F}*(`$}-l^+c7;F>2zcI+u9I#w# zh(AUUakLuyYNZ3tf~Gn;vl*>nPsY%HEtB8sHsa13=us1DPg)Fm=U!_r3GkOBvOWvn zl`=f2Cp5J)_!HrbimZV|X(n>R0L}nrha4{;G)U2h&p~D-L zu>!oLbwj<9)--MRukz{ThjPPw;HMQ*L1tc z`=ep)<|fZyyLZMJ1o>Zd6~OE*uRpypt_TWwZzOTQI3)vZC$q8#R_W8sM>x{cJ9q5- zI2O=yvnJE+820i5f*~@)4h%`M+iU?~H96Cb2xL^v6|ANC;2mWY%s?~lx0$j}$S=?J zm@z-4%ZIbjZoq8b)KQVQ8Z-9j|53Bkul`CxI^Z*oj`Z`gl)nKZ69*}*iiPqObW2+}rD zw^65y1(Ljw%0MuA9W1`Ry{Ukl3?(OBLy`ZGOM&D(!Dyf&qFtco;|o zd=rsxcFX~Maz$#X(le*|!Phfg#2#@lzc4W_2|V?Nsr*0r>UwicrY+ajQpG^^E4Z3pP@E*pOpd)0sSyVX7gOUNTFZ*pK>nuOO;AQw4sOE3P3~Mn@qg zlNz#AAQ0pZ2B55Jb>|&@jZVpI)Q`_E6PO}c$~-eQ{%wG(-h5lPy}4QRgC0JeOkp_j?fOR=0Bz zRX$H~=&2Qo1!x3Y%~?qmgtU(^(0e3>qFS;zW%KM{&g);~)!>2)u!_@0DA_j54!5vF zG@Fz@SW8J;l&b(YrWAj!(r<~TG>W<67l+xCJy>H4eVXy%Be2n++jHVMU|y9@*@IX^ zP6;V88@@XKP2E7l5e}bW%_gn>U{QNlca&#Ts|4nlJa>(N=l%7gUhW~bCNT#(qLrVS zW2>)_-1I8p8gX45RAe?XGFI(PU?P7R0Kjh9x6eANBxEFg3GAfnrar4z7;8+KdY0#a zGB^PqNRM@uIiuuLn_t7xQhYEz%X9KtD?DFzijn_&Q~G_y#qz9Td|K>?TwguXg9l&y zXkNpQ@mEP{`a>80Zq`+6{-X``)yT@fgziJW`{T^6PX{EYYKj`Wv7~QZzis*U7imMS z3H)!6e5fb+lkoXvWDW^T0pM4Q=na9?l>TLZ8>9Ib^2?u2Q6{SPZ=K6a%Y?>NitYmi z#a|fY;yYU{=l-goem77LeM?slo=^FA?z>}hGUIJ~d-xcc6s;;U0MCs7HmlahYb+4{ z)OAV(N&2-e7UKA3EmG2<$cHMgmKnB!MG;HCcKkUcR^~Tp&n9MKm}aHmu9fOw**jN) zGMf8O#OSlu*|8x;$9e5YKwIZs=3Rk!^_xVt{V~H~Eh<_v>9?2$*2j3|T{YK2as4Y& zPnDxw>$W}~DFUb6$mU&Jm=vTdro;yvw47lwv!y>$ zS~nu@G!_r>Zfx@V-WL_&H@;WGEKmaE_6(W~6-Pa!Rp3!*Z~Mm5j0;=~w+2%9RM;o% zucG1dC`p~0mxvJta;lw{Y-WT#@_16?v{CU9+>Pe>iLP=N z^<%H0;OBw07xZZyJ+MXzw`Sd$V8cJ|7ESg&yN2!aj5PRE*x=eS#YVT+x(iQvNmA0> zir15|s8p*5L4I{;`V!;nQa1gTme3kv`yAMZRw${_&g5Kx1^fYU2#nGgb?{KCdj_Gb zd5OM`{_!CvXwsxazXoKmzdIWYn$!jY3pOmbOTfSP{ba>z2&gFe`)|3W#tQe&_illL z-NgsFVfUK>O+OUknDS_8fiW(!EwkI?vs;Yn)|6uT-@h84g3cqmqP&yU5#DWBu9{tF zfBY6wWHLdhmhoIhkSG2-60eGWknynd{yk@A{OE-WbuMNkz8GwG`=-r=K){Rr)BT(t zaLxS;Bs-E64<}vk4!81Xk(v8Qye^mX3*1n zN66XE1xC$D3cc%854TS$xdh0*z#ZVUrXk^Xw@KSE2rS)#kB$vXuj(&rX;AR&2-mlBjKN;1?g^bbvAU zjWIa+x?kBiIyIp8~foD**8zBAAoCNWK-fy@eZh(TGA3QCVSpdXv9wyg^D~! zjW++g!>j}Ss+Nw9JTh!e?qiY7^-PWZoap?mf@fijYn2^=#R)#0eeIy4zHMl@0WderB8RFDcy=qPXZ?Y7~1{;9p|t{ zN4u+EXIA^}5npb}<#I#C)%|hR#*LVEnL)w)Tx%+;Y0sugJ_9Mp!}-mj99Mbu&A!}y zZ2PUQfMAmTuLGX4^X0Zv%0Jl>278xy@c7|Qu@rr`9~ao6inaj6lyKo>0Dm_j~QK;SdXW55gn6@ULDIb5C5fT*>N#;7J=O9JIX(B>2=pmF)F;Fqy@?20sMFL%-8WkzNNx{a=%!$EBORaW2 zzJAofLTIiBK*qiED|m>yJxolbr8ysN@;qh_9BnV33Eb7V`nx3pVo45Pqq#l)z}iy9 z2+!a2L@f0MjV?N`e992`@loXMICm+&ZcV(uaxMCfYd556Fhj%gwU}%XAMMP(c)C2z zCpjV!@O!*LS94<)zO%y)jK~g-jDHO}1F0P}xh#$Mu)P7Scul1XjyU-swW~h_*muop z=6L#dhDiv%GwA#8V0QA6K~Y6s#&W*ZW#6KR7_x6H*xOy2cDUI+u zgJ4ip_s*PFmp)h#*!3VpIQosVBUoZ06+|LIO-KBkG5NNX)!~SQnf-=jvKBh9yb98? zEphxfW@nnb0nLKmQGEYhwH6;?NEv^OE}9@soIwf>l}v12dk5t)|N^ts3FvA1s{SC=QIiTFV>F?8DSBfMXT$;TC05cd{xYLOrY zcigWxVJs`}^}zQImmONVNaMk?&ZBD{WMbMjl4h%F_%rm?=;$nqW&5n57E39P`%%j! zy%zcx)5O5(6=i|z1OMF_KPcbLI8D%rCPyc@MD^m%Ng7?J3bxl1Uk1+RAKrNcy~iNnjgGp*)G`Kn#(EUSjVj2P`8==XBY{q3P}dIrb){U7qj z`Z*$Yyr;TvT3s8|e&{(W)%(>g&0|0M$`&(M_##M&ysWb1qHNd#8}?XbPE}Kzp7q?U z^)uAyp5``k^M=O&MpfBIncx8XQm)UH$IO`uR60+s*CTTTqe=6P=bb4h>Ww!(i~Guv zKN1>Ni+FgQqBx6t4ApY9lv)!eIf4@Iu&R)V+ouR2`y}ipP0!m971`|3JRE(Za}!T3)=CVzEAKjIm480-m;@lH zJ?{^Y+d|ecH$t0ez2>zFiicMLY8e9Kv3~M&vqmhj^j>LQ+DpdY?JcYpdE22Ec1u$U z{#a-@*o;tCD$xXNR`ZrOG2Ye8W}EZ~3|AcBs2uu^U%ucchE)VgvNX3&c*ro`v9v3f zxE9mYGe|PLWqDGVWHeZCO1jt%kHQhL|6E}AfNB_9>(G?-J_|72ywU|4<4dGxmd*0c zR*2#diw+(hRgw}q?WIE-5O8?fcB|--?78bOOoh)gM%-`}? zF74>Z#ZYQP-^XIeDTYqL_%wf)^=x_K-9A|5Vm+(^PFmUM?^}$^EXSebGKPPe^~SmlcZi0Xw;+qcRdR1;b-0$di+QIhVm?~s9c4L?v& z*cS+cnDX56TY7}L?$98G)wWTp z>9kl<<_+qCYD_O;4ao5&zRwh*L%5uCeFC@YRoE1zIQ%~m(M?8JmFcLTU61meS#5Dw-=YUJMZiM#|7`O{uhdGQbm7bIUSaXs z()^tQh^dN~6{sdWo8b#Usv_V$vqk|P!y4b8P)9-2^|Sby|#ZGVNR|M8PLh`$j7 zgyJe&H(lTDyo&ek=03kcFlz5HwI()vW@d;h!0&SD3Qi8fU`+*yO7WCCBt^f^2mv16 zWYA=G-GY&AQ&jQHyl_m+BDo6bpj9t~E2ipevk^eHJQQbIy71~HFY|40@aY1KA~$5M zger!$+Ktg7z*uYIX2I9O`Ko;{DUJJ4+Dn=wSe(jU$cwLxCLnCxF+tVzjF*jgSLeVX zlglZDCFrfJ>Ke=OUQzY94E*A$9B5jar>&xk9N=yee8vyenfH z-QrOiwSEK4<(2Pfu}W)0yYj8Y*VvAb+}sS=m$8%@pOV-G5N>BS6U^oiiFN};JJNc{ z1lZt@mIPuIlcOT(HV4ihk*oSS5>DyMO8)5{`?&*!L68JZFZMoX+kIZ;%9PSz|N%GIYOv z5M1&T4M)A_bVV+X!7ZRN8Sg#Qn-&k5yzCL7JVRffKntxqVC7YRa=PUxNSyAJ{Vc|g zOEjtVQeX)%K2K-C#b>hgs8;nWtJ3kiQ!eYxMnb@+*(UuiDH4s zo&Bi1T<^!qZBI&9R-tI}tWI2dcF20BN9S^_>|IkcqB&7dKvEK+ zM^!N%JC)%@Y!5(aBON37E3Q4}Yi!+KtS!2tI(wtS?l@bSl-y>_vUR!0IBunm_Y>6W zY3WY_S-Fv-P8%EVGFrIvYH;|e>>q(4Xi<8CL(Q#SPZzRyF>=;^CV>xYOaENLcqs!< z=7;9G$_u3rZ@igu3L@rzo%k;->DC`e#iUyK7^tOQE&27eE`vW*B=TbLKyKsH)4`44 z0?HYNy z^;}MIzz}chEKRvZ@dQF(Wst}uK@^p1{kOD66&+{}c~lo*VB}yV?8d-p_Rdcl-2F7G z$xW^{$u)CDf5!g$dBOl13WMO$jLS}P^DwgW8*#h})-oy-6fJk3grN&WF~RXzk=3*m z0%FO@%pMuvP+JiBZrOoA zmtQ_Md~VsRAs0RAq%P4jWm&MI(nBfIdMJknU{?VVrK<0^^!!ZV6Oz@FnK=P7r+E!c zcnD3ijWKKx7=qF+FoT8d$Tr}}nY1x)K%`+l34AZBKowNW@t0huWGozR zPYyIVJ3_<^*R6wfu|B1@6cX?R*w{xaNMhIkb?B^phfMb{NbIG~-<;ExVo!HXsjIV( zFJ9jatsOVwi!Vk=Y^6F+dN{||53qJbhCaY!B5d?#L<7q+gNEyyr9JX|w~&C(MzB*= zdZB4UXO8mfd7_WqKh3V3&;#goCc|lgj{I9asDJEC)jlS-=|CYLhLX@3Tqu?jBfwy| z8q?~~>s*U>_EzER>^_}3xBL;+iJo9zOEd!M!2=+!D8ZR4)r8aZenUJC_xXQigI6L+ z^8pq`;j`pHNHDZOMW`tZP~AE57*;;}grf}n(8_0seiLmGCP#9b+>CE+QwLaU6?sBZ z`OEcUf&~OlJZ*5tFXIZfI4+c1k=5}sqOg@r^=gc_n2ZBV>h52oQ=2RZL)Sc)rrW+- zG+yieE|TOlS!%(Kul9tv>fHGitG^YRQ~bOwOqA(|jF0RK2>_tI4jQyw`=jnR< z=NTXZ6P?oVfM@f&s10b9JUpnVlIiOfcF~J^?#g|=nHilw?b-(~3iG{I0QXgK>dP2F zv)=MHlE?MGTmUMpw=MZf-CH8R)o1@wS7_I*+4YW4+@YbE+|r&uthK| zZwD(o@SaPQqJ)$}50q9Lp8BM0RFR$e*;7mzcgG%#v$!yM^>|E5VKRXEW#B0;IOFd{ zal4nm!UAk9GuG|lFaSpy_Zi?!YQ-VpO9hJc5f}omkc$Gx+RWG+E6ti)9Sn6})j{#- zHl3$X3+J@U-}&l_X6nlQf@}%;I&D~?RHe_*3MV}FC$M?dp%arZ`uJGd<2Hm8N3f7W z7EH0CN<~M6vIsq=FleYW_&ur)(1nCM>TNnal?-oG0Ni=}@ZlJIVzS4~!He2u@r+G%y`}bFlFEr?_NK2p|+;0Em=q_&8juZOcGr z(3{p^E(|BEs`|Z@gv@Bs=PjWK1ahR#VN5=ibX&IuwH$DyholT*wFLYHflKB0gqOjj zJG6LrD>cbfV?-xm+^;nnx4mVDp-*_j{&Hs%(TmS3ZaNq>6gM5)hqi*$mF}5)40J*8 zu|==9S3z`EcBH6f+f03ALzAx=3^2q@s?@BEnXJExTh}g-URj$oG3^pSz~td+Y*yHr3zOo3#j zb1atgv;Fm7EbSOq;r$}Lz^}Nrz1y4*VdZn~1x0kvYwOx;7oJPsBW9j5`CM~T<(6yDTS}Tn;yK(M;5YZHGTbq85H`wfE%Qr!{3|Mh)u+G!JW&rf;`(K%owf zAp-q%=UNZ7DpmaTa!Q{Vg3q&{Acn1CCb3jKNxP{H2g57CnHbJ$$-|Rj+eJ}*l$?BnxJj1+jh~IJhlTCP_ zGsj-M)E?%IM(~Cuqaz$YpRY>j02ZkpIQoiMik>_3!dkC|FF4DZu!#nvXYJ>xl$Y>K z1`SyOqlN-qIc0cVrscD)r&vnsxbh;y8Q5$}={J|DokbNSYF#gX59bmOkq5W?o8dqa zYm83lp+pG`6!EP4k&odAYmZldnYd6DPlahe<|WR+A6k_D-hjWc^>S;)m8X=b{k@xX za9@$;rzru^I^fL_tvfshKTz)Qa0Wzm5Ic+%*`90_?0^f8E&u*Yhs$RYfak4@&6!?Tq?Gz# zN?rC=9V^5EssOw&%V>LEYk6wT3B}CT8@od*Q1SrkEx9`xRrNLCHn=iaAXbW498pV* zY&~lVmG+4ocoPiy#OnwV^{dDGxh$4{#W1s+*FCm2#1&FRuL5mm z9)dP)Q1<1IBvd@sMX?BU`jx5%j?c~qKCG)hELE$V9mvI^rxs4TG>e85r+9w)W{Qvf z9pzeEFwG5%p_P^k(x8yI_ldNg(#;|9^rt_{=)!BLk40akMa=3H(>w}qX+2SHBa+%# zZL+U7k@IhFZ9M8sNK5m#;W0Q<2K=()waW6reK|Jt`-&4(=hGG(k*4h==t;FlJRTfL zZ`n^&aJ3*K4oC5F)3M@8Nu%eUGTY;=RfpuVq7aeZ6R+uo;k;yy&uF-P8b7vDg%^pX z>Y-gF!DRW^@LGTsaed;x9PMe#!XnCA14LK6%xRG+&9%?oqs8;)=7vhXS+k!FTY5)6$MVW2 zINeZouT>#|>vE`C>Kfqduk9-IXKEiGIBW6XPY2@L)KbTkS8`jUWND4&--!U^gQzkQdF8zbVSnr+dn&5S(T zVPHoh*Oaz5Yf@&=o6{&6g5$E%k$(7O=+r?Tof#d=t<404Te(qT;!=2Vx*oUVyXRl{ zm>!d^jS-leVX>$%sv2FQ6t~;&TZ`tZzGl!Lsed6p%a*^T&c~-#N;-V!Dh0tH$ck`_ z)*pE2FZXagQu0}N5?a)OM!KXyj@@|k_Efxgv%ivJgCEcFMnHGRTzk`;cL3vLJPr$h zzV3Y{dYnWPB2?ha3Wd-9VCL0{b7jHQmxEX|9yCPWBkh~PTA;X73^xU?SRzdqMuZ&z0+?QV5Ak7=l;D5``Av1M8Mq&;Q!4f zLdfl~{dL6N!?rct{?7*h|Av3oIRJb2YBP|bTU;~i>gqm?*}fKSZ}*KDaSBPiPCA!?hWX#{sx~ zP29Sx8uu_yjzG+YO3V~183Wdf7TZ=JvD-9eV0^}7{X#H)&2y~13f_G$Vd8uEeoch; zeAnXf9-;xfjKayJZx{M|_n5cc{}`mSF^<0Tp0ax`_9#J^&wT{;!R>*@CErr9!kq`+ zj))V2%%$6UYkK4#-cxZ2cAhGTP(bPP8`68uKBIZs$%XU9-4ky>U+4E0!O1YeTi6pa z_tZ_iyP*Il)d9&ZP}_#*dAob`s;@7Q4By0o|CLpK*rwN>b4%%QtH@(5vhlmlH^9*yU-=LoJ^sfk7o1lKN)(ViFEQBeLydWn%7+FAz44I-BAhFVgDrWX+93UdU&6* zzWJrWSbiQIqL9!ni7W#3@myZKTX)(8N(2YO%{PjIBg7QdluD$ zWa}|yH3*VnqV|LS^N^ch)G?nR8{YC_BGWXQtQ;`XGL+ksL;`tR@9_E+&v7eD8MjfZ z6S2j*hk4H?D`oN|8?IKT>p`0SU+IAH(tpyTG6Vu`zsb2Qot&Ve4Q--p+^T{~Q)G;L zc`6FebS=Ag>V9K9dKJ7w$u-5BaOFCT09%((x9A4|5%Yg z8pw|(uu6d08T+uVYCE=@l++v*nD?sve({IB4Zl?B?1V@&L!p~Fqhr3tVwI7%DWb-; zd=l>KhYFGCuHtW85H?kPQIm4GFMKP`bn6nm~r|t6{Dp?_th#-TlK1K8TX)2JSv0GCa-K~B;D@3%{P-RXVDso z%6+qooD7y=jttkMFuw6Tm)on%#Reiee7!O?>z_b4Bh}cJR?f0iQ<(c@t$J-zesd4IJSE*RSHp0L=F?Sc_bc*H2 z-3pE$@-nYilQ+B?rp7n1jmkF$9m$DUkfX|3lb`FHlT1&a2(5m!Bf}Jw;x&yTaqpR< zqx>Uevzm#AJkrx|9^=7QJ1yIbAuBr1hG(Dc@(*=ZJQk&WjQLe*#NC2*sXH5Mp&Qo} zzYXQM8kcmsr_s11!Aw407os*^XGPsmKy2%QsHNTH+CJN)Q2%$PCbQt#aJ(+A3JLYX zNRYg%iSK~toI~{vn%lQbB!sfH$g4`tDMzlOy~bY$PZ*poR{dqL_0bBL#gkW3*m@>@ zE(}U%X4NNGlD2~x{DzcTond=o9CyTxDLh52vA(_3S@<0cQ-#V%xGBM9Hu=sbBlgPG z2lsLx2Hx$b8MldStYiGc2&_uz543wf=6$fvcUu(^!9(o~dFUevy998O1{|?~Gf9%i zl)^9~Ssn2b$l$&&)y9msZAVpJE?6YNq1Bs23o?NywCcwVQP^f7X_4)7Y5@t3C?+@3 zH?+&h*98#ag750{c0bJiKS2MHE7`XbffM5GFEY&$*_C(bVb>$7EI5hFkV#EadW&ch zRN7u?ez!MIS6P+v1@UV@Fhdk)DM*s?Kp9nG6k`@^;hNY41hPueNXVH4Kb~RJ z$7AB-N}X@>Vmq=Kv#^-QW58qxOBCDcM1SH8^!IC7oKs>Y+m`$hX6iY+ohlgM&jvhG z`O=s#y`WYWV+J$NXmVusU0T7xv^TvajW84@)CF${K$0%pRVv3upN7qERWS6(s@o-b zueD>E+ftW-2WoTKwgftSg|=XpXV`7fBde3C z_g_f67nVFC!!DWapMy@hFR~q3ohde74Y{g&F=IQs;Ku-SaVc5RgG_wAJhnXfLIS}) zJ0Wgt{*qqiSW{KrM0vEh*czQ-tJkcZf8E4nut6!T*_MVd!M=Of**QaDjKSM>2tZ-; z-5=RM!6ceAkOsb(43&`+$ViE-O;nZV-?{5tQe8tybNBKVGW5N4Atiz`Dl)}2)&q?l}hU+5OG+YL*M zhA-Ma&+lz(P;%=;Y!ChqjOtW$ijtkbqmLTm(y(GrV!eg;i3dxF-y8lfpm70?fxgPna~skftYeX8owD@YrQig z*04@);aBi35vZ$PlztPsHxhxE(+e;E5tChlcSidG#Dw>ebtY{J%H2c@cUD^XMDX`x zLXy0veSTT(R8wbtx}%-}i!Fm-`nMTpC9pY_`S|VwiuJLi*J)DnB=>X>5O|8#=d6Co z$%@|n%kV$3T>0=3|IL^44V zkubHryTz#pR(-GEds~HoLf_lh6=tNg{JkWGbcTdDLn4%{a8@O?cAwb^0)ztc^)V|1 z0TN)GE%rS+U?$jbKZQSzbt+rX`zY+-2kTd+av&sa@B_~8lub0l-@O4A86x1{?EML1 zR(@O01+z;GfWRs`#ii(jP>*rDP~)R4#{hvIV#gdllUK~n8Le3JoXN6a41^{PhcM?{3;58<^E9$N|PDzTMT6RG*k zm~w;wkpf0rMOo1Xq#zU;)C=T=s3Ysm)~wuS;F^NE_2`3pk&@u%^w+aP#!c@|XyKMy zDdamNQo-E%b_?7<95V9F*~LHva$jJ}TkzUC!tjEXe$ z4yU7~%P`_MKs*#Y!zDIdEusjnc;>3O6@KI~Ix8rMcx}N*LdOJsw0D@B;mH#!@C>F7 zxJ-dv(bjb@H0EQi9J%R#2=iAzoYKDTH4);Lim!^4mr_i2p0WEKj-vl_s|DQ0PczWj z8en98?Uk9RRyxzgq`lg)4nZ=$L{S6hLooel4>8S(S^k#MrvV0Mce}wS39lDkRFn_W zk7#RtE^d=$`Q-5+TDjIkaP?>qlnm|H|8bH`G7du0*D(fyV2!D0j{U8#%MoY*r^Q$y z_7|QNRr}Zl3?y$94n~ybIij@!*0%2h8Or$WCQ&iuLHO?JvQ)PbH__k&N)l9eoOY6q z``H?-8U+NybogpGymJcJ7G0pOh9AD@_$!si6{=gin^32lAhK%9ey~#DjJfkPM=yQ! zGp@Sk>@Yp_vpRrCDc_UU?TR0!3Q1c@S^YWj1rwJQ6ozWS@07x&Qdz=6G%|gMR(Kf% zz2#E8NuhZ6wnoF`DmKS(P+`ktqy@UR^r#9MZmat;!;h&(TQe#@j6U$iUeZY-BvfH< zK#QujXopI(t^j4Dop)gW2VEX*r52@svScO8>zeVN+O$30CyTnS@YS zjGm23c^oW&i}&<`pO-KnmrxCYSp}JNr)o-#m-^O8TJ}{11jSdG`!ivUds2prBH@oi zoN&Z`?xv#GMPzjfp@|de>AWWsRT%X)-iFeISJ0gZ0`K3~A3~)F1Bt7Hy*)yXtEeFw z^wNz2vc4t|CfG+i8h#7BT$YYo+&LC1ghX&Vg<2?8uffuV%r!L=S+n8ZjEIqNxg+m< z?ngl&oyl+Zf%Cjve`ycz)@vt0aMz~TOdl1{< za#8r-5q~NqZ8+gcJi$1Uy+LFHliQGr)^tCjvgd;)zac4EZg^a@x3%d03bAa7oNPH% z53#V{QK@w}H_t4ZU~73AY{(dd*)hLrY(*bz%Z=n|t0CNm@o)Vk`cIN^P$~lxFe4Z1 zwEXP=MLi1Vc5|^tE4?{ir zL$)6i>=X}CQOCXs{quEKW1kl+;*;_Rm;3)w3GkxYhjX*pfNpbAVZR2DKyr#CMwp*( z)PuKCQ0%j<)iTTml$yKd(u5%_mztM`c-VwbQfnoOd!4HjV7UUNlGt)%2FaoY;+uTw zkdimOs9!L3+|36%lvIKR=%+2$eU3fHjjEi&zn<&LbU(nzzZ4x$J{4llZ0||W^>+zd zygv}oxa1EY|2-V7I z30l^?7W7+f$%9lW>MNr6rXekODw6x~R0|&ds}2yyk=jQ_64x!iM1nuIkSLRAR_{O- z_F{Q#Ts|@Sw@GVAM+Q`+WW=0RiIRcJqM@qAG@10|#E5lnAh&pbF-ItcOj)(HfaCru&<3x=-d{-lICG>#bE+tyQ(^ci+$R&;?949AaXkQ>O_yD%3%TVWN?vanBYrL>O(-jPVd!X^U`ds z%Ds$JS{H-oS&WxLCktFi-`<*G6*f*{=eZQj?2DPjMbsD=`-$L3 zfG?C)Q>ARSC8%~y58ddg5ft>Z79EdFe|vW`;65C$ud;>gz)9zBhRpZn!_ziuV=z_h zs@{%{qbvyGW@y&K%>-7zqO3@Ljw!RtfJWVCJ}b#Z&zj>%MykIf1YpW1hp3DGnE49Y zWc!@X!1h>3Z_R2XUBGxTqM-DmOXz0_lD)k)#_n|2WOw5r08hi)mUu!wLB;z_f5y{N zv$(wyz0#Uo53!hA?}S#cR~-iXLFd^PSL7}3g5^gM=|t^p;GF#2iztjJGWqGHc8r8bKk+ierq7qnbqR8_v;Kz8A z2|}6w#o^(wS1sW;Wx|NQ@K5g)<81JPWxx6f0!lLdd?TT-a6;`W8rPS92gAE6*Iy{d zKds_{Kp0mETbUSKJtQ+&Rn9R+R>cijpcjvmf)clD-;3TX{&(;$r@DV%%~Lz3xmL_i zaj7v0En>#1(cm&lo@iErh(W#^>jg|Nvkl%#Tw<3Y%b2@iaQ~`!XGL7dKB+#zTdI4X zBx$|2MVsvT=@nwlFIv0{V`00TPE>7C)m$dQTxsCjtTV2MEL&t0lHv&=?V`*Z2C#ES ze?n}278UDX3O=t>DY-XxjW1hZaYx zw7;`d!Q@$~!lRlPMd0F}*7E}pO92|qkD$C-p0uX&p^SM;nONiA%!shrSK+aJm<2U+ zwEg3k5L=0+$EO_;s$=@%13p)|Prv1NI)YRgZ3lj~>uE=YfeUTAm)u?NCyn*Z+IAkd ztwxtspLY`~XS}nCcyt-aNf_1<^q_C#f+*NKQ?Igl!mq)W?=ECX+$ipSso3FjHUoHh zUGJ_AgcjC1I!GsIY5gvlWY$gI?#2H5T%tY7Y1}XT>$ctHJBio5yiu$IPhrUHk3ek% zSqHBCfs1&lZE|I^HIBg$yi^_79t_*;-UAX;3h~{Z3;~rgM%2ZH!gWL5(~Le*{@Y~Z zU5i!D($u)jo%9R)KlkLjtlUGRfLqfDH+U*^#N@pb0nUB_^l!~|0*6xU)p|}nuX%gg zt+~Rs+G?bi|2pZgmGEd8GCKQ*FhuQ{CVta_Z<1gSx&9b=m!j|c!m+mV4>CaHMQD4m zx7QxR#>IVOVE^t02#G-8jrTnhb-OY4P6!s!^6#wY`mC z&-ouce3ozjE+#i%Nv>QA0xLq+BbdXWDBkNHRb6&{#(Ved2>WcfoU*;WMeg_RLWY#* z%Dd=CHrM)8pZPpn&);hsR#VGFiCfkUv#+B<@yTgn63hJO*m?ApfmJspb8|QxP5)W zp2Vm}-fCt4K`(=T-44ld?VxA1Tt6Vw!j=rjMj)R<%wM(&;^Gjg7fvEHB?z~Dx3}<6 zVST*-{O#1ic_%by4t>5N{4q96H^akRVU+?GeFtv_@-706BRyGtGUw@wn2J5NjGVa0 zGneQUoF;ENS8&2@uSo{? z(cLs{1le?(A0CKzgxv*iXyft~(V&-EjIA?4nb@MCv|k*wCtX|=b+ke3`XSnc1xMa6 zRg=OS#2wW|a;<>%I2%X%Fe=H+H(G94Nx?CqM9pv-`rptDb3i0Q@Q`{UJ34TKknR3hEY*QK~nG=CR5riC5G834EgoR>;Voe&K_0;1f- zDSntS+de`yMzGFk0ss<{XkPL<6UyLZN!Ijd2SUI?PkLLmtSL5=Pd>-Qf+MV{XSWxW z@T!ixTz<}8i`P!YYDbf~o*U1HqhMNdglm#2I)4*HWKoEDSNv>_VU|Y{&ec;y z9QZEupB0<7Xk8IgwZEy-n=DYJ{$mnA25!6AbY9iP#MMCUj%E}kRhN3iA#1QzoODvU zG`oT|nk>SbBPL432ai+MP<0<= zK4GALZr13Ci=Psd&r<$knz9OKKcjS}m#|Rot^`uzV~is|*7&MFP8y|WTAkdWF|(GY z)ew6L+`vgqG32{7ERY5;C3x>TRoVJ8{dU8kT(VAK;rt(!JygfEdAouSxmx$)B!L`X zloe>534h^Sa6PUWwQJE|Xr#7trFRri&nj2vZB7iwuWoSO)uc6%)g{Y2t&(ctN{z5p zVEX*QSk)#)__VOC%^2|Fgv@shto+)T}yr( zM*}?IIyJ=j1|hbpkVZ;NPsHoo!v)u~W7rd+9A(&6KW8@!P}P|L$(G>4g=YqgDC-ey3qp>)^Iw!iA>zA`-T*Hr?Y5r zDhetb;SNG5x@b-u4*}FQwCQs6d-Z^+Ve;~&1*t?pbxKfjjZb^XF%Q;UPqdb-x#V70 z0c>sn^^l)%@UVGJ-{9&fIp^l@_*ty7`3XASU`-99I4{P8k7!p%llI|82~Fr+Hvm9B<}|_AYzZ&yZ5L+7gflRU#uK!vM=M# z>~q|;YqObWA>(h)p3R}3eH>f6_TS%Oz2v&^^NpD!PD?UT z8xuP@MU@o#_Qh5O#ft zRXusEzi9?WluQd_Sm_aphvSF2ntD+0bVwA#UF)8T>dvz6z*2~&+;zdA7L38KImFnS z_`<|b{I^sxVf+ye#8jKJqTKFQo+P@zRHlb!dd9P9BJb@%l;kDYH-o-e9J$3hv3ISg%8@V{8rEHQe(ds^gAS+JnM2XIydx7X7*12=c`70b zs7#R=EGD<7ioUnakmOLUZu-441LAAdmj`ET3t;on-giJ3D@bEkSG83T!NtT|AC>z! z3x>r5rWsWQg+un{Z15q|b*u4gGK!=1;^%QGL0y9ruJxRks%mp8+pyYW&5~RZEL!HJ zS9PiCwy&KZw;0)(o6!&=y0NiRhMoB}&yFNZaaCe5owzB7nq5lQL%ffrhoVbmHk{_7 z42zGIgJu}nR1WjZQ+}I?+yGBJb~8FRyy&CPhnyO9bbP+G34>i(h_S}K_FfY{-4cYe zK6&*)N56L=+mBPOMMqb|zLBn#tf$BO$J}2WoWtJckh_l1d3GT?1sUDaAVBy!I)51n zWBWe6g^vlvzCI16MFQ>4fRB}=z%}HIt~%kmn@F>5&k%?Kzxq}`hS!>K&ge(uy?J)h z*lk@co3{5iKbi}HZePHUPicgpKu_D9kW7)pq|EGZsz`Wki2u75JO_Sb3gUkjVlN1A zt;VVjs{xxr%eUJl)0r_@O&ZG`?P2E-Vn! zm^?m+{Gui>EE2};71L?|;WffA(#GA?|H)|Y-u$bg>V=YJ#VM5fw3ii%uGluFF&rQp4!^pi?{YjQ0OPz0~^ z$I%XKbkb-wnzl6$!rVm*3MrCgty<)Nk!J%cAw6M{zZ3^-^__Gv}f0gNT%tD8c$sD=8?*i?lEwS?* zwv`kB$9F;7A-uwsF@@E->!_A6f-uCq<7}LD`6sY&?{xP=nK$4NT`@b-7A-(ELxA^y zn#E_A0`)vnL}6&rP6q&>l|241Jdf z{MW0`WR#-X5t1+?`RStz}_`+oAqB!1E=bkWlKwcaLF#@z^X62nCEBrem`Eg4~X^% zTg9TdghE&;PM;wEVg%1vtZ4OCH;FTx!8Hgmx3gxM9)%)XI9{>tRx|cun^9*iNR!<_ zYm=2yc#?MSb|R1(a{T@T-ZwY3@*t%MA@k{65S4g)#~B&x@jn6WMyY&muoXz#1Zzla z1ftiu7clhbY9etn0)}rVMyZ>dkbxHRt zMh80C1;!h<7daS?&*+rEM+s}TCpoy+T+S7DucT_mJnwt-8PJw7F2v`Gl#vxvL2x;( z1)7P*VWW*lv>m!!&!0*SDhN~dk4#dW2_gH$Sm$!{TFR{V4k_O%`B@1hj8uBZJhyu$ z=d*8r`S;Lq4RVI{4-^7(I0$e8aF%I`Mt|e&cB+OK4$|@BJ&jjx6wUs{L29VD7h`a4 ze#VHfpZs?$4u!C0s{b*f{{TwlviQQe6kM2|t4yDxXsbQxf2DDIN zt*{Tf-9q9+-#uEc;qf*+t#hG~*$u?U$Y%j6umj#th+Q(SoAA!YHjPHB3GVJbzPQ5ZuiBuM8iilgm0xdlNsuNF?*q z`skNfXC;ucY~+e6w&`j^w#C?p!T}z@mUb#hDrV+LI{r10 za#$PDovDM%25#Kn#rz_6x?pY5`r|G%U3=Ow-X&3Zy}@{ivmT$*bitd7A}#boAxBbm zL|K%Nwg>4s0Ehml8CHvN@7MZ^aeBQz`sD#+HkbPnmiW1)^PQf4y7!m4Bdq)zvlK#x zm7sn{_UlS&92_GEhr>ai^#*IaH83meMY|PUtDV>-&XL}Jri!CtqokB#$BE4jowuCJ zii$gf{+CHxWi=c#70)z*E)urvR#QF zafzvT?(^qO5P}Y)j0kTF_M9hV=$T%146_a8!W?fCL^C*xDQ*LP))LiuoQdd?rG&3d z&Hau8XA1Alm0A#oQ8yf**z4xD6lSR&|m28}wC&fGk6- z{k*)NM#h4boA1P8B%0m(TSIkbb7ic!4JxG%_XwpufUWlx{_r1_dxib?vR|fClqAPz z#l=)5rBAH&N-`{uX%77aHM@dClV>&@fUcF$8DhQp((kwafrWuSgixTy+^6U-i!H65z>XAz9>QE`nq%e$q*93CUBPu(yGWo>yM!XWF=_t?hj!Rv$*S zcQ>}Svd2*k)z^LXdySKBsOL$^V)L9p9rm02Mh{AD*f>wE|5anDP*hv8r?LtEN1P^a zs#lXtkxOP_(vg~XFQ#G8N#4Q?O9ir*{HBAxkoiHw9@_94rX4|!*MZ}W5v5;ydw=BU zmF-}{jf0zP4%PQ+?%mttAf!D|wTpW!fiyJ~`U2d{s15CqroWQbTB^x|B@Jyuh&A5+ zSOXR6EwyXS+bisIBXofPYE4e9F@jm;*56lGP&lUAJj&$1Wz^E%k#us0Z{i2x1`9^x3c%Rz|v z^MVr<1%<$n3GI803Pf&s^HMeJ(c10wz{O4&fFi+j2{6ITB@otXrhYVW*za2%|`TnBQ$_!0LU!J*dMRAY-RVpwxIw zIp`qRhIP^j6YfgB10T?}9nzq!sW!*(AXd})gXJ)~0NahA_xxY|c>ZcxZbjAGu*l z5+t6i%<}i0DDSbJ@7Y!ce$ab{8kwELwjn!3JiS{4m}@Co}y-pVyQ@1t=y-WP&c@ZwY)u(Xk+nxS&OP*&Qhr(DVS!mh9<&r}x@DU@SLo6}aT z+Y2&#DT>qkGYCHum`nPf3t7V0!;;ybFspIA5vDog-Kpv7wa(-A_vb(wu3xzFn=Q0X zMv$F&uWXa-gwfTTr7#;S=&9E;X2+jp;E+r00g)s?NL)*fxgM`9)|tp(ytaKNfj zcrCCVhZNf%j~z^FtVsIr^BCEX#XB8OJh@Frdhd(XAfm-aGr5iKMm}hv@|xk4&Cq*W z_`!`Yos#dHz6P!ayGO_CCLp)1(S7STd7Lb6Wa919;IB5gH+q$~=h{~RJo-ZTo!n#J zt)~tZ8snhzQsiW_)Tz!M)B5I6q)wQdm?SQk#REb8V1mHAe>k-d*UlPtW(|s)J$Oz4nbT09y_hf%t*H#!m=BicZ^{6Dk>tPKPnMG0* zI3Cs3e?EF)s~Xrb=f#u3de}a2cCI(0_}pu?W|Y@yc8#p3E2?PyNR#IG4xuxmnX#T% ztbE8VdZo#9njEC*>KZFv5IHuQR;YaVCHR1W_xxbHS`F0ERk|8DC(W5}#2OT>W!XVp zBOZ)6z|2rbzn{ltS8r9nTCsg5SE(gYoxAGoq}k}SGR%BFKiWaKnETq;M(g5zn4vOS zB=d4WPPZemfm4&;l&$3kTcFiBX|cwzRpIvI0JC$BK9;R7==dzJK+DSb*95z_*{0&A zeKFPx%#rJDE>ME6Px4Am*CT41CydI{bNpKcnT-TzV^yessLK$6!A@Gs`Bn)GDDQ(x z`S;IZgy~wIlSg66hh)m)t-jA%oxy^j=Ly?<^INUsTDALd@)SO5+s(;x862C}oNPhy zrbf3Vn?^5D3{JP%BWdna{0!sIr- zLS5D-HvZnj2HY99T`5P6lHBe3txb!3k#+IXC5#``sngAie*RvI8cS+Q>MOIvV*N#~ zYky>NR++giJd`%{v6r0-_`VG<`MwQ5x5?cai%RV~TW6w9z66015<%3rI~5B+Qh~eV z&%q>1OF80|M+8QjsCHa&No?;y{{W#9F4UhQAOH56+zk18tJB{Uf(0AYvC35&r-}Rn zxihOP+kd`v@=R*O%g?_tG7iUGQU~}8id62bJI53{N9wb=6aWQqe@QM{DTJwx1ACuf zdX*MAIjyisiU}#qV5uaj21Tnt=bC#2I5BX#{Y2oAJ3*u5JrPs3=ln<3uin(7cryKc z0pHlXhxV5>M2wl4IdLH;_K3cGd>p;HK2nVc40Ix?oM~M8``YBokge0_)vdsUQo;5< zzB&@>cu}RFBE3_;H;PXQF-RiSBp(j41P-Q-4qDv5?c|=!jKR~Al?KkueJEVn70aSR zGI7luZ~=j_mKS*S zII*x6h)Q#m`X062Ez5&xamx66a$+8RBOq{8P`SI3eSgChVk)Vf_k%ve$+p^YP{;KV z8A?btCtQQQLOUj)Snd6A7r#+SYg6t672hqBe);=cJ>e*tLtPO)8f8N%PP(b=n02Q97S8s(2Ck>bkwda4LOf2G@wfK}JDm$*9PodT&kw=1TwBzw}b z<4a@%fWohu{@IxD_%|0I(^1WE5fT5S*eCJ#?nA{L;3;{8Gwz zH*@O2$u1~O?yy1@@Z9ZC0KaaC4bRg~f00w_M?11VdK-mbpcp1}PUANZ7->_M{YQm4!_*_Z1Y{)&f!|s_n4VD6_P*I9>nQ-jul%$ z81dRGHU8`jkyzo$O3;LBCQmSs_S@+uU#z=Kb!m7ldBYPs$gE=-|AVw61$k0I z?iSEC<_gYM15$cPAlN6vyGdNC^)7g?TPW4zdiSbioa>W-kd$hogKf16-8T3${+J+y z5YAcy)X5}PRvRnt-q~4+=UVV0w&1y>fJl1l1>v{*$fcQ*lL0w1@44a-cP5yTQsMd4jjz0 zE~{XGr467+fpybrB_yXqYyK3mOoB7LkCNJz_5wyfD39@*+70H3VW@?J3rBf*8g7&BB5!AxcjhCr$*g76xC z1uUiG5-}ov>;L|;x{w!Zs=*LTwXZRjCCk@h(V1RAD$ zLw67fvUY{PSTGY6Z97Nq&6a#emj+_DyKXc2`Ix-#L5j6X_;7mJ;Mk(Ja`cxz)`lXp zgkcU@{>8SG&ZT9LM8be2&f}6%@qe;;d;0Iw)l+^Lv)1VddpTEl0rNFCtr`letl)`8 zHWxUd&5H+t>$WM>oHf=V3<&!qg*g-9ySXyExw-_r)|0_lESdGXJz8B8^rkREqs@8< zXhsvUt{U-i%VSA3xGi3KNI*=`_Kt34bmG8CucCw%Y26Iv${M@hs1^M^9BXTO=&q7OA4`M(P75{PG#0bK_F5sc8Qq z(yvw91#!~#3K4hmiyMp1i&ml`LYk>4>#NdR71`bA#-UJWRNQt@k=Cb+8fC~;7{HJT zKmSv(JAr6`aAm0ud`Lg}VO(T(QXl-NN2t!2Lq#aK3@#*PzflmRCzzd~DP(K6g|p3> zzZk8mTT?1zdy=7`rG7~kDACxCqAcF*TB~~PNxl>$qgx;BHj{FXoVNQ-m3L7qfu_{(#>qBX-SgsZE z)dgBS)feBXZ(vl#kPi2WSIzb~SbMeE)6Ay%MB6h#8x^Ig;otivR|KVQ%yZN)7X?c; zMvn;gbCoGedX&aNRyHqAJ*`TS*L}8-?LrenfM-y72WF>5R{r*R$gWV(O(6 zUZQ!A6aHTAZ#lzWE4%GCT{W;Kf&fIX#X#F7b$6dz1j%haL~F2b;T;%=e7NpTe=F+J zwumkztC7Z~tUN4k(MBkVVQ5cai>_yKtF!;C>nnQV?(vsgN*f0s&*)mIpCefxXpL?X zIg%+cY^lWyP$Yz%BLsaBD*poAG}n6){14dI0+TP<@T@wFdQWw_11>?MNYSypudv#+ zzG?y~v6D4!O8L9#u1|E$T$h_cdY1V2?4m%B{&RVh4PCSIXPMJpZwqA``0nV zBn5yA|6>iNG9Fm6RJzt)nt-ZAu~Ln#Bq8p*)6FS7R-D+|?*z^&XlE+HSv%>QFtq5@ zRG<<;W3%Cs1uw9{{vlF+U$o6r4y2&f(1QD_G7a8_59||OIe-Q*8p(?>3|Tmo^#{f0 z$`!fu)hre=3!Phe zx7SEWqc%fHyj^OITBi$Bw5d>Oz><+q9WZ=)KW9Z-JKxRmtQ~wlMOFVfGxx+AG7uD! z&Zu(GG6j6Dv{u~1$N-DNQjNz3y<`#&DZN6lL=Z(ujA(@{l`k&kEb8KpKT;4SPBZ8! z74OV2WLn0ef!~d{QxAW|S|a#XXbkd8^Z8t})68AffYu9)dY597Rvy)L_n1snHP1sr zU&~zjm<^%moPy!a2GJ@gA_(`y;Y!BYm>K~ds+Bw_$VR&FfqlRRv4?J?a zJ#U)Y>jvt|A1Ph$Y9U!m+Ho9o4EYg#)Z(~-(f)o$Th1mg&f#aRuGA zJ}ZGymGEI9VaWWxf_-Pw-W>qv!zyb8m?2s+&ghaVY#s8L4%7P7KP?P+5743nN*aZ{ zT5pz-pM{y?t`9CPnnZ4~KY#2%EN6QMUiVc|0k5K|ickoRzrf zQ=lPj^wqJ6)~gW3Q6R7`U0$%A`$zL!1#OxH=ey(q5pxcc=;HMFEp5 z7@CW$=*uq)KM2fiYsZW>8?)*>0B z!Go|bUj=v&n>hRDE~8D=zEtAUqNBYDooq~))PC7xWfyI-zkBl z>~#IR`zKCS8b{<5m^s$_sBkf6n(F7Kyynux@Tw2MVWqVwa}_|bv4P9TKjSg{+o>Z7 zF|$hpmfxJq0#q&fD(rA!V){_GCkcd<8VuVYX&srvlub?cJPJVV)#FNsn4XK}>}|)- z{yvSG$DyoVFz8QgzDEa=kDV3vDBN6LegCQvt&`yYg}uWb%C-biaawplXo4AlAQ z1JMc@x$V;3rN-utsndNE6y}i7Q?hj+GM>SNgf1qidf-C4%1ii-5rmtiL@y6$(ON@t zT|Z!^k6IYP59hG=%>4Xa8$f==%P>M(C>k9jras7N&)+f#&Nen^)IY#sso=+Cdw?Wu z073a4vwINmU!nyGitsZl)#t%83wOeRxqc92_(n-g6{~JnPe_;^!kg17hDTisrVZSj z`bTtm2V}?e<&7=J1+(GWUzbt#8fA+{abtwXI-j4rXsJUIzIPIAb*?}(1pOVBl^#%a zCuOBZsLWXMKjNc{2%j|hhFHKZSx?t{_W|x@bN>`KyNMP>lSK)^Q{*6Lr&QQw0r)BOfZm7q= zf^a?Mb4Pmxn5QHfoMF0WOGG=O{Nt*pJ13@WpZ9xPmtt;Jd+l=M}&IYn=#XTfC2WVM<=|eEPqs}k>5Zj@Qy3t4~^-EHIvj^9eUG_MT858 z5C8W^A z*)x~Wm6lm%0=LOxxcz!Ts~Tu?uro~So7Q0~YwrY--i&qZ)T_?D#<~elakOdn`~-_7 zbZak{vKncv<_q?NM_VB-dmV!f{$KLr4i-xO4=Upal+x zpKlaXM1=D2ZkFYWfBb`FsMZmSIvs4+n{Nz~MTCTe^41HUCx(KQcqW5`gTpl7{=pu% z|AsxrwB2j|ffxn(?Y8Ca^Jr(4?Rgar)c?8<=+B}5JMFk`;vD0@+Q%8!?*yeh2zB=| zr_o4_<%7jE_z0+nI_Addu>4{h*k2IQc)X)Nmvs~=kJFRbgLH>G4LYR9-x_);2`P<` zTy7<#gvq~lj0^R9#V&_IjKDRk_1bfNPawirxEZ z4%zC&1uwor9xXfg0>@Q)|_3p zM!fnwNa8`r0W(=QC#O+yNwV*3M~q)!?L2XP&7 zpq<_EtaRaCTv3|IP+eYK+B{qmd$W)d$!LxiTce}*PpWf2hJTwsj=)8idZ0@W!AVRZ z_?tX+-Rx&6_XHv=o-tcK;Kp&3y$}glU=PMU1L?xhY(Kx-ew!Ej|4YW9e(RhJF;{D@ zpxs`}57P&r?MGb?zPUmWUh~!`^W8%31W`zR=Hhls^KYl$V|4STnjFWEKxS|b@Ldyc zS1;#%TlCtVR96VAp1f7P%;EZTVI+K9q^x{|KHBPYc>PyYsdfBfPS0$N>f2rR^i;R* zwk4!9P$H1xin?p_RQ4CFt`fMhRCHVsa04^}MJ9LZ_-4r^)T44aN#ZWT*#p#$2Bw$g z@M^CMKN9uT0hU+kkt0X3&iX8wabqhhy|)r4*Z-KiX_J$DP~9iuPKKt zU*VsgN@a)|k3s=>El}B{-RIe5RbF*gNGe^eF~0|!u~1delcFVsz009do37ow-q}+{ z5{rYE2K^ehIqG{hbBpWB-r|m~?bW*h)F_ja=8C%F>+<5&wR41YZak-H*Kz_e(vNY1 zd5aB;2+IKuGs41;RlBqmp5mK_qYOss|;^O$oI`_^PKuF)VO$gI``S8oKykkmNtqoz$ zw6Q>ODO`Wu+F$*}sv5|$JZ_tyoW_G&zR%T>ch5Q7`pL&q5!*!X-456DIA=cvK%Us5 z^H>&=KJ4e{bi2q(ZwPy^LYYBf;Y(-Y2 z{9aay3l25^B2lLo#9d*Cur1xSEKQe{F;*o+4HFnSm|IqXV_f(XNNfx?)2pY4?Zz$g zu%z}UfOAKRAw959ldX=#=i!mLg(Jhd%cJvu6MyX1CVB=4CiR4U`V!1%=pWqjGW&@M zKzL|ksc|K$2J)6*2$uA6n#ER6!$BV0E8c5;02Y>mU%= zblH1sMP+4ug=Fe3msFE=>1-zS6+PwsI6f)@ z)PB&K9;T?pF|(*+oIry#WOv@ve!A`B>i87V;%kr5Urxj-=k^F>CL|<8SIk7r$^ALz z1P{=XXQA8VZlj-9<+8T=w0R_j!om4?KiM<=wf_A3PiCVX%~N!RPz(@^tx&~EF0fVD zTkWkjG;O=AMA3oltmj`UL|BgqJvEnt{Zayq=AP}_rnCV12dtiA0cSTT$i@tu+GeEiiG;bND5jZ0q0xOos3^N78?_YWftbx&8@+3FFG?* zIjiXf&07)J8&dy21o@932u}Y0mmo;>4-0L>(b_vn*^THY%Tl2;DcX;VT;;6V=8Ka2 z>&aH*Ony%sfS(^|(ttPK`;}j9>3-dxMz&5VIf=mq9b;N|=;B@BEzP*}->EkvZj#h! z$g4&Ka=M+-W0Xg^+VSDNs4R@8k7+3E9$~R(ZLO9C;*|z8_Rq^qcszfhs?~ouC<7k3 zyq#WA=ylhFpR7uS)+}iCJ-69)OK|&*u8N#>Mkab+o2W^rEZ!Q4$xq;{(F`s*q0gGG z`UwGZ_RhV(o7R-DJ@oY-!1<+zK{jx9_AW|?$7Kc<6CQGp&?~;IK^Bj=66=97ISt4CKxXk2z<2z3YCS~^=Hmp1g97;*3Wysk zMoR6;@c-JWBje}{opO}r8TMf^IbH%A!vgKAoNp$9Kr>g-p2fl700$P6Y-(h{DhZF4 z{&~})JzBs|T_=SwMYID84kRn$WiVysBVRZMvFh*+OYI&-yGWqYKl2df}8FRcn z1YqV_1`|$vR!zk7?(8!#YYE1@2ud&^fAy#@A}Nsl3S%-euGv-?&yKykFs3LpO<{@Zw_@S7^Dz4I8Q0yT+a8$E@K$z_J}F*OnEKU_Gc0o?YQs zY(!?~y_3oatD%{ZL1D~9A|b=Bx=3flK!FI{8#!%IRTkV3&^#P_Ph2^SNfhAF)S6j6a!U}}8(X)l^8gO!O zJ@J5z!P;5?SEJdIb&%$Ya{#*cA{B_STV0UZ6L`pPyIqt5Gz>m z_O%=C{?FzzsjGmCyC)XPfu7MCsgQMcZn04kPbIU3WmXU`Eo}*SVdYji*aRHb>5@ z;~G)6PY#9n3@|MzWGyTn69j()b$lf^9>&oC@g^=Chx!Xtt~B=(E}X1Tf7JgMLhuXI z3SdV?#wA8$eir(dFNmp(d_NnAfAE>Q6VbeFaH}myY8P_78KDHfv2jI4$kwE!KR4d@ zgk2G!?S)o>*053{@~LjXR#re^RjA%adhdqnJVrUr9a9Y|lJ9e<*%}sb5VG#1y zahT9YdJhSZWy40oXz7UL2qX~tIpIe4%04Tgz)w35of+td%MXn2p&sCDWea5xY_|ys zRYD!Wd$s0%%qT-_0SMrduQoqE;{%aVQGw9I&*88eJmb1kzl#ip;(E0|APg1O?Eh@4 zqDKK51xT}oPS9xlg~@Vc0>F?1D!2Lt-a3LWb#X`wjfE{4p0UIP<%V`dTvyENdk^(+ zYZvB$VB>vB!F0d4aBjYj_{$yZ72X|nBmXBMsT5|S{VN2pEdD(n6IQkJRqP^LbQAn{ zFLZ~rz`UOuSniSjE>qSrYkxfa<`xHRKbI=A7@04ieKv5Ctt=^Xi8jhJdcOTMt}4H*2m*SMUpzYZetK{X2HZ0xNJFmoVdZ zbX~{$&U=KpSa~#=LY8utco94+G7ojuPx-7xC(AVj6>Vf=xqQ?00GHysQH@nR?3j%^JU3s0yz^|+Ll*y-)v}_Z4U>aAEm4kb*QUww@9`$PD^$m6#&`liDl7kdX8MC` zNsN3!;TkA3x#jo`h{NnB_YHDn-F3m$bj zJR2x>2Z+$@il4lltn8r97?Hb~oIz0NPo10(CUpps^gp%{Y8IjAB%f$IqXOD5wrgwM zxAZOTnxuyU+k}o9+i{? zQVM+WD*)mDslZ4L9aE3n?5Ve&9~^KUs(R2iO=PKqv-*?jS$WN(h5mkRjd@HsRM*dVmlFNK0Ry<)q7Q89@^a?^>PM!d6`yJ!vaT30^jmc#QJS-2M2h zg8np@x#K=j5$$5l^l+=GJrhKv8o?vqbKgrzlR1g`53Pcld2wjepOUyyd4B^ls(p@( zZ;M)Fh;PWi=Q{qV9~3^gN&%+B*_+cLO-G?J_bj5p7)eF4)u^`Slb*Y1)1=z%^Nj4~ z-{pb4rJRjY**PGpHZy!!LVmvAkx7oj2$U5&P%9;OmokF09p+tAFK8bf4MO5u#6hTUv+X1$pKPU-Z zxFGE9gJM%VxaL%>PSR7yNmQpjpQ|u~3_xrVw@kC~r3I^NAFzlKY0!KeB;8A8b!(W- z7rrZ<3QQ=$Vau=0E18v^Q-*Sd4QmCC?RMiYvm#D`;W2Dm=69WRW@mqpWl~jjmwTwi2t6n+75a=R2Ns}vVr~cbF{R zSY9dFcDaAj+CNpH>E2js(pC&3M3QWICP(LPajRFXdE@{lGmQZIt}Q-_HjfnY^-#W_ z4;Bi3gF;-R1HKuq%ghq$8Igj-Kir#B0-cHpP3d@}sucUpbo5#;dbcLn@GEcMw69*< z@S~MbWhyjdZXe_C;nE~ktaN04{Q##wba^MA0hjd$$^5WBOPB;a2>7B+b@s^I2|Hc$ z#Q$d}*<`JHI(x0LOS{zr7C{F@^;as|#6siLj*CdCG7<9LGD0g{R&@*`D%Kls3PWP_ zU$cT7zr-KuV&zYH0bt4Z;dbMLJ?ptPWhcJc9C*B5n@JpYv15B7T)a#6?1UReuvK^t z==0`MQoeCflgm=)r>&VWURZ~&&AgB9ODBoUKr30ORNHbV7uStly=B%(W@?zh zwJCg|_5TpeiJiYA7!xG%kQPQd|CV6JYyXL0a0dTPMr_-gx(kE;;3^d@LRCPjb>y9~ z=7WfamsxqgJ|_z_GWs1+-Hxw5Ty{f<0zd;&>=9 z<$Dnya#Ot6*-c|~J#&=;x>4$)!AUtT8sgqaCcRoUU(OAUaLjJLJF{|K@8DlyI}f)Y zZ5uF8EzBfJ?g6oX3a{qY$H22T28vBm$oAEo@5NU4x40h+s4Buu5u-UWnharmG57L3? XiOI=(SH+P(0Q}{QaCfBJ2a*2+{3E69 literal 104312 zcmdRV^LOM=yKOYdWMbR4&6(H}Ol;dm_XHE$HYP^Lwr$(Caq~Uryz9L8u5f zpHi2g;CVXaZ(tYiDD^;AG@zVq)uLZs&Xf*&+DZiOoVq-C4xZ z#K76Y&X!ok!p7wDAs84dGb{UEQ!O+5etIw~`+iaZF$>FniXSuEUT`1>*FjONQtl)! z7#J~_l<0RA_w>^>H)o8#mCmb+b-;|5zc6t?04{H^WD=>4MJ~DpCi+j&M_5`~>h@4} zF;T^0(&?6IzG*&5BmpQ0@E^l%ZdngeP+yTHg;i#s(&L=iSJzV3+EUEiGM8}VM4`kK z(Z!lzdNy>xKfmow75V+ir4EfH!=OhOQ;f$i*1vLVY>qS_(7c|a9ne!scREnlwZ7wY zVtNglQI75O1IU?QPw^5iYb3d2`Ya|!>e&uFRo#0q0k0m!6>F5bwvncl(Rk{;_#|Q- zH;_l_+UQeRqX=N1v(!Op+7gLZJEsxp(vZmGZ?F7MkaTSB14K640r?`ODJ{-KYIaXP ztTJBxn|ftjrAicHD?ZY@gVjZ3!{Khu9Iz?pi1nXGF7FFJFnYFzFo z=$C*;6))b&wjb+_h*5fJ8YD~_iANK2E?hNw(dZ%!&|Dh7SXQ>j zM5VghyO6h=XUlGu1p%_KuhQ6)NHQA9Rk}p)XgX#lj0Lo`F7supOHHSxJ=x24w!4J zF(D8&iB{*slJDD9x9R|mM%LWALr zj08leZfwPBB8ENu)k|%# z49oFM4~@c%EFESZ-=G?eSXM6SF1gP-76%JjdaG~6GQQRdbXDc?O7a^WFHf?cB@!uj zajBnx;h#KaTcUTRC?s#0Xfc~xyfUm29+i4VZzNY|oE2YiGs$zlF+pohH7t3*`N}X> zZH-jSQse(l8}qMP>~FoB0aUDUgTszqXhmI5d0e_Q=+}FqYUYyom=X@X0vZ>&S~MJUW&MzYExL47AQEgkZjMp(90j7h28*3fT~+a?-g$N2_?H4dPQP^Kj>z(H+q)? z*%s!h8HI5byW7KSx*_up(;`L`CpQQhe*aLpct%)Z zGy_N}aj{)D;l__1M5XolX$hlvGRil7?5MrBk;A>cLRoC*z$WKEuB4IwsyX0gkxC81 z5fef4Uz2zh7|ZoFKi}JJi&zltrH}{`Ai+c)+ogQZ@!d9#kg6FgDX0CWgiebJ2>24*qKL*EthYn78!sbT@lLI-7N-zS4PJYiHcv_C>hD$mnu9XhJpEY4Y`MT+M63q{B& zzqOikC%s_Ynk;i(^Lma(M^tng(={H<3IoTpmx5GYioagM^=z4<#q}&U0*zNXzE5ZP zPLC={OjNtb`0O_2`sDbo2Jocvlno$c`O*-#Bt=SE%v$N6r9S+o09Z?@e#Z3ti zTIA9!6MLsh!zU%RsJV$7=o`VL8H1Kj6qDH>=CV^sAa?p&o9wKlO-fqP!@BEG>OSYK zX8PVNo5+|<51EFE9HwRRWZj`GnqK3kE(d#ENetP*eg3M%i!_*2_tpzChQZ-+E4NnX zmG>0fr<>39F%dZ)dxLS+CAX-UVJ)%>ZXp2^bv-%>^6_+ zb>6W)3}@GmjDAJ|0-zhEP+4Ov*;r(yD{3yfB9pZjwft z5v+{67IgCCTjXfHTh-E+eC!zIqWd}1*i+njc6h1qW7kp^91f0|@->pBUM-R0){03h zW`v|p_+3N1pN&%5E&a>VpDXxrEE6x~Z}z4md{PQ->ClX)LVwj*uWK*4a|V5$TxDBW z%*c)P*ltQFBi*BV{x`<7{E@)*KYam|`=pga+c%6cR$j*DHbgAhArCWgyR86F7pK~* zD8TI)Rj8@y5f6DxQ=(lkFN{z~D)Wl#YwEA#C^=*u+YRwv7eLc(XkBRF_t&g65-B8= zddX*BlIs9DH2ALRy(D%NsieEMyx!pNuebm@2SgMH{5U2nui!$B-4FwbJ{K}|?1IU( z6LKAGM^kO(D-PmRE#(wOs*> z@1d(nPeU5p-rgXZ(zE-gNkh|3B_;883E;5 z!A?i%Ypo&NMjn>G?%F{@Ituz@Rpa~`CB!)ZK`3-@-=h%TVj7Dkq5`t3(c^cByvn-W zlZ)n`)NE-KQd&4GZQy%(*P9nR677XX+{e-s6dVstxCc3M)^gVc(&aUa6(34BMV@EV z*od~KD>~03>{-;gep}wJPx#_5hrMnKG1VC!CWTy;5g&f0IncxjIxF|FfNL$>$0gQ@C_J&}GAe;5^diRhnQPnO zjjcqe1{OV%Z^;}01)h=Py%woTMcfeq&T-z-_+9qC_`XmKFoGnwNqTj9T;jv$wNwa% z(z)0v?&D_$gbkmBa*ZlYwh_mpuNC3E`kf!u_s-=wi4-12oh?f3)`t)8uu6`jc?%VnSN znE8l8js9{6?wO~0m@#z!RwF!#xLzF*l$euue zCJwhBejK)VFJ;tjjTGwUzIPsl%~T!qt)mqa%adJp)E`#5zTTOd znTI)db5x3v!>#0_-&SfP9Yx3@oFveyBzF6f)5w@Tc1{d_!yPPw_z2sib=iv` zlZMhuNs@5BPYX+?uvP2}Q5U@A@^|t)dhnr6tVF!}TQ1cieH29e2ilqK;^N?=}9f3=2^h z7ENV;oAB#OUksy-6I)f|`JZl3k+126^x7ZHsmI8EgSGfGuu)ZA$>Q!0=oZ+Wu~W9s zhPqKPn9jv!VJ{YdPM?Gr_q*A4pX8a<81H?ZroH@EQW*W|Mo>xxZ|m%6kWq^p$m_w@ z^+Mo#EJ?bdSeukKcdUY0nd!*=ne_(FKmuM1vvR(y6unpb!5fN`db>3t8f7Kr`+fZ= zNYJibF)@y8dHO!if?lU7*uh6@+9xn3&_^%VxkA^p@pDx&3AU|@6cJf190e~}Gfysi z(wGykkrTjWhk-Dcz)eqYK_@5<1*9CCsHI*ZbEfdFBrsq^z}!r7-3vs;Dt?g~q%N?I z+o4BuruE}tRHr`H1g?=NTX~QT)&imf}H7_LkggS8{8iq zP2$}+u1ru+sYDBTbZ>9RM;=8j9lp{Mg<0lL*GpfD37)@QK04DOlWUj`gwe6&1kuAr zEPU%mO<%RtyIL=~enOxS`MM;s-WuPpbz4QLZ_te)L*|%VA75#HJrF!`C}K5{bun!7 zvZ|D*BabHR&iJPkWW4`cw^Nnw<{vX;_mY$hxo2e=cbS;_Njg;HVhl%vvP-7mgU8ey zd?>YIY~8Soie`=#wx*X`;ufRWL9re?I?rUAXxBU!V@N`1$gR!o^| z$ccx)Lk4wGW4Z~!(y6E}M+qgyV7ubS!)6T25N1hVUkM(R!=Bgb<;zrUc_tq3N1a(b zU6ll%oGRhW)}()?kHJ%)v(G}N`B@VJzmbw6DZfM~40F%)v7!PkZzrfiXFNkjhzaw`6QS?Iu(~>^Y5?jxxEC4w6%9uQt^pd- zZC*M$A>j8C@h`z?OZ2wjF-ks@&{9dpO9Jg_v!Sr)TyfuJRTW^rMkR&{91MvGq+N_L zxU`eTr7fMeMg}4uJzMpo=&ilv-P$UNcl%fyvbIPGcS&Dw$M4{5pd@UnI%bFP)1GJ? z;^XON9A=irgl1KFooS)J7qz~XQionM74b4*{3l(LL+uvBSt$U3K8tKv;gAzylbA8v z5i%2G7JJGg%(0~w^Qax%+d1V)4Q6ZUKpqpfSAoy51$xw>@7d-27xgoTP(U4;yDRwx z?voLskZ^+vvzpP`v6!5cRlL=9Sy>%)%sjIB!EA|}cufRi;&QV42;-h8+b_+OD@Mi% z4jKzolZ02`Ux||9tEq@Dbh38;Rd#Qd9P90*wJ?<899oa2?Z(Y_&be2cOFc|>T(6(w zM0pN%1ks4dcJEKbow#SCeNdqYp9(-Eu+IqJ*#%Oo=bsVvuCHQ-8ZI80x(qXux!{UxS5L-ghQ{!jp}8;Ap#}$N zGgnkdCRcc|^fN`>7-Utdwhj+?o{O0(azR-zz|ozPV`s017ME%IRzN{ZEt;8;xKu+K znM5flh>D9sF%{FbZ8`}xM%uTrM2d)lA|R#OswiuXn~T#%k?Z`025pN18rew2P9uwv zG_sAgwXhOwj{b$MaXWv?+7L|KUUgoShRnWzrf*Lv056z5k<5a;x@xT|Sqv!$R)PivD z#*@%8KwC66M~e!hmXxOK}4bzq!P3BzT0>bH@sKdt@!RU2-@cIuBeTPV$ZWEz-Z9~Ax zYReZHR^>dkCywoIZtttMzzxh+l?_?w!Wf9*#_Iq3%+7coxWCx@`}!%w<{DbBQeiNe zV_79t9D$5EZnSdEF!=9cC?L)?HlD}pv~F$ZP?HBQXP)Bb#E z^j_sV=vRSDnD>$_!uf8eU7F-Oc6&Jf1D&KJN=z)=j=qG__Vd|4Z{ai%(x8#tNjOM~qaCvZeck&}DC44qWqV@3@|=G||lJua|+ zB-R_D@nxunV$yU*dcX4FZL8Soki^F&i1d2 zPy?zS!qjO&!GRxIY_(rC<4{rL;88l(4@`%5MiD|cG^d;j){j*iAJt+nlioOh;Wr=o z!mJLqPlyrg6y_y`gA|5t&i6}xl}E4XpG)9kUf;o{q}F~0N`%nE!$SP#Z1FCkwp33c z^|qs(Q8+#PZ(=o~SPGI`n6kE`rzIXNmjy(sIVKbAw|g`<5M_N)dmNNbZ}pQ6jbXKn zuxNNZJqAOUtK8(M()OCow&a^wb3k$*Sz|VOL_~rlFwES1Th%BZ-z7bo<&OW8xQtVX z=T|MQn2kh0F-p`Y@$?%#QxP7;bsOCSl67U&hzXV*lHh(#Ra|}bqnI3_6*tPi)l6dK zi3~)InHA6*R?ac4#`;Sq5GWtN1h+p_YbO+azX#c89F@ojk~gF5utUPc>EIJ63hQ0u z&wu4R5iQ5g{^x395TK3q{!_{bJ{G!`IHhJp`;NMUNpCzKIW(WB1-p}Y*?FxSOIlu-++!SD#2QQ_q|o5@gKhW<`XUm16_^iLHYOBJR> zjVv(SNX;R?3B5eA3`>>rx%h(<^nTGq4v>w>VT1jbjeBd+BYURZYmZoGJ5p&Zs#*89 zv)~gJO0W6cN@lAWLqU(>-s7z`i?v;gMib+0@(!$4U|8Ji;Litcpm7zw5$W##`jn+Q z7}ZLNgr;{YI$-h`dOhY1bTJ>2C?#A*`5cYq{yEx+ zfr!g$_@=UT03L(>T)v_TxW`l`fstJ=a~L zACgks4XNEo4A+M*36DwKXxGVG;J9isDNLm(it9u+jtCzw{(;Y|jTeks*Y~;BXKu`UM z+Yzy}P-jC#&n5jGZ6>m-}vQUm^dAeY<;w) z&@2om%8Gi~3M&xgW^A8WFueWi5Pv&Iju8ou4F7?>uG+y<3^@?glIy;cNoY=qnV8Eq z76h)+W3EDkPC7XZzY%rhQoB7uDqxC_swto)SyScz7CJhJbZ{RNedbi4xM(lt$4l;y zJkq&T<^E|b}r$pHEXIrBHs6yFITeMy~EW4e}U>| zJF$eKLW4WMyCV1#boFPWuB@Yc(ju^c2HUHk+B4kVwnB`l3E6^~ID#dWD;>eKU;e*A zaM+7^cyhP=r_c8^t#)tBPI^{9CUoYWO#AdLpDm)H^b7Vk6X5MO5wS17xphno7lBS@ zC}({x=xr(& zr6`CiCL~Fe{0!>|)f$;y&w`7~Xk0@=I+WY7+J5HjKXfukzq$%4g<)L(|h03U3 z5dW73k!az>^e-uiNEw6oU(%F^_}hQW9k!<$3ehwS5WU*31WU)rQhFO&xuXWx-K#RO zJ6VAn~Q6Fa)94ARgpJ|?&BU>Kpl1Z^DuuAlz zVdYl)bb)2*Genn<7-B;SE&Lkh=FpIVWf|+ac_$j@!FM3~rz*C!K*sG!lZ7!a6NVHz zHBg7sJUwTb+I`hdHXOXctgT`k7^Hr+;h1J}F?mELZ6}pi)a6Pl!|A2^5YAQC!~v_> ze1*Y;UD0AReR3#Q{`Yv4rdnSVCRdZm(KT&*W11EB1iA&NQ@8m(V^G)J2^?2}8U5-k zmz4<{rfu#ik<`hdF=K(RYeOHWt)$69eOrFksuX0$Ma^lqRCCvGaTo*%*pKO3HH(sspkY+FB$3@Z>Q+H(&G)tu|QK`Ay#+ECW(qUqKA7oUO$8&fV- zm1*yX`$v$;sbFSs&lnnmB9)#rE=1Evo+Ll0xuf&YiXr7%2kTqP@7p%(wS?}10M~$} zl@0pw6hsPnN7bOtAp6(QT;mHyh8*A5H8p#EbBs~pe)GRdD)@~D{Zz47cX?|;Hz96J zazPWGKdE-@fqQF%O7yt_DO5 z@S?k3RWoE3Sc?s>eCr-}PWRkh$j|Hc|x&dz!Y$*i2{dZ_F3)?PW-=V8Ohadtr4uoD7{DGz25y4<1-y#^z+ zXOH*Io;De@f*Pog`m0>e>ymjq`T*l}1rb&bsaQMyZ3*^aW~yT^ajeA;R-_bRQ2)tn(WNj)Qve_&e90V@%2FXFHZ1d)!oo zFYEXpJaTUw=K{FHlK(4>?6!J_=XY}TG>S6IFAz{KV2bvUZ8wYK4STsDsV)$q(ZaNO zT{e+s7r(a~TwnWUj4PwYXsErB=$vJcZ?KU>Z37{bpmua8%DThHwRJbercvYgB@FQH zD+WVSBZ^WMRK#LD>pgF?Hhyp8#gpL(a!i!~19yedGL_fgNvYL3A;r>I>_B4Ead9tB zK^kzqFnu^*J6-qkBWFM=_pBq^IPYQy-b40J=#3BW!6ma=!pq2)Er2%} zDx#uF_apJT2>Hf@Ox4)zEXixVOm-;6vzs~^-ii~PT|UaG_&Usz%c>0Y-w82UQmwb+ z8j@$-&&+tvWBFE7HeH7^4eko`f2Sq0i?Sv6o@3C*m}JEttm87!MVc{8(0B#S#S?#g zbJK~rI9?|zaEoI_JvTy&TattLrW%V?gg?POe*$|x9>$uKGe-efc8VRqr!6na#CY>X zZEYs6c>Q^db)U3Z586!)4n9dQBV7Jof_{sZ)~DkaHXoOX<~A}{rlqq=zu{a;*7t+I z*RUqU?)`e&YRV+$HjlN`PJ{;Mn8egyk^UTjs`|IAmIz3H<4G|xAH$F@8Xd)dXY*R_ z(hkV5B~o`Vn(Jcc;r;Nj&?(M-Tp2U0d6I6QW-z(U998^6+f_~t#N{|C`^WQ_Ct>u- z4}YdnF@=789jX4GrUmA;d-2;lA|qi5%>0iv7ZvoqEMXUsw-Ft_wkZFD=^6sW(v(*k zb$a{>U^ltaCs9+bQuXtbg>uYq&iOC@V9vjD$+YU9EovU6uFq^uY$)a%=4VSf@?T^A zU+dxjFGH2*KQx*g_cneZ{j+-ts^yw>FzfTqFHEXs>Q@rSpL?6jpG#<21?GOy_CV+! z^iNWkm_VmiW7zj?PJFHC@0aVf6+_P4mn8M>X}`SP zD7MZE&lj1!VNtaJQwH9{lDL`eQ26kHrW&7%V!c%kFEJ6DsXYaTdmPnkzkv(UKb!`# zinexERidRhQ~Q~+riV$SB531d>D- zW-%2WiV;lmTp4lk$`AImfL?9_a3;%kLpVOx>RuNb-MHe7$c&x=y;V`3H+#+DUo!yi zlsUm*L+BXY$ z`(W>C4Xa8r*i46rTm#@~aFJaBl74&Er^wI_PB&1FK$`@b?%`fl|1V4$2_;SzKblC z-oyip#5H$pse{E=@Y*u%WMU+~c9aD7bI=?)e|*I`F!NKVI+4I$yYhIq`}HlcvpYWA zf$V4zR>>N?30u{q*ZYp$VaWBzx5qfZId;&3Y`)!%%Jq5LFvvH$cALRc@Q$ZNxl{j! zWO8OGWrnfUrxwp^DqJ@}EO0x=VzGyR%9g3XoD5gor?dc?@fm%jVd)7ZyPTXnIfQ-6^I1@HV zou?k=4(Y^Nd)nVz1cFVkL?S4JYN~o0&6xOo)1jgS21D%Wq~OeKD7-G27celI_*AVe z*PWM-A%9St^FL%y|D7?tOdwFSb?mrgY))3Qi#p{kzjRccHd#pEjeiGewEjJm8 zb)on9U@6OY(to0rKYXAbafz@GsTp6W4#x?4qedJ5r(L{uOy+D8G!|aJR0xDF&g-xB^tOj>RQ z_7TQWc!8EowjBN(o@5hp`wp@}n3NTv~> zSEYtyq93vFW1d46j}KEL4x;|J)&eDD>L2UJ|0D~9jW(~A)35!J0UL{0R9&;cPN4|5 zz?AOA-V)vakm0pJGB8ferAA5%>@pYb@!hEa=J^H3T)OV0Eb!eY1}cHRC~XQYD%)qR z*%p(hvnf}M6pb#r#-9xX)#>I$sPG`koLLmAVow~-eZ z$!2Gny(bUhOAkHP-8iBSK|tH-wIUGHyexSz=P?)cr1&`WV=uc_1mZ2I-%kzDD}Y~k zW|${TfK_lK63R)iBV`_53+Y+&B>{ zVyv91`3tLj<=DH-PVVw$15lSh_t7=*OUz?-$=~nFmB9F-tA$;=kTjmrcKh}o5*bHC zc62Q3@aqR(OUDP~Ig@&Rd9L2l&sPyr8r2fk2*EYUW^;8i(jl)2Nh{*N&N$b&UDan~ z$MNOz8AZG|Z(Z~v0pWdzs|Oa>*e>#NCz9bEL?m4R_doo7hh)5khIM~YOrZu;p;bmj z-Y!Wa>uj@TSD8X^ZYuVESTWdXwX?$_@LvyUl_)@j^59Ce$YPS#~z|fPO z2>)$KEWpScSz-9fb(EfRgInP54U2d+(6g46%QUg=_nYKYWBnZ0KVhWoSj~5G)1EZ* z*{{cvJ^u6dqfbbkW`0E0>zI$50wq;>KcT9gOSLY==?{vO>YfcYcrlMzpfI734eO*5tI{jW-2yf~S=0(cCv_UT~b?-)?PXHvM)XsGP{Z49m%=H5v+8 z3?-KESr=gVXt|n451GTzZZ?n zD=Nd=vs6m?N+x|R>R*Dcr0hdIyfINKm?cLfjW+XR-S$@$)d@$@1}$HLWg=zo*X%7V zJ17~``<&Ziht{cF#=0!eOu-Gty~~0RQ#W5q$D1=Y4z<=?>L}JZae?F@hjqefQ9nk+ zC|jvG1Fu2OFnym`5^!PJTSu0N6+WQ<%+E52#gp#OkaC|q3hWVmq0V@Z&%&7XWg z6xBOn+egNoikl%(bM9?xN`#J@njl#9OeVDp=DcdGJ})`t_oFAB0xIG z@(-*%XdClqvL%6_$x(4jS-o4!E)BoY!ldkME zq&pa)DjVj5aBfMhL1&qNzVXtp=c%PzE6q^;Ow}^MFBaEx?<=M!az<;}yuIR3n+7aK zS6@kwL+ZVow^washItnkxs1jT$CLtnTi7yLln}?WKiKvL4{Un&am25l*PaXp_Euq% z;vq*5H~d1syxN1*FX8E=KuoTtvn)kc8KpPu8M+a)%DMW45Utk9<(UBq=E9XUFLpc% zVE>LRXWw!i;RYzhf$i{GX-Z~B0c}mB_?E^~McQp3AT?+v*`6kiZ z0IBQRN=kFes|b2BjFEoHzj_2XKAKo4I*jz*8oBhT*-I3Ee}?bgaE1g@>dplX0g84z z|Gi2hXWNV|7}{`jMQWc)N*pJQbwn5~EUCj?=i}ng_Sz~pQ<;SH)3Q=z^R-{n!^q~D zVK0>qK-$44hM%^Pm|Hk{gN#i{B8WL9%nT)ycM%yXBf2{*?IA$9^N`vn@;iFWb36;-3LD!}Y~U~@y8GHXUm+kv&UL`)dXOCLNWGBWYdaLjlX zyr@xLHWt%Be2P8KJpd!I+knt;7FpzyjrAy=?qJ86FxCziDum?5(-R6REGsQ&_USqN zu&HtW!7Gy=qKCYf@5VbhOfn0>0!Ob+uSGf-{1d^(7TMQ|N(@LAa{&@+)1!o+uv*$8 z90{JZOVn5Mmv-~hh#als+gVIueJrY<+l`y^Y=B@*r-9cwbG=6Cp+W=aQxUN9`1om$ z;2Wn-Bv;Bf+}3zQsYG|;=i94KaQImtq<g*}E3RZ5njtyemi#Ve7ceU`=-Ky4 z7v#zs&%td(WW9f@#&=x&`+7wgNwhjp?H^~3QRd(=hTU&Bv6msFPy0f6BA>p0I<8P` zIAfoYIZ%dhgku8#7%6fD-M#WUxOH>D1GI-==z-5C!X63QiMsk}_OpS1DEN(v$LXAT zh8Ml}?*M4C$Dm9uNajZ3dhOz9^H%R($qaczn#{ zc4EMZf80t&aI5Xl0kVvPt`@e0VYddOHg8X@D@k;il~2ck#qN7tIu9sSkU}J(W&PHuc)+%hqRkKqhPH5_woY#*e!X09w^d@H+jTu_l`=0%`bTgQUR~2 zc^>I@(JrdMk;aYPc|1eTz0p@oF+OPfeFMa-UZu&7Jb4#hNYb(ZVLK$JIdXMA%^`~L z7SGh4)@SDwczx}crSZ07N;&KB-{u%xJKG`+Y80bZp9P*7diC;8|9u0wA4pZYu`+Q? zzcbr{xH!LX4)?c=+kDk4wnxUxR)kXF8T>K{`OY&`m|my33Xy)F`|=8Mxi) zzGDOU2sLNcS-5ODf@5C-%LH_+0!^Cmm^XE3^djA0xbBN^YTm3P7oL5`;{y9Ezl%(| zU_qFtCMqT#(z;W-nZP4bNVW{7JgPLluNG6;-=}YCkz?2GzV*b7P{9#MG@~IiR%DKE zvoSJ@{cH_}*^f=2J}D$Aro$0>cT<{@Qs<528PL|J6>h5WH6IrpFC3WM_a7<~s>x!B z@SaL9N@lZyJUXYKK{JAo+F7k@tv!4LhlD{i-t=laoZaKl#Ps=kfv`NHL^B^=m}Rzw z#Kv<3HgIJTuH}uQ147oSRvFi$RsL%59Xc9{v;0jUhzjLXW&j&HO%{xLlV^U!EKnze zQ#6s;G65UdzY5oMAxR7TNp*E;fa=05CLmXtd1kTJ%whsjqfP5i)xIvyuHAdKED{UW z3>oyFCj75bu)Gw@9b-X|Fs$~Qe9jlM2}!ua;Y93hEgn0#e*ilk z(|`^R>=-F#3zTTDEQG4Xqe$*y?#PpePJXt=i0u4^tbH1sYs}MuQ_NV%nTho6EeG3f^93p-2W7wPs^@NH$I#@;Y!D`y1_hdsN}eX@f}8G9?!A7nQMjm|O74XyFOd$j%c*$8T~-!C5^ zx6G?w7+ORC)2z&OuOHMTBv7bO`P6>7)H>);ilL;$xrR;arH0>w_jG$17ctO9q0pg@ zzF`Wd66Xf2%l!CCK{7<+)kY*Ao$c!+EPA;%agl_CKVHiLGRsKe@Oo#*V@cv+T9qHs z%xR2@H9o zXw^xk2k1+CsLccTC2YTW@rYs%rHnP6mox`ZSLtwuD-6KzmV_fmzFsrjV3p}-aio-u zROCt3K%38EKQitRwkGmUnM&VZ9H{?_P0nNY(Yo)O^T0Rw+7=y$2TICo>z_F@#-_90CUb{WR5yKSro zM|ytE0hdo4Z;2ep2gY)A@CHXpc~7k)7)q8kaIvvpI}UEgyO#qS?mgU3_& z(eBQFf+`U7pT8BdMGyZ^csp)Nt19eifWukR9^@n()P6O;jX4FRtd+z;gjTW+O` z>WSZ@v{JVg67;dumkRI>SRD41IFIG99f5d;rNc$Wd_we^-3n>+>;&#)ci~!|@Z;e9 z!`pTeW(NT+hl^*fg!nfCV(;yd=RD$F`y6F!4yR1zYa2nE{H)`bg zYzm58vpslUXfL>IZI1y~49_op?0r3N{eaEPs!i=F8XRb|WpCr#82$YbZX~BMx52{9 ztqgDGz><5hduK%&Qa+c=C%Aqj@^-%6`!u&U8!Ssw>cS`^Ux4a@ID@0zi~kZ(fjCB& z?D9I{K!zq03G5oHSW5hu6bc{VWXgI?E%FH?}j~$7K6Cz}2=jHLxBn1m+8#L!xCZr}~f_*4ExcczO^? z53Y%(wb(-}ExIoa^FwtM(K52hy z!WLq;1QRNIIKrc6at-RcaN5)T+}peziZ>H$1Os1Xgcwegcc0N#e`5!Pogcq|BspHK zVOIoY2g|jXt+|xIID5D~X^Rb6J5r!@q$AKd19NI<_kv^xR9i{o%3ja2u`R0UMqnrm*qg4gf zAH9%^NrHLsDW^HvUlYW_NE1+_Cv-8nu_*<_ExcKZh>(D-H%5~CQF`9)Rdo>jIRSJ6 zS0+3ai#tJq&?twXm@6E$6mUO1Dy@94nf*?1wv_I{h8hA_ZCni*r%=g7wlvJA530uBB1w~Q`Eywzu@ge$f27eYoUV79+pwn zXLXU`-pA0&&EY%Ho8ceFeOZS+>Q4xHJch(zbpXuPn+2mJIU20%L?K@E`=womuyBf{-KXpR_i>Nl#FSwX z2#x9`q2S53)IYXmThSme;yzfty1H5l98~Ebr2)T#Em#Q~l5bd!9$5qhR3uQUf3e#9 zl#`2mtn{%6aFK$&)pL)Smvp^;NPC=mUOC0SSy)Ao(&(nC^ywFHMtfw~uCtIDOt^_h z)iz5f?Slvd3Xzq+SkM0Iq$gG)mL}}X7pfmG%`{z%&z6Z@GR{4F2tI<`-4C=QqpbbA z*d~(7Iu`vD%ziUKpey1;mChzHQzoVGEu=Vsh$_cakrLMYKDNyDb;g!EC%$kD6cwA0 z0mVi3doWdT))+7C2D7Pp{2x@yAy^=<<%>az=M)mKZ6|6UipQ_GfcL6hxkTycRTflE zla!NNaHpqCub+!fjk}{!m6w=U9CP>`dtik`!ihWZ&Yz7XGwYaq`MZ~Uw2TAZZ45YHn8N1Bcy_`^*|S)=;ZIY z{Tr0KuCGKaha04}jZrA&xdQ&VMr6c4Bv#s*)tv-hUS!U{f6w?~pM(BTH5c#9QTa?pSUP+$6E9h%>~_Z7>95Q@jBEnAkyOK;QPU z1R)iil$cux?ELuV5=g)4a&MKGR0)F|fU51(!rD^zC%?aMcswpD^OwJJ()lD-xe&V2 zWKwZ^Y+pVy&M?KATQOlL?RNDwza0+n;*h^mcSpx)he_ zm=k|kSPPT1p&uV2QM}i_ENR3hqKPAQ!QFWDx{>s)TWX4UuVryTy4a1>cOgS*HQZn# zK8HqkM~_DbM+2EQV!xPeu+6$T?-T79r4;r+#@#8P za^r0md~c0WN^2=0yI<;)YaiWYNyIRAFB8qAP`R)9ourwno0PJ(&dogRDP3&x7b-73 z=E)kB^2-7;T5$0T@^gVszL}9atZFcvIUU1?7Bw-wX40wzEd>`m%KACRx-K>Jqg7J* zDY?YuuefZ{QT*Cb8ZP)SotHHau4^|=lVM?VBcZt9Z8)dAxdiI*E4Ea z=d>y7`lzfT%QbtM%btB->(F?q#ijZyJNRjM@LvT9DgYRa(g%4oePjvb?^Alr?PKbP z>04iC35Q%RaI?&TYnxU^=~O?gpNiPSy*S?et*X>9XD!YMRVBL)yM5e}W1Wn?G0WtY zP3$u{3h-JwGg1LTC)eU#C#*xP)M6H_p18;W$dTR_*CiDpN`xZW102$0dnb(ZgsfI3 zay-P3MnwTauw{vDpJgJ0gWcA47Ic*y3>vLgZ}Qp}_;pyvln!I|cS>e*5+u!=ecvy_ zO32%9+>s<)?nOfEl0{PdfF7lSHyf!WxnaTaK>Tq-gJZO)nTgwxP=KzAhntXPk zy&u$z;lp8)(6LlvnLV)6E+RAH--SitRS?1Lt?Y+t$SuCS^BV!-f~TXP#UxI>|R^+-zZqmm>AO zz160{#M#Fk!4!}7E@`&B@Kv~(YgVeagLKCckCuqg;mOAE(*-T!E)eiP z(SqddMIMk$vi7l@KU)Iz)BS4na!d4nn;m-cF1qtssXAQb|m+`4cu_JW}-^igD6ZoxY!bQYANhmUBnI z6!-oI@#yspd8O~%_+~0cW|;`D@#)&jsr`oJpnDf|D%ffv2vnU+1y0KRFT3ou``dZr zTfEx7tM|jb=CY(=y`~~e%Y|T7 zKT&Zv$9(lCjeT}8Q{Jqxb-DYH3E>?dE-G0Gc)w1KpZ$Gk#_7=axB{}kU56IXoTF8$ zvDH&hM`}%Hzp6P~sa}wPcsirCCf<=LDh!3J#8>H44If{ZG#(s#`p~B?s1g^9D#Dp}_)l zR`n=k1%4bhPbG}5=CDny|Kwxhm_2Eq*$+tCPyWe4slI?&ScRTcDi)1PC_3J_mJqcW zoCD9zH8a8IbGrn?WcO?CZxY_k$HC-}ki5=6p$&eb+`#01Sg- zTxkWq-8jDF_5y=N%V+0;-j`|(Nq@LXQI=i4#&9o#sg%=$ouwi)uQ!6u&Mp|6PzKnw zk?zvyl;<5ekSV_jcu<6CF2G$3py6%hsNPTh4Fqi`XiwAjyxVGN5yafOybHxiVQDTi z=M31S-5T8Wul7QR@1P;Bk#wAixXu1>T=6d7Wr9aGflX}MJSAp~3W+ls()Jd|h>D^r~Ei-nOP_YP{o0Lq_2tth)J>k2~Yw9EMB)^Z}3-xLj z+=PLxqpWW9l!x;g$ShqVasImdo+LwB&20Po=Z4Wko8BeiV5p*$383)S%^fkYAU&aM zB^uXUZKN8h1uMD0%1gv1|EMi0dDu}j`WBv;|HN2L4Pla$KA0q(5-hPy?cQQuJnpCxf1?!kB8g@iCEB$VM!0cY5n9adhNsEeyPovn)9@23xO?8`B zIXNUZ_*endG2KL=!;vC>nYdah{*{R!#RN+^4VFtrMkUo#;icK|iqMiyoguKh7sV8| z`&4JSjCV{3h{;~UiA~9%Vka4R{) z>7bIV9nYO!*TV)gG9Z8cKL6N04<`=S7Q zfVn*DO@*EnqTAkRrQ2<$%ba|bQkySB5DW=dE%u_WY7#PJ!)W03aq=IX1eBf_{SK24 zKlHO&@;K*ZXI9AtkO&;`O_MeMMJ0+Anc*uKKBn&e3y zy7XC+Tew~bdBdC8b4)erHa#|am{I5@zX^D-RYsO?iDOK>rq%}u6=lx)Eg%|Aerk6( z#DjPG^jiwIIIhnxI?TRbRy9BH$)taBZ|DijJyU$Xz`)xDl*MvyQcU472E%j`(1#t)Y^l?(FRSExzj?`0@(Y3l?)d6Uq$ z^*8_N?hnra*t?{|x9UFexJ*31l`iv*Q5K&R=A_gK#yxpS6hyVV>ANkx4ahqAnB%Kn z*sN9<&dsQsUp^@ZyuC{h#a%STQgl>u*V&l!#&a2a#@OXRz0*IueBxuVvv7**JWU8i z)&RbifvOT_&uJO3 z{_`_9(l<0UR<9QLk!&*xM^r+};n5;bWS*qqnPRw{$R=`p=`kI93pEctUe;8OD}VMg z8^~dUe_VK^(_wnPe||$q!%im&?=SrGPso?(Xwquc9eMr3vbwr#!?{l0l!3JxO?KPv z6@mY3@rmU)_gp9iFvOE)VPtGVW{RB1#2-9=05BS1d_gQID1N5&fPXgpBaZ+uH28|G zIQUOs+b1;VV}ngIgDnHrkv*9$V&&scy<1XA{z}k$l-8V)x3|}5@9*Q;5L7T?gt>jCp zn@4A-NhUb9R0 zbnA+7#iQ2+-R{Yqd>wGod`~%$JP!qAAIXbFILkPNjEgfJ!7I!8d;(I!bZ;|v7e*~m zx2sUTr%fcdwvFt7f0Qi-_}>OO_M&s;ll3EG81&;{35%WbxLfXTOQDsdt;37WG@4lF zf>}X`%omt!#?UUEAF^4Hp*2tEC>&_G7ra24>E6< zk3LFbha7_}`4g9yS@eb*G?mrd$MhRMw*=h!o_xX^9%+KGG;aIzm7Gv+>`}&Z@kSNi z55i(=Gl>n2{Jl?wmD^Voc~5q$0y|LCj=kpd@sTw9RAdcPoRYz?7}5b!TKB63!#=tq z`67w@K9T_zY3h9A6;y&Lq}78W%jYQ5@B^cW+foXqu$As1tmer?*C^I|5qw{bca%6S zqw_Trvhh%rX@r%8#=jDknG-V2OANwvg#)DnkdW}GB$!rmxW4!~c~b%mTkKkzk)I)K zdw=0l*u1O8_>O{<^sWaT{PDY0lnI_Ts8p%$-U}cKzS5{K++?U$xs#4TgTJ{-O@I=U z7q<6-aCxYw+NDr!E>)BtPq7ngg0z@0RYY2>+1fy=zLzKJk^uYM5)5c<^9q1&tVupuPT67_`= z?Uxey8C~b@Sb5}gcb~FCMft_xglNtTi%C8;PgEIbvUq;(u!^Jzkyg93PPYyE&79pKFaC2ODRoIGmy~*rUJ!p! zD(7NQ<5@ODIb;}xep<2HD5_c3G*fK4TB@I8eOL9`@traXuq>y><@Dd8E>xphR4O$dp&wu-tYjdb&^nw+-4&hRXgnoT-5?@k!~`gaLfh)iUU zF_Z94Ux#467bg^wOi*`VRIr_zLX{l2uPO;_0oKhOZ)!aEz7g+G(*W_YVre$&+I&)~W!dq4;i>zQi)&RCe%0<(=lyE#h!adp>g2?bi}1jpArZPT7f<@7rNc6{)8SC?zv$9fwR=L%TmrhW>H zeY`1A>JG=U$%%v&SZ~skYIeoWBy3psOy#E&CY9ZIdhU)<$BGoTdPdtoOqATLt~P(By3v9p{_s10nqLIe_n!_G zxXb;3%XssKOs@?146%2J_w(Dd{q3%(#>4&vFq=W~dGd{N{x9%g^b%rI`|*Ak|J=IT}35u)5| z2v}Ej4z4k*R7#lpyKcjET5Z&@I{EDGV+(Wo2&Gu~>AU;%LdbdRGhMb+1_$A^zPhfu ze4me%SB@f2`xIG+DSor!nRVNHhlzc+U+DFE4aaY_+fDKt?nmouyHk;-`J|#|agsd- zj@wA+cmar@02Q)Mvr-TCxYbvefbSC6Ci@>0D(pOJklA_gMY{tIiH;?`++?*uGoF1i z576w{m$$-ZXpK?B!a>X?L3V39gSXT7Bl0!SQP4k0YBULv6E86rmQ!?-Ca$2P@o9*Pu^DE^PUEhExPT_Cr ztJ!bd^o6*{p&c1LZS4e%g|Vs>Fw*Y@tOyDc%ftf_qj?A!evn_ye#gNNPQDf{L^u%s z%3|@)?4_vsHR`c(f)(j-Y5H;~Z4b3@7>mFn!Sy^Cd-O16=iul#?0qBna^D%0#yr`5 zi6AbVYO1a90&41gh25&NwZfEAeH%KJkZ?xM_2gwcj3+J>4yDv}b9w7kCZfZc0YX-m z!t8%Ln$RmO}Pn#1-W``bYsuG>`y|J~7ah;%Nsa{`8p zTM=wP(7ENJy~fwl0%_FY;gH_Hc1=GE^|HjVW74E;E_T;eZ9!ZcDlde67G%ny?qSuo zw60NXz4VWCLnN?+kdj^(|FIC1^8y0VO8&%G92Q1wXilBqcw=o_&1Uc``<`jdxm+>- z%LNb<>@>;NzSTnyL!yPz%f0J09S2A8t0Ud_rds{d68*Q^Kl;Y|W3_yaV<|cdtm!?r z7+1U3-5MRCkelcz%lTZ#rZ63M4kxv#&+t)|E`Q$w;GZP-?UsRm4)YQ*p$pd+U+6#r zD5b0V$Oa{=mT{fnn{UvUw=hts68ocmh2<&z7|o#qmECCxkHaUp>@dYI70y*+$@h_K z>En*ird7HOA?zn3SY|0M{7NrQ5nse4vPDDM*FBZCSRQoxeM&5wd6fof4dT8L;(gb3 z;$qC}oU1AdHFyu%$^nY`rnq-Sfi&X91w1Z%ul>52OS=ih_CchGs@7vhp*kAWk@g3L zs1i}O?(uf$jEIPgs147``nQAXjuXX%P~314)Kb1a_*`bzI!Fk)NH-VAIu@hn!j2Ge z$kL;sL|OR&RYk9+s10GMPze)>!4DI|JbTT|(KM$4sk%Kz#-wA07<9RfG6J$&S0XG) z!*LN{?SI@&Vz!PnLf{%C@2vHuQV9P6jxW|(t^d1x3V^&tuS-Re3ZZ(}ED1(zM8@4m zPOdELZf8GlU%2~L%@DOas8LL8x*f(6srg0iMhf!{e@4%Bde@CMrI4!1=SCYA2e#=4z;AAST_G{JEC{_k<98da3#59f|d_H+VS zC0I%UKNiM>0uCg=%3|g0L}e=`UY*wq%LevZAb0gYYS3;K90ge^*JAwyaaj$S?DSmG zc6QSd))licD^#R{`QI-MF?Njd?ikO2bOGRr5JrSH$65{SG z6L>Q<$zPIAuhBP1nk9fN`Dx9mS!@|74jWX*XcKfLP_8Z|_WhL$nuSDHM*&RGOGhr%=P|@g95m*a@QU z;8D1Wk?E*yU z-J;glcy8fDlHcov9EU6@n>aU^BWUX6xia}yNI+{bL=1mpw8Mxcrug1``UB45*>OJT z9W`)5Yl!F3IbYBL#$gX6=w3ky_ZNySw|4I{i`oQIgEWE3Nj{N^HhXy5iVNUrB$b!b z9S#Yg4xy_;yS|a$U1}YM%~J)AfAJPv6Isb(?1Y&cvD9x%8H3gu?At`M!IcC`W$n%* z5Wg||$lTy>KRkA9SBWR(G7EU>pNo8a9Lu)-%QS<4FhLfW*}rU0f9A5SPkNL-*_pcD z8y-tNDHr`;eW-tPpw_Mb-yA6Vx!{d{z0XeYUQ?*UVE9eVA;kx)A(F}wl04Hf=#h!x zdd&TR)urep@q}s#Pu<8561_bqN3%t!o12nvJle)#B`%4W2>;24aOEy(%dFijvw|8Y zlub(d76M?!oyp&T0m(ynEvSc60!d-b+p}ekeBL%Cck06|efgQ77O3piYdDKx`~5 zonS0+z+~jE%PR{O6Fm4ok%cw!KlxEcoMB;b8M;{;a_hl%%pS4^uL3*e4&dPaVW7R5 zIx0=i?h^{~j(!6)WzyMY?dPaf!J-*y?qDh5i zPllr14Z~Z-S45)@#E()9hYZ!aw|jbb)5PuP?PYL+*+`SQeAN5WG9I z0Q7p(0QgYp_RXLq83|aEHCzpxH{NvGN>z(37WjyP1T~)L&k?8s0gd8|*)H6A&$BaL z4QI4HWH>RBA)IqeK5jSibNyXge&Qs>pH2-3QwkUJyi8x6#3ltW1&lEaoj%QQTOSW^ zZ*en%Rp}eNS<@SR?|-~f#JtW##TUU;cskQPL&GgIIsT}ZC2)}^m^hlZx${n2)}l4A z>GD?YG(Ha1Uyc)qXv(Oj#qf6^) zf~D;0IaTs#I#U4la51r4Z#n4{RY07@C*=0Zq1nh6)pjm$D|PyV^b>yL$w?gDW7&6) z!!w!L-Jn~o;jJZrPXAj$qT0ZU>&7;&e(qdmhSiE%WD$rKKU+}0K$%f*M@D!ne^Dqy zTJd97QkiyV=KZPZtr-bV3ndtXdvKI^J;~GL!q;#Z{WL!mpM3q~0$^=5D7Q`;aEn?7 zd*Y9(q3^z!!;VTrnAl2QZX7R72ivR%P0Y(~ZHys}!cEPr%uvyQ>}yR_4a^T+yn)!# zQ(eh*082Gm1_C6g!U!jND!yyUxRPHicGqUmt@0IC#&!gm2v`mJr)aHT9=!Y-UDg!Z z{2wQ3UULv2UlUMGMdGcG0L7%B?0Dk3drPaE-+FZk<)Zv^9Ap2Tb@0j>U-RPI=#}5nW{~`Y9Psg-QI&vHa zz<(9jasDZ;=d%J0yH>||8-ne3Z;qHbBl6$}n7z{;c_MJc^46f2Psg$kuVB}1mcDHq zr}lO+xUjt60y$gf{+Z6qswMqLft{E~1za6P`%%auG>X~+_E&yTj<^2Ljj`e~cgnOt zQ2O+V5#{EPrN0_7a5|?Q0Q2b|HV7Zy{2_aLeTFYK6#r2ZCol)492wr!`c1+H8^SH_AlBBR%prN4GwH@7n;J(M4JHEwL6Opk$od40WCZO=I$wvLB z^4rU%rTNv6t5xa;q@`E`@v-Y>Vvi>8+@-3IGnDXPlm>*Qkp*S#(qthlcy z0N!M&%8-JeGK=KhmZjyTLgf%tW3WUutq-X-9-N>iDJQcGUMlJo zX~ih#@-~Wnxtq#~20m&+D$%{;4B0{sgh`Bt{2L|x^-!iHA6YZ8z6oMX^3s2nv7N4m ztNTB{p7mqvA#K)1+7A(`No0_C7nBqtEyBAxFvLc*ahdFIL`p@ZbC!y#(scKcDR&x;opnBFbys@J~{Ncn8Rc%4n5}%x55d90$V`o;y*yiW~vA=2b6Uqsqth|c@ zGz4j7KWN-9n4cd$Qa2hb1X1;AzOZS#ud}U}FnjaoFI@x#dd3e%an*tQJl;%`IIT}D z+KF53a`?>Im2vsEFilGMYc}PnZ|K_y61msopZj6*P;sVUF!{^D&13G{E?Nt4{oeWC zrG>s_e6qw;3Y>`6KoO{8)z=tJKicjb)~`}VjTF3lU*2AKIx^;=Y@T~}q-080(#!-m zBr0mSAxK-1k6S<~pA0s%0;Bo=F|zIq*W6sU?b<7ah(&E`q82XWw_rutlb*P7b~$_5p{jt z3NG<3Y@1MHGHbI2cGQ2i9xtw!`DokQAe8>r-13iWjwc?H9!&qXUEy}91C?L5fBvT6 zA-_4g^bK=V+aL&Qkt&m4ze&>9jY&XYb;<2@s%wkz_kUJ79g7_KKP_C4Sfom{jFKgB zSwkj+emPXPh3@KIBP>2(4_=h`ELkc#`5szkTKFVVwEW|xe-P7q0f@wxYl))Tc1kh= zo_}i27sk>n>@E4QAMPvehZvkQzLq$J{_}U?%TVZwvB2I|KiR8&Sj?^w?qG^m1F0d>%V1$Tj7j08EpUmO7(y(T&}T!%MQb31|C>TzUYVg zi8pVT|Ki!d+IzYm54g*uH^)bKpargN25RgMID-58(tiF<2$-mlw=J|0;lyqyuUhwA zzVQ84ap~SLdcWqe7$>vt#EuDZa+Yp~iQl?D;cwhAC?HFk@va}aHSwCY^(KE&a;+fNQh*k zhtVZJjV;{aa%E*C_;#NL(BeB{TAvJ{{BlLsYlmIWN*_3=*%`LW(wC}WS(&kCdL&vd@-Mx0@mZT{U;(wYEE zi?*=EK%hab25fMdTwH}bqw%YKUV2CS#CX=VT_Ikq(D@QrPl$Z$R~fX?zODYh)7pnZ z;L(7=CV7|HCgl=%3m`iV1ivn(S<>FqwF{ZoOZVun@36i@i2fNx|U{5r^kHq#W3#i5) z=uPxuW5k;tjx4%twGL)jWxdmSYZaj3{_6cI$+l?ern=&dl!1Z%&DBJjW@bqV2BE>w zhPh5rXSs?%$9u^L83EjrXem>g9Hw$S5&@P?{X5}lV3*aWN>pjI>Me$WY(i5qOuuxe zM_x5YP4k!4Z%*jcl?2FQK}r*T7jds~Tw;kD^BB3V4fVzDy1Ng(+M=C>xL(iOhM`cb zntt0YIH(VSbwJKsiPz5jO!N!07`?}H&|(AbO1Vpg(6P#)8u|4r*S z0HgGY|0KlUw81%%OP(<)x_FA*`CU5*H=)LB_E_o>%i@?yc!}V;8%NO-w|t+#AvISc zqYUbs8;Oor_yXa7>pUbEUgI5K+da}HhSNb~i-@G)6XVm#XEwP48o7H%! zQw~BKL?|S5l2yOMXq7p6*_OJAi14PFsDvqmNR-jn&nlD6T&QlrTiu6RJvvW>rP<=c4Zm{%i? zEWH;Uko@(#IX6<#;kC?RGlI88;$rfuVYE~Ri<(^)_Q%4g*sy6-aFb6=QY9QFBH6*z z_u(RRnr{J=j?UPeuhB=UOJC2z`xY5DVQ7e&l}dihW=!@|*{?=wVV9si=wmwcsJq!qhfXu^x9Ac#qm{JUOExW^<>OYo#V2 z2@{bJuXP-ohgT>a7*nKq6Ry&8^p=^^zfj>z+4PB`S4T-P*q>(LTkADdq0N9kx4@2aJ6*r3jfv zHZiAcK3&Vb^wj5upb-p-5#8~ zxSQ~;yWeycs40#Rjc2`Tev!$^PZ5tki?8hobhmG&|8B}_wVb){T2%i@p1nwf47v;5 z@!H?r=K$F2kk2zuiG_9?q)Je)64iY6%igPR<%~bQNjk8WL=o*5>0JO=*&V!C;LZbt>+j zo2l7FYwkJ`3ln)s72cr|^X(q$L2S&=l_cxd(VTC#!t(^tQ3P!ekS}yKR%eSVu)ih)a z(pk6fyy$qe)M5+BxlH6(g^&_y3{i4x+q@Tgu5!%gTUIiU zKz`&-ETuOISOhnHH)&rH*Kt}4*4I@fp)}KK) zbdIgt%{YNww)-ADo)1s4RJ0aDjlsY@K+E# zVjx?6I)`^C68~@dI6hZhyt>B$G8&$kj+C=Sqj!k24RU*O-XO&6@rtF*&%tlS8kB|? zTL?;NPJpAQEY30zZ-&t%>p}mCZfsYDFDD>T1!|H(tgrWBeDylM!gyQ^$*fvu{hT_N zwacQn;Mvn=e!PI~loF+i^-O4S#pP$OX=66EH=q}3l&i=eaHvrcwV*H}I8l|*ggnw{ zZTLu)xHITOF#7ud79yxGTBn_SoIqcu`S*81ph%g{N*=DcX^z*hlj%9b-dDp|%0VH2 z+}5qzzRPO1vbX*SvuPdATW1mVYi9vC;*$L z{=Ppd^fl@m;)S#B$-51|lqO?WQoGl1cA(0{r-dLAp(&V=Wb&5d&2xR`AGLQ1%qN&!95+fBNIp|M=sA#_Ii@ zx||sROrYu@&zR;!@kFQ_??z#Fyb~L^XV%+B0M&;>E}LARosV=~3==r??FTbv$Rgi} zar=p(_5-uOo@OYtAc%Bt=2|*isG((t$;}h&UwUdNOO}>(h0(^99GF4zbnXD#__wI$ z%ZDUQ6};hnSAoH<1H&@kOVG>=b(P|G^bqHF(!*`}G{g^BO4hi*o`BQ%LJCL}wBhza zrrn&gIC3eIsDhV%;&JzH*N#u8P3bm2DPLURZXZ0l(xucge$d{h%`pBXG6}=tppRm9 zg2M~R?Sc=40KW`x(#mptgvp0pS(s_m5xmqR{BJ`}dyjwp+PmKR)=4^xifC#+?` zm_a*k-IdGVt39p;nqTUGQP~%k5r$oU=Q^NeDUSxy= zyX>bQTc(JE!ww@69{p7D;-RA0-a%~IE9c__Zdb;6sWIG8j$#4!m!Ce6Y;VQ8J5-ud z7s&P3Y)gwNa(eT-8j1>goQtHlANo;1fCfWn+~8L^aU8!p&-H$H!lyh~)qvd-xBPN_ zjda(f8fAOtPq(f!f-+Dabu;yhx>oxd0fEAMwiJ6o+$ z1|SH54*hr~JMJ5cU0)yS$?^~buKYILn6p{5iRt7Cq5_M5csQExadC{sq^&apf?R8* zGp{LVE^Rkz5*|gjsVyVN-iZ1ye{GR`4Ge);x=1Ndo1g*+){s+XITyD!``_GZK_Wm? ziT8A;5NAq3&HN2Cflz7Q8i11g*W$KCT)T+qpJAw;t&egm$`z@bml>YFPQ&Q>EZ~#& zR_;j)ZE_*Zr5MRZv!8+dkNZAhn%RALSag!thDNF|BlMqx8}32sicW@a>#MdNm#~sQ z0;Xbr9<_g2AH?mU-=C2o1QkI=e}W3CC@4hd20MwskmYb3)74GQz!D+PT&#O{3fO>w z((frj%)Rr;d)ZxHoTV(MIJz9Br=WdogC5Kbp=GJ&s)0a8(DYic?^rtb9+iRQSa;c? zTJuSb0IKu4EbZzc~S zB_n^|i12|t2R1ksRwj`+`|b0?9}w&ms#?o_vkAzY*x+}nW#SsXzW!Wb)bK60a%N6VP4Ln|dqQ=>+DIA{O!b>!*}@hZd)byC5TvA6 zV7nSD$uGVmU3X2!`R`U2yFj7V5if@ObD^4(axz%b#VgI7=99C_frm= zK1u<6NXla#H{4rEoNwMk4i?I<$LU^2rx#stgm0q$kj{zj&AfzJki%p5XS;d1#tDtj z=Otz~>n{|CPBfyAXMnbLqsL#G~r@%DEi{51=YfW(}n z@ibK0ZP)) zn|AE4o5Yz-r#d6XZ-iMj+UEu>%VtF?$46Vrf%k!L12p~oNzf4iF%*X#!zDl+^KvzX zoN6E-B@plG+$Rh#-Zdg%CZc=)?I?S8YM>TO+qY?B&yIXJo#kzR-IVsyT0BB1TgY0J zB5S5>#R@NvC4X>1U21cPDPm-LP*55uB-*YFLeuyeUCOYbe4|;IXfG2~g5Xr0D^*;O zP%F@@{~Dckq4pyQb5YhH2}jVWUQM}pW_Ba*JITr8*4l0&*9{OCn$vaYv~0^*zFbN& zA_D%sr=)s6$ajNnY9_)zoudqr60SAQ3o+%Xg9Al=~&THyzQq8LI zO$#j3ZDm?@E-_}-NL_h5siD%Mb$-P>Q_CaGC|6N|p*}fV!@|-_;ycV>hQwwJ8}!BN z;s&M{D^nFaA}|DIApXk*FesOIN%f-%Ev+4s-fzZ+ml|8*2;;Mam{KgwS27k(LfzLW zJ=Mu}6SBzeeAs!}*MEq)^82Ll@jIqF!TG~U z<<`VzILdsW!8*R<1{As<6n$@rYfq?aBpAqSb(t++_^Qc9d1)k0*u8L;=#n}J{7I9& zActE!1fbl_1I}V0{f~58z+9TULi|x!i15g!GXV~gPvD{lt%zSU2xkC1_j?s2--CGn6CH4&p7**!u3s!VT1{ZC>`5|Z1^op}z7wuru3``}S#TUwPx$E+@M>%MVI z019Rj;6XjYb3nK>`P03v#hI0K{b$3;H=AEYTj=xHyB%477Q_DHG4ViR?(7(_YiY%V z?C}uSSc55$-Qi5=NcMa^6F1$@GEedG@%lIzC)zq7d~7r5=LWn(f-=U)&`{gR5ckQk z8^Jlbc;x8NS9}j!HZNLQTEe6Y3jd1!ub2Cc7c~0%`q~VbetiY4_<|w>LG6H0CQ^J% zj5~UaH-@~pVJjbe&7_dnR}^UcGA1JV3T4`w>gbrSph{HtRoqY}+IcC~IOD_$!tJ1& zF3oI&R8#Dm$Cs}17{p#fIF5K+O{lX{ZTi~hnD1}jMWsl?SZQ;xtscp;H79 zt|g{&fxz&La7a&Oy0(Mm7zf*}nGlkuWcN>Qr`;4TGyEfv#UaBbyZ7T8wSRsKFT)3L zV27|LV{>Y`9};x?oauG%J69iPD?0Y9_d{DDVv^g&?$f3F{j{Pp0Camj zt`rCMpZ&veTUYSC-ID``=|UgMHLJQQp2VL(m))w5&=jV`tlt@%Q9?;C``d>*!8mb~ z*>)5-rf0p2?G`_#6p=DAkcd~jezRQ%yjEi)v-BZR3;w>^%IZMJFu`b-WT&@D4RKwW z7fNnKOV=6`#{vB*)RS0zwAh5#cJ4H_;+F074*GOqaDZlId*}6>Bq#i?j7$`IK-ez4 zD)~gkj|_dTZJ>c(zwG#RJifZYpNC=?PkuR^w~RSwvSk@p1TFOtYe-&yv=)%kGuts| zKOgBT<_Nip@n!I0FJhH?g6tLq0Rc^2!!xt&@UIky>Umj!ePcGH4Xjfq zdb&GHsx?0_Zmed@+(Y8SWn>--i&V2HVP(Ig)Xi!y6uFg})?wUnzIZnMfg8{~t5urk z?`z_M*BE+ud4R*r%;Z7Lqed?%o{`GU!||eS)~h)P$5A+OI4>LbWP1OT`-HX51>SU> zpQV{*e1?=njNCej`+LL9S)fAP*3 zyCBNEfBYSci1K*-8IwFXKfWQ^8XrPkX{ibVuu$39Cy6p9KDop2hd(PA(b2IQ zb-d35H5{^;x+~PAMl^u*^9WF8WIf_lP-71a%KORyAF<)DPmElyl$4O;>#pHUtCA2C zz>4f_2m4`($8q7AU4;ofmRn~lRbc$vtcp>8QocW_IblQ`7SxpB{H2c1d&HHHlF8T% zR|6}8!|s3Yr`i)TCNewP!|aKUMoz5Yhb!^+{*tX4%osMl!`v04`ch;Sm7qix_SGDR?tyMZ_ul?EI=h?2veuUn8lka~j2Vc1{;IcwH<*`Y{JVI=th6zMlwe62TMH@9JMk~i>;CYUNRR zI%BP&3tlZGo=2{e?wiOk%*b`x3PHeAv-N>Efj1zZ?{{#b8-3GL9q}UM@0l$>T8k6C zVF33!o_J={S$*YIM#v80i)wyUOc_&#?tzNl?Ci zW?&#bjD2DBPX-j4qd1aT0FU9_SNZupA&=+etUeH{eAY-N(Nl9lTmh= z5xT^Bv^NV+N_0r{Aj>x|d~kTkzoWvmcifU#r~U_=5RuM_(QP8#CS0yw zk#Ib4cZC42RRpS?=Xi@BjE8DxEe}!)oC|2(N#u5F(Cyg}4@wy&CRZ{DjQmGNi$qZs5R{gA zQ@_s<-ijYK3E9TaKbYi;AYe^`5H`~w)O)uf6HI=XpnDoILZE(LEA5^Gf=nPmf6RnH z;$3)QRYUVcj;PGRK;^47BO5e3Y7Mk0%HTxLT$8U`JaL>&6xrtyU?f{T?l6Gx`zu6y z)q#p|Pe$W_2I{)F+{65D(7JzHKnf%2Z|_)TVFFW=65L=rCM8e$p_5iu5k!gWE|WU1 zX-!&Q!XysI#W~YsC)kKJo~`1slhWoXC%RopiU^U{%%6aBg@TRN0uE5`_cQPVa$KX+3) zd8MI?=yrMH>+2>ryc>SP zX13AAQ7fXch}QzC9b4U7BM2BOQH8EhwwcRM05ADLWz7veuQGUQ*@&ZZA-XUWC=MD8 zB$OZ<`V&P?ToFAuWq_wZXD*grO-fWN)60>C_Z%44o+pZiMpX-F^qg^6^XxnLsQ<%cY;?=i<@$co_k z))u&B9~A`!OHV&@@gqZE_h(HNk!;mwfeuPx<@X6BtK+q>QsrHde`nmQ5 zm<`Znq_Z}Y`pyqbhDY5F&+pZBKxp0Bvpp|iE6wLfC0&GJyahOi9i6`-QoPm6&UeiV zf#y{lZbe~=G6ayKAi^t-?&Jz+P=DQO0c+pR$65SAyXpjhR?`S|xDYcx zB<2;LRYjUmAm~;*L0h)XA+&+^hN@O@Y9tQpc1?ROoe<0enYLkbmu&TAz0{RnG>^rp&>@s(5ohelWJ za-&d}(Ivu9J@*wq#`7CbAvREu6Uj@qV z!)IQDeCcG5`yVkmqH=b&cPk9~p7*P`RgV!%fyR2PcJ~I<6r07OcX~LHceGPO2@7YU zDE;1UMJ{}IM$0R@+OcuV-dSZ9!7gLt&IH$$ljpTFXbemmF22Yv2cjyoKG{8zqdaoe zNqFIcY$5HanIcagId0)A_ZRA@u1uF8aM?dzcqTx7^d&k{aLE1z-faR1~ z?ziEXS(G$Ln7KYz@ycb(t0d zoQl2c$HeS}x=d9zW8qd>|H>i>%-sK-!r+>uj64epn6#|*IXBEHme0@imBO9DzeH=$ zEp}*9raG#wQ@!$@lq*+Q93BkBl~LfepQFG=j`B1`8S$u^1B2y@Ym$baIk_&8x1pc~zKO>Sg7cNok6#;W!Z%vb?K)rN#9+fa(^!uU(w*iK zR)h27WW{o>szdB=mhLceO=^BeQz%cV^6#fd5CX=6ngU37CA*`sILoT%$D}1br-{kD z8ND$ER~+^C#rL0yw)lS$?UszTvJ5sKeQp=oJ?%Z$+Bm zJ|3oOqdv1KUCj*qyuK}aMf*{G^ zND7qK7gF#!+r}uxhL&HTk_!xc$aiwtMYIx|(tzVxV;u@`nH^%vXhdG}Z(fgjdx{IY zCBC=HHE5E~iBWOZ#%NK4h7A3uA#Y+r2uDY;`UA?Fw}sX_!oB2no^jV&2XC^y(AmWP zP3%IQ>YEhqqWHFcn&TMR)`zz-N@6vbuj`N5K+EWrz?mu$J37;$hzp*&k@pXOhJ4ou zC{ti#W2g5(di>G+zJr}^$oyu4jEnnLaQIIp>aa8=y4)vmBGb~+FzG`7S;ygjw~kQ* z3lcWQ^a%s!<8J+Uvce+)ERQuVOaNdV6w7|8;;S(Slg7d(B*Ll zw*1kI?3dm0W8VQ(>7&nk3Mi+VacuPc?K$=FZT;EEnYHnP8BK+gT!003>*GLwr12Ar z#gzr)T(0Rl!%SklD?o-aX2U!@Kn3#|XR^ zbFq(AC$~LbN-jM^=C0FU?oI8^TC~D#f&hhXt*{1Jgz=36f|$E!gd#-^K#<)FE0|5 zswTq%-kX&WAovfnt1mG*>gslpe!;PH!l1aA5V&&hC=s+ z37sEZ?=q$NpVZ+}UP1xc&R#D{>rUfORbQsYDQ880@wTHc` zi?z!6d!sHZe@MUddN>Dn-?n_}`g^D=R?-k|9_csK!SZGjOt5s?^>I{pfxh~qg&Pc+ z+Qks*oKIt^dpLqN>+F~;on`K8-(am?ll(!1rij` zL073JvzN8-@!x41_FL8X{5bc+;(yJduGTq1^PDa&uC~qf{P^C1SiP0iOQ6O!W012F za$c!4ze$_v>@j^z*8+p0AunD^o1)IiL~zZDz44J@LZ9={XDn8dal0uGmZu|cMk`AJ}_(5F1DE*6h0q4ca?>9JK=nVS!^$5gD7N2UiRICn^ zEMVtkwfp#j*=_6s52eN(!>c?weWxk2s_ypH{VLr<95u$7_&(~MaQDh)sv6FTUnSed z$Vc0FFv=*f?;mR5+%T_rbUb6ZS>oj88Q=9V#CDmn6#F2eQ~u}p1npi34q@RJrXT;Yei*ov?py9o#MK+YyI#ktw*(yAn3tL`D8mx)0flur@Xw` z)u7xIa1%TS(pKbrnZ6p?B+ac-vphdMlxl(#bu^8q625VrOV{hBa2u}h4f+>?3*UU{-=Mb8S0fUV#+J+8&utm&MMXqt{RBWJ=M z4a)nO;qa7p^Xx8ep0#S@fFkOX?snb;&8)ZhpJYIoQn!{RJNLKQ`n8mSH zk%gj>HnvBh;r5hQa*sv87MH~G?A4-7w`om=S)Dn$w${(bE;hP7wi}>s-A%OLhs(#z z$n+8~RMiF9wP6j*GFFZ~YsIcYme4uSMJPVsE?L5t{euXMyo>j%A1pp;9;2bEPzZ{K zCnd@_IU@hw*>ds7Ib zNA>-`HH4jRUgxe9*1^*;UEl4rM@!l6y>R0()=A1N;8gXH357(5kIUN{$_WKVk6qNq?2MWiY zU5E5rFw67JlijjHA~Y&{VHrqHiBqru|Aeg%j%$u9KaRlVbl`ko=Vh4SJfjfANB*p? zGvP}d*Z|KzK%v3GOhvM|zD~{Ib^byj%K?{eZ=pGA0)kSck&D8LidIKIFum|?zEk+^ zs+~G+9FL_fAZTdK_pmknW%b?8F&Vx4;@^J(9QnJ-*BEe3sH&4=bCXk47)p+Jo*0M> zPK=a$^7Pb^ARg&Xu4s04b?XMQyDh2E4?O&ek|XW8Nv|Ex0e}&9$<2XwX5@Q9OALQD zTU3_)UOt(a@-0fUTa)3T6y>GY;|p&nvk)LGm#}ki@i%16_W*GwRL{EfH(v6eM zDZ2}IB~f7}S^8_1y9vfw1}jEe<#S0FzxE9GP~{1CUjp2&j~r2XNBg$_>(R`v$?#u_&!Y%CflAUEt{ zdwMv4*S~r1=ee}3u<|Rp_j;Lm0R`ye%sUn>3iODnll`qD-X244?<53={;8JtH~LHP zFf>IU?MM%^XKi($&+)bx4WGp*hW`rR^u&QP4^2T|M2f<^KFT#C+Cy-)-HOJe+1>6$ z@2Af`PW8N%ifeQg7`~nUnHj*)DyGd-Yd+Oj zk9;tRtY{WF=d#@k65aON88t3GDG;)wm8O-VqNBv%VX}?Oc>qe1Taq6&))~pe!vj&a z4aebree8RgEHD-_rOj?SrwwMsBWol{i+tDiD!kXzZhyq6MeffXLP8=dajREfS9oZX zEN ze=w3WSBx?^;jn3?Sty7sodyiE23LcDW?4n-@Z}4dbUBQ#joD=3B}rZ?qTRn!+Ca`w zl_3Naa zd}z9JdSKp`Wk-4ieFtKSA#a?FkV$}{)XQcqs4`ONUY9F`+Z169k72<^C%jaX{GpV< zfWWgVAB4VM^~88WKpxdTCbi^B7=~)M0K^;<*zAygF~Cds_NJfqvJum*UN-t+)n(ka zh|L7L0RX@52)S|;)#9}R5pr1Bp-oQMe;j4}UmP_U$cY{efdl;g9^vZ9GNSTmpy0v#`YIB}S*w!Uo9|HP#DQ}OWB9hK4dqnsS;HX0~A z3crVxM+!{!lS+FH;`CNc>3i67GODvTz;h%fwwVC=-9`pd0rcPDYV1F7^{B%a)JBg- zjP)P4(oU5yE`!l0P;T&?)>G^cznkdpTLWYD zI6>QjLVWT^5&aKZ>Gu!*O5?f_fxB2Bv}1?$M}a9*1p$+kjO_{51{(~%YfY0A!Vj=D zf+(~)nl@J+{wuIwc6|~2Ih9R>gkz8P@@SfDOLpozj0jkUIZHb z4;IVVja4rT#E209zFxo^H2W{-YMJ9LD61YD*>cH@Lw@JUfY59|Zct<`L)L6yX*_B% zwDR87ZwtZKeiVWG9b=iJ&}J9_gr@N5a;xL<8}*=?6d7%?`TqJLuWJ0@y`hpb(JY!Q zeQ5JaBd)v;JiG!UsTI>8{ta6JTQv$Zr9Bn^4I5S z`EaTkSyO@46s6fMv*_f-4i;WVAe6u9`QJNF4mM(BSO|}H7@UI-nP2G@XozO3&n*8Y zOs+5H62K_dUJbLikrl()65vQz0fB%laWFW$H5ZHLn;woiAadUkh#!QcyTArwvN>Ph z7M2DPLRycrk|KIoDbbz+(FBP*#c(s3 z9x3o*{UR$}s_Qx1adoU`u(w}tm~Kp*q@><_PR7TV`;fN)BqzpT(Vfb$Fvf=AH;L!u zZpI<3C0Gl(khi>Z=ZaMFDC4q3F}FxX{An#KM8xm^9HDQKQr@eg9cg7W#mAJ#9(^Uh zZ-luR1MCyJ*AJs+A?4>=)jS|V28L_2dX9tnKCMI8Mz4;$2>K0kPOK{(u18wIyuDOS z;ps?=l%9U=EBM*&Mo`;em$?`wa$^!Ys%E;`<9b+*x%&$Ek#pKc?*3i6dp4+4UbGtE zax{B%`sZdWsFY>9n)8Senb@N(x5A6KiFJ>Egqg5)tW+~=p>aze#IuzjnYP9Q)@bpn z#6JRUBHQ~kfWsjmzt?gRs1Nz%@p^*!Qen(F&L!x481ZPRc2;*KtO2aZo0gD$YKf8e z_ts^b1Bz8e^p13C+=?mZvD=22M&FK>R68xArOX4zu?6+ZGW-vT++EywUck?~eaxs6 zMRZ_!7-L<|rDAVY=wnAHp^)2wBO}w9jPLQjZ*3J`{gIy8<^|2Uk^snN&0tW}Zr~=< z6$+{*1OoZeO>p9#J#6QKMhgmQXZD`n8NTs)O4wd_Bwgl4DbwEl)G0nC2|79zz9@6X zBD;3SA7Y`|U?J+$Ty+`Mb3m@h4B8$c;zxJ`c`hUj7(!ZD$W?dfd^OF6l$3CDH12&U z?@aS!!OymEYb!y~*9v>mPqLWo4)FDPc&44R?Hdap-MS%AphW|$W>4C`2)^(J3?TLO zV67otp?yv*h7Yw&Wx!A|Hq0)&Z{~W_pq_KkwtCW$-?O#KU=;Fgt-z)ILL|XLTs=E} z6u-5{!TzS)LiybcsEkje(*}t1w?^pG=JPNG4GI$HSw^l#KLMUsL8hR1KZH_7Am3sT zf=`}Z8y&$ebU@Dnv>Z-%Xw26eFlJ!bPU=*{Tz~ma*LE{-N%b4_=KUE{=fl~tz#UA5 zcRP;Y6KriQ;^DsfE%fhfJ|G)h&cQR?5q(W@cJJ0#1#c}8!26*eD2Rt0$y0vU-W_Lt z4?x8`*E06fDxo&74G-OsumDP_94tX2Pa`?znY#}$s8B&)oxd`bK0Ru(2ZcL#XyJx$ z?P3Ygm)(O+S^?kJ&ii-EL=6h36|Qm%+6y}K6Pa4DS#;$sjL5ijSDa&a`4u&)LdBd) zROh*xRBMXMVhb|gCYbSQ`bR_RT>=mg6Tv%N&BM=dFegH67)<9^16+af&wBOP@7z$Q zbm!}EU`xC^2ZDp<-{_E2&r6xLm>;734|K=3EO8K+Nmha&+tU{?xg^_Z9w({x91IAi zn?>y`tse<)#YV0$41+^`*3R`LsAHz^jsGG*@gumfaz>MK7|c)L&_)He!!>%%Sl@K_1!U}({ZI5{>(V~z!=s~p z<{baI-Os4sg?fCZ(PFZ)ldu>f-(jU;M`QelJ!UJqgIcz4BGf?Uc78mevTiXGe$@Q; zivNlF#J;ij-)-pjlyN+fn!t2#WBOvn@011)2TrI#nbDV@*B$oAZOHIzY@)V`6Nx@B z_Xh+uI;0;UplYPLw{XDSnemIHqcr$lg?Yt+3E@vyW}zD>;6+Yayaehi@P=r2&8|yn zcnmpzGiB#iMi2c%nd!X0h@)!m;Uczn@16CM@N<#nd?@L$>gI2+!%yEwYEDf~g1!yn zAg0rWtJ=fy$Z81=ju@Lz4*pR6+uT2slmmP4qOnndnL&aXem?#04MO9)m& zQC=ab64v!4*&Xx*C;8jqm=i+rX22sdyt^{<>qo+~BQ0R&iA7Eoy=0bK)r^`lpnijmTZfDrAT&I=!ZG;j`AeF8Nt z0)f$Y(vIR92rv?SnGomnck00_F|XjtFXNOoHDAM7`3tCU?pw}rx>MtO_4wdMPq_Dr zmxdV$p*z2tvojoQ(L+gP3W}A|eA>@j<+Zp;2)S!}`*hm3_xoGT0@Tl@*+BoNJMP#K<0gYnEGtL=ct1Md=2q9eHy(c%uqXjtbcYIRu509uVGskBHUh& zH;|z&YyrSrF<+Yf*+Eifis{{XisuNUz>?F;iBD5d)Pdh<3I96_RI&Jj>vxCF3RP^4 z-DgNL)+P&{z$1@&72YnkDz*;>;D>>Y({xoYim73Mexenf7}7EJ;H8|Yil zN#u8IGXKxdKGJtx>vo&A;kfGenBA$$LhE1sJni|;`+aGA4}RvzyP&*P2#?+9bGGjk zWEj&UXxc|VYz@>H0W0P%wNJl<&X_ChnZKkasH6#8{noJ1-*xp1l|+p8L-VvYnb;|s z^15zo?K~+LYp_5B-6VcmEza_$ibmT4^u4s^K8-~GrP4Ghu^7~~ezt)X%FmRqBwX(# zr3W8uzvgF!(L1Y8Q>m2_cJrob&OWZLu=s#cC=kXX`tsOjJbHw7LjbLsrR)dAs39L) zgGXy2dOZOp)hr>XxSD_xv2a9*W-|e}G%fO$*ZNq06GM1^ua?wgbi(`WR3H&S@vvni zS|@0<$7}+gB!UzG%2;%>MmAkLneb>ClE3_!* z-#2I|eXkL=v$~h8INOr!n=KYVXuB;bg-dqGtdR?xsWc-1Aa~XO}_6HGbUX`MaA{GrPT-+;Nbpv8(;YnW8v&86E(E5S)SPs zTfkhy_z|U?<_jIY2vr9AWba4e#O&5k7EKyFnHHlz29X>|$5f>$teg`-8g6*!0%$JYr2c|sfR>+Hl zBP|6Dk~q(QAWh0Z%4%u6MkF}_7}2tV|)C)8(&=M>_Znr zo!)#;r+2Xw@BCo>idvnnI$L)1tB>dOwUn=_rcX89^y^x-B5FB^FB;6ug#6wQU`X5u z)9Gw0TZg|1AGB%Ox`}8v-`cH)XNFWICuF$5{`xPIt-MS-t&p&8JgNc?HTl=*-)4|} zd&9(<8Ky8270%8feRL=_tdUQXyni%YCR|qdJT@1YTO*G+w-BglK?iK(}@u zL3FLzBG8;z)4j=a%sAnUu+gcGwH@Z<1iHIlnDO>X$-t~QKK~|AvsW7D_1%*`MZp!I z!0@nt1*F20!KZR{2RY1qX%uR^|HkuT%e!tQSr6aQI!?$?#V7U zpg{F~@5$6Ehr{4#%AY9gblx2rVsz!;;#*cD$@wAy5TpUNw3OW!yP+PZ5@Nxj#&&Wi zyQ^sxO0-$CQavRYpQHJ6R6Nj zKE2c2?9EqfiG}SD1kKK?0plnbe&y3)#a#3S@CN5q23>B7%+) zD1xzzP1LI+!9iX-s6wlnv*S5E7NwUUJ0cidDS?jSofGI{@Cf_&SE2e!#RJ{2Fl5Lz zUvq)AF4=`-Ai!YFObuIo7SFlwI9q$H+1WKAY9U-kA)ymd;0^X!p}0FSnz}-VWmbXm zy@McaI77(e084AOX3J3#Y5>&0wAh})aNKGw6sg`To%>gYM&hV};u7rjzf8j8?2U8* zNs6#Yi=SAH+^|LA6POGllia@wk3@xbV?yyy2gHDd3PaRy?op3vw#UP7l|Ux@swTY^ z4};32w-o(H6c zG{pSf?ANVhP{DO7RmI{^@|fYNPf+6SFdy-zAknMM*Baox7yZ|2_}e*M{R2I?I**WU zBbvkHVab7#6=)l4EWiWAv$%bSWl<{4j;)kQ5D4Xip~wTZ-Na3_ohY%9dK|%Up4SJK zmvBD=kg+-iKvBYfuWQCm?Hh76V?tgbG3E59vR@EEft=%dN8gbUnGBK&?Dw1=*CGv2 z0SG8_2eY9(?VnE++D}qT`semq@`%vAA$KS)K}%W;UY? z+pPY|J5jlLcvo9#G39~yyuo#);}6fpjYNVLs{IinFEZC@9RKVs9ORgT3OI%hmkejNI^4J)*5p2O&IrnuiP|6evoH;Jt-;o9TKpWJvO0go-1ok)k-`vIrv>_EYs|hFH_q`;h~g zfvwap#JXKPL_;fp{t~mVL*k3aj12xlWxgqNn=9Q$a)$GA^cwy@*p#5KIzQ;`9q$*uQ)D=bI zs*MH|XdR}2u&U`s0*~P&10m2Wf(LYvbeH4pZa$jv6laMG9Jw3p)D<@Wpy^R*EQ7;@ zhih{a&i$#6&-Q%iJ`XnR_t2T7$cqtbVGf#Wax!D1Hc}aEq|(1KM+67jf7$0s1_dI4 zgMhAJiKnVT2cm{gca^)D9zkVx*c0`>)dSq)FXAhi_85QiewPv&Fy;)DJH^&wRLqA{ zRsPtEZx9+&3=Z9TgS~MJ{W}!#Cau3(W<=q8at^H^$e84A!?70ya&Flby%kRbb&1dH zD(P|T0qTc94atdVmSoNWX%-FR-iQ^{LR+EF_ezfQ$~{1z$3~-S5rxRH9ZXiX1E>c} z8fQ7?ECKaaLrGYM6AsQK-QdqMFuI7U4XBL!9Aun9Vfb2s24-NmhNX^`et;e@c=5TC)Fhvsqpjv9ab*RNd`sK}uT8{iR+Pw*>c8xSHR zO6Hy9zk6+Fu2aW=)3b#snB&!7E@guB>OBhzYzeKA+8v-=&0r6G8ncZ8?IPqBbwcpd zm`F1Gs{|axdvizW#AnbLq`fu(YhiVLQr{z`yF@IzZ$N1Pfhp@9r{+y-V6B7Rm#!X5 z2_5T~JtcTt5BQaORUkwS`@l8&SSu%Jfj?mL6-o&fiE;7=Dgf~8(Mn|bjx4!lxAWmk zJbO!FII zb$oB@_MH8Ucd?BX8*dD4zf0lqy1_OVDga+<(Y_7YA0b*jQt&DZO%uN z_W;>r^w26j`{NhOmv%7tKxTfH6~Xk?R@AX>s!+{**;*}xv?hOd_c*V=RhuH$0Xfm- zvlQ7puF{2I@4UyyZVgb9Fle3O2qV@)J`G3~+GxA2<=w3kdENvu5HNvFkHlof&9QPJ z8r~qTr0i74au*rNDTjz!ZjVv6$$u^b@3UTyh*%p$U<_Ko)0eihf1a^=e0YH#L@w;l z77?ts9FfLw07+GIU~1m~;slJeuh{q%6ruQRiT4%YPP4LX9pSb8ie{G0HS588TcgBWW05 zgpl%<%ZOK61{)7mW~)4b8ZE+*QM=$r?AC~hIx%oWTSb6{(3xRm{ys`%E6ev*krf^C z_RD93D%lGKS*+Jui2Je8oI!W(Qp`7iaY2d^55Dx+(g3Zn4`KEwNYE}pM4c>xMQ1dQ ztXz1iRuKXtk^@26TeF~MYW$-o5V)&r9Gvbg^g`d2Kv+gU_P-Ombp&@3qNVSd|B431 z|6Y*@hF~(9)H989ybYo)H)BAVAW2+~`IQ%RRq(}@<$RIM6mIH$pl`fnG8e2N{q8WD z&ZtCUv&UBNLWPJdnMsc^@i{ZtV7Su;Dk~f|{FpUEenjsL#vjm=jL8S{< z=2IXiA?yE)XvkL0PLD>){B|o|%fru`Zj-rpvMm3TyLCccLlj7e_f7Q?PW1=`>~U6+ z-?G;1E&|LPJ_Os{GNUFd1Fh*k2PDTjYJJ^EY{{>NUh)5Ye%e$H!LGDlLd~<(=uZ&7 zDQ*1Ce$j>`on1vV!Id2(xYO1h8wKi&(FJt>8uxXb)$Yi5PDK9cyY=qMDK-`fi19VC zMrL!I@nK}}z*OH)v~^Kh8-U=+=I^9s8@MJfjdyzTJz06%RBZfxj408Cq0UgO*s!iT zShTg?o|P_9XReB?dh6t`X9fE-|G=z&2^jS*n=#wpD@k`R)uj*i;O#3P@-E`Hk8%HC zr2A~e%ut03&NQ-!T6qv{1J1#{Wn1*a3h`r{OmhN_oO#=i_U%it8GfcKqcL2`!rrNH z7QH`#`m>i187>~4BuH&c5ElI0raNbN&b|2IPC${=^{WYWOQa>m|1IF(e(}3%Xu3eY zPmlLGnGj^bNS;?+k@J~oVqjpReSz?>5#bSr!b-?=P#`3MAb~LXsk2_NU8R(9!3hUj z9Y=5RK)@o7)CInmZ+w3sIXlcuXL7jBTuoi4A=wy=k2R*EjBbkD+>PF?AG0v~30ps} z#6QRxUbbc?0MR7h_27T)#F^Xu?D%MHO`O$0sZ6ag)o2j$W)cs*M+NG`Z)!SapEi{7 zvOb7>BgV@K0lN=acCTH`$;``<=V?5lEjh=b`IEo`cJYEG7hF?}1H8A-c3aK_8@X;d zbPDAOO6~v~%pc1su_vn^{L{-GNdYr{)0HODNJ^h}j_YE!MpoOD0Kqk7OVN<<*h(ch z3O8t)?H>@Ggrub~mwD%s$?yQUCboSQO zSOwV#{1Mtp;AcNUI>+xO)!O!7a|blt`E&F3gCtTerY)}Qx*R?NiW#D>5kto$%eRMQ zi$zd8e%RMuG2zBzlhYW$T}d7S>W-1rjAkeL(DTIhho#}#H697{6-8fq)qw^k%U!y_?b7GmjwlC=*ZrFTAb>U5xok=5iYj%lbEY_1e+jCo^3q;&<7 zkv)Uo=@3Rk8fuF7cBTU8zdD~BT+sLJDxu(8plf84P*Ie#S!S*j`4?)S zF?&EnEUjlz4k)VUXy^J^vA{sUjwrp<)}=m&ic78@+ut-$dC1qUmO3svbWO|UEQ9d4 zB|{Jn9^z`Ji2KlWTnIR@uQ*ynH+g% z48l4H_XwH6g?fr7c^l>ZnmuvCL$1eoHkLN&R88zZ^7S?;@rO|;@9wg@^6D-J;K=I; z*lM!1wb{H>k$SdN-NM-i9jGDBXp1tAt_x@<_$S0_;?*5%@tw#cyEn?)2lShMk`uJN zUd3>?Y>|9c8~%io3!{j=hU7%p4pw@e%U>+I%|5(@ieY+#FH}qx#Fi!Yz!>Zc*ZVw*VcXdHF>_{$;Q-WUE2WNvkPOC`g05 zWl3ZT&dmP$Glsj`?S8wYf+Uq=Y$6#R1cI8=v0=qlNxV-~+Oa^z@|ESt;@D6%d&FB) znn`s$xaJi@#(R5j)xbTM*?bZA=k5XZ;rS|I4=Mh4ZgH%Fk{yOvsvG-H_lM*V&c9oZ zD?`<52ZpDb+z!@Z-pkVx&R9k76WW81l$l6l{P+26%~XNYG(jl`;aoA}BhmB)d5OKQ zs3r<2G$aUZX&%DoZq|u7e(0R9WgGB}l1a>}IY0G?=(yxZDdl7hPuN6QB2m;;YikKp z5OLeW<%Q8?8sXBsq;0)VxqIM~gn~$5cy8=IbF9bOrMOdFCq}A1hDuK$>nVFOnzL(U zOcHb1JT7@(_+2~BH?AY2+8BRE5hG5_P*;Q-kDp&&8irqzqyDW*pyzEFyR9Keq_M45 ze!I~1tB`Tnh}L(AMBTs`fAmU-0p=O(j-6U()L-ukpvMFsnop7-_%$3D?*FO2CTh)>&Au+q%b?n+(Ziqm%hPwnwy%V=k|&wxvk`U_tZI}Y> z+x1qxR2TjIY_ae+u;>&Ksf^f7rAQYQfB1M?qf=RLao57XnFivFkhG|%vY#p)H;5x~ zB<|f370ixu^6S!uqN0?Xe3uEfM%*3lOQQli2!AIu4Yu&=8)fYbLV+I9nKCgZwcetI zA~I+m1!Y3PUea`p)Vx767BIf=l-Df9PsB&mbAJ2$xV7~1?KXU2PhtyKMrjF--MN+{ zr{{Xq^a;i*qdx|a$G;m-=Ro}M^;wLT(OoVsQq1&SS-7MeFW>fd(PHMi_I58z=sZ%FIvaIh zT|vQwQ1Mv|#NHCS@W9OZt4lN zB?x&toM!P?*^lg!XnTH)>DgF6W9N}ls^sk<^^HJk0BPDSJI*`_OQN(KC6mQegRE_~ z2IAPpC@((GwZV6@4MuDkl^zgRQx<~+xasU3)7AD_<=_)1DQWK52PjS;^nWAW=@4Xo4| zVZRMK!QruGLDIg1vwp=S;tAwLQeCnU+_Q+h-WRwv%x@@@$e0;p!FkX|;hAx{&O;nH zzF$k>9YfjjW?@1+mS{Xd1aB5xIY=M*wbNvhvQpewMMM~u30<6ChDc&CkQMK5zFP>q z*$7gq^GlEi*&7^zq~Ot)a9(IdYoWtYS<*yO$Q{`?v$`oed+;z4b~+QK?yvZ8*|p_u znvOU;LX9v$V^uCZB^&TPrH*h8NFwEzq_lf=K>7!t` zh1LD(bDCOTXR)ePe;dmkQ>8!TfO*PR;c8{`T0(VsDFr3BFIcsp^ax~&(D653$h)K~Sh$&g;}=+Ez0J|_a|Dd{_K zlth*~ga5|dKL%O$MBk!lcbB?s+qT_h+wLwKyKG~ZZQC}xx@_CF&3)_lKj%igxDn^Z z`}E?CPb+4uj9hz1u3R}sjvO;rHAe}qJojkIV8EpI`o{dV=DN^$0N0hxWDMel^iM|`&#~7JCe@k|Hlu(*tX>jEaxwz={en%!P7$7cyZis z4^irP@_c{YOAtNzzFrDiR8IC{^D8##tTodg#8QruXPhuSi0n?B_U}8COOsZgFC;zR za16i$l{b2t(g=2H!h`Vyc*>eg{HwdSK@sz#&S-3u!Ky+pB|Pc1@!``O*9)ET9ktfK zQcqAkV9U_xuRT@d@Kf7NnB@9FX-p-chb{PFvZ{gbZ(v8}cNj2yYV!ALn2RdH z@Q&m;i{WC0uN)P-lg7z|yeq%S6$W2)TG2zqCnxo2;b=3G9=Tl^@GEnad} zVY;{{pL6;*Z8F%pw?5s{kGpZf(6Uy(Z=`-WUvLdip4xqE#r1eQLhL?d*n4^H(^5UY zB>__sIbs5x!1#VF4S^iab+&f8edf4zmgj>fbFvL;_9q}+&4M&VMD}uq1O+uEF>XQ; z0N27hz5im5zANsT}LJ<4A$o0rjGoXB&F>tz2apla<_JvIGJEf;=;V*}O zwTepz_Wub<{I5`OGo9Rjj}zAH^!V7C-@^NKykh!4P+`z(n*Rs12n@RaTCjy5!f0*u38e#tZ@+^~Bq<~oYfSID6WrJc zr93_6m)5=gTMKY@U7Ni2I@aYuwJwI@kEnYPKmNfnCp-^MClS zTu#RO6gqpSB=Cq%`a2afeqGtG`ZhmJWo&*z6Lapty|v(zJQzIrw`RdYhc0&u?u5K` z_Qz|i%@l3fZ@%rpJ#j?MZqU53SP9~cUu$d`tq$&ITs~TDJwe1colb106gP~O(Vww@ zj+poE3Pz^4W)IZe7*p69->iCWx8g}?)tOULW0z=tu9;3^qJ9Htz!fwaNYOOmjfJfD zv;$mGc{{|H`Z?LsA*Vp{gFOt>A3Dgh8eOvZj9~tO$@UAzc+hmdC6rClZiWsw#QB>d zkvegTL0xMrFCHe5;Q@dLv%=ZZizS!O6xBuFXC!B7kKJ7i$(QCS)~DeIi`#m{kKr(m zgP-<}y$!~CuReG(Uv?6)m04cwt6Lq$u5)cH;`Es;Cq+5^7aeW zoo#HN?H-tndzX3eA|IhM!B1xY_MJ=#pi7=|>wP~=BSX^pSlxfH2u7WP5t8M$>P_Lh z;0+Xm-pqFGxx%M(OC2=YS|9Xyp3;T#WrX_b8_c{kcw)wOb`*RMDrgXzBb>ow9>S&GJ5(>V=gHf9sL4i6j!`L%K%=ZeNJuF607zai&hzEjgbS;Ut)x707U2B$P$R|}UtwfR5O zc&1#gg`**iA<}0s>JF?r{k)yge9y05+<=#IB47+QE#e|Ixd29iCLb7irzK`u>znlI zjV^cBy`Foiki|`1YCnB#B^&N@S*3ylSDd(RQe#m;k>ef>3i2_rX`m2Ycie0tNb_a; zfIzt>sF!!X%R5B=(maFO^Wg+$^i zTItvhsYnb1>J9s#_w>rmJh@flH7oRiU%l-aMGGm=`T7g~B&Jv2Zk(Bc1C+X__Z||- zg*CJdR}!94$S+|6iVD1ZH=&!jdvm;01uS=eU?Zt1x64N*O=;_pZPy9juD070bRwC= z$1BjKR4nv#N{57I6y7(Skv%EIi;C8p2pQPjcskvv`8wdY;T{asi$h<6Dvb9D>j|+a zoyW6hO~lJf^QC89F9tSr6*dLk#A=RAdP#*0X+YuDO~7Tun3Pvj1q(rT;w=I-An5h` z&6j(7OboZ^egNI69lFsyY(4Rtbl1|Dqe&DB%Q0db)#NahzFmv(Oz&Yp2_wWYUh!fzj1;A7&+JKQY4cU6Hqld>!VF7J552I03KiW+h)`0wsRD z^Y^1H8(NewsWWOitqW zVe(#-0wuV8g#IdKnfd4s4OT&gDd>+I^}=u=+)ZR`+4q~~^>*lRIX{1+M3^cpQ6qNT zKr6oLv{+md{8Rb@Syz(4#nXlB!=pG}^|EWvG9pnjv!D>FyD2=r>gcYM{&xRI-;#&& zsnTqvUNgBzi;%SqPrEH-4#MnQ_UZ1RP84NtiK)K+dmW+CO-;w$AVXG?5|W-pwtkxY z=uB26P-`T_AiFqUsI}388@C=N`&h0fjgmXVE&K&cIzL6mTJIXFL@jgnMGcLS;GGya zA7m{5A&^)PNo@6zBDnLcZmbCFQM>DQk2MFe~MW&tagig_J z>NQ;UdfEGY8DW$TPi{C`Xm~dfsXfe?^Lw)1AC8ZD>OZZYs5_KrC1nL9PODoiayvXZ zEUfvG;h}cJBGx8a_&;EcQx{NQ#sMg(@mwrTr~*91MhC*`CK#=nH-~xL&}1dX@y@rf zt5^{=8gVugz{I{o2DS256_Z5}I&#@s6d_2&rlz7(3SfZ=; zJNH;o9Zl3(8{j$=dK@^`Pwc{w$v<8OCj_V;p|>tooajGP{-Je`l_dSVjjb9*U`Kyo z{aM8uk0Oae7*LgLwRHRg8bOsSB~~l7tw$vezGiBKZLv5`t(1nyf5(*JRya9d-|cvXwsZ;)x6&%qh&9 zFr&rbZ?h+u4g*Yh5p@h7N)!bCclx&(YGK630_)Yx0ESZ^9(90Noy{Mo3uV;{wtx{_ z~VSJUWa(2Uqdm^H7z?v5O9Jzp>1Q)J!QQ@xyNo-|L?TpF8`RH#BRreuGYgsH5Kz#E2H6E;_ zJzZU+pBlU|$SyHy#U%Ki7nD*xSvzo~h|FNDN5$3yWbPzr5^>5kjZO5zX0S26Si}=O zQV9JMSh`>RjYpS%eR|6|qZ1m&FWQgiA#65qSw&Kwu@i_(hXE%)FJqvpTuICzbDM3b`L7U^||lr_|&{XFY5Ae}Q+d?&jMAgDMF95C+f zSpV?q9Ehf7`nmOwFIONwuLp16*bov^8R7bDxc=O$16FTyD{yWDJa2maP6Od!!i+i? zR9ET<^WMYCa!Ju5&|Ag&hl83Zx7^)SMf0ONW1V$r_u=3y?A47g$D21t4pz|g*iNwS zF|^8SYtUch+dxt|e@?!4uk3y}aP+{oz{-#%p`}n~U}reNh=tlOx15Fxfz@L8tCEy8 zY2yWL=VA-X;Y1G8{ah4Rt5&r>M8Zl?Jfn!MOh^{}9>Ku?cj$D=#o#h#hcXXkNJ~!k zs6g&@1lqVMDh!cjceTCnQE=X2d;)E*U$r7-HPX5j4(>Y+)8`&zTALI8oW9ObCxnq^ z*Co4UYIq!?U(~vAhgI;`W>^v$`IUfJ*W}9oH(VJQ#?$UTs`#P7;N~$T{{F+A zI8?t}mfMQSf0P>~zTW>`Jg+!5mF_vQ#ZY~{7Sf#rcTY;0m`#vKPhOft1e$Ewl8lH8 zsf!dCWQ;C-kQKXx&1MLHD^h|;whSYK5)ZT79k}0*miYJg59imfx0#*)Xs3`5U8fo! zX|gIyLN)*lZby~oD!NXZ-?E)X^3k$bK~R!|hI*`|?m7qz4tc&D+s{yelDP%XdvM&a zua2wO=~}2R$7JU{YQJ4APn;V}5@96e-|@{qtifpfv1QI|qwU-sKFu9Q&DsO5k)6G^ zuwD5*Ax73h1x61}TD^D0v8quftXp*~?n(ReLipi>=bZ$uY2xtdG(pB)2k z$BC05Cp8WUQ`y}mH1q*Q|J8*J*f=^}N$H`EmpQM;H6Qs(k7#Mgoqv-MbllpqcB@S| zO*B}F^Qstf>63p-78fw}vM0x&81aV>xLgP)?|!*t;18{k;&qVyu9V->2)VJZ(Qm9e z_OZ&MX`xYNH2cP$G@xSYun*Y$<7o%BeIdmhQVT&|By z;*VjgO$8~WFfMaFL67QrtMcf+%b*}z8jV=(X`XDxQND?;2Z*Tob$(fQR0=%EtSmQL z(`$%F;}5CV?zX}@ZrB?QU(dXtGjK)dX@?KvQ0$ECkc&$of}oU&`pP0m zB>CXnQ4O;v1d}@3c41N80BR1@OvH!zD&S5i^CsvVcoI*Z!JL4snuG) z`tW}3-ty4waM15c%00w2Sc9TuyR(5W`n>s2bY*fmdD-{~SMBy0T}eR-UXIFGgKh%Sn8k+hk&0rz7P6Dm^43iF zg2HyYSU#qc+GQ~^v%4jh)4r2>Cex%!Z5{;*{v~DMsLR>y5APRP*>k}Do%*g#bmHZn zZ`^^e7p=m=9kSy+YdsCEf%zc|w)!AhH+*)|)u$$dV9%DCbcT1)#lF$*aLrLnSHJ)k zAg7a=SKQDCi@Yiz66N)pPinG8^Rbz;sJNm-75h4vPW!XM>(iXv!LfqW$n{XSYiZY* ztBRA-o}rdTJb+XtpVv29cZtdJ$tT9Z*DIci-w*d;OM5gv26DPF67z9<3`?YZ=A>w) zGIJ&cg~xumlUijYJl!d%%Tqpf&)`euBYO~vS@GwWgndj|r50Cmw_N^DCX<9@7wCef z9}lGbtrIaN5#pHQAnFG9E*&}Hq&aJS#x|eD{WM-)yoDIqYx+jX?$9w8x}C zdxvKfEW`ZW2G&%LeEcLZ02fL}Wa|5i69F@=7V=)#OJaLH7W)7;)*DMrFES zhyeW9_Jt&+05@&}d;ICdsuE)*k_v4#-%@ht$6hF(ZVNa;v}1n>t>%Wav4_ikLEF__ zixBu>B7SAK)=2hUwy3I=?AWO~rDw$diMHl#mJ)eLNo6--k{f##HvK`}Cg6s{xU~}+ zGtiQhzn0F*^+yM*lx0^(z`GH-s0+UJ1!A|{ZT376o$ke)h<*$z*O)BUt=G@M4IQV& zN;s{@p(18XMnBgf!WItXhK+gFGq|gF_M9uX-Sh%R<{M3Hm&$VYZsGFrOaaEzoUa!8 z+1Vs2(SZosPC264_l+o|yuHz)!&1rELw&vdb%gocx2IGL;)yQS&|l`)X7QPEy?55? z51T~19xf>iOG9d|?54hO6iGn#^Zx*Zue$*4;z*$-ZMN z;)pryee+~7)ghaj$Ql|he-SZ|A8yT{B3TkA1vP4TT`EJSbmr8=cexq=`7yU@mC^CV z48MDuztGvnbmX=8eqye-jk$Gy+GC)%cMkuWpXMI-ZU1Kgdbsh$ds}pEt=V###8_ls ze3`pDOX^(NPB!)a>@w#lyCK}qA*3UVcou=;cFVgCv5=f#aA^V#W|96sd2mq7|J+`9 z{QHk(U!o|K%B7MC%)olEmKIIJ=OmB$Z|hrV%JZD}jfH2k+?B#XUnH9)E%+})8B*U* z7(SdXJhc=2$BoMuyp(z>c4EHkyK4PC zlYLJFMVb2)5%8irX7t!+ZksG3@ARWr&!JZ_I@~WdXr2W9`l9u23j~{;Q)DV!)^K2aQ9swNaf%Yw} z+o(z@*>-f>r79~M=hlR3&;|Lw-M7~|^K#aU;1FgDj=fG=sGyK$jW%;t`lN%PJPeuB z?H?j?T~aWgeKbtJ4;>LX3~+fY(FeB-M0#o(ZEiY!$dyx?F_-#i1$5~$;pkmcD@8q$ znmTNUAY+d_XGdc|h|TP5zM0*|Tdi=RvPOsEitnBo4sPJc-3?KoWSn{pa;%*cMV>7s z9{=K$rQrNA*0f*MwOGMw=O`0b)g;=i zrjWJuPqcdBQfW3>Miz4{up8d+4A)jD&>*Q`zv(*E0 zMA3?l+D%UK)Bd|&7`jG^N2AT*#8Sg#gH0a-;EnxA@*FZ=4V_~EFgz1pijTVzM|)gZ zWv(*@zE+LtPJL+7F36hX#z&=8grn}sH^hS88ENlaxibiekURdfcbpzvxt<+3xhwYD zk5fx(2$*$)qQ?TZd?zC)?3A+1)(&4aXnRB=&gZo;EYK9pZRc$Ck(Xwjy^;{io2`by z@>H`Qv+TVLSN#n6N_tYV%mD%;&})n9XCHIV3x{62d^%abQRC1959|>9Oo_I??+grx z5j#2|B4>aYXaSG=o|Y-loiTv=>Nwkl$2&OR`WSYf9V805S54I#tCK>sk_Q+FNp++eI}WKg9E%0|QWmmf}v-jQ7u5 z_o08qiUGRrkAKuBRzF0ze6%gm;lDWr!D|oK_41&-$?Fq-xGo)mFewwlleT9FACWLI zhd$A3l-IW9=b+Met4j-QH;0jRNUYQ^hY*(c7Ev-XWpvLeX4UWo=m~QD55)b22XBlD z%X4GShvwCAmphNpr0Ph^3K`3FkL)V$Yqz+ZIe?^FF8?G-0JbY$>Zbl=6MxQw@O4$a zEO;FdN6IWRwfTbTJ)q2vqIV*)TwSC474P5;6$TOjrrf0E>2Z;oo1VVRY5TRNvq#o# zKM&Ju>IDRVL5--gmfnGw_a}Xw^G@=YT2u8Vb#%TB0;T}&MgV*XY&TJ>tKsY=*X}Mt z?OxwvDqiTz;e;KRVZ-$H27M-vmmg}V+3Z|-Y@032Ttt@w?;2(I;5aIW(+(o@og$6} zkUCRAf283+t=a39;%-k3?jW>o-wCHoiua{7iF0(oMi%P{)}n>$tE|y~q}-m=I)An} z286^r$)Oz`7qn6Ctz%CEBSUm+mmn*f^qG+5e!;OVJ*a)q#v#Mo93p2C-~7D%w_t7d zvXPZ$_d-ZV3}?u?O(l?j@YOlgfhxQ4co{B6xEj%V1}MJCa~>*q)O~&1i2ceuHnn~+ zVvYaZ`3$)Ts;(q9vDoncMK<>$GdSezBZsxvgCMTT(rk11+xCa&V{vXiWxKblr5jal zDsx5+=bMaY33IE^Pl9a!#IUf!&r(eQ_`WcPSaED?XI4~)b(k)Ni!nJ}cmP8!WkZ6h zedfMq9*`O)cM!GX^QQ}(=z~uP0kS)?!PTXIM1Ox3R8xhyGg|hYV!;F$Vl4= z3&qeM3V8SUvJ9J`X7AvoSM|Zp7t|1+c4P_t!{3UDe9Za!J@e|$+ep70iY%u}%n7w} zDXUXUb*o#m+rmi=a^+p`1jK~8M&PA8>G`RP-~Fgd5zvL&EJIGSZ~{X@25nUCGlF|z z30?6^N6yzWf?&cnLhye<=X^G<59=L@nqKC#xS%E<~wJJ3*A zB&BMsxv3i3{EJAm9uVhmiw!rr%=**G5psU(1@A1rxEyG72ehabaCzbnNcYR!EJv_D z{5r$uU3+AqF-IifyirhH8nzr~B( z7BP8rGKJI`4Y52%9bs{qb0MlznaV0)3OAJt9Xr?`myEo-a0uoen8wDT3TN>YP48`A zPi@ul$OVr%$mX;m;KJClpDNGTM|iYb@bg{Y%oc2K?`L}(|IA&jwYXcu!Ffu|4-Bru zs7imyO^Bew)%TxP{__m=a9ASyEjSkeadsU3+yyH672n*5UL;grjd}TE8J%$T(OPDw zPWWJdK3nwpO@*Z$rb!#l=n@dTow<|6|I;VYk~2-j z1z!kXe+QU8AQwpmzPXe{K>%Ypi+B%%m@g{I*sValj=k#ADP&`X^`|!pyZN5aFf8{f z0smS}md)$bWcB&X9`7yMHqJjNk!ngs22ibMO(ii=Zc7zEq5x(!ovWs^8lx}N8>|=- zPH#bw54GkZzVua19r*3X0U9Y#<6`Qc!ST8NqQN`!J#_ryvbn)>VII08qTo zps=kb;A0w%C-iNX5G|}lgUZ{t{ny1#&CE>sZ{BNc8|mjgyQCyf7C3_&(6iFlnoTg}>%ZNd3e5TZi>p_Td>$_+Eeu(V z2W~&?J<}D=SdN4%DS|2L6HCb-rJYH z4mIYM9{YBMZ`1YUD*E4Y|agP12yVyBOr#1Xzwp)1D;Cfa+!+V%ZY&yA85Bib)Q?$jLh zsr{nrChCJ^5ouu@jwi)@tCrnv9RFjdKleE-8A}}tWUAZ~hv>|eJc)9@Rq4|?D^fAT z^mJ|?V+e2UH&EQTCXsWhe>*S5QU4zWP$raK&3Wgj@13un`sdmi%Goq&7Fx%Z2S2CH z@)Ny+uq#aOluImwuo&YGt|`h-z6og8C$^k+Y}99mPjeK7diC8OT^4xx`A0}e=>ib@ z2V9ii9)(5r2=XQU{Y`CZo;!j^fePu!Up|zDm!9W(AQF?N0p71EF!HeAf2Ao4;sK9U zSM~-yCz?}y^P6&57)qi_7pFkRyDqs4T z>gyU93;;E-018q0xLiRG5-3(p?%W(pw~L6sza9K9tCX1i4P^AZ*8|A;Z_*9+RjXy< zcnLy%RQOyK9@k4vDq=Z{4m$qn>jBTLuvNtKb%rqMZGL+CxhA(r=6?xpl7+YE)NAy; zYtHh%u)~%f)Bc2pL#JM)?Hp6_KOw&V9cnbO`04~C+E~=kGKAi>0lk_T9P$P6I`dv( zkuMZzHvayvMV=BJsQilV6XX!v?#ph~LO|9fD)GvRxRC#1;BO2t{;=e@;sr|FQg>1xQJfnuyyD}Hmi-m+KHW4nQh<-zrC!7=TRF*G z?np4gcD?1V8BNQ9RGe7~1$dh|%mP2YUCFnBIO?BmjCtE1J;QHg_8e^2ME|#%W^~N) z0~EH0LM`E1cQjwLJJp52i;03z=k5Dr$>y8g+VI;3@7?tDQkv(nE#*2*NQYXpH>FC5 z;E0T!@5rqR=UR>4!F?s=@wCymDLL(_i%XQ6yzc`L5fOqjV_P|4mK!f#TUl&0yq+m^ zB$w;%2=uRkdclRZ&sL)!AWGK(Ch51NLgleK>u2BfCLR8XqpFYE<>Wa-g;N{B-__5bB}xrpk>MtuyLZdUGXO z&oVMA#$>;U7m_qZxH#vIdKv#TwVt(iy!s)+;Od)_wkKn6cv#UnTg98aywIuog1|}e zfw;3C+qy?Z$j+8W1rwsIP{%_XLY(J;mW7L7{AG!78BPg3cLwe5h0X0p<}Ig#i65TF zHdQ@#cpl*De$j`B&F;cLiRV|?;IR8GUG!zovVI#`FcNbHtubZ%zqUdjKbo$_+l)`keA<`uVrWeWS>|GQD-b8oXzSZ)IKsk!I zSnuuM7IzWBFX0?sp~TF~tep}9QQ=UhP)SJAPsICvL$;k$OrZ+~#_Nyj@gLDsLc8G( z_tiQub`jW5wS%2qC$AZ*3X_J4ANAm#ZNJ&tw^j0SE+ocx|H6~9#NY7a)5C=4_jNse zO;(Ea4iu(%h@6rAO9PP|?CFOwa%3C}FP%iqb28XVHPkcywyCnV;K^1aI#zc8BQrw1 zzqtHoC_8%rEBs;MHrc;t2OHmaSScSGt>N@CR7q**knA*2DO!GwHhE=Iud&$vMB?Cx zp$ipKQj}%K>R5X5`7?P120cwp6&}2pfC@W2VeA7!Y0aQ_3sx(+qrKyHIk=GJ?+sA$ zwoqY3sR)HASV_o*@lJCPhhR@yo`RgK*Cnbp)p#etoj%Gc(v>5=inPI0<5+KwIwUao zTai_PeEMhbTrXWdVK;M}sSI#CSFGs-6H?DuKLc56_M9IKk=2Hcs!-+^6o^X| zpW(u!L;K1o3xLtl#ny%YJEe@0uU~2Y1J%aGh1cP4tVZsvLKlh`+h9b>3xLr3O}o0t z@*%Zfl$vt#Ij*{hKSrKw$UX`sWLO-KQWpk@$jWSRaGDTSw-p>;k-dhy7SD0WT*hXc zIjFk=YJ6v?vv9)I=H~{cf}I?%(;Mfk{>yA>pJ@ceyd14l3m<+ay(4$Ts2t(7LcQ(* zPSDm4eg787t=;rq^40ua`w+voV&)Uw)K>B@mO4&PrcveRp~dADb6lYO zv$oWGu#nv9-RM0#o&Xd>5_q7W&5Kl2L;fDE|N26c8N5KhMgvR`tK z{DLv%e;t3v8cTJD>vt|~b^-757?EcpIWbR1@CwU_b3!&g3d54DyJtBQ z#WPPchh;UI?!x4yPDrCGQSaBLen*Ma2k(D%w2Bx znc&>8S#WGtu6A2U(hk9q80sJUwN{(PKH5zgD%b%XF}RQSc)IU;wmWT@G3oK5<*D|@ znG^@R@F6yWe_!EGo;hsfqG&mc%A_g=Hw$ewr@FH1Upe=5Yp4JJB0pa8fMeexdQ|13 zHcMvBFUKAUJLr1COprpbqVS$fj`&^uLUXp4ASub)Te!&SCX^#EE+coepZ!3mgE4l? zd1geBB0{@l-=2$Uf7M^O;m|*T|9dF3ikbWWMSX(lnd8!|;1!idX?^^U(C{#iZ5Bm^ zE2lHwY^=iin2;Da7lccaOH7e>lp%enP<-;>;>baS}V1|*}%Htqcz ze|*5g>!bItEWksp)7@PD#|U+ran^glBKFH;LCxQ=gCTC0ZLA?5&v=%0>qoB-b}PWw zcp~|4Jn{Fqk!%r+Lrf)mHPU`L+o?9klmQ#S=wIuf91Ie_TX%dp_5(AkXf;!)i7=OI zO?lh2biy`lz(hFCEA=!X>}Nd%cF_E%Z3~sl`q%JU3j3^MlCtuo zv__OhFl_s~Ii5F?%?MMuq@7z_C>2YfW!|Z4s`5*JkZE(tQ?{b;&#a#$V(CsNL}BPi z=%T8M=i3IVs`DC(-`8MCN^_~gYQmI%xkSh(I@?bCQ! z(SPW;<^xj#&YlhmFZG3QEhz>3zo$kl){;4Mj-_1uQh7I@Y2)rLS|?o0hm8VL)#V+W zYxYuGg~JoM?XB3Ds0doL`xOA)pCl!o9PKEA({l(N-i6)eNogoS-e^MDuFB+Zg-NSn z@=5NFH@{uX_xP7yb9zLpA>2mn#Ckmu7!B-?<}cl=@H6Z)eY?9qxi22Mw?hlAF~F)r z-?eyFrV0K5I3+VFz8VHap`T@i?I*l?!Jmf*;4DVeusTgY)^*Gm5*_6dQaHcJ>!wPz zdj906MSFUtAT+=Oq$bfm?fw%z;C-Ft(}a*vdtG0`g8f%!Ft_ZKCRkMD1$HV{mU|TI zFh7Sqik|->X=JRLZx2A3^sA zW6PZYX4+eD$AxGoNhW`vAcz`gV&>t{?NWehsSlzGf;o|UCLOy143#=>v$A#;?aM}0 z)uzeDWuS4^=+3WIN+(D863|5qONDX2GF}VM7R(^Qu1wK+T{~bfm*>?TF&1Stnjs2* zJgp_38+1d;J{8kk5CU*|{)sV#C3l%la&4oqr2eTGZk2%o$xKThQg_ukmcewn$1ic41_B|4d(2@0$9HsGdtqZbCIM5cYX=0I4T}`s*g&rH1kt z%XhL?y-v9yyd$nHT3tD}T;EI9p?YJVk5oT73(ZO@l=?V5I`@4iytV7qAk4Z1YEaCh7j5(_t_$V!6%=(tB6-Sc`gGdPI0M-ZNO!l0CONB>;`ibTrWh zEjJ;JFAa3D@K@JA<1D1zK^b*NX(tuU-bQ~C#x-LpONH8GK%jU%Rf@l)2^8uW;Ih(}}L6Al=r zj@(Vw8T}({G&DY?m02Y6sb1{W1V;(8>3piP;RSSQFD2*(f6Y*wUT$%4yur}i0M6Nr ziwy`)6QbK+tPdx9eS)Z?D~2RDtYAR`@O5-FnbQ^n_NQg+eR?*1dsvux{ZSW%Aw=E0uT1l!73a|Ztp#Xf zTVX8*YTEdt=(H7+sl{Lrsv*nPvDgcB>$G7W6?!c!F#L{}Rw$8<3p4K+k~E?XDDv-Y z=p!d7A$tg3-BmkHPc{ z?a#S%f5|zxiG*;Pt!b+)CBmeH=%i|fAydNkCsO)?Z&PF{t_BK6%?`6PrJ{ljE#RS{;XNBVJaUs5OWh;0^t$xP zXFn5v8$?hMg%>n;#(JE_U#OmAlI*^#>6cn!)JhFaHHcx#xp+_OcA|q1(0o^NK*2_$ z1Up1;UjntH6c!h0cJot-8}@+}K3=o$(q+;jhE^OM6UV=qVAchuqGZQ4k|0wb;2}O=-QcQ84!0Em#%6-ukCx?dVwR^z2k)4$(7m z2JaOisDh7zhfn%Pz*Om1WlJ}02j8_#oUoQaV|?l_rlf=+6&O)KPs*G0`@F7aP^Bxn zfmZFkRGGQ3A|8rbM_QxpoFvUlS-@^AZx3zkZ1#{L-^+%~Q2>YZ8lzz6N4nSh#Z*0$ zN#6M9E__={a!#rdVJyf5Jw>_p5WVc|fVAn=o2ntfH}S^XDy-#+o&}KQN!YH``qwr^ zXr=EPc@VE)>fqQ$e3%njY+82US90qyAXFM2^{TguT9#hAUWD63mn-g6 zV)ynpB62o(Zqs2N$ez$;#)|8*zpK+k4mLQk{ea=p0;qwr!|CRTX)Ab}sf-t_UiYF? zl5%ptw8HRq7px_jj|<}=L(kjH#ECoj>TfE6(I62j{(7Vi zj_v1w`!qx-(0MEPR{Z?w)$vT5eWo7+*bFu(35#x4b@1hLd*;v$n`;Q)zUL#2JtJ=~H(MjwzE^ zbBT;M?sIdlXU5;%qs}L9U+`0#mgw!ZFCk2RIANPkay^kdyF_K(d}|Z_1HXH0H6$S3 zsE5&beOtfLY9X07C-ZOhXw2P1z>O0OO?7S6WW;!;Kq{a@-2UjI%gtGiPoyWK_pXU? zy~x7e0WGe9Hg8btMgumh>xz@oVOY8FQ^#8SlWytunHVe(7rh{=ov%7%qq+i}cj=VV ze9a6dR2mnjocKPyHcSIYZwEI`4A!lEXK$Rrxgstt$bT-4y%lH4d(F3N>CR&bWVfBp zCkV+&x1?r9T*A8CWP@9D`Ks#3rF^KbtPq^JfBk4Zd0DeqozXwv07mAOh3CiXZL^e1ql%)%-;+7}V6%OJC<(zc9tTT56?G zmK9t_|J7tWC#=r-@s`V|g|;_L3+q3$4jj|{*A{Nw&(P9&)A3L!rceb46NN(qPiuc}3xDfcG3;#9b{DT;iiV+S#s5hB-+~r&1Bw4j!aji1j`;?hTJ>OM*b@5q? zpUgqu2i|1V?B@aMEH15^2?To|S9)r@6X)T5qt)?Cgu51^7g zQ`5Y>q%@9kmC8mufixwN(Az^yQgbs$*N=txH^yI%d3w_6J!c3)bL%GUwD@v!4Afxx zy$`_bjwHgZQ@K8mr|XyI0N8FuZO-sZ{!J5&EX)_n#S}gRPh7jLnLv;=-HGx(6)WM% z-&{hQb$%B}R)J%n#aAJAxARb$NpfG(y_NXZ=7^aVZ6!1a$2Lk$FMt48z8qCKXBGvf z8Hh%kD-0_ESSo>`_)~Hae3e@j%~32{SN(4u;imC($JOoZ@YQm~_xOqMx)1Yoq=1x# zXghN}cI~dg+W?mR_KY~i;Zf!;b0yBW*6UxLRTy}^H|riCU(I;;$^7W-f$$iDBDsg3 zUgrouXy;3o#sq86gav6KFnhXG!6Nd1+kv!hW))`mUL{f$=ZRj&8Nh?iUl`{O7I6|0 z@A_=(cF}eHJvOp;A|Bd~*t~EgFrs%aUk`rPu3ZBy{+-c+bfvtvR0(V~(BPllG9FuND59a~beJh;qK%LAz7(`xExHBZad`bhZM(>;E7YeOaiZoz z95+(UF(nIeH)`@gRWBm1p{JjW)2%&&(!W&8f$>MM7C=_DyQ3nk;!4Py5aFeFOS+Ux zkPL$+{W})Ez#BAk4rArDhzz?$WvBq-C9WzU&meS*UPk+Z*s=WDp`RTpo=D@*EFI;xFYStNpvK zcSpwC3iI4d9U`=7=D)e9H|{feGoQ&O#9Cwrnj7FY`-MBbn4giGraJAhVm3vHUyjDO zHR_<24}tHRG;O1+MvIdwJM2zs{F;(Hyny1JC1MW$7K&b>Kn0C2_`6{(N9*W%N#U-a z6T<0bpB7SsUl1~J=pAvej^R-0^KE3$$zm<3H|I0OU#a5d_qnh<*lIO(C+{Ab&DMLs z(q&iH+LdQujlP}SB+1&erY#KimJisLRiwa zN6m=1h8AGs0Kk)wCWE{{K!mJBylX=<$%HZg;>cYH4BH5iJfi5zHXYa zj08)I=IY79n6VxJ!;BT;7`}f;(Gn0s+3OpSQTtlIvFmG-$|F-}E*X%hiZZ`QIURic zx=Io$g^2{=8S=9u|M=fuw-NtIDwoXc(LzJJvHG$Wa&DW7EGn5w6gZG!*-q;sqv8|w z!gD@&m|&Pe@FM5Wm;G9%p8n*@pq_d&b$4Gl8Ea74*WyhxBuLBwh>EUJUU4>Im>I!U z5dnd~c+IX1uhtDch{;h6Z;~Qq!+bJ|#YCv?Nwkkh0;>GgA7p&v8g$YQgDtNG91${; zGw5Qn(Z8VKZ_quL!ERMPwLnVNy~=sg5YWxk0fs57eg7A8ZynXv!>$Xqw3Olwr4%T^ z-Q9}2ySuwP6nA%bx8m-u!QEYhyG{E0&Ue>2v(CMDX3fl6lYg_4?Cc~v?<4Q?D2sLc zdw?u3yy9q9$t>5Sdc!IALcsvhFe@T+PQ)Mh05xW*4_*>O1wHuqh$ctz;Ww7>r5ZZ` z+ZwOA3JjRWiFJ{P#Eu!} z8pji*2Ff2oT(yYf%PhUZQ)~@pkQ^DpDm5ms)Lr$CWF^93i>WQK7MetVz&fjD^iPSQ zrP?%o_T=qnS~8*tMeO^yn5P#!)h4l|6I0A$xyx!caD!s^1h56E`1pr5ZI~blFMT1y zReSv|8E+kSYfRo?&Eosa2l6yV1kZbNyvo)VIu!f0B+)hR&u zBaGbueoyD+o{daOmQbkLDMM048A8@?BX2mJwa$aeH!#XWns;RKtMfDc*7`x$b6O;3 zkM56V?ii}V^lY{c$kIx4kGFox$&M<68n<-&xI^121MEVLFu#V?d)@OoI(Ls+n?a-b zxU6F_@aL0@mDxC%t3``>nHG4Ks>CK_e8HZk)t? zz`3)pE>yEWBwHhmW4wjBr(#dmp=UWb=pGsCx{a1Hb51-Ix27KI789QSJCXNE_G=Uz zhcQH>*MT2(tNz_u^pu!-?Ys=c>A7@8(OvbUG%G8^{Frj0hg#Ug5*=`@I$ zynZ1}{-u#(U~t6Bl7DHQnZ1}c)#?mzQs7g+%Mph}ZE~u%Q{2~%h2n*`8qr5w^@Yqx zXDVA%ik}#eOgT&zIbHN)?|>m?wrJpKeLa$lJK7+H(e9+xqv)HtC{Tcb+?^F2k>H7b z$EKL)KprN!ef++N4#`xGscn3ieWveRA__mj%Oi1omC-~SXLFC_rbKE5FTvfxx=Tx; z4C)UE8F9WTaQy=lS$fl4MTg-p-&t6FMDHyo{`h4!OpX_bzhm;Yhi+Fw>NRVwg2RxF zH@c};=3vx{v-HPz&K07Ps%>QvQBd~6nk_Qp`{CgIp99vU{gr~D4o*DBYWr8CtIw2< zty6h5I5O2sRG8Kxzyo^E0gJ|@4k+zvT^8-is^mW_RZ@V$?WVa$C7F@8^+i38kA_im z2@DuBQ$Y9M@smytrl&d+Z3$zKQFtY;UUfK3@p-+%e_RGk>=w{`tle80u7cz=R^n-c zRZZ!_Jr6wJI6R?YxxGSntq4-sqggPUS6j3b>Zs?6=xzx%(3x^Pm~{OluCPN{0|^FhXrr!_-eWy}@8%nMc>rgQPQg^xgq?C?LIhcQ+&_qRuq-*jux+>`TAk>S>|1&C zbp+3%tz2mYl@YRHz#x+8gx1xNBL^o=Yp&&a-H{{Ti(EvrtUz~p5lF)M5LDbP69)LP)# z-F+Hgbnl`u?qQGcp&lgK8rB9$$R<1#aWn>tidn6{0Qc0FGFdB^oDdrjPjnAcJ!|$$ zlLnGZWh|a-h4dE*gDd^}N|{eH1j_=vBSSGQGA??g=*NZqy>gpI*ELmt`QN#k9z5po zQfQ}&<|x)7xf7DI$u`yYPeCs(#qo#j4N*Amp-BBf#E6|;zuiIGpndfBy7KHNsO>7> zU2DVM$ZdKJDNL7zTq$%05qx3k!O80sWh^#3LIQ2v5kEwpiHy0`@}m-2!nw#U|A9Me z9^HwY*!?2Xp!6P6tLB0q#Eed3FX{cN?BFLGQ69C)-PA1No*PdxDGEE@63+(rghqH` zvtU~L%w@2yec@Jo`SdFLabY6DVi;=DhP}$-Mz>NcNR1itM#ApJ%J?EUCj19mta7Gj zaL||A!pth{jk{lg#@uE-77(oCZ(LZ1$)d$+{#h^+bMg;1!-kYu8YRH^z~hiA4Yz7s z{mOv~c!*)O*s>c|wAw0xK0$Gr3mkf;qTQ35km>az)?X(kw=q9vHEQ-E()uBMzZ13> z8e>9b?!J6zBz7NQL@uL}(W6+1&p)2p&Lj6FQ~E+Z=1LS0k7#vOE`_UOt!5VVBU$g%F2`#{6O>t6=+CP~0I}6Ae;!4Bc?E4K+6` z*!+OR&OMm?H)+F%knj*B?=m~)t_qxJ>6OP&U%>wF&!&qt6?LUJ_{4jsLJ-4gG@o`P z`ajD5w**?)r%c{$OWD5lx7zLBwb_{@814A6dM99(rb1dwUtU{G3C3ySG15TasS*7omjZm+Ht1^Wp?AbYwtc&c zovlL~ZG`F^9%!_Qx8VMoh>!(Buh?X9ZTGRhG%n@$&C@3w8>9>! z{Ah*fv9ISucGk#w9RbyGCH#A3UW+&bZ;m^N{!@JcWRqaN&NzkK!l?X!##$vf%J z^E{IExw^q_3ku$J)DVlaU?@>(Mcd1*M+(mwktw=v%;B@qkStmSm zOS3vkOe6&TjQt;>$LuUp+*;DDwZj$suZq>Oo#O5QMbv~=hrC3{*Uk@ zMZy^BN>u66BXiDa|M9K;PcPYK$cOg6Pna_L`kOqbs11MS% zftMY-?zDYO%3kp)VV#>xe_yO9F3k~zsSPHlP$Rx+-6Q3S3Fs&a7_m!@Q~Llt{zT^n z;?y!f^c;2~?_E~-K^sHHzaqypE1@OyrO30#hV^iX&4KB0FlB(ku zbkPAxEtdN;88PCa$e?gXe)f!uk@sSR41v=nROrxBKmShoLs`JY`h8j)s{xtZI~6mP zccQuLOSDgSMCg=|Ca!X?)xsRFZ{?izWCIWlA%U4uf&Y+67rBbDr3VM?|2C<$DgR$d zEe=ID0t0TPizJJR_I-`>+qU)FckCu&U{p8!sNV_gez23pz&5~=kG(isH`|(+kd9Dr_EP$9Eh!hX4xJrc}k%m<@Vl6POmpPyUGaezX;W&yi0KP zK#a`Tt`e^nlCaRy(l$YifGDpz_9~;1$O&(CUiK-5iMRA-R+lWeynN4Uy>;7L6VFPA z+kK{-s%`Gr>Fw|0IE~Rs!nx-*H$s2tKepc6iKpWsoYR&zxTl^wVYGAtH)Cz=SAznT zjFxGotEcTA41^#F^H{v&otT{$w5gg|X!l#-9(TD6lrUJhT#9VtYq~qpGPttVg^P4K zOt|#`RdcM}QB_={uNn9+3-6PCLz)hA7nDXhXL>gkN?KbhG7~ijq7()%NiE5JqaWxxmN0ysP+YW`*9MV|SD17A*LMo1P-*o-^HF+=3MzH+G_~8IEnjqUbP;70XF`T2DlpMp-QHktzR`ymwuXJJ$P}3S${Jg? zX-&poxiVE7{W^-eIu9}>CVrPnMET|NC*kELQ%3cgRo;d>Pc0Kqa%i8cmC(D}~#Ly8o%_4FWQDrGP~`FR7Lx)tQ^ z)l4Q^$h?TMQpoGG1p_>kDAmpTt||eUju>W?o<)`hC-W5+s;uE|MtG_9)`3yE_7-z6 zPV7;C45lzNew&}j$wgsQGdU71wTS72-7&WOlKzWXAH#73VRUhL4D^M*K;293WoC=3=f#8{g?m_2xfYsnCbR{ub)FmDr}HYv z!7j4uLWpx}AdElnS!zkMMWU>vojZZ{?s42j-J7Y67PLB^c1ap-zq}4n-=(9_ZuCW` zjH*;WIV0e`h6Dk`OQODuZmJb50q*1=5vs*b(rBIG{85qv{G*3-F=78n&F;fDx; z<0*=f?G1*LXU)v?0mneOY3$Fd26WA5m~0npK6$d0v?fKjEr&?!eAv%rq7+>lzcS>Q zMB`C&u!^)MyAP^A{An=S;{wKS>Cs$7UE9C7+rgubCM0r{VxUbUu{wqfsy|Dd{6a>c!c}_`14}?^4^w#!gdOe>IX>EgqHZAj#=_(nJM-oo-baXDx z3;!A}obaHw)9Aaxtf4wpOa5-|AaJ+#W0&ClGm1PY7Apc>@&`}iLd@Tr;#@|>iBx#-TfWmb*r-L z+lr`x$>u^k$r%K?*a;=!!PjQG3|Cz}@R)CpfjD>4eef&~#y|bP*A0iL#I?@_N)s8b zJ1wy&lbiidSJaSq$#X?`ggd?qDENO0&~Pd!uvIA&oPC`82RQ`n_WTPvz&4_oeW7xu zfr8N|JBL+sVca5S1*f?dlu1qHEd>-x7R$qG?>S2u80uQSe5F~#^@HEK*=pbYtoU0qv8mBWJv)s2vDbCCbVdLAa!t*&kJs;y4>=y@6Ds+`Hi?MkIZF#YIb zrSCtdX*M~Kk@CRc*ta0Pt@TsK?*?~#*n8F{LlqRE*u}Eobbc|h(C}|`+ow=&g%T&o zl;pvBcL~8wCeSb){Du4R9vR%S%g>|`p{#12giuUL7Op!+)xWd9h*ljffhYc8V)u1( zfD)4UYokG$cpR60YVaHeX?23RnB1+&r7U_k8pS8f-PQzmTQEM!Q14ggm66y+#U()Q zz>xhV!=Jw~5!AZ=Z!Z8a0FXOceGW>rLFbk2ryvx{^=t3T|GBt4nop@Iz(Wn2Sqxx? z{3uAtjgNwRN})6dXl$#O)Bpe`Zm-mE(!lchoHjrY(6>?gH93EJrbLbq5ZfuFRdy~< zsZAH6EYsxwwA5!1nv_!_2qGt#n4=L>EaL}PSj4D_hM<6CKKBEd-mNQG_x`#Lyp%G{ z+;6VvRCoBo~+=FJg(}P%= z@hh78Hj*gYV`Ir<)DB;(Cc7aGH!1$=V>hD~C{Z9k@Aufvk8)Y=Lz2)W#`p`Xn=>T; z(#7J90QzQq;ysZq0E42n0nLYYAk3c$oLOxky?Fi_fIn|LWBqh&^1zIpGjs3 z=$Z(9s+%!@5?KTGnz6wRm|z_}Vw5G2ys@rObM0bVC%PS>*Go#bCt7M1?IdUymq7Tw z=tYt#n6Wv^-DKhe`P^4w;Noy$ggY5riDVFdT=Jd8bN~aTB_78e8vgHH;~L`?=7xlq zGxpRdjhw&VN(qTR9{L14t%||Sdr*<*g7HItBaOV*4?%{kPW47?SV4g|6Edrz+U>CY zNt#mBxJam}^CEr;3+F9ntxuo)PW-TIB3iy^z_&K9gg-^~)IY&5-=*~6SH#oIA-PGa z^if1qCMk+VXyR>%Cfzg3ALG)ho3CrqB_bp>=Z%6Vy-hPaO-Bqnc0bLPhU%)>2|y5m z>%xManC`q*gY}BiQyBl&s)@99xS~y~N6O zAtwuC+$O4JKjeS`p91+u-6JI_!n>USj%_lkq%0qw?%S{xr(ZNfM(2f&rxVSwjd_j; zUMo?@ygmxe-sI1mE)0(~yJF1OStY_Mzg*cPS8l2#N)DG_@Y`EgCEpJU|Gd@2nr9hI zT;m+BA3(3CI5(XNh9m^v}|X4-QVy{iiTI~Gb5g*-`7&XCohkz^}mX# zgkc$BlJ>^6w-3+_z_)-~klN*FLfM(#)~Tbx{way;1UZ3XG4FqoQa_4u2o7xGg?j}f zsxQl+72NR1!}(#LzpkmR(>AFFPEXdAO>L{0vU$+wLBvj_@rZFWiW4M}Eoda+XSD^5 zjcgY}ofFQA9O}yu`xYJ*7>hGL9OMN~JKlJd;w*g3_%!on>O9Qk?L26UvHC-3#NqP7 zXm{?r2PdqJdFwaNGIT*%+9Y@1ev$)*pUeKaZZoEK7!YVwKLo;u1!f6gNk0?nLx4lQ zLYo27)D)YOh}QHkYtF8wyUwR`ABK(k7rhuIzjlwB4YDvsey`Bdcjd*hTdSnVAa)&_ zX=B<~4D{}(cEKXIMwQ34=D+=lSI%tht6w_lawu)kY>5w}%GLrk9=jd#^`ghj76~a$ z;F%XMCehU>N09aHnt`zlLp(YOJ#0K`$gJYq#pQ8rZEDSKYrRjL-?gyqM#bf4Hj4*; z61x?CeNir_2|nP_xCdJk)m%?|H9KGNQy0sRj(q%@ftY~2rdBUDh*M?{z0`}R5m@+) zPJQCu^QIJ5Zw{voQnS^!&skMKs=OSkQD*k%!L>k5McP3GJz3pLoF~xKs+qhDWxb1Q zI~0Q$m0y8A)MTL$nin&y()mxlQgB+;V5dW+H{+%eJYFf02TVHjHK?Y$#UC6tr5KFpDNwc z_C{F>>Tfh<=vC3Ba4FuYJ8>Mk&a2%EuErzNi+4(%r&Cci7g56^$nM_XyE7ulQTKO# z{_*$(dIieSSCu)=mjxMrwCWd=v4G^m$rcLO*)#doy8lrk+0B>9)ST?t9-9N4MOb?B z2RzS%#rgS49m|;Pz{cFQaV3@O1AsKp+Xt7Q*!G*Yo;eXRhz6*ay4B1fd8D-U3Yjz$C2*T zvrVy`)*RQ53T6LHouLT(C9c@$>XqQ^@Oh8d!Q!)jiNWb2uteNsJRN(z(ELEReC$)L z^jG{M=b97$f#%8_ymYaw{q{#{oHl|TvO(PjaGsN&IiminCHsAPRuabV8cT*sO(-k+ zqCeY1eEXI*w(4A{s$rNl6VUr3XGbb)5$0mlVOf@v#q1nX-O*b4!jBwo|Y=n~y4j1UV*txLaBCK?c zt;@c5ROA~Lu5&O+wyYpaTwcvy*~?oW$KD#UT*@PjN>&XQ=K5XfhQ*@g-6>sNZtXJl2LKvc2WC>l{KY`u$w`wG;_tfqv2ZXx!Gb5YcqSr z#DLt8nG#JQ)t22#SN_x|GT&_~OCB!5{{H5^0uG|{Mf{~!_locnBvNvtlBb@kZA$qL zZ0x3n;T8DuTv7y6Mzc7y;9##C>}CoL^s%|!{yC|syNHB+CqWs4{DY+Deloyg7?ijm zs&9L(hi#804y-{p!BlQ;a0SRlHKi=!hB8tUVIBsaTm;c5V{eXyY==d`f_XM6cp{p#A8Go!+%26S zkpw92o_5{lwha{lC295{=!v-qO^doW zRzP4h8_v#eJ2V3TxN}RJ=bPI{yqYzRvs8Mw&FV%N>DQMbH2Jk_)S4Y*TnGG`H9Y5} z%nO9==EKv#)kGp~hf9pXGt|9e>IHOfPqn$Q-2X?4 znY-JjRoUsf_FP#ESL^QT*F_mP@%iEMtfg0SeLF}XX+@= zqrgjodlc(^`aC$o!mN&0XmW)fEX@Bir@ebt;K}{11sMvOyS|%4L_b{e8S_}ClC-q( zPN9T@1fkO@FOD`O8a8v;%}$F~VTdO(wv2ced;t)Aa{?B^l+& zRhg?iG;aL;Ip(Y=@%lRVN1sAWrSocdYl6|j{#-c)5}La_=om}+7)@2GeACZ8_UkqL zPe3I^g0*+lI5pBM8i{lg-D}G!JN7CqYvaYrfQOXFMjB}lPU~9a8nR&LQju)|-tJJR z4O!`FbBA5w)Z`S9A@cv4Lw=VsA+R7#im+n~)M%SegcN0sff} z3clEPIo@IRMH}RA@Y`Y;k*$ppV*Q!-QxEUcDotL*8y>d5U4#(pP|kaPLDn|-cR z2SP}6$SdwJwOJ*vMS*hFL2_H#4*=OEZtFXeNnyy>e-P!TZ99yjkBa|0gS)2AQLn}@ z8=sYgu~u?ZFixw{B*}z-WYby6OvYGSQV@7H%z>pj#f~vrX$|Oe3Qka;c{0ihGS_m zFASR-dtfH8Z3OHa$9lYy!S#5s1(h2OXzUo7t)S=s41mUa9T*mmXe*VSZ62bGBEG66#BTjxPHjj(7$(h(oFLZP5()O5-28TMyD|Dh58$blz9RbaC6)#1+wiF3Ytfd#5ma_yJv3Qz3gW+ z+qx$a1T*TTtATO7kG$})S~Il;E~e)%$pQaMMXb}wOQYlXm_VtMv_yeG)GYBDGtRe| zmuv5Y(m5>Bc!UqFpZFuVW8}CX6e2h9KDs1`DF$_8)Kj-KyLel^GPBNPM(wzNNwAx+ zI*Q7UU_-G1ULdY_<~&BlzS{HuvyOm z-hLh%YBPl#LV2fK}&CiR!c_-Xdl^X=hDfShIM`J8~Dr%-y zk|DL>bi~t=T>lGN8GM;u?o*sL{bLEjEF6`A@iD|c%|@7jVgYZNddV(iww!I3Kp~u^ z_?!%bD;8Gz9dz&37{8-B_?q{+ zSgSvT!!X+)ar%kyD^0AcPOrUwe}EPa4^5^k)~d}n%h^3!rc)2U9YXmqmsodb*CrzH6LWt9WD56FU|z z!*=GRPY^!WAFvAeIVlG-LD-K+t8e_vD;< z^r4AYy=8#C5$i0pO{E&j83E}NItvY!rxf)*z%7xIi0!>3$2DgRyV%~9#_EdM#+$L^ zDD)ReYXb8h>`pN5TekGjIYv=MkB2kQ!EDBmrL^WWD~*;Eue2iWj#6f9D*7k#3}y`O zGl;R)Fxh;s2sduWOo5ItEkjpDUO^);8Lg zLX0AEuGpCwgt}Zk!Ha8qS1V{n{+E~ADKbOdaM3pD_npjCaiH40fRBm zu)WfyHP^*-*JkbzU1Fy@O=I8V)&)YIS!>awmGKt3ruLs#>`XKH02ym2FWcK@ZwYc$ zJIB%JxRVF#_rg9X*DZ8~5ThuMfk63##LewZ8k(7UB|>flJb=0LL4s@0djn;Jl@Z4G zR3|1i5(=syX`|W6oVLgQuglF`?9XPy?U9ojCURmKBKRdI*py-8&dO zxmT29HBQLm@r6?!MWDXCn(Tn88Imt~r6p={b9(i8UZ!%;DzF9banEbYCc-?JPQ){- z+9Mjz54*jY-y~094RQ6|%~Bm2vyxPZLAIj986>ZH3cQ!Gky&`CngTF!cnKzo2}2*R z3w{aQ5WFWeI0@1!M&pZL1I4`v0d9%;o)^CvOVB70!X!QT^a|WYl?_$Bu@38LFO`tw$9}1966;EBwY{O_WU3nrwwKvDIEkq)f^>8l}yRB zTXeXad$5Bya9R#77`T6gV4tUOE7f;&d8eQk%{R5S8hkt?nmh$?mNd+YS}4*pf=nV%1`#uZYEY(uEry&)H<(U@nJ(T)n* zyBj2_F}R0T;PKXYcCu?al)e_O@y3z}i=??yRAWy}4*iS?GP>;RUR}4RT%l$kWYA@E zO!jm|0FWyX_Qdv98fss8MDcpqk7Xs|q-|DwB}p11V#52GRkzD{B}kMnN%DP}tA;Uj zIO=eu-%%>~it6@8f$N%Oe?n6K+DBvdx6I3s-pb1*=liMqOWh-(lQwD*!t218GHAQn z6zgmDKkS6_)xiA;D@Z=l&WmJ;-I)@x;cT$3_r2%z`U}hF|A|`Z&KnMVy_K4$Ru|Ou z5LZ*;ti>A0Dy*>XuA@k(b9gO{x3$}&pBJ}OTfgUAV7k3ms0Ir542 zk3U%A+KBoLj}-eGdDi*-WE)D_2*}34!C`E?KbFo#BC<}K`BXT4lc-x{&r(|`9G8<; z!e#~yO%{?*1k@L~aXam>iyz)3lTu^y;eizlnbIh!-}h-Vt;>CX$bTZiBE8rW^_F9$UKL@;4T)_7@h zrf!QCb>Li(ZasBLy_%dMhb3moBSet$*|Gm_k=8J>FyZyc5m;Dhc6I>&R;XMzdkKkQG*IF@f z%kA{c@D$2Y4ckZfjPQO$*?us+0QlApz($VnCxB+LoEq!ev<~_u%Kv1pMoq~tv~`s) zcZDZTVUNmCAOBWSslg~A+&LCU_L1vwVLqUs(@O71J=0?7GXHtjHlOpIzU-j0_t6q^ zb1H77)rA+D%t?YtxR#bW{K&dv(EFf5x1U5B`TEt4d$q|wh`*|`(Swzgv}ptaOe#WW zH%*&N?%Y&rS&-(bn98*7dVXUYC8oEyLWy1bZoi=}JxRqHf=4W6@CFUu|LD)+zF!YK z-#!<4IO6EAQ61GS5|hdDi62!a71L!vdS&mpvRn)e{Fz$#5k@JkUM90LFE7XR1G!g4 z5JQc;Np;m{^eUyT0g!~BH(_Bm5=25RA@MOk#GgVFF@#*}db(QelW#|j8M`z=b8#gGR3C|$x{3EPg&H}I zle&Em*|@+7-J z1rio6)$(+7MtQI#)l)o%oSyz-g@CO%EDPV1IMn%UNGJN0{~~v%q?| zXHP+8@<|DOV`o8XA+H;0k!&WfXY*(2Ys;tPsmRcupPs7@(mRQV8<{Q2Azk?ordGz;dk!6jVm zNDjB2a;PxBsh!dKnp|^nxZZ7i*H3NRT2j69$L9QFKrYcxP=CZ{QB2smnC{`#k z0*>&}7qs4&podIC6J;TOwg#!_7NgJV(kTg*VXRI=u(#t7%tx21p@-YimcRv6hTyY? zl-SZRRzy$2wHJkt0~oEdu3lVrJYg;qs_KRq4rTM zN;)c32{&UeCWmC$*^j>uWm!|}iCHc8pyQ{eFO}TU`eUpdT2DfwWh|qkV^ScZ2Vs~# z#&FR6941R62ECzihXw^YGQ46-EfVtCSQY(IBq{XmpWxwb>TdYJQDtaB{6e?DG3;HE zQoSUE8B_sOZ8HsDt2+C;WueAmhaAII;l404-?5-znZ5uL#EiwH9JWC{TO@!KF002v! z<8jcR)I^!QmFdzbw~sOLW!JQ$wHd-URsFob5IMQ2g_gf{c2C#Ewl1D}$(5bNU9IKh zBC?*vd$9eKXgdi{Kv&%()fNExSnq~RF!e83q2B*7q6a5QcXkS+6Y&FAiL*Fe!USBF z`t}tSmm`z$IVLcbx1;_0Q46GBf7#Zzh{^bQU2W5l^ph<}39`Zp?nY(kfH#;Iq6$ru zCCCqyqVg;kOi%Bz`Wl}*bbohNhfQ>4=h8kEpX33K&+r`iGVM>y9q_n=W{3hn#cyy= z7U*%y8r-IFufrR3@ZZWf=kN;PkW8zma9hM9C1eusDTh{_FqDe);A(8&M=+ ztm|KZ1wKR^IzHp7sIc2RW7_$D;oXrwn|~QW4fR<6F@pNhKMJ4KHc=DCJ%DRXUsgoh zIHGcuBkam!{i-i+?JK$H#BCiB*i;8?7)g241{Zn0Has=PQ_G=tFnfn}&dfOeuP>T*05F9)?Kc zyiDL z%=)p7f8$c2artvo^Cs4MY|gpWPfc>AK!da0PJ$KrwFPwLjqj^Z7YC;k)YRR>C5AM% z?!8E>nyb*J4kU42T=p|HYKe3;laqC!hZ*G#UT?64k=TPL+8q*6qch5{hHme?CQ^)K zTbbjMSkFg{nVwgMMxAWYztbFp&*n}UXq!q7f27&ccoJI?o=&AuzJL_jvoeM!J5W{A z>@)Ui^|3aLS!-)sE}xuXA5XV*<|EEWFMz0_HS>zU;Y4-2d)vRY4-G^gU8lUieUN~~ zD_qd$c?HS9I7#hIyjk1l4}b2^dO+X7#@UT%eY&2{Ok?bnIZioPvfq<(*9BySy-RHA z6W+a4(bFrSqbVP8aY#BK4@bEwke8JDhleI|B2UG=QLLST|DMS87xuLhfqVit4k7OE zUZ%>u(i)V^w)a((x9pvO6Fc!K^-KXiw?K=h3tm(0HRV$bOz2X1b#m1(5*`#}vgo+Z z4(j{55@K$rvL?v+SOmllniKi38tGk{BxK&w?1!O0f|$T!VBD>Ii&!tY*R~N|SU=S- zv$}TWb(I9l)J%N)XZH|afYzr2QC)DX-SqwqItwIS02hE_M1(f}{X_&>DQu$_VC8op zo~e-n&*E$G6`IYMqS4Tx(P{);f6X62QHrD2IlaWnrDOChxyJ{#@!^l|d{$ z@1fFX^YfQ%9}p|mO1AM~k0ke}?A1`bUqHAvNE4LonxdA4HGW<&p+@v@l&G^i!a%ki zDnYj%y0~NN2lkUwdodNfUa%PSmxMh^QUe?9s4Ry!h3o|J6#vM+$&Ui??`dMgny1pA zi^O2liogN&%L$gPV^=MNKoAwELFsDX9DXbPg^^OF+>v-lNw|N=W}uU-!ZLH(T}dw{ zq9y&YyvSv7Ww=$C33)iN{~juY=n5;ObrEu}GRd}{5`|qaW%p&ttrcMe6O7w0;iCxY z>0{OA{A?Ue1)~twi(>~HnsCsvkvs7t(KJacXTBhqMt6d97GXX!{ek65RjopD#eZUZ zipuD3$%Fhn8= z%;i(HgHr9U*h}+HT4v1MZTYFt{-RW$6E*RafpE78Nu&OIccMgO`E%&ytMIjEDrSaz zW3MD~%{-+sKlLwaTRPj_&`|G2?z)DgvO-yjOodWK7a$WqmzV^wvdGH#@rv~>gEQ(F z=QqjGkMOtX%lDLlSWneOE(wFI^$A~5KUWJYdWgfK4qcZZpSHUlsfiZloKRy7s6^?5 zZV)2vy~HEQvv{ra)kK{BS_;&BY#-Y<%mtlqI2t?xv=+hr#h^ocxDgPFjq{?uLrRn9*KI7Z`` z!0Fm+m0X~fWt~E1gMm%$l(eNzuPtmvOT%F8A&Y#3ltXFi=zt?frOFOPYnva=33Hrw zJ3~g9CY;ViuIBY&-xT4uSJ&w`4oN#}iMGS5$WN#wRc42sEoyjLWGgO08 zMtl8HJ(Wh*)xCeOZPbm`U9?biD$Y98?cd(Ev4kV4+DEdHmAwkeMSG^C(lT_H1BkY+ z=T~U*N^6Y(vBNqmiA$q2dF8~|RZ}=z3!39Clbm9E2d|O)6VyqljC%{ueu%LTr?0Hh z(4CaF)VmmUys!nqDv)n*B@vjK=J$IKcgZC9@-w7x9=HtOYyJJSXQpCNMKSRBd_x`S z&3@whz!;;(HGAykj$Os_%gGUo$&m8)y9qC3>u?gKFbumv4%tK}CWp_U37BN7NeIyT zl!6=O931`v!LKmTl=Gr#U*Qmb$)SjLQi*sv8`ZE*KJkEfgex0l71bs_R>E^cZGT@)q4kL= znEDg@RuzO2Hgo+VY-TICHQ-0^ZjG*o=ifj-)?n*6$4L}cHN6_RU($O0yIulMEjyTM z0j0MfqX|)X!k}^sUTDx@^aL*HvT5R5TL7$kBC4kt|LuAI??@2QX!*~v1ocVIvCpxi zk7E#hKZLH062Se9`9*PgL^X!?5Z~Fc!tioK1$nClXx#*v0pFp8QOF&p#!#k0_jAY( zRr3q?6IFz&m#bwFTE`-eW;h^V*9emCp=4~hRpJpE#*PNkr zG5+}98>_HbD-0V8uijCxqh))5uelo`|IiO^SB68R8gKGqZ~CT&mE)l>1vl1?d%3#o zPllNi(1*O84b+scj;P`rR|fo%Bx^;H1bdH3s$B0l6V?w?L9y_V$I0@!$tI7d^}ztgl>XzTiOfcn)Gxo3ouNKp!(i z+daYvl39GoO?szzceYpz<-TN+{DfA{Y@WlZDJ=ZgiSVL^Xlzh4sizH1u2s=9`exRI z@r*{noCfi=rIJ9yl82A&RF3oLX`Nj!Z+*WaYX6VHD5nwc%(T!rr83jCc`1 z+$2^xC;snumku%jsW_d8jt!AI(*9N`(i+ zxM2k_H6cgG_FfJL`w`zKxy}GZ-l14d<(IT5K(P@C?KH>?hLG@UA_+03`v#+2teh+a z|JOF?l@f7f)4QHQO-QZ)Pj}b|jG{c+vNRNl^Va399ySc1*00ibc&>A-Usa?D3>!c_ zRSXv=oL^C8a4Y{m<1UJ<(*L*Ih4R_NyWI1Lp)zg>8AfV^OB^IeWcBrJ!{X4v1u$#` zq5F%CsaTm11{zm{w$b|#85FD3OBd#p@f12mgqo1>$^=z1vVBFWoEfh~qs&KOu8a^=3P>g&C7`eyoppC~5KZS%=ot@SR^{}|w=0fX zOxQ-IOifR5Zd9Nq&r{(dq8(CRr3_tk_o6Oo2{wVg(j~!^{e@PWb(3nVL0#@CSDJ!^ zh6!!yQ08zpFJ$IY>bnj2o0tFe`7^bSQp?hVI6{A+LqRdAaqaVhpTr`=vUdtdrgP(f>FkDV( z)DZft-p5s(I%_#AQu?ea$cwxXIkTtI>~Ip>;Nq`POX`~&JU%MTSs{3qxBOK#R%wy% zS}8Jdr11Zs?Hz+FjoNm>uw!-XbZpzUZQHifv2EM7I<{@wb~5|@X6Dp6!IUj+}P%YxcUMEtL3Xp2sEfVvKOFCG*xAD|58pQb9YI>WSnxjeC zE8EYMgjf~MW`79R)AdZ|aTR`_8z3bP=>%fKrq=$B5R`s`O=laGQy!wlEg=gdC7kxD zl~jT$2;n8}HU6PJYDitD_%Pihs+-Vdalq9dq>| zEo*1);`w`#w_DjMs4U=o;UST4IE_q10OyMy@3o8VQQ#zV*Ss;vQGVqA)7%dtSGnciVcWQ^c^`is1nuD0Gi z2WHAKvc~t2yrA7O=088T4?vIKmh*?)><@YZhvO{)iD+v@I`PqFQ5h;v_#!p-dpmQM zZv5u+ZKpSDi){V4i{tg;A9y_Kw=OKJ*|i4rn;*sR>t_I#vT6OT05GHb=856j>0C3_ z4%duE;=?l7p7V{r7qBeE-!S?S-|;spRRnK2CY0N@4y-H?*R{8t)A;T1q9OHa-Q zSmFW2oW|hr@U}kFfA|OEv2$Wu?vl=EqUsp{NN5L%$ocubP2JA#m(kRJ$#V0gVa@(S zY5=IFm35lSoAx~P`ooZ|HgLx1gsNolG5d?s zuFwijUzyy!Osu)CCfm~S3TEEpY-uTsdcfD}O&$9{xjTFRCtUO(j^G6qYuf#w%S>mrH%76M)#7{Zd*&i_=KU@(m3><(f9MK5Pdos z@bNqT2SMhQN_YHk%?U@dtLl;)Y^73-tABimOJa&!U~+yci^*{r<5T2R;zFZg5B4OH zwZZtR9D0h`-RD>K;XsWq*pm6QkdxfDx0fy0y9MvLH6Rru;U~Qxqr2kpVH&n3o3SLH znYo(KQ=2L~_b0G?o8c4}uUITyiD;#KWizQhS5^qEWZ|_h01N}72kTR$4C#gGY5}%~ z7pE@{sd-!)?`eg|JVW;z%>U=tB9N^gSw@GM3;)UC<{bB}35o9Kna8>Y(2!`cDBFSl zoFCbd*6wo5?KI7QiIR^TRLw+~DiWYXTncB<&miUN9GMMBk@FF13Gm|%XHNGD3eqa? z4m-GIe;zq!dcRodq~8J#um~`%v%Z0@tlkeSn-7o>Wxr?>HFDJ=wi!>7X%Qc;7e047 zYi~a(w`?*`$btwF6f!!va_S|BzxJF$J9o`z2u2= z@-k<`SqvTD(Ow=@l65Gtjlxw%^0{39#4sIwSD`Q#kU5Bbh$_R}58Br6?yCi9;kzfd zlED_4{AF{^g!uF1bwBw@gp%}<(z!s+Dz&QiSH*n8Pb9T0xh2NB-K1w37tMtz;{Hj% zl;H?h7v`6qrl4Sb3z3G`>-m{4GyKD#?F(U*17FU!C4z=pQ@FM2XDOzEE^V8;TK>_N zT^(m}*)?uvI>R?hN%u1>zAbrGdLR)WV~-t*fv&4{4e#GY>%Jg8d^)`hZJPAv1+lqm zU-BG)_Jd8Y-?BAtB+ZVa1oW_RZ^@Q9;&x=qvhN&Ee9BeGgNgNs@eQ6ewl-QrLB2{R zt)aD!;c%F4_pLJn>DpxE8cFhN1JCTa=HbWw#E_&(!Hd)Rls^={b-o~jtb!u${fZ0a z+ttd-a=n$|D<_5-_GMtna%ia+-l&ky{yCC&Rp)wtW5*1U1^!!4>M|M6p68Vyluk$CM2W$f!n07@B&#rQAvL^q>^%=CS{qJ#*_l2Cu4rsTtW z@=)!Y@!A2kjGe|A2d!MgL0mQRMYxCn%8GpXPC+np)j1stUTilZ@XV44MZvlcG4Z0_ zrnHC#F!ra|auywR^2Nw#@T=r;XBB`5Fus z*4cjQiNetS5!u_>PH&WFrR8xF*NF3?P0f*55Vpi5AJ}Chq5)ww*7hU!E~rt+G_o4Ue6)_?Ru^a>87MH_dLS;3C$*@$*$8M&+0o)Iz?a35;`0B+uoZhH8jI zha^bRTH=Y2atZ>{EV=P*AV^4|)_8hyU7rI*p4FO)Ya5i%VdpD)JrZ*wO<*3i-OY7A zzm$_lN5#Xd+(NybM=93FYEAgdBv6Kkuk)LWRLeR6I|$by)x)dv{iy8+QIj(`LIF|I zf>`;1s3Fe{G1pF4T)RaWjsK;XGE@_v9Em=5Ok8R_c}>Imko7={x4|6qcB+o1yH?7Z&7&=7Lu|233c#fR>t!Q`h8@=U7SMlPuy963&XBxie(#qOMpS2dXOuD5Hvcn)ba00Sy8A;9t88{v%)XU98QBr;HmpIxRKv!nQ6CehLzzl8JWMV7`*CKCH z2~ZWZwZl#;QYd&N2b@%d&bG(`_2R82 zqo1;voA<0>op&FXp4C{-wP`^LV9uGYjd884071?+GFFX z$@YWEZ`6OqNY#a#^0N|B5<(EPmtTSLHiCDzutknb=S{u_pl=`v*+Wb738U@NU4CvT z0eIVBp=!m;HVdmKU~`RQ9rFDm5$H7QivzHy6cR<}vhc$;ggOvXjejug zgwqA&wkAu6hE8sktzBXA_E#K$wgjbjxu>_k*3`}!*-GSYAgK>;FHYBmn{WmPYuyqx zV$Ak7Ta&Xr0uAkEc7gXu=!nlHs?s)N#r51i1uNy7x3?xa$^#DLl6A(76LLmVrl8DE zjj4UZDAB-&e)pZCu7#Ns<4C;jsKfTE;`G-0$kCqo;)s?-{+AkuBnbjd?_aumMA1)Q zdD%RATXH0gj#zJ%W0F7Kqt!+KydGQqBaIyEq5HhgIlE$xU;5I+&faGW$nELal}=aQ z-*kolYY?oP6-DrupFox#_O|y6a?iI5t{!)9%o|^K|GCS|!k}mMebuUU@VAOHu0;C8 zD#W&tOAEdYe&%=?>o(5oCxvb-uNLoD@sdDZ2&w#uJMluQOdjX_i|m}K-oz8fQMYiOt zJ|*qPet*;b2$dV={~6_|eP8n{Ayt&hJErWl8E<-2Hh&0>Ql(2X_y^&7Qbk^d5*i*y z&BqQ52{}1*%HWPEn)Zww)eA_)&R2K@V^0QiF3dXoY0LW6n&39mAJH7Mt7Is zMe7^04>`b(5sDlSU(_ik0cI<}kGB-t(pF!jrRv?5TA-4#ce&>Jx0L|!BjldQu}wSAuGBlhD9lR z#x4*vJ6f)Ph@^Nd1NXx&;;$Dwp;eadCR0K!mJv1Zk>&Qu?VR9Ij}~8s*lbz(uZ+1a zPYI9*_RpmeYRM&qNf(Rl)$T#Y|3e547L{$qLRhCV@UYr+dQvBAVuE;2S+qXb>i>w< zbor#hb9={_pBGZS69E$q1E zt_>1&JHP)%^G%5`q8&Q?G?lgH0a>w9;(EpREh75rFtwBZ10v~$mSXCBwi`srQH7zD zDhV)3M!@TTIRQoq{D3VA!e-CLdS3Q9MNl>P!!=SY1ITS?*aIEbZ&dp1|KLxoAE6*Y)K)^$V*EPo*49dHaSU`tR8m zWQ}rq9G1}Qb5jV`YU*4NQJt!lU{WnKI75`xQo{6>*WF@Zks+Oj#XCheyz~vW^3A&g)kCGy+@XiXo2F4HmNO*^-s zH z7J-|FCoC~#+pSy!Z!Wqd80_>#PB6b8d0P(~Dvt>CtM3QmY`QfY-x!a93M9PW!dpl% z62F=D+p%4v z!fRF!<~a;N?rInMqd@G=2)qK8?2(v6u?d38z2WEMdy}meeN~V+D3)Etlq0Ag(Z;9Qy zJGm=cNLRq0JXw-`W_(J){^CxNlqtVX84BNVbt0IOd}mcBpWx!_>YHU%sV}}JVD&`xn)Xm+sld&~hR9E;$eq6cN{$0= zRDXCt32CX7@MnpAe1uUCJfH9AfM^FH&vACQBAM9nh?{l+k!M7f7-u~|pNn(tUROG( zWj`;h@}iA}Wr_MQ^PY%wV<}E>Oqil74ChG_)1NYRzLZD62S>@}@^G4VdbCB1iaeIm zFH826^BqE$dnyp%=M816BJlijAZ~)M?${KBTX9^sE1y`+Rb@P=zg~P&8=Y2#tlG#P zF|9f*t#^SDV=IwtI-Ls`UJ9x|DYhro8R#_S3X#nAGo{SexQlW_8>*mv(ns*zf&)cYOy7A_Eajgu-l>bi@)2gjU`VAkRNa=b` z){hMhm0?SQakcc9mgj6k19X`(HcKMML5C9AKWSMR=pli!&(nJ#kp_jq_F1#D|lb&ZNtH;*;vTdAb_Ilj+e^U zJ7u`EcefmP>uml(H|L8wgy^TR(+4%4kJLIE@RlY{vAKcS&j>=WZX4aM z5M=SWL~;LEf~^D71d9-9IgXq_t$NN7?w#ztVq;4K7shtzQWk7~D?mVTw)Tj=>^ZUP z%ri%x&*aUhGL*}_bv!nh&=B6sX?(Ed>4VF);tlNo9*CS=^ftzW$u0Zf<1q6%m}S2o z;F)td>w z@;}&f+#|FT*;KTi4QG`S(^p4c)&n76VZRCgJ4n!>q2t)mE!ezMV)c4AlRDeZwgvZR zA+3zd0UI27g8W$kHpn)N=hv^5kssZ#=Klzn`dF0yf1`70pb%dXx^B7dKUgxo<}9x? z7qYVP0#eJYiFNJ9kmX#d?!5DRqy9H&p^2X2918I@vFjH+{L#u$PN$ack-r20&+Mi8 zABkK5jnn@?odwFq21xu+09r8vC0agH9~eMXeF zERlDQ1I^r}LV7v_oXgcQ6Pgo$Vyxv{^whL{tn4oaavMJqh@)g>X}rQWutRpQ_hrQk zxzZmm(lb-m>Y^;j;bbbq*cK#DPI~n#++aOJ#m*Ft=hje*0n>BedE;!1RWYhm!yj(> zyqH<(R`tm!Nv6ur?)$;w95LOL$_>ABcK0AnyvQ}0JN%(h;+4GQQ+lDx$_BO z8gV1G^In0O*}}iOeC>gK*&LohP!*_##7yW94E190G|~A6Xrx+4v9`V64LpzD>YY^i zK2gY5Ig+_PdSz^XR^HyH#&Lc;36ZbQV|@lJb8PI9r~lEil)F7^w=cx}!~cIq;~KBG zxEh2uw0QG#oTVW2>=^9!>usvsBcnyjZ2M44@yynXcWEy^r6H#(cF(c)HuHD3R#Xz~ z(jGKy30HH6!F=rBV6;%@D&Mn0udM7{ynLb5|Q69W}pd($quH4I4X8gXiKyUmHUpBgEB~fp}jzh#x4#4g@-_kr+gG1#*$V{ug z{;k+s%FW`|t4;2@(jJOF9to-?{uki)W-FlBdO>urpsgAIMfkt;^iar~v6PYU(KFjZ zSrazMXcG>=Q{c2TgbTIs=*dl@ z*deo?-Afdl#_-%5{E#Zr%nDVRMz+0*ibrk+4m@NvAzC8M#*wI5VA0f5+={4UzDMz6@u>f|nm zJCS6k`-M9F`sH*2EnHNh0nDG0rWOy$8;$VZmp^8_7ZiBUuJ_jpGQtfecV7aA;ohSA z_YuN}|DW*4bkhIc3O+hL;&Vm1h`~UXp^Ieei*wfQnox+?rAHRP$5d$yR$PTjOt&7K zn3264n)YOJ$E5aX&scEVJCq>zo-2vMdo+_zWI#zhWBzv3hOE(y)|Vm`TlN`x{Vsf? zeVUik7~_(Q8NzmBWN$cj!s|VdK+8tv?^EHJ*kgj{rc^1c;48unGZ;2Y-1WQn@rh+FYn7cmULwfo?J$LCV>WaarH z&*iqKv!h;@$)E`gfvebe_$F?5{gFDBRCz(P6c+uBsS!E8Z7Q!bCdJ#&5y^+NM78Jn zCt&KKl>W6xj=chOonjxYR{tRY*_eIn_NCczZ;|y_4sUep2A>*h{-pll$J62B>!!hc z#p3?5$DP80n0*scp04if=-S!qv$u+~23ea1K!=Cg5!J*Z%J(==k_% z3*62kBpuFQXxWri|M%>*Uy~?$0&iKtn&}_M*L(j0KtEd?38$v6H`gCjH&L^jrm#6K z#SNz_cI-i>L9N!}6#oUlWsc6Ocym4#MSnR42p-oL7M#7{pluVwx(s+_zTb)-o*AX!Kkv@3{0^eOrcXK64%t{)5R?A4q z;g;kY+dFs*+aIq^OldS&aD^wyHlDspJ??C2$`suE2E}2o%bbCDD=b@bH&ppmF6P=m z>WS*W$1A|oXm6kd>!2}I`)GQ*0+l7p+1C%z&oBnw^4%1b$SJ<=t()Ev@ZfGgA$7r# z7%zRl)`;^_gl;?bkj7{O!BNt|jp`It_z~;qd}eN0=5hIU$+Y|#TSD^HnfJe!)#=^+ zQ8x7$`$Iv2OhTTtpPs4{6nK|pJWYIoN-!XxX~-z6gqR;-$$-=cRso-YyfD`c;2aT< z6W6Je*$~pR14&2_zmXcdc2E1D{l8+#MYyKsFx%-1ZaY{YF~C zdRR?pJcV4-SW}zAbTGI$?!B}O1;%xg#B`@Bm!o#d0B>4s_Odlk<>h`w`;^vNdz56f z&H)k;BaC3^*lGm}edX>fv@JOtZMZnPtnfKNQcB!rdsPi0)HAmfJ#~LM8NENo{1b%l zjj53lo)D1!^khpnc_rm&jeog`A)Fn^+`X+>?6AT5$RhA$)j*dl6CR30vpF~T^_WDg z=wg4VE~T9Ua8ACvU0r^y0Ak(Ts%Ce!Gq#HHe_-3Ty$CNLcX#>rAHX^_i*>lHs*k&` zEwpdgg|4Ak?}Wt+zOa)V^P{ewl$o?u6otQz3^_YZefllQkMQ2?67VTQ?PK-F%8C1o z*8r!Q=Hx#tyc8P%3oi!1!mAXXE6FI-z+lT=!D~w%pLSREzDH?g>CBdcw<0tW8BB5Ydg%YA0IyxXz3JectpCsb)U1va)n)Z=|O|XPj;GyAw5l?avN*@{ff3HC#&TT)u;9=uPmnMmeBWMOOR)>Uy8Z077OuH8g z=#NE*0iZi&B>-(A0SQCK&a?f@J5a78lh|8WAAQw2xwaw&F?t}v=NUG5`3Q#0kSl~%=soo zsF#aLg7Q38x88d=2QdWt!dQfe2WCFHP4y5^dZk7SlpIR-mg&7hma`*_XrROR48#1j zFgA_40}L)byU1v7_@AyY9e7kad^+WS9_|ReMKCz*5~xQ_Z2yVn~yAn$uEDt>HcmhGtz<=Z+Wf^DCIxLQ{vU3m^ib2Pw}qvYIk! zHnTRtD^LlCh()$A82&At$oK7~q zt~Z^I@ko7^{Vk&*f+$59I~;+Y3i!zbU(biNJ00<5(9m5Mf6LP!PGwUQq&K#~Gy|a? zg*bQt-u=y)hF?2RhR ziu?wMuj0yZNoaA7iXiS+cY>hAn!Lxw>W-R7cRe>zL4kUolngLPHr9-OLNGHf#(;S8 z(sENy04!q%(|LC{H*-BH3kZ3c4~9Z7hZbu@UMi&ELQ-R`r13ZBGh4*p-M&;c%>_wY zx>Nn;@Y&Whd49$5-SZ;3mZIspru3qhxfXu4=uvvVQ_FkZEfO9Oya2qv5 z4cXWRHV3h=%uL4syPXYAs@&P+J(gTchEosyKpo0@oZ_n!0$;_a*8SHIcALQ*2J3?g z!)~#OG?nz;_y%7LOV(r6x*3|4e`_nuOS>N`TNU3#${(UH~n6QhxK)274E)} zS+cmom0<7q6ubR1o~bzes1I@M4K?}J{&zd*8u6xhw`5VCywZ(Mh|0O!erYF+_33nI zHaLy+#ygbPawR_<8HtF1M0I7rQ6YByOY2BAazxVb>)4h$(`fWGAPu}IomuBS=*F#l zj1fo0}1S~oS1i(~{e+*VM*n&~PC-c*T@ zIHniJi(fS+>Zxe7qCoR@W*?Hvs_&#G0E(YTw5>WQJC28SUXlMpS^hvhvRY%*w(mXn zZ}d3+2BN_r482(ryczFkRe#g<_$cRaAIV0YhOnDSDPi{ssiJ*$hCl>0d%CM{Zp7# z4QpDE;Ks&&!fa?_bo4VZ{-lhokoo;e&m}I;V@J5@k_BJQ#^;9Cv+#p0lcDB%=ho!F z4{G~gf^Rf~Yv|QzFr_K;^4Bc#_r1q3BjZo)s~QK)w!~1oQmOr1Nn=|uO6FS$V{s%V zTW!{Gxl#)sy*xJ4PoOXuCT4nXreAWSJP#8t`sBioEz9=?q$sRDBWyKj1mi;s_Y!0?Fid|!1&ySuxS(}2SSJR^Wfm&VEf;(Lq70Bb;w zS2D|uD)9Ya8fAd_&*zw(qtk-_^H2?q{~05`exmoBE3!8-Fi9wE#}~-#o-%(V(q;Dv ztW@zNXU%`e@3J4W9Bmt88DzNBqv0uAYPFLDICMH9?Cb@nz*$bg^$+-1c-W2uV(A0X z?LJKNZP-BAkJc^g^z~{W&j@XQ@m;04+8sme#23Wq@l>Ju(*)-w-^E`vBR!F=P)l7< zfAE!9yS^5m(m13=yjo`XIJNR0!Ao8y3OZ2q7}EXEYQ6`TroU9Zj{+ug2+HSg$h4gH zrY>irG;qY)A8&rhYRfX+;91c=|Aq& zZgIZXh%wq7PCqj;o%F?4VqLH2>eN2#E{swVEk~P#QQlWFQJFo^r4RT|IE{6l#@No+ zPn;z+y~n%pPmDjzlCEeRy?LRnY~vzsLz6~+!)a6O9k!^lrrU#ODpn4o+vapE?Tj%A z-F9%S+HJuXp=yQ)N@;C)aygixyk)>M{`8AJPH^APPXh-8I>VF4y7VD~c{>FYbuNn0 z(iQ^7gT0aJY$UK>D?G|>LykUtXuh}5noHyeL1OINn+9fthNP~3n;@d4tZAut{&RPn zuHNs2hCw>{POJo7OPT7P&)-D$_p(1xdo+}NBN`AZyPBtOYttX&I80PXdI;{nP`R^r z4>1Enf_et_F868D989i0PSuwXJhSn96|xy@znVX+M}4u2L$htjVW?B)G14uWeQqG6 zU1Nh5Pg$Bg>%5orNY#cFHo4^byNd2tPnO|@tiGN?8F*{BBZojBpn<+Y|4^fi*}4d% z^T|#3NSv-30V_HqTs!>M@ZuACslh+6w6=TnaUvBB1V}mm7&5QOm5^ zjVTxc{h|9~aV=%e_702Xb4xR<)*haGup>J2?C)?xX1)tcz=cP&@zn1<1Dtm6gx!Xh z6YM71B1X6J_1bNR874h&FJMFOt^~H7QxE&phN`rK^Ow~_SNyXFv7 z64L75Wq6VC#1XP1B%5J;1~MK0U3O0uCw1Y zjb-m6TkA;Bpj4tM`Ju8x-F_%sF}hy zcqNw$J7mt*t*MPANsF;JTDhdKwaHg2E1YPg)awk}o6JS0$KG}J&|qNehV>cZPY6Z z@VA;ME3&#V=S?|dGjL}six`gmtrL=L@sDGP)|oi}1!F~1ffj5y4aSCQD7*G8I}uMw z$7BxT)%Q6sl%3(o2cyD4gGh!%ZyNQwt3q*C&;}(n1o{X9B3eGOKO5Rpc)yk#PFag4 zS#ae4#AWwzNrjI8IeAon^az&YiqcA8FM>{v)XAYiEIJp=s-%~D}sJFaz|(Zd{;ce;{m<%FL@?X(Q1?+*!G025Sb#ZV%N*ljrc5Y|rI z{%l)X_8QNxa3P>qnA!Y}S%o_5oWtv^q*Yl>L9~6e4U)j@Ff%&t`~Ytp9D#~?SW^Nd z|9C#0J5P+3d-{j`?D9%VF5A3&xE5Vay&L#p`LVb+GrsSS0qm1oz9LXQJy<4f?ntX@~{k#MUq`(xV(euLKKI*kHfCjX%GF6e82YtfTS!HV1-W8|wg$gL? z7u$C#lTNe~Z*J;4k~**W^8_yh3S+k`a`Oz9=DgCxu!q9t(Hj~=`5`4emCL3zSt#db z8o_%zNatuZwAiZ@^J^^Cu%c`i!$1@g8tbwS9?i1I`SXU!qF9V785VaZPEt+dhq8jp zUW~-mF$Vex-^TZyB~zR}n*y+TK*#G1)ipdVs%KW(=g_&$4C*Bm^46Ec{eoarKp^|V zUHCXO)Wu0tA;^{rD}e+N%N&?ycWVk?A}7*^aIUeGvZq1F&AZfV6gfOCzyxO*&%3uK zn^(}?vV-}v4yAWBww%iu-k0CdA%Wu2m2BNxO^dA`0c^w{ zp2_UPIB_xyP_lOW3hMRq>3Ddu%8<*HX;VGiF1^ucnes63GR8C~{SGBB`L&_T?_PjA zfj;+ObJ@4*(-Vh@nj&kVpslg)cD|~_*^zQ4qq+a|=1lg+v3b>~-&2=D0BOvyJ2h)a z2hR~L8ck{eJFHn*uKEqWY#Rj$OgA0>rmN_)yr z<^t;LySH6r%fS}?v^ag)@Y>S+Pm=^S8gv=m$=*YIVI}mO(#U;Q_`_!PqIG1jz6gu~ zvKt+@Z!D3_!F$1cko?Jfwd2oY;NJ@`*S#tVa4k0cP)z@~L)J@as()kIo$-IdZ_Vei zT$&NOXLeQRJ+xDSM1pl+d3k}oVzdR%r{l{C$R%nDZ=?vv5#B&k6=@BY{x!%0$*cSz zdMPP6SRC;usURLRIfQZ90p|%%L50SpJO1)IVAH>d@i@gS@=t09&xGIXEiI4uf`m{^ zh<7xnJhuWDFR#4&puJ$pKy$LEcz~9@T>lHV(YpVzjE6|GQfIOdE{4B$bqA87GxKkV zh^x-wKz1;?5)=;F-t$3Kn-&jTnQbI0Q7ta33+_gkQeXkI>hlY7k{*CH9^7uQK#kx2 zQFnX$RZ~i8sLA98$?aMU#iqu=JTzztPh!54OArq+GCzDq|DYF>@bKczxy27X!pOGG3 zRJ;Cs{al7#KHGT|8JNF`~4K#s^v$KD>gY2hap@{Hg|ZUSn9#j ztYHXk+d*+Lg}6j}6sk{9zCJB{jdrNi%NjqGcXCq5W9FK;-aR+>{N>rvE(Vo=>vRW2 z8b&S@=hE;8)L5GX5hj=D%HI^sRpvV->+xon+_zOuFVg2@pbV_S`U6eM1Uv12m&dLz zIk|{12|bum3~HW+*Mp?24VR8}P7AguU_<-Gtta|JCG4Nvl)p#FT!c$0Lh(6R!SCi= zZ6#zxDS39ys9Ed7f4yRY8IzV0=5hcg3f^~$U{sH}Ja!7BRi3zS5o2PgDB`WK9li|Ql(W63S%+aK8F zYj59@U%nl>jLDSj9*Uj|hE>Yxv_PJ19TSAOsJKWdp~m3l8irmdAVSBpFg_LXw14iR z_+36=bUV|(@WrJZOEVgXKh{!bqafjT9AoUk>Qd;GB+@(ex|&0v{(2;W;W$CXfc>O| zxZ6LVDR!?@3`fW^OJ~8A2u&bDW=&K{XQpvW^OY8A<yaTrJqcP7i^nE3cT`VzX<&rPn0ComEfa|@pXS9u!3tW984ZRS2(0;+B`^@A1c>8u%<#m)4}XOd%j5SUT+^*g-~3!* z{pD|b+$5C6;9)uO1TYF4q>$(I7@9TRGCpI*U&}5dV>cm2^C6RBRHht3YoHJZA3UUB zO<2J%o}z+{W}LcThUnDpN!GxY(O4jm5)GSfGIzUlxM5(81o+@!1Yw9aG?>gR46L?X zf_#|~biE&Noqj*CwKd=18)#Ppu{zNt>xVjx6r+CRL`QSIhY`mMtwg-*i zVgUn6qOL>qH?HRt5cs>_hn-mE3Ti^Wj&Kz+x({P)0-#PT8Q=ac_L<{|l=A#*lIpYEnARWjYS&|z z=TiI>v>7YT)?_~g>{J9uo``-GT|N6*xcnBn5Fb{MG(qVBs0=2!goq^i7LrYnh<)Jn z0{XfmL>UT_97nIcyu6JBW7kZ%Z)652m;`mq;oA5k4GNAoJk zRA5t*GvqHm4B_A})|?_Ksl3DIB-`8BNdKe|Be8191?z^M4yYdUjbdQuws4h)6e1lh z^lCkCc$)$d?T;g`swoidOukUn*w^=nRz-WRI-cz>SElJKtq|QlXmPgvJFQQ+I^y=? zh`&)zCvks($7iQ87@E*MAI)RWw_{hPQYy_HzTtsYSRQd$!04V%15}frUS!H7i=Vdi zBxU=DxPek4*%Ot4pgoySe`tU8%!1CaQR>~RP6dU1hegwXf>X0MdgHZh#`$k1ruEu$ zNh9uRccW2mXu_w}?!{{G9VB7Ozpn5{17W{dP4i0%kaXSd$%(W3{dU^$;HTFcy6L@Y zH~>n5tVV)UL!!URjMdP>^}(GM^2~r{`H&mB50VhiQpU$RJh;4}au_AXmj~t0QGyy|5OE;0Tsnx5eghgy=M1Q1exHy z(38cFTz`0tq_OV)T<=XK3aC|9Z*TUlkUc9c3=lU*j2AVKwr=U}oDr-er6)wv44h1b z{Rda#-*!QgqUqjXeI)-HVvq!`3@$>Cvm1+k56Tv-wz>kmT{RM3?NuM-Y7u5mO zI*n^xh71p{gBi+wSYQ`DMdVtieL%Ir61gmSng@M(5%EzqIQ-q@h!F%m9Skcqn_@~R zyQ=@yLC`nwht4b5q_?Hp?cQxK013Sz*WYe2psua^_54|g)!-4?0qcMYB`{(u^vlF%gJZ4b-!y|odZMjoQVBK3i(86aSsEIEC|FczHj zA@P)z)fPOUn8wa#i(XzH=7utsVDj=G^aZ|7E!HRkbVz?oD9rSdBf#5uUhgHXG{>&M zajRI7-qDbu#U(Md`PvFtFacWt_+xT-EmAsuPN{3z{f@;La zE8;Z9BQW3Zq{m#)sDI_>_M`va4&k)>?j7pfm~A7h*if39&2TK90 z-Nm9FX6rLokM2fLMqPf?3}x5hvnV{2!b0OU{j?VL$dM9fW7lwE^>J3KDTO4(XL~5V z$~Vp1_deWaojGjgTLs4LJYxxJ#Q$lZ!tG{B7aRU16EvyoFIv~!Riub}uM+d8vxm4` z4|sDg-n`6(rUJdI;09-i#Z&hLO=vAXMP1Vq7PT0n^mlswHl&ZR*(XZcz9Hi z5xe&>t9E~;;cn{0tpakjPJ3~9$u`8R$umE5`C-JyNUMR-CT~$$kbJQ&)grXxE!;pg zPYF$SV2;a#K%y_=9X9L1sEk@tq^*C+QWPSvIaYTpKHqsrhCmG>clTZ?^dOZJx{-A% z79=9A(M$oZk|zvBoCSdL2SZwN~t%OI0Pz zTq#xtTcm)xKi)C+nE1p>p>_2Mz2%)M^_d!83z`~QB9~wV#-HMxp*bS-xEtJHR-xXJ zg4V*TT%^MC5H~fu{;Z#7Q58Ry2Bky?o4a@gGt1U{O zNUSqtFpRx_cu_w4f;Ai(tM@j~f5zu5p`XjMI+T|CpSU%T# zW5Z*n7xI0#&c0GSa&n_x%Y(*e^Yf3*T3LHh9-GmpuNsfnw|f@3U(TGp@!x00 zjJTuxR+oM6oDh2;D%EVD?;gkRGDZG}?z8@k&H{PWqM+bH_xy%)Q$9c6w^!iJ%hdE9 z%O))*=kT0EcNBF6AL=StM>i-gQf)hPw?))hc>$9`Mai)%Ki@CPU7}wi<}dL_G$2Hx zA%2_A5$n0h0mm%mU!F8ixWulYvrIB7%-rVdV!Mz)<&Up7l?Q&k;!?6MSbXmC7>B(p zR~x*4>d?_pdU?9Ww)!l7RxO@ioZ5Chj+dU>UflIKI^y*u>CfSQZig4u@JwGeV^@}3 z)vK_?isRQRes+7W_@*BR}6S+grWUTqU zQ2oz;W%Z*c%``v9Ka78>Q=u;U+;8q7*V)XU#e#C4%|10nFYV5rBB|wmH~$@Q$UXCi zTS)NV&J!@@A?JOLvwr@vKf3q7S(701wWo;(?yo&=&vH{O^`G`1cQfu35ctPK)ZEJX z+LfDuQ!+rXZ9=jbm{B%yZfg$+#HOSxDg!~X_|3=@AaKLAj0`3J_}?2|?0j;fp_%~* NJYD@<);T3K0RVSRBoqJu diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index 07efca6339b98..9c89867025632 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -28,6 +28,7 @@ fmt geometry_msgs kalman_filter + localization_util nav_msgs rclcpp rclcpp_components diff --git a/localization/ekf_localizer/schema/sub/diagnostics.sub_schema.json b/localization/ekf_localizer/schema/sub/diagnostics.sub_schema.json index 2e2dca411971e..eda9e7d06f6f4 100644 --- a/localization/ekf_localizer/schema/sub/diagnostics.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/diagnostics.sub_schema.json @@ -24,6 +24,31 @@ "type": "integer", "description": "The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times", "default": 100 + }, + "ellipse_scale": { + "type": "number", + "description": "The scale factor to apply the error ellipse size", + "default": 3.0 + }, + "error_ellipse_size": { + "type": "number", + "description": "The long axis size of the error ellipse to trigger a ERROR state", + "default": 1.5 + }, + "warn_ellipse_size": { + "type": "number", + "description": "The long axis size of the error ellipse to trigger a WARN state", + "default": 1.2 + }, + "error_ellipse_size_lateral_direction": { + "type": "number", + "description": "The lateral direction size of the error ellipse to trigger a ERROR state", + "default": 0.3 + }, + "warn_ellipse_size_lateral_direction": { + "type": "number", + "description": "The lateral direction size of the error ellipse to trigger a WARN state", + "default": 0.25 } }, "required": [ diff --git a/localization/ekf_localizer/src/diagnostics.cpp b/localization/ekf_localizer/src/diagnostics.cpp index ecbeaf8b2445a..902efeafacdb3 100644 --- a/localization/ekf_localizer/src/diagnostics.cpp +++ b/localization/ekf_localizer/src/diagnostics.cpp @@ -139,6 +139,39 @@ diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( return stat; } +diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( + const std::string & name, const double curr_size, const double warn_threshold, + const double error_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = name + "_size"; + key_value.value = std::to_string(curr_size); + stat.values.push_back(key_value); + + key_value.key = name + "_warn_threshold"; + key_value.value = std::to_string(warn_threshold); + stat.values.push_back(key_value); + + key_value.key = name + "_error_threshold"; + key_value.value = std::to_string(error_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (curr_size >= warn_threshold) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + name + " is large"; + } + if (curr_size >= error_threshold) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat.message = "[ERROR]" + name + " is large"; + } + + return stat; +} + // The highest level within the stat_array will be reflected in the merged_stat. // When all stat_array entries are 'OK,' the message of merged_stat will be "OK" diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 11fa2b6713a52..e541939026d95 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -17,6 +17,7 @@ #include "ekf_localizer/diagnostics.hpp" #include "ekf_localizer/string.hpp" #include "ekf_localizer/warning_message.hpp" +#include "localization_util/covariance_ellipse.hpp" #include #include @@ -148,7 +149,7 @@ void EKFLocalizer::timer_callback() if (!is_activated_) { warning_->warn_throttle( "The node is not activated. Provide initial pose to pose_initializer", 2000); - publish_diagnostics(current_time); + publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); return; } @@ -241,7 +242,7 @@ void EKFLocalizer::timer_callback() /* publish ekf result */ publish_estimate_result(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); - publish_diagnostics(current_time); + publish_diagnostics(current_ekf_pose, current_time); } /* @@ -390,7 +391,8 @@ void EKFLocalizer::publish_estimate_result( pub_odom_->publish(odometry); } -void EKFLocalizer::publish_diagnostics(const rclcpp::Time & current_time) +void EKFLocalizer::publish_diagnostics( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time) { std::vector diag_status_array; @@ -418,6 +420,18 @@ void EKFLocalizer::publish_diagnostics(const rclcpp::Time & current_time) diag_status_array.push_back(check_measurement_mahalanobis_gate( "twist", twist_diag_info_.is_passed_mahalanobis_gate, twist_diag_info_.mahalanobis_distance, params_.twist_gate_dist)); + + geometry_msgs::msg::PoseWithCovariance pose_cov; + pose_cov.pose = current_ekf_pose.pose; + pose_cov.covariance = ekf_module_->get_current_pose_covariance(); + const autoware::localization_util::Ellipse ellipse = + autoware::localization_util::calculate_xy_ellipse(pose_cov, params_.ellipse_scale); + diag_status_array.push_back(check_covariance_ellipse( + "cov_ellipse_long_axis", ellipse.long_radius, params_.warn_ellipse_size, + params_.error_ellipse_size)); + diag_status_array.push_back(check_covariance_ellipse( + "cov_ellipse_lateral_direction", ellipse.size_lateral_direction, + params_.warn_ellipse_size_lateral_direction, params_.error_ellipse_size_lateral_direction)); } diagnostic_msgs::msg::DiagnosticStatus diag_merged_status;