From 603ac4cee9edd3d71669945ecd3c164b2977149b Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 23 Dec 2022 18:45:01 +0900 Subject: [PATCH] feat(lane_change): update path generation logic to consider lateral jerk and lateral acceleration (#2428) * [lane_change] update path generation to handle lateral acceleration limit Signed-off-by: Takamasa Horibe * remove unused code Signed-off-by: Takamasa Horibe * remove unused code & fix precommit Signed-off-by: Takamasa Horibe * update doc Signed-off-by: Takamasa Horibe * update docs Signed-off-by: Takamasa Horibe * update doc Signed-off-by: Takamasa Horibe * update doc Signed-off-by: Takamasa Horibe * update doc Signed-off-by: Takamasa Horibe * move path_shifter implementation to cpp Signed-off-by: Takamasa Horibe * Update planning/behavior_path_planner/src/scene_module/utils/path_shifter.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/behavior_path_planner_path_generation.md Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * update doc link Signed-off-by: Takamasa Horibe * update doc Signed-off-by: Takamasa Horibe * remove unused code Signed-off-by: Takamasa Horibe * add common min distance computation Signed-off-by: Muhammad Zulfaqar Azmi * rearrange config and rework min distance Signed-off-by: Muhammad Zulfaqar Azmi * revert some changes Signed-off-by: Muhammad Zulfaqar Azmi * remove warning Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/behavior_path_planner/behavior_path_planner_path_generation.md Co-authored-by: Fumiya Watanabe * Update planning/behavior_path_planner/behavior_path_planner_path_generation.md Co-authored-by: Fumiya Watanabe * fix spell check Co-authored-by: Fumiya Watanabe Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Takamasa Horibe Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Co-authored-by: Muhammad Zulfaqar Azmi Co-authored-by: Fumiya Watanabe --- planning/behavior_path_planner/README.md | 2 + .../behavior_path_planner_path_generation.md | 97 ++++++++++ .../config/behavior_path_planner.param.yaml | 3 - .../config/lane_change/lane_change.param.yaml | 19 +- .../image/path_shifter.png | Bin 91428 -> 148776 bytes .../image/path_shifter_old.png | Bin 0 -> 91428 bytes .../lane_change/lane_change_module_data.hpp | 4 +- .../scene_module/lane_change/util.hpp | 23 +-- .../scene_module/utils/path_shifter.hpp | 84 ++++---- .../behavior_path_planner/utilities.hpp | 5 +- .../src/behavior_path_planner_node.cpp | 10 +- .../lane_change/lane_change_module.cpp | 2 +- .../src/scene_module/lane_change/util.cpp | 119 +++++++----- .../src/scene_module/utils/path_shifter.cpp | 180 +++++++++++++++++- .../behavior_path_planner/src/utilities.cpp | 8 +- 15 files changed, 420 insertions(+), 136 deletions(-) create mode 100644 planning/behavior_path_planner/behavior_path_planner_path_generation.md create mode 100644 planning/behavior_path_planner/image/path_shifter_old.png diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index eaf0837c45948..1952f294ad097 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -155,6 +155,8 @@ If there are multiple avoidance targets and the lateral distances of these are c The path generation is computed in Frenet coordinates. The shift length profile for avoidance is generated by four segmental constant jerk polynomials, and added to the original path. Since the lateral jerk can be approximately seen as a steering maneuver, this calculation yields a result similar to a Clothoid curve. +For more detail, see [behavior-path-planner-path-generation](./behavior_path_planner_path_generation.md). + ![path_shifter](./image/path_shifter.png) diff --git a/planning/behavior_path_planner/behavior_path_planner_path_generation.md b/planning/behavior_path_planner/behavior_path_planner_path_generation.md new file mode 100644 index 0000000000000..da2ea34f1d673 --- /dev/null +++ b/planning/behavior_path_planner/behavior_path_planner_path_generation.md @@ -0,0 +1,97 @@ +## Path Generation + +This document explains how the path is generated for lane change and avoidance, etc. The implementation can be found in [path_shifter.hpp](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp). + +### Overview + +The base idea of the path generation in lane change and avoidance is to smoothly shift the reference path, such as the center line, in the lateral direction. This is achieved by using a constant-jerk profile as in the figure below. More details on how it is used can be found in [README](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/behavior_path_planner/README.md). It is assumed that the reference path is smooth enough for this algorithm. + +The figure below explains how the application of a constant lateral jerk $l^{'''}(s)$ can be used to induce lateral shifting. In order to comply with the limits on lateral acceleration and velocity, zero-jerk time is employed in the figure ( $T_a$ and $T_v$ ). In each interval where constant jerk is applied, the shift position $l(s)$ can be characterized by a third-degree polynomial. Therefore the shift length from the reference path can then be calculated by combining spline curves. + +

+ +

+ +Note that, due to the rarity of the $T_v$ in almost all cases of lane change and avoidance, $T_v$ is not considered in the current implementation. + +### Mathematical Derivation + +By applying simple integral operations, the following analytical equations can be derived to describe the shift distance $l(t)$ at each time under lateral jerk, acceleration, and velocity constraints. + +```math +\begin{align} +l_1&= \frac{1}{6}jT_j^3\\[10pt] +l_2&= \frac{1}{6}j T_j^3 + \frac{1}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j\\[10pt] +l_3&= j T_j^3 + \frac{3}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j\\[10pt] +l_4&= j T_j^3 + \frac{3}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j + j(T_a + T_j)T_j T_v\\[10pt] +l_5&= \frac{11}{6} j T_j^3 + \frac{5}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j + j(T_a + T_j)T_j T_v \\[10pt] +l_6&= \frac{11}{6} j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v\\[10pt] +l_7&= 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v +\end{align} +``` + +These equations are used to determine the shape of a path. Additionally, by applying further mathematical operations to these basic equations, the expressions of the following subsections can be derived. + +#### Calculation of Maximum Acceleration from transition time and final shift length + +In the case where there are no limitations on lateral velocity and lateral acceleration, the maximum lateral acceleration during the shifting can be calculated as follows. The constant-jerk time is given by $T_j = T_{\rm total}/4$ because of its symmetric property. Since $T_a=T_v=0$, the final shift length $L=l_7=2jT_j^3$ can be determined using the above equation. The maximum lateral acceleration is then given by $a_{\rm max} =jT_j$. This results in the following expression for the maximum lateral acceleration: + +```math +\begin{align} +a_{\rm max} = \frac{8L}{T_{\rm total}^2} +\end{align} +``` + +#### Calculation of Ta, Tj and jerk from acceleration limit + +In the case where there are no limitations on lateral velocity, the constant-jerk and acceleration times, as well as the required jerk can be calculated from the acceleration limit, total time, and final shift length as follows. Since $T_v=0$, the final shift length is given by: + +```math +\begin{align} +L = l_7 = 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j +\end{align} +``` + +Additionally, the velocity profile reveals the following relations: + +```math +\begin{align} +a_{\rm lim} &= j T_j\\ +T_{\rm total} &= 4T_j + 2T_a +\end{align} +``` + +By solving these three equations, the following can be obtained: + +```math +\begin{align} +T_j&=\frac{T_{\rm total}}{2} - \frac{2L}{a_{\rm lim} T_{\rm total}}\\[10pt] +T_a&=\frac{4L}{a_{\rm lim} T_{\rm total}} - \frac{T_{\rm total}}{2}\\[10pt] +jerk&=\frac{2a_{\rm lim} ^2T_{\rm total}}{a_{\rm lim} T_{\rm total}^2-4L} +\end{align} +``` + +where $T_j$ is the constant-jerk time, $T_a$ is the constant acceleration time, $j$ is the required jerk, $a_{\rm lim}$ is the acceleration limit, and $L$ is the final shift length. + +#### Calculation of Required Time from Jerk and Acceleration Constraint + +In the case where there are no limitations on lateral velocity, the total time required for shifting can be calculated from the jerk and acceleration limits and the final shift length as follows. By solving the two equations given above: + +```math +L = l_7 = 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j,\quad a_{\rm lim} = j T_j +``` + +we obtain the following expressions: + +```math +\begin{align} +T_j &= \frac{a_{\rm lim}}{j}\\[10pt] +T_a &= \frac{1}{2}\sqrt{\frac{a_{\rm lim}}{j}^2 + \frac{4L}{a_{\rm lim}}} - \frac{3a_{\rm lim}}{2j} +\end{align} +``` + +The total time required for shifting can then be calculated as $T_{\rm total}=4T_j+2T_a$. + +### Limitation + +- Since $T_v$ is zero in almost all cases of lane change and avoidance, $T_v$ is not considered in the current implementation. diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index 6dce3ff06206b..df742e7fd4142 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -2,11 +2,8 @@ ros__parameters: backward_path_length: 5.0 forward_path_length: 200.0 - backward_length_buffer_for_end_of_lane: 5.0 backward_length_buffer_for_end_of_pull_over: 5.0 backward_length_buffer_for_end_of_pull_out: 5.0 - minimum_lane_change_length: 12.0 - minimum_lane_change_prepare_distance: 2.0 # [m] minimum_pull_over_length: 16.0 refine_goal_search_radius_range: 7.5 diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml index da89dddc6bd8f..bc5623e87ca9d 100644 --- a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml +++ b/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml @@ -2,19 +2,28 @@ ros__parameters: lane_change: lane_change_prepare_duration: 4.0 # [s] - lane_changing_duration: 8.0 # [s] - minimum_lane_change_prepare_distance: 4.0 # [m] + lane_changing_safety_check_duration: 8.0 # [s] + + minimum_lane_change_prepare_distance: 2.0 # [m] + minimum_lane_change_length: 16.5 # [m] + backward_length_buffer_for_end_of_lane: 2.0 # [m] lane_change_finish_judge_buffer: 3.0 # [m] - minimum_lane_change_velocity: 5.6 # [m/s] + + double lane_changing_lateral_jerk: 0.5 # [m/s3] + double lane_changing_lateral_acc: 0.5 # [m/s2] + + minimum_lane_change_velocity: 2.778 # [m/s] prediction_time_resolution: 0.5 # [s] maximum_deceleration: 1.0 # [m/s2] lane_change_sampling_num: 10 + abort_lane_change_velocity_thresh: 0.5 abort_lane_change_angle_thresh: 10.0 # [deg] abort_lane_change_distance_thresh: 0.3 # [m] prepare_phase_ignore_target_speed_thresh: 0.1 # [m/s] + enable_abort_lane_change: true - enable_collision_check_at_prepare_phase: false + enable_collision_check_at_prepare_phase: true use_predicted_path_outside_lanelet: true - use_all_predicted_path: true + use_all_predicted_path: false publish_debug_marker: false diff --git a/planning/behavior_path_planner/image/path_shifter.png b/planning/behavior_path_planner/image/path_shifter.png index 91542fdd0d042993bf9bcd7b2fde5a484c7e0293..d997f2d5ec577073a0843c23f381848f876a54bd 100644 GIT binary patch literal 148776 zcmeFZ^mHq=8BXhG0ibjw1;fojy2bP0lv@nOAV=VF?cJ8sz_zUpo z+b7&yqyN0%#EvHhRIn1TV=xym;&*N;Iz-O&X`6Owy(W+*0^onAiUj%x92XS^sK8mqivv?bi%7*o|aqIrXs&Vq|$$ZICt3pcL zigAB<99C3v`tP3@ouSiMy#N0F{LKIT>tHwjZzq07#sBTZ|Lp_@^M6tBe^Ky%QSdtk z{%#s0RiskRR{=VhA8^iu87JvW# z7DgxUZ}_cPSOpaol?v5=t0)Qdpa?rN-&@ez(sJ=3qNxWjw^!)v#9wRu1=sE`KK=b= z3?@6=gQDQU_S&qZsA#phrclcP6GcBz@r6O>nAvwvyyFZdC2?`OUmE`B#=a;qht`cs z5FM(294|i^?w)5q-#;@@US47J=h`0K^~VebU(EF6&ui}Yk{bN^#-PMu_`1N}#_;^s z_~HNkdc0MkM*7O>ie4q=;B@DxE9!Y86D@H^rT)9YdOPl5YD`%1+H4PR^0e>c2mQtN z^U_hr$6^%{Wk$OVW2l7pMi_-vKO0@xjM?9eSy@|S5YIE~3-2*6Fa1LNd1jQ)WoTl0 zy3XHiC2nz;$bF;I=+UF3!8_P(!R?uBKHDk90KM5CxrO_C+bjZSPQK|fF36jATQ43q zA8_B_RV}uAd^8bvMx>Vxabh3Cet!Ruu?^>QGVH7HZSiV zIU$3)VOB*YbgvOVdV1PgTG->K|J#P|6{n=?hW&+w;-~FxY(A8h_K_Mmcm=bl7&Ju- zLRePy+4Vf8prn)v_^6(r{-v#AW(@B8k+E^nl&hwSippmr9kcJ5x}u#K+A$-u}?((=Z2d#zyxMAWZWMWp=iIJy!qZ}cO- zuh`yvZGJ%bY1{7~!CB-~5{Yk6p5O1pvb(!09*~fb z@KLik?+bC}X%r3w1O%hLy#3_D{huD(4q;W5|NIgy!{fOaoP8~1rNN2|EWya!ya~?4 zaHRy>Wn*WjMY6K}f1t5+Uxy%*F7h>Kk|my}|9Tvp;}NDhSC^VF0TOhvB+Cl7=0+IL+} zH<>^Cp<_pk#p}v7A1H(EtKV=muj2a;z`D~EuZGqIQy&iNE8F{(>_Cwp=yzRc+z-#^U-!RYTWUCu41t4JSm4f{jM;s2b8|@2Q^4z=r&(>fninBf6o^S2xiC~Oz;Sk;#BI4xY3i3VAoACbq`vpEo!7Q`B zqV|rCQT2f><*OP6uaDEXVCzDzu(*(-ch(u2nxST%DU)ezcJ0f}brWgCVFOn6ut7q+ z##KW-Jvz3Mgqv0DLCVUB6Ixv z_ZNwTHgt@Qceszk)jeW0Sw>2gZLYVh4qR!TouP&gVmx6tKygHt=W=w@12*&x46m1mBlUSo%6dt*(xBb#_3>|SXeXzqCE-A}wzgW~ z4Y^G^M~L>?Fp80OQe(kC2sb+!b0)mK|-2*;|ozI;)_dsTtMewwBFj zH*+7I=eqm;`ewEJPIY_NHVHC!FlWbWlh)NPE?(CiWWoD6eY86E0s1m#jN{O<01rQZ zxb=7=%Gz&i?wfUyeAWz!vN4Sd3l>}3+t%B&`HAW2X0_vjj!SxgaWOQz6QYiTp2xGG zcIM>d^ga{C3N|z}Y(5p2 z^eg%o2J3iu%<*GU5&v{oM$_*4Knz6D7;M94)Ba9Vq>wBB?c29iGaueHD_!kWR8f)L ziUe$OTuM_d4+#c#yGlj7YdzNUrRxbmE(UhSc-uNVLq_XD zWm&$X1Amv5PDZJ1+kNDH<~MTO+Z%*-D@Ad{q4NgpHe8?U6A!rUML0Sdsx2ccD+>vo z1!vi7Rd*#hB_(`?uehjaX=k}e@l7I zLT6{=jVQG^-1Sk$C*AWEo_KsviUahP#~KRP`<fNuZ<=2F3vR zE32ug3HikqpPReNAniPy_qZnn7w3!q?vaeq4!0^!)k{2m`jpRpP9whB!xFKCudm1g z=>YagqK_HyLT#vSZf;hZp9Y|Vo3pNbev+(8*i1Q1O=-v|EZyYj*LhN!m>KGDZgoGC z)EC($c^R#`Sg#x|w(u3(F6o~|3VZ`nMyhVRY@57S&xth+?QehI_%7(nYfXm^2~kP1 zf8Y*QR#ry-eMt<&pgt|XKRholPkf+E<7y%#sI1VY9w8Nf(Bq!G(SGOo2H0BjpY6N` z9VtqM)9J-omcvygJ4{n!LW7=&}Gvq zKo0;;fiTQ{EjtFqPa_mC>;2tzL#Uz2$!|;DpBtN)WIw2U;j$DMQ(wN@Q$9K_yzdz8 zJXg3=6SE^8FN#Or)!Q4nUbbF}IMD3(Oj5( z2vJJ7Z<#mUJ;g+?I zx?<{MIEC9gJGE8|rFG*7aE$oIqJg<N?$!tD51$yKTbK&d$zSZkwY55I~0wbd*&~opRqjRUMrxo=;!F#~Pw)jed4} zzP!9uw<0nNYMF#T)})k^L&)*&quy>#)?3jxHSwe;&pj%dT(?fc-{^bzljZghONM<~ z-2;Y>j*iV<96%=(bZfukpp}Uhc&no2NG~oA5Qo?YWJ6%l?8L;QtC~eYhB2-@j53km zo)QU#!CMN$uk%`uP-N=W1oT=r391%a>1#O*JxAw1IXf%u>gt-3lEN%V4Tp%W)?^VQ zrER)OeD{lP=*w5Q68FyG@YvDV>}<}AvMpmM2Av;O0}0Oa=xr{I!ka?qFMm17Hd6nV z6R7vMsgBgP=H}Nx(gG8s`O?zT(A%N);&5PN$ZOa54!qGIGx5>tCnL3CrWOJ%dBZQS z9*|)JG6DNVihX#&> zsGHRk*-l#>AjSpQT^!Y^IE;NuP{T%DsF=Aq7Gd)I-+5B1lYY2c(iu8~Wy4haQPsU9 zX5Dz79@Foy0fPJgH8S^0Q_nX5G2u9y+qIM( zv&#z67)<>a+)WsR+)@Mk+qCMRy6`Wk=M4B^WFD1XMB`9A!~#&+JX#+Y7YDVh?hUOd z$F*x=At52a<;|)LDXFO&yR!|g0X-vy-Q5JR=_x4^j~_ptnx2NmgnzuBc_}wHS3$^K zU0ogRd|6o;rJxg6Utgb*k&(Eq?W&aUS@f3SRS)&#mV662u0~6FunOVA1>?=2qlIw; zMm(0=r6m~v1;Y?FQ8m}NMaRUJz;C2+}&eg(F5UU)kVT`GNf7{Cn z5*n7@-qmF|S{vM5WNSk0wlO5IG5Az9-%OMAO85`n&i>`-b-lhKTR1EVxEZ*?EWmm$ zZtjNfx@fl<*32F(eIM1Bjp}*Lc;e0Dn+IzfV}`R{_+gSU3ep9k@C$RnZ zqM}eqtM*q{Q)_K)<?f0v9U1++z&CM z%t+yQbloeqvM_%rw3`cF!UFNzs#$vC=gyzcc3AxB#P(>RY47=y=ro>wy# zdsXGr_Jr;9Fr4tsAi4DFH7-m%p5Let@b`sZ8L0`JoSSPL9Mn-x*LVx+QxK2`Za9#? zdUJW)dTFEvb_wL4fV8x?y$GplQ!~oKU%YsMqpFV|N3FO5SJIzsjW;qgYlO=$Z%t>6x6%*X0p{!RQiFm) zyO4Wxuw{?#%ZUB4YF+lF;86M+P4#IO4jL4FmdB#LgnkzGa^Iz@B>7^vq1X ztlLr`CBMz(YJVDpf-+J3-0>cK;wVVr(vjEgucBlEW??w>9wVg=iPIP@c-^hUs4W4N z_g`5?rxHT~Sd%Aaugx{CcOld3&`}tC{0=~_Voym zlR}5ZhXHz^+98i*p95p5LsVw2w-8v6FuCwv@3>GXD8mynN9N}Ys%ru**S+IZi#KLz zlH5x3>6;?E<-YA|O*+YCU2xo62KhEUKVLp&9f9l(RoJ4VjJP`mvjX@jNQ|e)iN<;h zt;PHMD_oic*Ma;?Z&B)=50i|Shj>>|SHDi1O(o=V&5MWz1rlO^@a`sNSb!c)YKK8j zN&yEfq)_erZvXt~T90|mlB?g*dRkiANjUVu!9iakq@gb>j_;og&=#;terRb$|1toV z9GJ1=Xcc*$o3H{zN!8TV6VI|S)>Ks70Ja`bKXYsh)Y#}ucQ%3r;6O_d$A(Zfh|So0 za*Py^iX21a4hR=G7s8{}Z%U}JU0q#?z+v+9d4Zg9F5ZK;*QwGlabEhazuXbLn0c83 zg*ZlMj~LseP+D4w(AWyV^ArJrenU97W0P|~=jie&Lc+1u_!;O@>u~%yf z#qvtbh7DQaA62zNMR__-1~Nr<8He51)g1;|4w6vG0w)7>-v15v1E}t}_?3(k3IrVj zSi8AizR_i$qxJFfOyD3Sr=>-`*;LNZii(#EWpKQ1us3I49?_-kE@Sttxlv_dJUKc#8sf)7K*!9; z=&f>v0Mt=WPfxlUDBOlK5kmQWcIrq0Bt|S7#^4@QY9+IQa)slv0}uN0_Y0|*8kZ+F29RZp{R|D2-HlVaoR4Ry0U>Z!Jb%g-w5Od;LP%m?GbM=R-e2q*@ z>LSd`-VRs$kE2>RHB~!Q>9w4yy~_-kC;`&YZKINA3|NsVk9mJ&RaF(!z(6pvC*nLH zVRfj__rwb94LF`=Dz}DI?$O;paB(~eZ&e5oQ3<;Vly5eeS0T$Sy0f!0HN6c;pjBby z*w~o8U>5{bTYGyD9njU%_a23S4M>Ospk-T))_zpWWnNufRRxb`u3*@&*Rq;Qe9!#p zN}H^36v(wp`vCC~u@9d_>Y`vF5!6mOBnm3)spw9zr`nXyY?c*>oYI z7od#kY9KR#-(5?4`@+l1dShY8WxHpf@g!TxYa-W)+naI1TXBeJmfQA$pJMv`)5Vz0 zdPAIRrBTR%0xp0KKmcwus`FGRn|32yP9Ds$7cY*TM|S9#$L8NmvS%;*Kd(8gk0K9) zAw35$Y%}vcGxhM;>U5VOfS`B)Y#sP;;I1YnCmYEhS_WFKa5c28tBZG*pdKoPM%ikb z`Do9;o*j4@%ix1?0K5<%t5^8}HZnpTw-VUeMc-xx?mW*zkOx<;Tmg<2(dh{97^X^m zw-zWy6woAaPZbmt0zr^|guCMAHZM;F(y$CiGXCZHNwCmM z=L(T2211Qa9IQgnM*S}!mZnr3=L*LWkEcV5Un0KM)*M-bkTF1A6AKIZfEYum`I=)e z0m=oU4!)BG7y}YcW?BH2Ce?S}XXob|N%QI&!OF>!OKQ<4)xyd20nR{OOVlleFXkVu zMY{%ChZ~$014z`+tC|v!L!@k4kpQ2XxtZv6g*R(t(fYt}RW#5vqp0IL3{=INH3w*fMn>^(Q4tn#f?QgB7xV?Xi&Deg!V+|B2*zx*m^*L;fPl%P-y`C z7{wu$+xq&VK+zye2qf9KZBzckuimEpC4AymP||Je?a|RH^gk&9!xc?db={qA+)5y+3jDb9y3P?xQ zNp_uH2q|k|%yczdtJ5q31odWMCi}r}rS^A0bs&i}unW5^FVro_Ri^LA17PD~*wZ6S zY4U2R!4k;9qJIR7`=@i>Be~}ocsMw$I;yLHrTlLFfDjQ-(AJItYQ(CVMR!nZhkF8? zot#?x`=f!(phSh5+9fyuRuPUaKu7LPoT$GHpH4qy3`A{o$zs*{%_)`gaJUSJ0TZoq zjjQ7-PYI^;#uxL&@$yYrK*T+H6yzA@^0sA04t!~Tlweo&M9-m=10M;f3Y zqCbJW11_A5veEUxy0akCm>O*0>=QCF*!K74_oGE=T)B`}iF_aMxNKc++XNtg5`wQ@ zK~^vr?>M0z*hHJDG{+2h7d-E%8s8yEpqefGO=*#ldJqc2y zxp{eh=32lak{7sG6}3_yJbXoZrD#ewuB@ME1H~ogE2>-ey_TYTGfjJ}wzjr>RwH6% zP%;camQs+De?xJMHb`MBcmbAHx81*9hGYpy$+oSI2nhHFP5VA*G6a!nIb4KJ3%US= zH7B^dbVz+7^F+HW5?G?k#BG{d=Yj41UfV9s?i{1Gp!sEqjM6nV{_EGq4QFS`y~ zJzsR_+`G$wi%$p*f(Lf{2Gag`Js_)qUMf5JoaZ6SXL=Pho}Roj$koe=yE8JjXtJ0d z++A5m0ALy$8PyyYTJS_l|2QF~n4zH|lqe*jU3P|PnxH;s{BUv+L^p+g3}HG*c649S z)9<~gYatYtkp+t^TEJ4k^T3kb=gUwy65`|Od-BbjO4s`%lv0)B6UM6c!^`%zrV+VE zOla^akwHxWJ+BM2fIPYjsC{TapWsiU$M<{Q<*B_9(JOg!f`NmX zqK+Q#_O~dhfWJ0(&lpPSSe3gNax_)*Q7=c$k8kgm1zhC3xcpPl+Oh7x!N&`faynHW z4|R2e-@JJb(EV-HY7&?aztc(*P_5Xcq|0%`t98?>KmjIKCfmIK`KK8=1YGWWJMWrs z4O5}_%8F$+;T-h8>NGm>(AWx}LwE1oxy-;I!lII{sIMO{6C;!c3|^-E8(MtGksm_Af>GHEG2IZilY# z@%dfN%bPEKeA>a|NQLg~WPGSr>)!76YDb2f64=q+K0aLhS}{<36}7a|x3-+pGz#T6 zH#bE@k+3{H<|L!&R$LTp^s7dqYkna-YH&*8&Yfpt4H1c{=|vJCCPDg^#v@jsRdPR& zQI>~a>jrd9U$;%Rn`D$SWOsjTa-FlTt*K$>NBu1itfi40A2}oQb^-%i)OGQYkw@+~ z-^Tu84d@3l?|4$&wyGrHoq#Qd-biS)%aV9}eEiYJo}17Y?_6#Y&Zw#q>2sbht*xu$ zRzW-ew<`fNVfw+c7BszJx zb)~OgzitiF>?h^qa9vT&`gh_{DVQT-Y^5s!YHDgLQS&aMC&{iV!Y{OBVg@YBw30P%#ZtSl~*PS*H@gmYBV0gBq%8D!cna>2pD zMRP^dHXsb@OnJ^zox~jGxBU4GI$QGtWl*(zPvVI=4Lv7oZ*Qj)uWe{hGBZp6{L*9a ztFFU@b%(83K(uS>&43jwAs4@D5d2nE{=jt zl9HVKhE6q2ndIzQ^7Hr)UXB}I_yjvP0SI2|?hIaHIJ@o(Ph5u_4&@o`iF$I5z?u(7 zPm)dmFh_g8dZnM=!)@L#kfv3t#?HUG72WruCjSYTFGYX3Cb)#E3< z|0jtq+=U4dTMDYf??Gr9fj_jh9JBwCNg-hZI%h8vq$3Q(NWCiG1OJ=^zoZCMXs+F? znluE=Yt|uV78XgFM1_DAkjWEZHgR(iojw5_&5qXAp93=D;_O(03*d81fJ_P~8nC@6 zB-B56=f=WM_TKw~uWAFTY*MUj?j$nYb>8V|=oc^g-m!nZ>Aw8Kpy0=m4`-ynXwryEFKkB~Q@~!pp<5+MJ&K66veEyuB7r zfByWbm*11?zVDWHKl9e)~dzbZ|+(DK?AlO4Rk2u^jK_I4E_vqEkI9 zF4595t^CSzEag!HpYJ=H%Oo^385SbE>)%z!IgCuoJfP|DL9l0*+PQm$jHsqc<%leS+1b- z+dwxbCnPY8j*Zot^7z--M#>}#?QQ7l8ycDbHTCvOn1dzWq7iOEyNjvvnGTGF9TB}p z5*$C5wbWV|s3-21kc50Vc9??@pxS=%ZYx?mVqm}Tr-4%@3Zz&G;u@G!;(7BDIhgti zOE388eW+>3u6Py1u)JBm`uc!-`B+noFkwxxru*(HztzY;xT2JpI1N9M^*1qb_3Reh zaoo$pxE+4Rr=sa)EX2ej`I%SAak5uDi%!%8{*sV=xk&bVl1b3|*H3Bz#Lq0lD3d#7`++9z*i#m05$q;|8c`<8;>{?2kZuX!|}6VDtUTua0o z-Rd!Z*R33ow^IXULod#slEM>XE8ocig-I_CZOFC~$K_KpM~-CZxSyK;6LO#96@s6Z zCb{hGIF>>$Zf_Q5sV)OdRRBym5Bu_hx@Qyz%&&Ua??yuY`176y0Xb+BC3I!??UdAX zjt@5IhRBm4M6ZTQ0_*08Xh20mib0{g8ceE5P?oI-xclbaR8Eqzk|*Ybs%IPcy6tZd zq<;J;)um}41+AOpiAT&gAf)r4ey%Zg5WI6%+_$@Q&o` zIG&n^=slYQo9Y@r8bltaOYpXOc+ysTd~}q8>=^zTSO@$@z=!YO?>}w3pmDU$n)|eA ziI#cBJi*=@)E4|ACoSy@0+z|YI*uiy#OfZgkMPDIp5SslC!p*-D4>9YRTqtPpbggn zS|bt0kwS5W0g6t1V&eG_7~j#kb{RLfb>p7}X}R>|Y5X6tSsz}9rToH!3ofN=KTOb( z&=C|>>_Cr997+YUQi9*U<*WMZIG9cOlW?4Yd(aD;c%{8_>8JrPJu7roop;Zk9cg&W zSv^7Sp$#kn9b!#$&7m8Y$?K{Yq7{NQSGC+N`N;3P1O^4hRVE~va=dlw>nb6k#bRH5 z{TWjd84_Y(aqbz*UfIzjq*PRW)6Tl@@@r5yGQ|E)G+;qiR#sdP-)>#J006-%T5`~~ zM)qgT!%QEA*0Rx&kw@V9I6)wcSX|4|tN9z)4Pqb|oo0s)5)1}UUr+BcEo~)Qrkh(? z%NdW??C1Q4P;q-=mty54;Zt5f>6aiAl>(isa(4b>r{&Y3R~<)-*>OENaofd3Ko|+G z3m?JXoP=&;N@}WtvT_K#C+DE>jPvel*QgCY@cfIwT$7TLEG2r%p)oOsOjFFL%Gn(a)DTa-aEie$+(cJv5u~7zC z3yYAD7Sw2zX&%JyT>%DyBO^a{X*o+nFl%L~w6uIyI-1opizC@^jQF=cuPWf?C7h2fcdL21d|vR=OBLXJzn)<-y4Z<-i+z7@5H^QSrgs z`vhN)@auuE9-G*8A_;+Z916O;i#ID}t9OFE9Th z$~*_Y{cXrX>~DIAVGG=@VKB}9I#-z`rIb+E!OP=wk;TvxAxJc!1&=;IISRGphX?U1 zuv`*AQn6gUDg(_=#ap+&d`jH9*t=ZMPEL zw-{YPD|Ddg6wnWA&N4t2k`)q};Yu_v3!Y&7J&mor-c;6cf$7?-+A`R}vQ{ezAJ7K}uM2wDC<(z$)C$Nk?dAaD=USnw zaWxdE$vY4kZ>16*Xm0~?-hxz4VM#BzBOpxZl&<&6b;~zOj zc+p*^Jau{;U@)nHZ&lgIs|Le1O7iltz#i(%K#E6r)?hFjIe*^!hb+@XkmX6!nyx97P(pjrTAd6ARv; zR$i4^{&b)HfRd@{$AG{<5@ODRL!_V+m8GP7;HCtqn?5c1BEAdw=dtZVKNcGsYbkRS zgLy)NzzKsP4oOX?ee|kU-d^=rDOLE**gV+BSg^7{?g8ZQ$;-ETRD;bU0}>08?CDh! z?I{>BhcQk6_U`WF^z^I1x;68VNrWI03>;ek8D@HV{d?mw0Ku@HUbFo7N5}SR>jb;L z&)SWSj`}Jv13uOt|{p;Rt=1K9^=JC#LLhjDxffc(w@P{ZXk3l=81nnyq;Qsk z!bs=Rg$-_AUa&AE0>I|rHu~HDIk`IkCjJZv37lYMWME+C4-Z9Z61%vWz$V!W;GGQJ zB7&&`xRkAp&1H7>7HuBt6iA0HZEG-w6H$hPq0G$7s{%*^yj01+AOX(#?3pv{AFQ{% zJIW>-htnWn?2270Y#kjPnORvWw{HOa=`E;>V=$*iZ1|C!*k6MHdaOZyqZM52IN;CX z@=!1VAqZriS)5Hua@p8;e#q~fHt6C8$&Veq6LEVz4yR%Y0CrQstJ=z+FBm42juz;~ zaSZT507Yn%owH%$fj6^-}M zE1n#SFo$8C>=!msAWr~z>xLJ7wvUVj1pLiM>30a;Enfx(JZZdO7V1LK0qpDGYs+nR z=bxivLV>?dr!Q$`lku{a&`U*-U+!19d0gm#um&b93k+2uL8=9y79nPmuItgEH&WMR zWMn!AfabC=F^R)~WeLn_(C7E0fwTtu3IJ{LKzp|!yON2PR=0V4&8f5q0tsF(1WFwX z5K5@2@h2@=J$UebX=$nIB9vcz?z1=o>%)X<03^fchz@uaefpy}{%GhMkFEokg_dPH zNHCCs51ZRU={H|}2K1Slm>{=1_UdaaFk3IRa<@_~=UMJj7)(X}f=uMKp{BKYaHgT= zv_SzOp%N^RkOjmCc>wN65~#8VKgfPV8oWEn#Jcg|h^fd^Hzd~zyzue|Vu~Du3Gy3a?@xK@Q~*D{ zuc&zTfD6r(fT@G@2OSe5WA(lhY|5)>$1w^`*VT?K=u{9dd`Hi|fF%NC`*wJRhJr#I z8vAyFkx}Hl2*L~)IDC`23_z23`)mTiL$lplF)D?jBjd-9gS)1wR%~64j=?B2dsM}Y z#Wh8Fd5(j-A|YYo=C-ZRf?EC36IUHQ>I%SiYtwzQ)YFl6lTTXp-1cw216& z+XcYI1@rj(#rLTBtnPp#AC4;EcqWwYKn7`f&^1uqj=45K`cHvE%tg@%(>#(eh|r^d z)PN?nBL&bCygMV%-4aq#lq^Rnn>BM|Ez?{jQH#MKI#|-S_^me6i4O&Eiy6su|$G`J}A%F0>0ChPq zQ3PJr#(-;Adpo!sCu{5LSIDwO6&xK4*XH`J5AxU60WVEDs8__189|iH^!nm^vB){t z(f_TzF)wPTSD7zex&_ny0LrVOPeI#efQ6f;nk~XI7@2(YHd>L`e!3P zKBr(|k6;e1Xgu0E$71M<$22m)oY&2e;c|Uo)9<75^gH2v$oRrOGvL-n(4mu%k)dA6 zd@84=#$4PdG+0zpA^>6RH(!-}v46w2h zA4BI56m-_HR14S|x@CEL%T4g4_$>xKv>ZoC`e4qZ2)ZEL`n5qf-OUhjfuqppcpDTP z%>ALJ0gs7|jYiSY5o}06tKB3`GO!?t5JSh@_y=E6KIH5QjtE?-@eZZ?WAb@e+QTCO zhyo+4K+9>89@;L>PEdGq+;+Ew7-`p6-Zr_2z_WR6UNmk=(D?)5WmtiRh*OZIEGxX5 z16%|#-+%wTgL(w~{A!561NyKewk7A9bWO2nZ+f$m*1Z6YacoZ~@+k8G zR(CzH$l6nte@JI5E0=d*pX_D*X%l=lg@Ki);dzwb5DS6nk7?+-wn4^0_dlVapx`Ez zN#=dM>~8q)h3#yag8;SbN{cAClk`oX3Z0(T6M!w@sDv{LmbY-Z-bVdMR4>Wbwq$LPDn1Gav zt4>{|R}YBWeXcK28~3z&VZjoPMr+;H%104)ZpWg%P!#(0Krw^{`!1M>WBB>n` zxcn!72A(-|x?y#jSIvmKg z%OR`l#`hDeOtnH~MzxYzKk4DXnErHsutmr;1ouo3=2+D-A3jH-<#qyAcz303Yg&6h z#oTpTotBw|D6d3AQSlBg2>DTFlY<+jMf&P1I1Dk}rpmW&J)vU)YCFh9+of`oFDT*i z_7P^LZ3gB_@`J+q9d1@pG04-%qZtbiAVDgML)i~FCG*tc>p_`S%$WCu0(|g*;(K~d zP6h3)*3cDrv~(IewILt_+LINkxhvtB#EPbL!DT93kHc!<~R1frE_MkJ88XJ2HJ%|X8 zy~K+LG7xME08Begy!SfxEBm=|kcxd~?vypZk2*)GbkALGLTE9d(4v7(;fnSp+`KE? zg2!OC#n7$CKXSyOqum8_3i0SDb@#5`fYIevWJ$xo_;g;6nSz?ykJn8%(a|0u#=Qf% zEpcw-jP>MM{edG8uW&Kk>zNmDct-*1+5S>>=({(=69nKzjIbAW0;H@&4D5(N5o!ey zk_PZbv`Go8#|bmd2M;ddGW;s8moV#3nl7{`U=;xJaDTe321 zizGqLGIDFdf&az1$LE6%++3K}Fu0?wN-CP%GsEc2JanLy3Vh(nbZXd4MEFdx>!tVa ze&ZSD0*HlE_q7`9>f%t!S5YAV_Bh>{?LkTSRgXsd<}bCqEj+jB{(GZ5EXG*av_SyD z+#m>`B2#I=(-S98Rtv+Y2H`v7R{KOMgTpF}B+!+Wi5(p8H}v!gDmT0B&;Py#W=mO1 zYc8gQl7b=`YWQUi4tZ$X?OozTJE=p5OTi>?tl%;Hy;+b96>1vZm}IM_b?-2^9LMLj?wtdygIm)1^yakk&&j7pOt>;&O6w-oC!v zznfXG`XvW}y;&gacSS_b;gnv*BkOCFKVVELqX*K#X6VaNq-kMs6ciLep@%RY?{O&p z4s{Q}d|x+*nVG(-=bvA1)K&?;s{X7dLG2x3P!j*|#2i`HKypN!{WPbSjf?xJUIL?T z>=3(vOMynZR{2c%u-|oLbm72zb38@`(2=gjI5*|pyNd5O@FfLQ@H|09Ov6(bE9My> z4uO$jvFN!fj~2MURDhN`GkM*QxZ}iV zYKf&!$_WsT-dcLJ6zqS{66oJ&AJzMP8Xkl9AWO!}fIdODY%9OdEFUJ!-e+ZTjE;}j z8D#t3z6I}WhEBHPnRWM_5$fl9+7#XS!jUIygalvJOf8Py4~+O=-WYY44}$IBb>T=5 z&YW8*bO#3tNr0Z&Iosl%S!Gq#x6I7UmpLFhEpOwB4DiZ{s`KVt{36X$8UL`#iBO9* zJRLIDLR*$E5O`@zeTSga)xP*iRcsw5#2?(B@hH6+1nCaZtwYazl+U!;(GV5Ss zSX>_P`m@pLbU?ksul)VzS4-IelnOkewoDA&=7y;^mrEm{>$|6^Y8+S`SIh&Iy1J*mls0c!p(RL0h@VKIW%Ei-eIf+ z$&}Fp{1iPja8bKX#Vz3*0Eh@4F~kTyM<}TuTWM+ePs^s=v#&+9n_}7H4}uN*H|klz z07|ayw6go#LWuVXG{}vA5id9tW<=Ro*d+Vzj?B!M!XqyPlTLz+95DX`A&A?vO4L>K zI1_6@S#+4hkBJVqQjbM&h|ng1+p2G1u=T1w2raic2J8yAy1IZZ*L&RW z;rPnXNr49?Iy%$TclF1XvaoQ>CFqrr{|(6I!QQ2E#^KX;ysYF`&(3v$7gm-N(|oJn^Qn^laha?}n-7lX z%Z&OR?fq5l(psP+7<_X=uiMai-AzYx{NjRj3>aH8|Qh=6u}2;K`m!& z?knc-e7HmC71y*2JpBhep7FX-RZi|bm;gRp zYBBW&*)U)ZOA;{Xg2lgo`By!r>R)Sf?upXsye#6>hPs%g1%Cfn7r&@g$QJMi;<4+Rv*Ty7%y5tS8Lq zgn}#sE-Ee{^yS*GQd4J~yOj^6a(DkViS97WSWz!LE)$hBFfhpAK>cinV+Zy;AQ=hC z>Xxeev!l#sZXN-Q+{*#ZWo^Ly#20r z^);eT(6DzGH{ajeg(91Q#)X1IL%UK>e*!cZ{-Ps=Mu132HuEI`_SDr)kR`q9^4U~C zQvHT3TBzn$NbA$LKVLKt+3-V)4*9~5`-+qRZ+{e6#+^8E!p9GCz~ce9W>lX_O5j5l z9)yO*XTJRc51uhVE%V=UM7G0Cw72j;dMKR{Ookj|JanrX`g=B0?M!jH7&mBrQTvMq zgq58-M{h6_t@`W!$WG^yy|K}*|Xi8l*=&01x5t&2E27ke6ELk>V2 ztxRy~8?6+|NqjlH-AaptWb&UlXOOK56Lu*{N#re#E|(EU`~1%YJgULLf5hWu<)n>q zOTe^`pQmL=^xwKRNV37}!Xv(@M$1wykcd2Hy-6^$Yon0?jW~}MXc%r^!D??2ve2Sw zg$g_(pA7-TRVsAY(QU%K;lz})Hk4MetW)<6&!y7!c3FmuR1htCHnt7qdKIDPeBo7r zAOS|fs&@FH69sNB_;=MiX#SC09l{zd+MrLF z^oji(6q=?yout)fkeysm;Bdd1FutTjx0+B~9>yU-L%gsRga*tO)Mj!eaQ6jmQbCsC zE(T!rVAHz}*jQ2vvc$2+z%(AUxVF`6o~s6t#XHs2P*X#(c6O|`w)W7;dO;`$ipt8k zDuN|7viWrp_-lm?1R3g~0g@?dYDy!yp!3A)fDD$KAa*;m#S`)Pezm5W40Zh;bm)__ zvaIfRK?!>Af6&oGSG#d~DL5oGHI?ZKeB;?mRD#yYe)*f}=1`!cq6Cw2;R(BdZqqgM zb)|<_Sy)awAX0Sq?$?D%$fMV!kN;;~Hg)y&?eNr)(!G1{01)Gb;XQOHgF`|@bE**fNcb?xw4FmANVl{tMhxVi0|E6f|(6E@#}Uo6Zszmnr-12 z{=JKn-e}DbDP=!76hfeAehI7`dfjI>Z|!buoB~9mioWg!ahU6ZKXb@x0>uz6UleLha}2oPy+7M!)70<6ae^uZWl&IZsy_Z0e8 zU4x(^egb!gQAbqd_hzrp72HN+uGllDcaTTk(cUf=@KHGx0T98nPsn_^4|t5`gZ9^u zj?}F>g-86{>lcj!xDsFkA^VQZtMZ~(Wy|;;T-h?J46P9u+&mlUx{B7^blCgL5FGcz z0YQinJ^A(WV21#Gj01)v@BeVXf0nZR8w?a+E8o@D1>`_G;eo8YU2$K^$B&flxC1}^ zKk@GIl9`jUZ2~p7@a1u5qn&RS1@7&}v%e}#c}&2Se9BCMJ`SkzD%&>rpuQ6hkb`Pr zxYJ=JMIv6`=2Qh6>@&>H2cY)%xyWPqX2=Zz+OM^q3vEb*m&ncpcLzTINb2oFG#Y|t z_h3i|+z{|&4=DK%^g`->#k2A5*6MKBWh@l*!SHHoXDQ%;v}FJ|BnpUG(w+g?rYYj} zdoyrkfPr@eHFO%c3(Nv zh)=B0$%H<&qN*xi$~YkI=U+2izuyH*2tFkxp=iu@nsO?7G}Z6r3qw}e=Mf-8a&qib z<3J%ld;JFk=ohhs$HL1r?%%(5l}`lPX%D4p>x6V2p;3HV0B02ZzBmS>Yx-`1(# zjDJ)!*5i+ikD~*~>NeH2a)aIyfU=zMxURoo0^&SVsDdrvjF|tfQ1$v(-U2m;jxtsC z9a@Mb{p{|lkKZ(4fyUzy2kr1o#5-{KVMh^mwKoEDeeplogV zByao7){}z5>S}9Ye7SeJq#Pc&7je;o+q3$AI|_zN;5oyXrO-N3t*E70ena=0iU2s! zuX|>xTMB`%!Bb8`Gn4>E_h2O%J=xjWxlo;9eD91tfF|uhPvFnJk<)^8CmXX3n*-y1 zd6rU~LL#Z(0E`S^Oz6~P7>HCDRo1jC1|rhI1O!$`FV>e30Z}Tn&cIEZ8PLized}q2 znS@CI+^jTMEi8h9eZSKhKAB(=J{x1fT-)+1333QfT2m5wfd@u!TaM3b*hu-5_#)*Z z^a49!gcY9h*~%vaTOKB9&Vy@k+Ga}Asv|!|N#5mQ5vx(co2VuQw$Rk{ZI=WaRo181 zw5?001Ou4(R1@ww-|bOg>nh~Wb&7XT@MaCsizB9}kJ}35PFa@l_EYix8ar~YSl08* zl=%TE^po^kG{Bu>5C}UsI=EAU)NdNf$~+T?t+f?G8w|41qed6W-a}A)|Cs?$L7tSC zr;NtB-6P1_ALPI@XXqKEBt!4)*#(^ag!(Oi{q+|bPliS- zvRK6BVLs%uk;h;aG>!l9_MWoU7Ddj{F?<4WAok`Xz)C`se<)H&DJZ(9ooShwYb&@g z9-nk1rt9U3Q0t}>DDOzEhV zp==u=KLX=oQ?Jz}R7=zx-_pMAAdnKUE7rtmq3O;v1!Lo>YYZo-%PwX2%yz;#9%JQ* zxo)36z*Gwv#6)jY4%eP+f4;l$SD$^| z(=6xEl#PXpf-YYlC4PPFFzd84ZKAYPCZ6i9nnpICOCE)f&%7(GEdzteTdQ~i*Ipa~ z(gN`O?SM=G?LX87(o0EEaYa=puiF#=3qB$&80;)lo}T+v5ZQ6RCZ`ULwgQ_TzBTt( zLqI@=R(ibasijp)p%2Xd4#C&&7Z6Tb%%Qc^z05h;Gq2BjO_*ZYWMZ5DsvF7SKif;ZAVg%KcEuOpjUBCRg-3tXsYd8O3e!Holk9~b_^HZ#QvaD z@VCpV9)43oo$KU$bv>!9yG`?3}?ZWK2{jAQhvL@%Z2BC!ImSP=@CW_<1 zKZ)CdgG;3(Gd``ThRn4UGItLo$>*lZq_qf^9lI^mQc)yquDQ3#tunoEUMa<{qi&d+ z$LWq)NrRB*g z63UDSNtxLi>Ma!^9%a0lWu&q~MpP1!os}dzWN-fG{iyd_@9#MN&(U%8{q`E4ao^W{ zUFUUP=c%n=a_7~WRcjB;CK_m=j?QB=$l7e}>gt+sqX=(4VD$s!e(kfp$)8VZ)n4m+ z!;^8EUNeqf--~m?FZhZMB(<(zZZ7Jyq&qdgHklakswjPCxlZ#!-7u;qt=OUkVNGryWam zc1aYQ(f^X*p*?Y||H{IlQ8k9*d;ak!vj$$U&E)TV&-!J@m0^P$$Aw&v*m*?+j&!`~ z3^lhMFz9w}-#c}&T3TK2{-*5;vDwp4*=9<0PSjc+Y6$OabA8A@Gq}d_Ym1q~O9p?M z!267DSBvSRcdLwa`_+e}V=ay2E0s0M)D%>IaRGX*dnTr}-?+{AD(QVzs9RJT)pPA~ zb)<_7f7un8n)tjnK|S9gkBPz2Y?dznG3LO(9C51A)0lz&ep;5~yh}I9(+3W=i$IEN z=ifa@^Z|c;ZhcHM8Tt~_@_g#NeQ3*RYK(nt^2Bv9%u+@T2YsLMO}#r^t+2nR!pn)}PPmc?m+Og}LqU>p4PGw&$>)cy z(|w%=Kd74zeVG{)6nd~yN#uZnghr&4jCO2GYVWao8V#wp{R$#3Hs%l6#w4Vg4=BYB zeVAGE&r1R7hss(2?-iXwl8;=57>4ab^3pIu9NJ0E1@=$`Rm<+SnL<}Xb`dnRg)YcgwUe}wZ4e!a^I4X(#M`y-c4r)aK!^5fnm zDT&F%549Z|w zF{{~sPSF}}mE9YgJWywE+BOl&?64{^xhXXCXk>;$yi&ZGMSS^%iB*oHQ391Sy;JF3 zGxG%5TWqvYl=?7BS;I?0qNnk($nj3+h>uS8w*d8%~IKOWfZ$ zIi0w;!r+Npr*y-ZT1IDPgI>V*JvY^jWuDxRI&N!g^Ef$5b>YlJlS;H;#<1x?wV1hH zi3+b{8ryW^72Imz%_sdjl@XDR`~!{b3q$$Jp1X7PTvVT#2u|-UVC70kSCN^?+q5y^ zF%fjU!|r-?W-PPv`RJWJX@?%TJs0}>a9>W&cRQ!-@_?;E%Wv0p4+jL0^i@l1Yhq2& zAaVq5@4qqXAQ-;y*Gk9V*E;HzYo2F4mipkM=)mXN{101Jm{)Rf!}ItTiB98IgQ~09 zr7O%WDh&%~b0OaXPL;1#t7S%Rv1Pqy{-T}zu{Ls~tHzNkVmc%gJM=ZvUspj=rQxyP zA6b&n?%Pun*2$A5l|Gz>nL;tG0kJ~a{`OuyiqA~#t-sW}4wZC1P^flQjS|~Baq@KS zNUymOW&>iDIkxsnnRB+=Q(v zUhKOcg^fv7AA4-{Mnvl3KNDB|>q0&@HJ)2EY3q=^KQw!MZ@0OBgi*uuj1#BrIrW~u zi`1+4j-1f@@hD+JSG9LSi91kHwQ8e^jT>8li;iUN$kgfa$#U823^p6rv_v4;%9 zb_y>esjBqIEXH@+@czeEyNqPuJlJq!mW9Q|RZxOrB5JM&*OM;7uMdac?pXB}{`6wK z_?@2PS`X6pdd)=0k4(8dW1Fd7m^@ylYqp%tD{1`D%(@rY{DJnJ#X`;!9%=pZEyB58 zg4MoUj=5t6ZznSb2i$r{co4NL6>_!l^a_pEp(r(|5CosfDi6ZgMtv$$0)*pjHL6@Lbi5wU9krrQ2s550!Uyu%ZU5=G!&Vin5pj^$>!|3lRq>N zDj65%w2Rl$SY}E2xl$K zMi18)n+$z_AZ6zmn^e-nKj(p8rt$6Z2{T^Mc=^Y9oxHqT3hiA^99hO`arC2enws-dD#YW%u71zDB7V>(2#?@2PwJE@^K~ z!Iey3!JGHarmf7sv=$<^w{9^sxP5xZdr&ew^y=q?btOMCT;;~~UvbH@XO%TOHLB)k z=tz8Sj0~;cu2rm>mXIxcBRwHwPhWbg{#13g=$MO@Qe?eh>9vds0A1@iR^H%cUd+`n za#0c*b9kGo<6JW zILN-yS7v>(+k^vT^;o5OM)9F9jB6ZMHj zge^7Q?lt}H{AQyqY_XSa5T3BiL`})pE`lRLv1~i4NMWHT8CqQ$UG+(|;U%VBF8BDR zGUC(A@1G1z`ErdfKGaAqk#n`5UyQ7T2J4+=e0-(`d@svaxF|fVE~yR}cyBwvuGBp8 z;Ej6ii!9laDG9!%_GU9(!DSY0=I=|N=Jwv!c`CcB@td;Uwzhj+ttact6edi@7&z7b ziIGWnxH(g;8n4%T>{ZDKKi}5zbJr!VM-C;Po#*Gz%vql>usK0{SEJaQ8G{Rt7r#Ay zXBkg6ueTtP8|siQ4~UMAj649+2xC5J20DEEYu^n3igI+e%HC(1ig|gH!%I61As#%v zd$)vynfOxg&*Iljyi`6{KhrGIXXOxu8__8vqu1wIjrhsa>C0S75m0?IVpiwY_(;m_ znTCr`x?XKm#uFFqp8I=j+t?c;_sm=jk2%K|>hSF15TDYJiQxQ>!CTh$n!$Y?$hgNU&56e4hDjw53v1g6`{b9a) zd!n+A8A!M&GpPN&fAh`#o2etcSrg|_pGOKGHLeBk9aP1YcK}Alq@+|G*-W8$FLv%C z1EN1a>x!pjPE@SS)EkjWIn;2Jn&+~3W_-7Y+f-19_pzt7@iBXPDuN%F+0Jl#y^k(8 zE*2G2aIm|>mVHE=t*64;%{3t8L6f@8(2x#ovrFfT@vrk+=fvNCyF_HQpR&%5kY_Jd zbcSflJ)zRF1f06lqzR%hf#azmmj6IA zm~X=}o(<+_&K$9|O@6o^X{P#UAFlTb(ngfqiushU=OFqKj6ohB8?1O%<+%~NikoT- zF;2laGKAqorYHuHyrF76q3D77*U!s5F7~t07Ld1!LQkN{oP6Pea;O$*JQkDg56hi7 z9S|~>VKVq#XxPkc#A980X}Cf6l&PkZ+xXQKou<-VZa@4|W@;R_#q@r<-ezEYe#iYE z!yf7n7e|%03BD`$SlRb7@UsPfg7AglBS-G=O)ekldNPx)5Zs)*+Akydb9Y5d*_?YU z%<>K%d;;DJ@`O6m8tqE<+3EM)HygLYw(ZO{`X?lW4dXroAe5rDh$O+37YuiKE;jlF403WOdXFG##DSB3mcYBxzOiFTT-mVAw4qe z=;Eg0ndQ*Jln{RLgGZOR-a%;-;fHlWiaQ<-O6o<~*WFyk{dst_Y~T`)&CH8_t1Nyqf2W{)Zw% zJMC=$;g*-(x-J7LPD39KaRzrDYlp5`AG=hfPIi|sbLI5Rkd8%m+cqiJI-9o>#_pBo zNqj18+{>3MoM`bIxW8LluY+&(>ja^g=IAKbfUKUZ-Szq_%QL&xnmgaVi9N<@Id^|@ zTfU0f%vks3u2i#X1+PN2pvm;Gf$bkyHD5>F&mwA&xI{%gJ&#s=- zeX`Tga=CrX#7Ah9_MK~+RM{5NnqM|#(B|=GwelOi^(NwR!_^rjLW`58*Ea?xy%adG zdYMp8K7+t!MZFMqTndJv2pLM&|BrICChSvquWR^WL(zbY@5B{)@nfn8t z;TcIom!g@KPfT`~e`a@9t8@FSEF_A()5$COk*MXQ>m@PQA;Ej0GAvR*BC@LejB>3S zbuA_=RZMTL`;a*DS+sUoleb`hhqQ-ll1|2*5WOc^Y9p5EM_wM+jjXS}Gu3t=d1Ot2 z^r3O)@vaHmnMOO)DR$k_mw(&Y#&m^UwtDqqfi-CROSU_(%F8@F@^=R?K+3=$V3Sdt zYQsolcJ$C2A7=H@Uh`zv=G4Kw(4M31!OFJm-D-`c(ze-&dWc*5Tw;yGQ>KQUmk!@_ z8p=%At#mDvAv&mPY}fUPq%JpC4V9@=33BmHNnO!Ss}o9CEGvfD-468(wAA)AG^*cg zbDjDzmbuvNQ*`^|N8{;vi>JPBb?H?(SEb{&Q8kpaC2c5}-NKhgsPFia>5H*h_H|?Y z>wBs~WD?5OOn0f(4xG>oX19wS2=*SH%oA&9NmEeS!22=S%`UXQuZwopsGo`XqD|Yz z$i-7b!7=0Gt7?Z1Mvq_PT6(B*DkIae^AgV2nHsl;e$(9+>GngT{Ja|7ZfU}S>6Rn* zHoc)T;hDWQ{H(WQdh?#j$+*ciHe5^;lYV)q^uC2-XF{)^_4nq{20^KTva$EpFW+hN zMJIE+E(w-ti0PfqW9y#k*6kh}vtH~XF2gS2eGX&pzCGJrNT1cXKPro~qJDljEE@V< zk|%Yp_lys;F-xyj2Z^q>YP{%Mul1XQ7BgdNp}gr)&m>cOGONS8ErTA&ZIJqLE6b^O z%4-$%!@)L z@$pJ3F;iaIkvb_6P3O9&>Uzz38(sS^&$n{zUMDpstC>7=e){79HBXb+Blgn6x9WA0 z9lu65s&%Vm2MqeOJYcI%T&^dnp7GK(BW3EPPNR9Z@3jf$@d?Y0C2nqg69J!}tCvi> zolMT!5wRy>>|t)NJnOQq$4*u4ftTm(&d$`>I8(QU8Z%z*)G|H6!_4Myvm+v!?S+C0 zRW(GdajbgcTiU4*=}D#)Obb>sEod1SQ#|x)&Z+VKB1lv|!nGr6Muh{Z-0^1KzwJQ^ z<=y#WZ0_NYiR07Nl2*ze^ERrTf8*FNA>$f0JeANsk*Z|%YR9)}%aV48r}0gFqdobW z>$y0i_=8O8$qBuR;qluAGct#RYe$p2%^aq-NuBJ?YM1!>WGw20>%h$vOWlNiM!{o8 zdP-en9FKO-jOgyx2r#SE%u;h<4eD9A>t3aOXJ3`w)VG-$UX#B46J55wGtNi5GXxbw zm6_6XPuh1^s!SJ&_T@iy%z+f5}b%vOKk` zhP{D*glB-6`BBn&7Iwo00~1sI6H}O-@uRKT9wnrr2iXX;lb(R|heN!a5DL7btWF`b zw84UUt_~5mW$e-$^xVeFL&azdyf@$dn~Y&o(b!KPEK^v@GpB4#+mG+tg@rllQku;{ z&WB9a{U!5^D0L}2@sCt6d@I3+UdkgU_VpPn?Gw0vtD@d&`A3F@ZN7p`cgd+2Dh<6? zD=$1!aB(?$K>eSxvYjWa<4^XOANE~iE4n{vPux_K;8H=I$ek_9yQ9Zx*Cr~)GE$j) zzN^`2s_uPUrQP8-;n?=(bo=8$TeF$zrxISnREJ1D+jMo?Ottv~Q?>brLQ8ctTos(c zd=`s!7TD{R+P~#yJ(RIp`s2gmeJ*W1b^O8UV=N+P=`F$lPGC^ENF z`JT$L1u~WKQwt?*CeJ=RzWaU4%eRlq6lXXeFoc%yWH*MMFM2Kjl<56)0nvxTy>bt| z=UkF4n*u9LRbSdN?xp1CUrEtlNQyKDrVN=u__~CqQai+yZYMa%ZHyuU4xPQd0h|_} zo}yM2W<*9vBwvsbMoSNEMURP@3@i{zyoAPhbPm(1i*XCMS#BR(l_iEYGT|Yxguhh1 zr`LOQY$)oAz^%(xsgf-{9ohSI9|!HS@EeG7c+saCT~#ff?8^4UtZMQ5maKT~o;u^P zY0>eui;p>asQDIm3JO+_%Ls&?rWHZdOLHy*heDOc z?ZU+`gkQ1#F#5!0bb>7t#@>$V>grCi>(^rB_iLzETAFk0BE@Ug7l%i`xdi+A8cMA6 z9)9bl0?GZAAt(z+FUyMmjK{CqlZ!uS1+H>b9j zZ~7G(@pq2H|6LDHgf}iO-+BB*ip8F$7pJvqpPycGx|M0=Vh`p;^L%qs!dHFsDN&<5Uj(uR8DA*(U*-Ac zRMhW?oBKf6#87=>&(XH05t7k8lfy12^v+5!x8}AD6!ebh**Kp)k$76`@p2EURNw1W z)FnmWWr2OEbRlfe3bbpkIIxuI1*a*Rz1)8!Ym}!sXX}o0ta$P09rVR9g`T^=bqDNt zVlinY-Z2gSCT!bOX}nY5-#tS8x{|&g_RyK@|2`H~&b3T2Sy{R%7CalG-vvp}x#TYQ z@Z(h{MZK(l@I9bC&{iFZ;Lf;-hz6H&F z5yI%Y=X~`u{~u)r-zqEiOh7?8R0YF>{f?Q8PM2h5F+8exN{qASTg!Ixd!VlU$E%>s z6(~eY+!vE-tM1gLY|CyG0VLJCW2kfs2O=tgjm&JIm9&PX?%e$zT;R+Kyw$d#6ee0gtkcDjmWeRNh2y5M0jJfdF?C1ox;y9 zU1FF5SL{|oHiW)ApBD;>(mD5`Sf$@aCWP+4loX4v=^A1!xVIEhD7VC?8PgbeYLQ|v zBg@(RmYi`+tZZymkm@9R4dVNg1AQ33ifX2q-o|EIyKWuzMFM7vln%`)`#jpa71Kk8 z63d=5dsXJVK6vO50uBso6p6H54iBWZA4BaD>poOqm!T^sh{vixA{YD8u=vAK6_#%& zzxAh%(a+b*aa+@$E3_mU>KR)8_nx+mOf(-bE(*oo!sHhnSu*?#6(JCf?4V~syMy1v z@>r6DnRmwcirS|JS31_p)}umBfCM#_=ru7#GnB2z8FW-t)#tn(IHq(^Mt z+Pd;`sHfVLkWFwy3;Tx=O(n87mPXa8^`R)*2AZi6%+~&w6q*zb9k*! zK%#B`x&9ZAqqgq}R-S)luV_=*G5E@qWrC%)$Aenb-rjx$G}+u|kb>SvLSV{I*{h$w z`KkOZCBu+M@3i&wN_Mmk{0h*(ahRj1nZG|gED0tqtkjxozjwN@_D|7+Jw$*`YaO2) z9W^bg(KQM=JB|+YQLwZZm(#Xq#Sxj4_wNrQNZ<+zejQiujze#@0?r>_yUd@Yz13&^ zQZFQU{rYt-YJj%Y4Z*Z;D}MzL2=jOTXv*sw0!=Q-rbG1#0*gJ=6P7MpcGw5g9yT?n z1J)^DJ^PyM0qBl&!UM}I0fY0g;NO#_M|t{@9_zgud$Z3Z%*I_tuC}v%5Hsa&s7tqv z)fUviwU%O6BTd9SPdhvYwr@nI(vF9jDkI16Wo!UDwys#jyOzleBw4MUcO8g{)(8lx&%<5{1V5k)#bEW7AH@@7dH)CMf&8HG zxd2Xr$Jj|tFD&Y2li%kSb&4;Tmw3ogM<8Y6m&=K#P~-W>%adhU``~STP0enDyJ=BT z#-%E!mU+l^LL)o9x9_4V4JR^(Q_Jg9&uATptwyn$0#OhH9d(5GEAY88sI*RYLvyO7 zwSVNCtVmE^;=+-g!q$**W}UdVs!=V6xwui*s@ZM05W0`xn!ehBD-gzAzQe)2!@&V3 zcXiiJAM;J~=Uj?dMU!Il0=-#vJyLQGg}(1dB^MBhC;YNLH+R!!8TPHL48F~H&@U1$ z1>#4xI4xeAKek@}++_6vax%MrKaQLZku9Q}*45P|#J9^Noopd+IS}6PtBrPr?8O59 z_w!EG|8zmy01*en_Wh0^35Mpowt;m8VvXGV1RSFSwK$1o?Fdr+zmIo|K;dDD+cos; z&v`+H4Fa9=qs`hL#KPd^ij&;&>C3@;-Nn{WS~ThH%V)DfAmuU$k~k}Ta2DJL7KP7v-mmk`ea#mmSG+L4WB zxlGLVTL9kT3Oe9v>C)NJahDUdjxt0cVw?8AJ4iP2`n796!j^(r4mU zulpwlE}TFA(PjfjJn0!hCr0UisS22c&3dBHPL68E2GLxqcovHDP3Fxcx7mWH#c>7o z!MU?%6~!UdgwwhF6st8a^WpTizKbkM4ry@Dd-xKkF@2UG>CcRXlK4jy|2Kvl^!#m= z7#WZU?5h%txFEmKAqokG_XjekyZ+pZSF_-^9Ha;Ca*{^ZwQ@=a$+mbQ%kUy$0JDY! z^hcr>iNSIOiCx_bg)jXC#2NM0gPBJVe~SM0KF3T90jhJXK&19!XXh8mo|&G2z=b03 z?r1sAl~i&!sx+e}Y#m;5q~bgU2W$s<{Q73QpJ@shOJD{6@58dNE(HaCg1#{AJl+b5 zJg(EL0{4*;Hs`7nCO8m&w-!9}hU&)P$9>D+kmZL?AN_smJ6b9IPIW;>ZlFa}Pb)rs zqMdg>%bJKOCX2cyA%^r|jjhBoIjm+7_Y}t+|7^}eoOft!+;lCzUl*mn_ftx|EC&ZE ztR+{M(|Gs?q%mo}#4aO>AU4mRm)T%_xSJaMxtCe4p4RFgb0(DY(^`Ga&C%NzUU}t^ z-Ef50k7P?l6Wx(>NpiyB`)93@bD0R&nVZM{ECNWaOO$0&x*aky=?P%$qeryVI;^0a z@BjVQ_4MV~YTGVaML{G5S5k1NWprveHXiT?8u znCj_qt~?5}&oY;Q!kyQX@O?BP1?R*m>zz1mOt4>IE>Q(ldz-JX86jLz=2=A?pYk8VPTCzk8q2kA0kUq@`gw6?MybJEurVRxH+M)0*QGKerP`aTj z8c*yUa-|^g_~2Z+sc!%Mr`B!CB*-A}5U`F?q@@f3ec&=M-crywWOUm;jiDVHkyD10 zPGw`G5S7#kFq+dB|I0gzG)u`n5yMyKOwgV&^SM@WUPLxtFd`0!>yHnXJ6Qcivn0_A z{!rBr$7a_fgURV|^jpeJ4n{%ax)eNHqdL3X3x&^-Jnq z1D?3YzQ+$!V(9*11Q10Op7*MQ2eEwq{cu>!)*bYtCe`939Wxl9k<)nHNnQU4NWV~3 z;lnX$K^D({LXqj4=K^ES(ikz;9qd$orGEsO%^D?=nNSn3&IM%OSDZ05J&JF4Zut07 zpI#|XzWZNJiFX3MnVSjlK{*GBW2A^?-|O;#*qK3-=GS{h5m*W#m9JgM50PciAJv&1 zF{PzPsj7I5WH$OIn1^b&95tkKCIt3~YBx#1Df*7UHzr+Y4&-m6*Vhm)AduKfYch7= zPlE--Y%oE>PsWAlC*r`BKlgK4h(+Dvd2`mR4%}8)22#t89Xld0M8?=S@+_Z?3^?+g zDvren*D-Rm0%3aq>0J7IqOt#H4{Zm+f_Q%#@2wBBEos_<0NI+tMu8TZJOJEF5{>`p-)Mh8l;gSXPT>vP06|PMgl()jG%KpC@PtkU2i58)b0)RYLL?U z+qeq34kOOO=NNH`fJ@|SFRWkAIMEApM9ayL+Nl7OKadcL@JT#rvH>ufjiLprX{#Cw zEBdYeSQWYd{E@Y}-?IJjWiNG&3RWQ0LRQ^1jz{WbFb?fJ@XeCxFKNk^YMbAl3Ep%H zL9AvIodJ{vcDbpzca~LuhI9_YA$ZI;@I&0#z$Xpr02nP)$Iry6LYl=yc|PYdxf=Jq z*C9Ls*~PD20KwKl1~=hl|4pd*Z|kVve_7EgWGp!ljFv4kE3eqs#7L-*>0BiI&%criFU{5Ja>YAmMcy(x5b8+m_j z^;_&7^zrdSTYJ8|xjiPd ziw7$o2tP{w%60Y9R?;&^Y*l%Y0BapH;icZ|h;Z8Iw-$&v<(YcN6F4*l9#dBnZo@Hf zJ;669MM{>I364%qJoR|=&1o3uaNqHNF+>VQ^e;Nh$z4BiQ4*)2f+-niRMdOYfxrIu z$x*~J=V`!kC~tr_Mk$(A8v6GOjDqAjeP)pfB$yOqy0G!T|CJ(gm^}4>tt~A`WzlF* zgMAr2mPcrZ{P!0T2fYqm1pCFlMY_;X%WZm!KOo0of6}2R`E~zUVd48X-;Hn*4B+>m z8b>1vH=Wn?sX(=gvO4buE<*J`XQjwtawKLF^nyDu7*ID?91a5d&K3SoBoaCJzvW_w zLgXt%_#T6hq7S++Mf6Xsfy0pai2k~C022zi_sJ`LckpLIxM1NzTL}M*j?z%1 zvhUvgi>iwA6e_R(_EHe+APkjX9jlR01vnfrsjRWDIUf>XoK(mxRlqTa=~p`i3r?=a z5Hq-hgG^7fX=#X*zn(^qZ+QT@HL@Co>El%kHo{lomA-J6E389`JQz5q#;dcBySZg^ znnHk|gpH>Cvg2P#(at6nL#$o0KEHHGB#WF}ho#%ZNyJL3#7M+LRH*A0Y0+v{E1Bp4_+ezfYJUj+Z z@84lCf=2tw^1mn`_HaUglP<&05q{u*tC$$g7%i#z_v3!+BYZb)65`?n zu-e}?oqyek+EQ5)Ti$5PfA&SUl9)>k0SgO?2#*TVwV36w%4h)G3x?i*#>7l5pLY}n z<}{th_)`@<%TDtC45KHwX}M*#W+_Oz%@H=t18dM+fVB84S@AX5TtuGuovc5om-7Lq0`drjPV^eM3^c~hO*=$e6* zLX^&4z1mAHBi1GaY5T=VMB!Q9m5|M*hgMST)2AOXNk5ed&XR=PcN!;=(jo*Vk_ZuL z+?8yxGv8FE$)Vr^JPs$^wyZ2zPS_T31t5RIIu2TIlP`5)Tz}@Id~QB(XR2h8fhFuo1&b&*ZvDNlKn2fgd)kK=iq&Coq!NwBsES zgg!i~GvD1B)=R6hQqzcnJpJs668iUa5ka(-LdTZ=>?7hy*G^y=bVM1=>r#lR!M~r@ z1HT1Ez?Kh4YdCn1eN1?G9%&7`C%r~dGjJ;GIaV#6spb1bN?-(*12SOIjdTA#35y5> zIW8(pKXwEykhcWzb!hM2y}2&I0r_5KIma*?iTPZi8ydFmyGgcPSXihqTFcAJD@+hI z3N7Sk#fBw2_#L8;xNcw!N5wag>8#n{zelobv3@ZrQH2WL&okCHg9s?;Fq6%O^GoRv zMPvcG0T=M-+u^^uYvbH^yab*ADafl*b|n;G2+NG(egGZlT$`)&0HZIyp4VrKX(T!d z*TGNHoInC^tYS;Gc(4)?{MSccc^R7|&8DQqDpI(hf*y*_rPdw6f#^PnR6Qq%z;#Yo zbGCbbeGC5fR3^JYgFsT8YU}lgOMpLtMR3O)E}S)K&C0`O}4U*LIibfe%F=6|Js{-E1Byy#z7jf+w|Eq7^b_GD|eoN$)L zhImtL=u0T?&vi&XAyTf$!&jGrOX5wa&Je!j&V<7=0&+w7)fk~7C>H>uoe~m!R6btb zBhYR6b>?9cL2vr;s3VkQ-+yT7y>zJnPHu-$H~B`a1ZvF4bUhh*PalR48cTopZ;nU%$S&Bv3(>V+Bz}14y9i2gsOXiik5q$o|HA z*X+p(l9FvOz0z8NEqej zd3o!!7BH&Y2^Mv5#gHlqpG$F%BhmksOMi=HRF|)>*Z+PBg?1Z&*MmFf?_$A1#W`XE zg869r_F+t!K$r&rin}NI{_K0d6TnPnqN`p)^@AT8k+Lc4H*BaNuwPf9U65vN z_5SPQU1T)BRWUeAfa-r*XUB!Kw6wssG5{pU(bLjD*xI}>D$W0&-@e{c@A;g>!j{7q ze8x<){1NJ#aTWj!6hep21J#K9CiK0dwyjuHR5&E;0V2b%k8mJK^o4w*g}mBO6o2}( zRu3BuxEVd+Q$>#HZVHmofSrz_!EdpK(-&>8q>GD-e6RsfVXe{gQi6sAh2C$Z`Rfad zCkUzM{l3d(MGkqfDW#{vGL)HH>mt?#8vA{=KtB=Ih>r)yYF=T(6X?KzphQ;$L=q~t zap8iZk=I85IoG&%)XX!c1M+L?z$}N1=}~~A9}0)SLxQ>FRYN>d$!L^FERay7l@Yl@ z=sR`_O@9?4W|4RS9q3r0tMhlq8Tp4Eqp#4WDVeavbNclW0noO6<0g~_Vjg)0sBo-x z6^gJg>1#P5A+%cKFz!~K2Tp2{C}4@#kScIT%)iE>?*Jn){m+Yw!1f1740rVE2)Dgy zN5V=U(alz}vqM$wR$h|T-|Nczb>X&Ozmfz(bYa$IbgQuVLuBBkPU>tFb;guG)@5t= zI9_-e6#-G+5}hZaqD$bltSo728E9C@F=T|QWkf{6(5{=R%bt3GX9<^&PQRIdwj*5b zyT0skc=$dIJ(pxKB@7G<4vR))pjg`WZm9NGXyvG0Zgjb)=UnDM@t(e&ddr339j>dk zgY}+GkI>Y%LXq{0Dw!aM~b7Z9?%8zdtCo?&|ka|dE2^Q(J+HlQPZ z$k#4_f5fm3tp?oiDg`mh2YO%)gA4D~R$B8i{|IfwKDEEN``_7_shxExb1itNKRir z41F zN9ekaorVpmOd0XjpqmbXKK3~6V8}CsAb54!jt{41$G3&L=|VsA1)J-rfsSpZy0xIG z5DPKCOb;sWxD`N41=(l0%KsLb`#J?N7cG&K`fPdthmiBkPun;PMgi>~wfD7Bji|ZR2T_*MbG)3_#7)@7a;UR% ztD?^%w0{h`&x^BsPk9?ai?mMo8!i6?Y)jp}K-vWsGt<^QL!IsdrVcD6h?$+u@OLdz za-uFJ85SyzZtPbpH`+pTk+zR+=Kxt9(Jcyi-e;Qidc zLos3^Gb6ZoA|sBW5|Q^r%J^qJ33HudIx|k*$yZ6=j-X3EXC~*hB14#;Ed|R8sIHAo zxl-E>7a`XxcU?{T!!`#mIsCOA%phK-!PYvYT~dz_pNRH6 zvCVzL6Y8vr*{!3fu<1oIK~#Qyv^J6AWfn7B@)inY70fg)gkcC%-be$b44saxX)d^M z4tV^EMwOIzi}I@#tn9SuVby5S-e z^@9fry$44|x;)nCek9O_j#GDXE#M9;FF#*j(de#V6++kof;R-SfNq!h z>sp2B>qiHgoX_i?#K!tocim2ydr9`?C#1{Xk9mcK$YcvxBV~G1m3nCLw_8rPTG|wD zOMM-^kt8Mf1$kEiD|JAFx(c#*JRRDX#;^j8LW(GE0Or)kiJ*Fj>$oYk45v^GF5p5{ zb?OnAZ*4`|O{C5fvZvFrX)39DA-|oul%i0hlF|%JvGAnnV+9;j(ql8E=Xxuz6{EuD zU&|D=0|#l2b6C#HzaiE1Hd=u2e5*(;45kPli>E320>IYG;lgp(X1uS?GCLjsj|Ork zNYC6O;SrwIT5Y>gRudt3atw@rH<5{jcku!2&cv)N51)X5XryS05TWq`k}_Cpp3s3` zu#>n^{rb2cuzb#7NQVKeUXAuY_Zy#+X!G#3gr5mQ9}Nw%#Md~4L8OBYIXf|S z#KjTae!yo!e8Tysw&Q)jOR*qZ74`1;dyT9xw4!%(B(*+{ZvP$)V^+j}6XpiuYkJyuP4x8!CBGY|DlG@2jfrN6Ege`_X{^{w{VBO$S} z3P6cr$Z29soh#Z1V zQrX`Ah@fS3dHDDD_)T0U4&B*MidXy)78<1Kg&&VQArBHPOcCgN;16(N0!27N9-mlU z{rAc)%&~@V715tXM*+YOYk~0FwgH`Er=BDv&@n=NJ6>Uv8$|J*SWr86+eqLX&``Qq z14>=ycxNmrx$#g*m^uTb1JGjVP&YdgD+U^7}8MO(K$LcM zojiwc5$D+S-6CN|-xWTAX};ga#G|9FO?sTAdmn5X`Mf=0BJ0-+QzSLPwGTQlPGe>; zrp`7XY%e;%Qi8ar7!2VHZ_Q_D-5Qpb=J0Wwk}>Q=&n|4mg!>fSp~`^0+P2)&==48% z?x)mH9`3kDfmIVxe^4946@E(%^~+EZ?M%NKVUk)$ zGVF{7HrF0vuGiC$u{4%ED7nA%LpGDr3!Z5(Z$zQ_;r>nq#9bMaOeBkhafR66&#B`& z)1hVq zezaUbI@k$rk(?V@?N1Q*Jieb0-&gL-^#s4YT%DHj7ZAvTtOat{pZEo^qv z!o-iyErmVz((#7&?(UuGoOoLL-f$&1(Bl^nP}Jut*v5Qn*@cXT6Pb?5faxzBz+TmM zw+UY&J85fg-vt*A(g^0FCK`WGrBbOCD==jm4JFi}zI=8FmqFJ2l(rrPrtnG7wQ|An z3FE2zQcful;LC3)-F-JoB~%ciSjb0B!8E)tY66#xSaL(0$Tp_-YRENWE5BVmSAHCV z>vZdxGWabe!{*}({~Vt+6F(m3HTMxGT$hVu*yzN(;L>V_f?hAT$#5c3MO+rw+bF1U z93^*3o;KvymkBjG56}$}@wK?)@I&qnPdhu!$eu*q=QF;K9G}Qx7HA;ko_AfvbKvH7 zbI>!e3c&8ZcmF=*{}!)av*wV_2!LcqSmITJKMgnM<4{3ot*!@2fJk_fLlhDskMR)X zJOa2((O@Dm&E7s0iKy-5=!HMml4{u80S_%KT2Qdp=q|G*HI%&FDt_wC?Zkim#e@}9 z{}GpMN)N0#paajcuCJa#Rb`P1$%r0UB)83bkpClwpp6W#;4>ijt`f{~##fu7Q3wtn z@tGxTfdBkj)~z|W+R@Wq*uY@^$F@0`UOJy+`m;mZM&cXd?Cgkr8Y)*n-za>bGDn2MU*!8o0DW=kFW@0IXT;AI9Up!uXma~f(cb>) zWq~b0AEU?mA-*KAVR7C&fTnxRSuyB+^CFdi%HW`d%& z8jF65O*AVde3#3(O}GLDD?3kKMWwBtk_+HvKngAv`p04qws9Md3=V=L z*g^IcNmr2cb`cXolBi@fz!GRPw7&sq5HbdInP(!gmpXkE1WTbsN3yL><&U_1pged` zAHhDMpYgcEs>}12oO=FS-3x`f8_Ni1>=E?B9$MegKsy=xAsY8Vo!Zn&-kG-G6@I)Y z@ih#sRDrcjg!HNbeOXR8(Wq$X*b=jqRU&TKWrSr9dZU&Ai&lIU?RG21LjuBn0TFvQwE_Tx1I*_f0v{IdOlL`=fqmuv*?B+-Zac&P zjX0hnZCWYfhPJfyc>5MyY~TlDi2c!S9|3-rZA?;B@Lht2P(LiV@7DDzc2H5?m39#XRKc}_?&M88g3?%|Hur$;CmK+B$ z8AZbnB7K_s$`~n)(O!3ll}qN$A%sB^BdDsVa-?xat}nZ^+n=Fz7RitW^r?m@1jWa* zVkawX%gf5h!hz``RGQ7EC&wTd6i{H4{?G36^74DWzQi4pXzxph3b8!+?cAg+xW%k5 zh!aM0qti&w#w2aT?WbvmuW(|Z04F0Z>rV?&rU*vin%GctIuj#7SufrWDzz@P+&`0WnTY_u8uVSwccUv|O(0(<$eip)r;HR@2}&>R^N@d*D+ zkPq--m|WnHT9J*V!jP!JGtlzMaY0X&3G6Qiw7rxI1^ui(xWMlva1{R0s6~@9gHAsNb&9 zodK)wU;qadV}DKg%^%jUB`%gg6x8tiI7tAGiaID5Q26CNzA54u&TVIs&+gpmaU}(a z#(fz#S2^=V^JyT@;{=I>sQrtgfq~E&ZPb1Vu6>?*?Imv0iR2_1*bU`M2qng1%7W&# z^tWq>pyvyKTXb_fK~Z9q$@>1haHSX|#q_duaVblX7M(+PtTyK+zH7Ynl7kO|CRu0| z4Gr6<&~m}5Q8}{|oom63G>|`~+Lz>lXE9iH(h@^K?QYX;Zbr{EVTnfcGja0jz+#%L zbwpcQ8|*%RuKP(>nT@|m<4|ZaDte)wypq#9HYoh>{tn9AtWS(c6JE`Kehec-7QTmkgS{=%MdX& zF>+m~Vk>4TVFJbUWRbis$=R@mI)d##GYSbI0}TueTyT6IXEt#OMhfmzF(Z`~7gzM< zrts5zC6u5@USa1g6Rre@{=(RU(#>@cY5? zBg+CTEg!(OJincNY9ywTSrRmUhyxfpl2D2!W{+py-de{PzXi(>XV_r`F4Oj1p#6Y> z6WNnFqDwp~aJi)~WZa@xd^iaNK%N2^K@SNc$HB2n!|5K747Iv8;dY%oqu{zq55z}=UD=}O^ zPwMRLmyb8lq@2WXRANTw_T4!}H@@0P`wi|C+ z?)C`5-JBHA+qOYcmeBn1p25f=rha6Os{)Bq9P;k%AJ%|N24Pg>`Uvg0zlUW``LJ{$ zg(>?%#&zbtNk*$XUvKyd$y_xxL;V9t!}-GJ4sgOc>)GDa{2hEbaF31x$pD!4``(fK z9XT61-~~mxKWri4$h!bp5se5GDO(=T@F`({2P(%MND#BW?8Z%j-a;}g5@k-Ge&Z-g zQ9KIQmisV{FFj2$025RsP|@dg-!k##c;wd$j93S?qNA*~37?k+z(E>N6>fit=+C=T zDQg3P)GMyLf5uXz6A@m?OLuS-8de8 zA#3~gp^MIYsXiY>#uLi8s+RPgIpf(M^6o-dCK@5+qiB<7tEbEvUB1rsB?gP;^4~y^ zelkApNM=F0?G$|Q_KZ-|!e`)&1r}o`M~)<;gCrXgX0kJO?b5&v!b(!r&Aq0>rW57z zF_eGWUGLt#BQFK+c4W{XSlY!=vH3;AxhbI2m7v}xpq~I+HdH6=buh&GyEpMf{C%jh z;%G4v2|Na2<<{6Ob1%8W2OeEyUF7%MCI`T=$kDpHsp-h*uEF|`!smGxv36%3t>#f= zVlo%F)b?(L-I<1WLt#?nIpFiUT%MtIzpegswcC^i5`%XgHn0=m-DJ)BX4X{{m`hU| z?hm7WA2!}bQY^PZKjbO_7(sRBMWRlE8qNq7*LXxi(0-5U={5f2`|;x6-*f6=h!I+{ zE9wHtEzw~m=#T2mwiCw1K@OiskiQYHaa8aq(|k}5n3{Ib%zn^&?#G4K`pxQ3my6>n z3yhNXvZYpzTdV-Lz zS1+13Sef9ejz;Ucft1lHS1gC2!NErmy9YwDZh%n0`3sH_Bl7=Z>gNhs34`6#?i+DJz8fL;@Uerg#G=%^KFrcbK+&F*|bqn59ez@5UZpr<3c4y%I~j=@1HiBCv9aZz_SH9@=8=vEVjk zfD=y`dy4qMl4mM`whqo$jHZ&EKh?S`yEHOD7kwWQ5~4Hxf&Ad7DBm6}-KvWQOLPfWbV0*wAfL0R(jKGq1iK;SH1(p)f6z@G=e+Pr72w+pcJ0 zLVt7aHxfXkYhTH|^Zy$y`Zpt5xOA$8maWMiJwT!*$pgTBBG3uKVdm&p&vC%@CJ;2{ zjPOU1fY(Bf1tejl*N=l#=*%s=W<;ZQT0l22TNBqJy>p>7P&p;RY8t);=jSWZJQGCDFUA5>cr#Jx_0yX&3cgWyAmaV*nhSA+35$=sGDM{_?7Fd=7s(Ly1mHwSp_&(CE&H+{ zTO!M?y0bEt_{E!qx*V4oeYKn{TOuY6atE3Ns$faUnISxuM$1f@k_>Si#)cTO7ZlGC zpu#>E?Yn>{nZqX#Puc@bLhhD#9D{TR9>P5w7%;W~(gYw)4yiN&>o-C8`^k^zoTS+T zR<$a;1pVQ$4cyJkToO6WvjYq6?hE#9Ja1dJbNAaYTk5uT{o3Co#0uN9YMC|~3fNM@ zclx`?S^JG#bbj?${>E{(;R9O+m}>Ma8}0jpY{NW)u1o(6rHWz?m5V@C_2)#~CnrOT z)jDl#2ih%EJaW)6APOJ>S%X}p*(iaw5sq>aLlgwl_9JgVny4hd4f#Sk3TqHQ#9-61 z-By3uZDKwE!wf>vKvU^93BCHlj{r*`yW!iiWgkpnkdlyNf3~_zx?s5vNQLy|k9{Q3 z1n?k0U=if8yUt{<^_*f6W}|1Du%Tw$Vy-a%ub)WRwI=Mn6dxw%!1{3Sl!2m;~FfYQ9$h3TD#PcJ6y~;nA=*b~U(K zB%?ul6jrw!v6c6|(-;(&BFU%%z?@e|7S4q?6dz)&^u3-ah%J z)~3rJeIwN}P2LSJ>;AG~+ZV~z8N0H7*H1$XW@|u3;m>?Ya31Y1d#sQXPxUV$-~MKmMtVn&;l!(mvwIIh z0Krc2oMW)=!4y~(b`GXxCCy8N%Bc<_*Zi(uYq_@IZn(!i27Sr1&F%k4@0gV2{UXUI zSF&Y(&_0=1>|mR71P%k77nYn{*}hUZXBJx^z-|TtG$IM9gwR1bfqai9xkz}+CJ^rr zZ_|CLNet}?n*!%1;JENYi3E(16K*vs=5+K20BjiAP;v79eP&b3jkOoo^F2Rl!t1TL zc3qBX&N-3`I}f(Lbin_6x>?e${Xd8n&iGRa(&;4JvKyP_z&u-*w~DdTU1TptpI zKOmqB9-7AWt@q^tt;{yk|8gbdUp#0GYP?;Io8ewMr%3*999hRa*9cW5mPp5f!oAnN z{=#)ULf{LgHl|wuIeHhil$l5mti#NgD!4)i1Lo=bJcDFBxOeGH9C4V|y(H`Q!i+$o z8lsh1 zD(G($1Q2 zT&>0`6YzX<%0`RA{SdjqoQ?8)1y*lfns7X-|Grf5(Lenk&s!OBIBdT9;k?18>na;j zuaXqA^t8U;wIzEFv9enEFR-^(j%qI6zf=rnU#vQFa-OlSy;flKm5!kPeg4OnS3jCD zeleGys*LtF)(gm|zBXd7U!shpV~?vg;<9fwoU6t}3Z2hK{MDbl__`Q=XL{Uf{kH2Q zak`_c7X}_lC-_EW(gxiZ%z+=UQ(tDAuNd|5(~&%=Ol}okKoQSAv#IT2L(p}*v*)aA zxz*RSoq5&z&ePaud&O*y;e9Je*<=)j$g@lLI1_%aM2H_N@W$$YE0MGFXm^DXJju=? zc-It))sFxNhKQdwY8J8dq`l zpjO@Cg}apz&uJheD{6bMU;a=!r+D8U@#QXprJLt|SoQeiEPd9U6Ax*fh$V(1M*B_& z=orf{Ehzr~?zR`$Z4bc;v7MP3AsqrT3`9UM;!=AsVCOq@%A;o{OJ*v76en4=9Cm3H z4c$(fQ`|vD%lHr3MJH*Msqf}_;4VV>a=GT(hCK%ti?82!j_t`wYokXFXQt@;j8YKs z^r^65GaJ2%gC(POYar8ayNmScRPkEyPZvCpqA_|>L|48y5-|nRkv`FrF+^N#g|bG& z$mvSD+$fk221Nf#9SN#|%WW(}17_^<9B2<+e95qLqg1%DCCB63_Yd`}-1Lj4eLr#X>pS4FY~TLx7VRDq86ky|kiDryc3EXbS=oE< z%F4_p60#x^*(=$5gzRh*vN!+Zyyba%-~W4kexKhX?r~k`d7Q^SzTZ#hdt4(hi|e2* zPj3LztxF~qkfAg{lzBF0eFN<4`)ielP+S>00NUyU1a(7C*k6ae9&;-CTbkF?CD4BHZJZ#M|*1fy% z0t_VTt?*g+dW_c{7h-p$Om>DSc5WgPdgy$63lS4^e{9R&(ueG4E9m8GKmZBD;Wr^t z5}kxEJ6}0+>S=FD(8AiYA&d;w9h?yA0=h#OlZ$YQgst`cIup1So?P~u+goi`=)-b% z`~b2$yLeU|)aYIMgAGimb_Sg*7QKeK$m0jwc`V~G=owLFtQJz zxgX5u^WO`I?>r4BNbyR;H;W~oi~S+Tm>)Agq2Ra7hVl&niwuoHHWfT7u-HsRtycPe z6ZtN*1aJB6gpn9nwk8mJRb`TRrbA!}MZBYo&5(eBlmp}<;a1OUfCYOV3T^(U-owAu z^*|`Tf~`j9$GtHITvtdwegC))0}ybbBI(!qt(zAzpJ=K_d}K~Mj=T_i`^~q_cEGuE zIQ&Me&~&GP5FFny?SqY;94OTU8E;568L*Rrw+EU@6s*bf&?z+C81V2gO7+qlh(B2W z>hTzUs&32mU(ge~z|8%PSLSWRBGlgD3OFhr#z377Z&0T^*Z}u@g^y1as!+mVuE(wr zT+v&>$#&dLG5K+2z(66$NF|t2RLR`&{;l!Df!HeB_3MT$I?<7ldg^R~TPKP1j8S~2%qkw^ zq(o!puK>^pt{@@k^!$b~2Y2!Sx=YG|qi8VUvX>A}=u|q~?2}4uHn&5Sf#udOk6P*u zl+0;1O!%B+HGhOX3T310Di5$50Y(NEA3)UT#bvhr)^@6M?0=eG11kEmDH>hD~a|qq6^Ij3{J+NowgRCLupN_S_w_Ux?+_LpUOqsK#$Z_}TpSQW3FoVHdK4_kzV_@h6 z!7+*m zeGn5-*j2remKfdu`vR9R8kGb$^9C`hrbFou{s)CNYOF;5gFOk8aQ^L}^`*QXfvkTd z5kd=+;v}N1GJX_((rsM6V;V7X3!7J+oD8@uub=?AiMAgvT}CUxQ+#S<)Cn{GU+Z)G ztzJV38EOu9olt2671c01yTj29t@b8tf@T_^>rQT`ZEkFU9t=NE)qE97 zaroTUn%3jE4|>X7$6<9Vvw6(7{n$I^o|1lxUazV=a)X#66P;s{`Y4aid%I zkd7;p6GZnRp%~li%W;A4>?%XO#RSLzld$Gnu1`GXU_;(p7=DLNZ^+r>g9Ueb~I!go@}o>2xec3guz*NNx9D4P&8g}i|xz{e+|p|sA|%C+kQDF;rV7# zIdm5khm7FB!bQoCRgUL9(76t0n*0Pyhl%e_OEjr@D3ceou(F->gisrF_`NMg^{X4`MfMx7_G_WbN(Fvlu%p4ZHN0)9Cr*p zc~}xY#^s^cNfv>;Ho`?7Pw+)Spk>j65lxDT5KeqXH{~Llv8NYC$g8I;s@|fu+=_$f z-qiCR;_|r1$$|;O_^4+^W{+=Bi5|C>87SG6YbbB%U5);>;z+wZ>c?K*fc>OnjD!cq z7O&F%+2~fj*wr3hD1nq6K+o4P7CSFk$vUrq( zLXa{Xv^MM05OI$HOZxT5-nyL}p@3FSsK>xd51}nkr-T{`^p#vGa)6Fa(ua}`ZU^hh z)tG25`okd|}LKbt7aA=C) zwwSzU(`}S{jh40=Tf|07AaMs-L8cazErxaiwj$o{owwx84E1f@Ey#v_Qalz|Sq{)j z-v$O4M3stc;B2TL4sxXM%YyO-*JM@+IIhQ-4o%EM;~Hw6l5w7l!7Tp1HIW(1{>C*f`#!X=GrU8{a0oCwkDXBtg2$D^7xxBc9j`kB8f`_5+;0bO}2oQYw zsMz-Pz!~_fIOgh;i8@YshRBd3y`L|*^2&URxYOta9OLTWX6z=kZNc=E753Nz@bjisnyG>Eq5k7=<+VCt*fg`#{v&S zg9}`Uh`?6~$XS7Q)c7eMX86*8YG^`M?AVz1iSpcUAcz{LL_iB&)UOp$EN#TB;)vwbx4|8A63ld>wRyxot^H6 z$Z~xo?RziZd9J7J;?-gq(#VzR*yHiu2Qg92a{Lw$LEb<9uhcKj-yZS|bUkg3zEqeH zbTWZ9ctU!cWtHwDY~6+bISv}w12X|OSHn{O=hMkabk`Na|1KwM^-qTZh#xjff_gyN zydldwabjWteJqAD^pn{Iv+r4#MRWSnL^&v`suz3MXN+H^od`{-Gh#0w!wC9dHSv(2 zVdEjy&f$wlJlML3Dz#7b>y%+K!Z&O{pr)EwB@3 z1g4MSM&2Goe+S2w5S(}LbJz<`Vu3&i2od^9d= ziyUlEO9vm4CId)H&^|3|?tpbbi~b z1X3cR3eCL&DT5s3n_Hw{>rldhyS?CXD@i-6 z;m|Sa!B@g;Tiw(#^mG}D>0-S#(`Tv&f6B=Qi8u0>2J64l_<}DVdO95n_u@B2r?ewH z2pvk+g>Cws(?m}>Th)zB%O!Qc#}~;DRgq_?Ka%*-VU}jb`t+8=a~TCAF9Y-X&&lPc zUo?EX@AgiazE7#W`XE(JjH8}CSH_$0k&U6ofK;j4&RaFf4AxpAr*zpJKi6mRj_LPv zTWKfsPni`&j-ArJnp%^%P-nhdjKSdhBdrl6^v5_4vrEHIUJS^)EW3OIoS{X*-<*&7 zkxo8)n$?5B69s!1%17?*q24doNV|SJ=%o$5JtZ)Z9F6PnvU9D|AfxSrK6y)zy|KKl z(b9dZ0qY1jOyYrx_0D5$C!DVtB08;&T$=S~FKq_cKbG9?+HSZcYSveHTg17D{%79K zA?56qLelJc>WMPWq4%SCLsEQ8zj69)L+NwDE*{3pfh`(pn!kS!FLcC z8=czJc0a`wW{()X-onk9blvRK8xc=8cV@T~QZVwRdU>r_{*%z|tECfm*^7hhldUnv zojKNy_aEHorTgr#e5mL5j|*RS95gCdr_a$TW*N3Li_RIf_H1_koDWl3z{SllX86$d zevbdW$PPnOFL7U@F{e?Ru=Hq<(@c@E-=|s9hxElFJSzUW-7QPX1^EJaL`zR6q-VPh z3G~Dz#!B|JH=6aC_>-?s;q)sB2N3UhGcL#I?z?LJS!=l`S&`*KPppU~BhK$egsl?t0j+sPFCPA1{88>@gc;<|^jt`2GC-j93Qcj&gYdlj^ute49DNDCiy(i zQ~&MviuTM_$A?dMl&>DkX{Qg%Nz0eA-r*Met`hjnDL+Tx{W&%ULn8+%>)H^qdS~a7NAjaIE=7aXqYU{1{!JY9Ix9Qeq(_OZ7Q*u;|eY8H5urXsj@f0GJ z7pURMoresFRw-NEPG}x{<3ecZh72AVCS#q)TPkB_}N)T1HIaR)3VoF<4Z?;uqH%m?Abuo1Harb23-gTN|?!Gn0lOwP1oXuiaLyY;y z8U;ROf~b27pa5)a0n}!w+H3Zs3Ky+1yLdsTO7r!s#7}5^5$l~nYq;P86;rn_(8{m> z&XJQQ3}s!R*XcB)^OU$6YVgK(`NMBIq2r8N6cyEAXz9zjiwgK)Ygw%zpzBVf33(`~ zG+9Hk9Q_!1P0)>^)GV;;V6(n4ozb;4)xOs!cbAu&DW-n4RR8lz?xEOr3y;|?f1K^j zFx=HHHlh&y?tXt=9eJ4nmgn`d}UJ*>8(HGaF`9Z(-!@wID`P3MWRy}7$H zc5&KQru{5w_SpBbXIc^Dwo^y?)lAvL4N@N_+B+3UTzjveTica8IZxX#ay&s;_)YXO z>9^oQ3IAVqH&+>b94h19GY)3F7t7)e8SIpbdFO{?*gxCKXMJW$@>h47$aM5jYZzbA zZN@&*^(>}(8HEJp(gz9D2~P6q-E`9T7Pe+h4Xp;>+y5H*9{%dxs&T4X;O_GEo^Ye~ z52bo7=BbzTvy$IutH^WE2aUK>D{V%q9pA`auJ%uv(kGQ8j^Ow1wo)3+OB6e8JDUB* zG1qby|9Yxd&+0n8^Ks-1e(4+>jjUD zW!8&N*%|l@X&rgJ)W;$@RJl;v|JI%^&RRaFeRUG?mlRS&=-UQ+^qzcC$V@j!E?|{ZKIErAdju z$wRtbP|feo(59iD|M)q%8lQw=en`PCuC?CCLiOhEhoVCH*U(o~r%%->`f_HeUd_&* zd~@o@?*&Ee>xClkAtryc^VuMl#a^}h~u>wUgdc<3}+cs88G#^n| zN(t#p*|l^AsN6ITxa7!V5@O(CWkgS$@r{1{K^68e<(X7z^0u{d)F5G8nj8Bs`FUp6W%C!qo=$B8pAtLKP zBRBHOwR-CG_1)pS8j9Il03Y+o=|ki*jcAj}fO^Y`qc>G*sj3}3-tG96lqmRbk&q2{ zvYnZ76A)l6SZ^46AEh7ax9m*Q_(oe)dizR#{Oasc}=b3@eU$WzCZ{H18%SJ_1jm+{2Bn&}tj0b3ZL>K?{>gDr6yjAGaBEvDk3<*P zjVI7$Mh3qQA#7iF@uFv8F>lG2MB_);{I3@tvAQsUM%V{~u zrJojsL8j7~usU~JwJH4Tqzrw$BvMJI-OFpn#jY#ayjh-L>{?jY@32rOGZ$uhKz~0( zYt)k7mN0^Pow|0=*2rc3*+VVAlY<-EU(<d=0deD zPrIR#h2(n8^r(`i-`&P_jdNDG7!_>huj1jP|3c$HnXU2bUo%Z1x%ThG1w{PIn4iP~ zXwD?Q%dz;69|P_U5WIrM-#gxf#Hu(|nkVrCUSPB2DsRD2p8OJ$lZO*YJ;g|y zwGG!@uukDryp>^Vy;LumEzT~3@w#4i>svSS};N}?_^DAY#rpXSYEA`tA z)O1%vmeMb;kC~nsunQgg%aMPPF~y;^dKj0f3-I8IWSek)9hQVP3%AI6W)nDJjf znA<#OBy&4RRw`GV-#Dqrsgxji>t^ZbYTdfkvs?AAAQp0E`JDT#O3hSkxEObh2PXmd=7o_LwEr~Neyz(SJWd~W@&!5>kTdo=$(oU$z8m)z zvgfESkmryK*}S0^i#=-s?Hw#UpKvU_QG|xM90qOg;lA=Jye~CJ2u7A|n;9O`*O54N zWVK!Yq;!kVV|&5Q@oR>D=4n!s;vXAkA3jBK%xEfjeGm%NC(9B(&9U;R?)mz+rKL+f zzejv~RtiLLgn~sBG+$W~q$-+U+Htd38|!GnWVQC{(nOuaoIPBq4+^ig=Hn*|_Ky-t zOz0khB(F%29cQ&KIv_fKhE==`QZ!#Lyv62Q5_gzbVj)6*<20lxq{*2Z+R6M2KT~{|2 zE+2>QoghFP{U#yJqIS7Wc*cS@uj;1*PLQIv&| zP!&ELnUJL#Nqve`Z~QcBdc-izL+hD4MZ4>|%J`C}UxCx^6`t`8TwHIFjvQM9s>M$` zKPG=JZU&{6W=?y_7qF21{G7aC%rW^2ckUareRj=9Y0}a>MV|g+130A&TRN|`$iHRU z-!h=ZQ0gMxC}A6`e3Zlfkh^=xUO0*O5bc%AMd9PDko@@ic*N#BiJsG%qI4chR%2k3 zHTI^$F)*W!H(L%vC`Kl1wbe?RT!k$^gREJNk8g}FyFE+NR=iGanw+MlkiPuumdAsV zw@pDd3-y+1Tt>?(A0ay4oswF|A-s^vp*N9X6r%N=V=dtow^FsZhjeuO!^U2`dB)3K zc2+zzbyf#4fjAKHmIdQ=%Xg2QaDQGeeAMy*HYO*Q!3N3_a<>mPo=MMkD;;6W=N{Q{ zgr=7lx7$%Yj_r<>-f6ceY=|(@)!E6Oz6!-rR^bo{snGn>Ty4}k_hdZ8n>5ug!Iir$KN-G!l3Uub5G#p2RSs!6{6Ah(Hnl+IJa zCX@U?riFUq@u8o_mbD#pwd`$ToWmOOR?`qBX z0y>WtRTQ&hhMQ6Gs8MEkE{7#s);yU;bbIi~F>Ecj%ofIj{CLuQZX`d96RVFm%Mn|c zd+_xdf4?yWSHLghz7%(pL*sYezi0K&+sSLV{vcmbZ%KTCr^7_BU^x;`&whr>(7ZY$ z>O?1Z3!7448zenM9`*0mX&YKr=e|pRw%M_!Q#!jA7ued0LgJO?D}UEUF{PI@nOY+8`gm0oElnn!-8S7hv@Scxj>QdvgW zbbiJif2PfxjE{K6l~eA#(I~M|V6$5>3z-m;RaZH>dDh~V=tP$*TL4P z=g>%7n=yXoHT4}ufz!OD%Bi1w!=^GxzHe%VcPCXwta`QtG(2?KM+Lu1fU>1QvY&I_{z2VHk4E1{ngI>w)x z+!0(rHErmCMoq0lS}>0oRI8~DzXtTGa2VL77KL(oB)?<9mvfKlNE$P_za`i{P126P z_1pnN58e|N7of4NTX1omo82SS^#rs!1LD`KwriO=C%4`<)4y=2~q zW0gim%?Jns`p_qi%f$U*J~H`t~`c1d;5OYvQ9<0v)QOdUo5)?Y64@^?UJB z7VLSJZRWR?7L?+*0(pBm^hRD$7i7`fHBW`7JWL<^VraLOL#?+ntHfurX(k`4sJXH^ zs^=i(zgzm*&Z4WVnYBNbriC%T@F7TNDAB5;Z~(X_Xr@DQRfL!>AOsD739X zP29)DaqZjCvK`Fir2k%k*&itvVorY;%!GDG@jw`y5`iX*^V6AjPm{S8HVxu#H(qRo zZP5#v?D07I-P;G_+lRx?s&8*B!!!@Jw<-a)2=n#h({BGqEy9D61z7{oDV`9$ zyKrh|E6n(0R*B+Ru0Z01lcoNXjiH{|ma5(Fj9rHQE7ohvT%VUc20J?`PCsfiYuxTB z8gmNSvM{H5PeSc&wEYFAADBXW>?CA7WR+(NMU`hs3*IP>rE>htr;w{P)pVnyFp!H^ z3$*txxnb>HVwf}8sZ-Rm<;EGJ`zY?SfFjjgSeM@P>I2>BRS!kR{U~f%9X6-oWy%UdHA4uKH zd~N-hfp}Hujc}I_?!Q~kzY6%rGidzB8;N7ZM6~%Hi8IBLbB&E$=4X{!g2(+?M5U8h zB6JfQy&UE+7ZPJdP049=pP3xJ_z(HB1J%q2x?QMym9{8J`5vBGJ<}r0tkfM!y>0b5 zqwD0z_N?)0Qm*3MTy9&*vZBk?SJFquT7?r8R29|m>IZCtx(;81k+HCvpVc8O>O*k*vI>EtQ0fk{fCFcf+qSXxZP$T@ z-RYOU>D-_r3%T8|j!DNZ!@BsLpUNXy&ZZ9>h6FPFb>AH06<+ozA@LVjc3tavP(rxM zw`KEd_GhD}Qo+!n%w^~8TMk3g0{<+J;Whge3`%G>yr0c79rV98oL-uDtz@SrwUvj- z%6yqRw_;{@c_44Koiv`CYB*59-+1RMi|Jpsk#QPP;y3+}2OVYH4Q$ ziq)Mi`;lpZ?-xX>YuCF=cl7$~l|!qYNOsutq!XB_U>-Pes_HGt*Nd)zGrUa z;3(S>ZA??$B!`X&QSc?IR~)*{9g}fp6-!d`;DxALDHl9#3V*Wb`HE`sZVFee+Ry0Z zKC=13xu7tH$g|?9;w)idz8i%HWR2f76ag03Q$4+xfKtj2@Oz=KYA!_qQb~?xqdr&s zmv^V?O$VJf%$BTX{dBBLNiL|0#Bi&)4!=q`nR)qS6YCk*<@z?~VqV%8KJwMEp7DE7=qDVkQ2pui>n9`b2|DyI zq^AZKqk9du1WGS3ZihA5tmKCc*QC6BC|Ah(v+LXLtW`p8m1F-`)6QKHF=H=heqOR& zhn!qobtQsRXU?3Vy>Kx60zml07Z>wUQK6A;S)qjro66Cq_(NW$t##u^k2rg4U z@Ego${;;m%Ll9nljZ-B22QR75&OinXrb8zdz68rA^jwR;uutaNm$5MWpPmLWp!!zHk<8D`?Zya zOY@r}PlYN%R;yT~9l6*^JdTx}G_5-j?j|f&eaUU~6^F3M%i8#i`UhEBab|!@g-^g$ zSt`P5?>FT3RpZoz)Z+-1fNRxrSrMJQcF`w(o|t#D^hjR6?4u&d11pcEw$4M4Ek48{XRTwg9rbhZ*Xkq9{IS^pZ?)FV^e>|Xns z)TL8u+9f@*S!$zm(0uCC_a%Ga+z9Xn2vD=WDXr0Y8ft%o=4##Av&4Mex=Yzf4)oCA zhADe0PSoi2nv|#{^&3dK8h6u}SK~-Xl=JVUOzVDzUe<|MhVhJtjKd;czkUrtkbEa=WElgQnAihQ6C>{+>-9!_K9T^(~yn(${`9l4|J63kexp@UOP# z&CSieEZiyWHy%vM<~CYyi>bz~JA3jpMl+%8BvYM@aiZ^4;+R+)UOVOVQdiC(DaI?W z-=Wmbg!WW&+ibUlVUvg1;?$>*=<3(Mc%Kx>EVlh@Yp{$r4w~VvvHWjOk-CMc3#4v^ zWMyUB0N6-<{97N1+OBgcS%%Ys@d%MBUNNHpfwkj8Y+heUS=N<6ZW)N!h+j#@9-EUx~a!e0rqKx2uXROpf*f zi*s5j-|R+RLMtiW{YBU0uFHqiakyqM1jz#$#zKRc9L&zbK57bnxdS^HyS|>=bA8sk zdG@Hfw$OiMZfpHZzOi$i{KPBS2Oc3`ID2>_A0yD-%r5FWXaH$J|RM>9pXZq#^v z-fedx^qnl`-di}d+Fk?JVl|hvMq4XKTf_WkoSCQj34$P~a52BJ8qI9JUVeflOyp(b zr7mBBH?^u@$3;cdUqaWY2sHV?0J{*Z7djcx+=~a|CMt3W!)XlrDk=iV`7oEQmh9)rnLRx?U|Gm=E?UGW z{?|!aop%j=Jv}4{Y~HH@BlzfUf(-U!-LJsMCZ?oJMf;aKP)}X)QYv^VHNIezFoM^e zUaxSM!D*t|_L4K9NJShMp7+nh%N(^Z_3taN_FSMQZFfCpm+K4bKl2{WYaaJiRWIP- zK|h=?@Qkny2?Z3AeLYeAUOsjBHpRw0?d^=+jSSPJ$=1VXZ_XA1yktBK15!~Tu4FWZ z8+1zOrdfKEya!dmnL9!iDMT@jo6Xia7XAetHf|H`jQ)MIGch8jIpZNqmAGNEb!ilH zN?}~uERNs<>nu&fKnHf&pzW{O#|f3YFr3QA8w9@)t1|g{KD6rDSegN6V9>I+HJ5m< zU{KMK|Nd1BbkMf;^h7F_!X#C#o2#b{ApFM_ZqD?SiSRGHg1%!>_J2m1s(+W8{wQ;W zC`d%R*nFZX9N-KBnR+1rJ&w%mu}4|f^FWXaa2p;)50OK(xr`4xs5p&63g%E z=BK1w1(eA^KWKy=kV%nigO1N|K&CAVM*He8bta7F!l8vKXki|P2|HM??`;z{j6 z1%oi{n8XQP$g(&8;Koqm`UZ#Q8uk)`vmgqbci~nk-@ZBDs)2|{15m2)hJxZS7&9-# zDgl?^>3o<$K$3^`{|LbUOM*V;fY)$(u`j@9XEsDof}-5VF@kZhfbZI;tW^aDEHRi- zMtB5txg5T79c7j7CGWpWyJl|_k?jZ6cbBLjL-d7N`z#t|tcCykYgxNx7U5wuz$8a3 zBPbp^=un;5e=2nnaKmVU_)lHoZc_Uzv4o~6ewa`51H{GNh-G*-L>}`#{s6|r?`6EDE`;g%-c#N|nV+}7Zq)f=k|fz9+hgnPQ8tV~cyh+ZX+iI71h z+=Qw|6}+AJ+*}TTc??!$R4d^X6L;h}b(YKKxBAlZ@*N=|;NjyS7ky#Q=3}g`P6^%l z0g8-|iZ}rwQpt3(){b1Kr$pGBy{`sZBU2Qq@K@4RZfjePfZao z_Gkk)R;I)H!eKzUEqizzrkmYjIj6Aug8q-`EGU#H3%IHOSj1e&?gMMFr80N)n=h9k zgPPR#?hsf>>@bYuQ(tx3B3JTyD`+8VN0&-NW|$KHlp9nW1%0I;&lxSck8 zDMKE`2cHF0yZ9iE;@mi+AplPF?vjf+o92BvxzW#%&F8uvBBs^f+0kLyv)~+=ZocO*Ef+5JH{EiX&wa@9>|K--5zv3eWDg4d&u;?G z?rVet38L60Nc0C6yc9XTKHd7D2*e9Y3LuBOaurZ;JdWP}@6~YrkMzTD%!KJeNLDv$ zCE&X#IYMZlz43TA;D`}|rB~73&h&SrM@AtiX6rIwxqk5U1YSZs)D8&g7<`z}I1A&PXaix4`3?XWgII(34zULGg6#ne<-zc3I};Now0CV&7UQ-o zfQYfD!5%w2fBszK4JiZ~#}c8-Y+iCn+-l0AhjHitrr}`aU(1tqVPdTF-uVD20)^#TV0dn#$X6O0cH=U)0T~PF`Tf&?Seuu0SCSinywgc7Tz0ubrJ8PtWA!WX~ff2rox@-a^^|!0mlt zva`XiHSP`?zemh!oE(VWrQtN3kbt*ckL<6*6d21i&s-5pKGQ#V0z32m|Cd@4fx7{G zm`hnDGdaCaU=R~4o!>S5?*M3ykPtAdp%~zk>y^7r9ZV&FR(!2wvwu#zQ#r@L3%I0c z5vNd-Dt9z{EHQ?%`5Y~rjz5?1>*Tiv$5}9fJF@?+U{W{~o0$stPLU#bdkzahF%n>y z9hTxLd?9Z3^t=L?B>OtaW`6jFza^{_MArg^2oH=#oe{C0hO1vailD3lm)jEPOFZYB$>{tUFKAOM8+z%^U5aIp# za=}OUpWt9>jQ>-FqfrKD!!IG}UQpEqQ2)09$SBR1pJ3GN4A~^z_Vwfo%F#3Q#D`MGx zaC0E<$Fmdo$Ru`4$|2=g3QoJ=GiXdEM(h@_sYS>*_V0F$z>tKe^-s{n|~_L(lk0t;y6YmEQaQtbc@$S|F=zgKcBNI?Q!95Ik4 zh`|@D00qY0^PV7LkoY4__a8mtAJ1gCzWjkTsunsu zMl1uE`nj-2c2mJxhcW7AfA2f!gVTR)t`uEJUBUHesb+OhKZ#g2u)Xi#LX(eJm3QdB zmoL0T(y=ZH54(4{L4eZD;)L+kG>3FBuL5_NkVEi49Z`9;mb%oSYDEgXTf)Wcvt z0+-q4jm^zVRB_;NAq{0hb^I0bI>Ck)6cjK|L+8XDm^^>x1wG3RB`cpZ?kFqw=Jl4$ z`x-~h?*OP!gUTZShmiqoclyfSzCltE9bz~Fkbby);lP4Bcpz5*FxKw5dG^!RxIeC# zjLa}{#j?b>qno&6Z7aaX*0}<|&`JHv0tQHeOWJ8TWnqW4u=0P|PjRGu)~TM8HfY|=M+AL^zK{|W532%#fWSXnkpXeS8=GOThK;&w z89wMNAV+*11i>4`Ijy&Jd&XD?oAZS6N*yY|^*#$JLzlw;RCS zOH|0b9&cbe03Px@;1c@UBJQ7a;X@|@$m8?mIUC+ zBSWjXa`K=##FWUoo&MW8NhokfOL4<&&qNI{q};s+$hY)R)So&Za35S;5JWsYtSFMy z7$O6hmS)hPp^7{VlA1F_Dke8io;f2TR8j7B;;hu|STm#ygM)oQ8HR*leYd6o7&d(Z zPTGhOsDsEMpxuc=(c#?|U>XE`_jAZ4h3UH+Q%3_hkS7Y+9EYtD3W&EyL#ERU8K#bc zl~qLjKl*@^u^@w#UL)M8%a&}E#eY&l51;9>^&k1UpcGQ;>Q;Y=!UVwEfK)@9Zrpzc zaX>7o9kFAL691+C9-%Kmnv$~gFS%I+5j%tlQ2R@i5j$^vfgvCOu>g6T%i`ab7NT&J zHu^ypyyx}*_@NGL06Lv8IftT4z~(zoPVVRF3D9HVEILxQ4ZQjRU(gBt$?pp?7}p_iq#Ms(=#b@bkpqE zwLlMfY-7gQnG_H@BbEUiF+%0Mr>FB~uCq5_G(o6gVBmvDXCcXCc9M}SIyxHIC;S>V za(a!t*B2+iJ2M;fcUp=E;qvrEo;(zU#Mu8iQVSls^>Bq3N&zuXUsuklSQy)nZa*Cv z-<&IT<{pN@7jhr@{r#b2l)xTC=f9Sd2##U<)Y1!C6c1nDJBn6AZbVfmp#(ug70P;p zHOIrtG#M&?(Jp9Y4tEJ6_a(e~Kgvum`1u}I%iGfv?8UwZ01FKAk7N^h06+S`TLORU zbqgdffFcJh1qk)=3!}lv1Kn40jEw#v*B+pRPaWvuKtD`VN5CCG&FNx?Bg6*TWtZ;1 zV`md~$U}r#_5!>CR%K267jnWQ{|}Yr_P5IV;qdnY{H3zi@2P)zUU+lA7vNuK(Rgp& z1h6vnXEmD?Af~kLG0QpD;JnD;9F$)K0b|}$n|RW7I3YU!Q7^g_-2k5yy2K!;Ja66) zh&?P}g#`tP*MWRZC*v<=ZIZJm+7#d{f&Srl-~_stv4)LE{d82R;)M~})~+rhZ~#>; z?x#J>q}sROVA)3i=Aj{t!?1?{#847BfZ!$GK&)7JcmT_hsofa);_Q9TsMN;}5CzUR zurzCS0_LnD{lkxxi2B!L7U+aN8TA4*NFj4jc%bbPzeO(0JL91k^T=iTs$D#)s$16#v`K76$FuT()< zcVsfc(__ab2k5aeD+C9oUycx6zHo>cGCt=a#R0iIu#5ZR2fqNIIU=G>RdvoFh^d6s z)YOE8lM=TmgTGSmgu2MZ3|3 zkjm;*cKRmxi2%j+%?b=6N;G`Gvj3h1F>DfHUaS#>k^DbBwIG&r&|FAp-yAakrI@ar zJ%=9J@h{s6&}Wfpy=_xVSljtOUo5FU3(6Vm1`4An;Lr6#MM6#;JVeqga1|WK7leX< zB`BQhzYlFta$bJm9Dx8`>Uq*nq}#=6P$5M~$jG^-VGI%TRaQ_y_8UE2z}sT`RbjBH+Kv;^ z)-*&oRKq}~;`4tgI0zN~e+9Q%vReFqDY!0(Jb*7xP`g;GKJ;OUgDrBT)a@Y0nRXUB zwC=u{=h$DR(P*qWN0ekWhJURM9r`){1M3vzKWhL_nFPQ}ZbR~R1df##G!;Sa{s@su zfXSX^)qrSRgM1n?Uf?o2ea|!1P%*2e2IZ&z<=MVw1DGt(Yyj~uhS=AmV&L3YV$&ax z5M#qGG!b@5KrpXB;0i7WXfoTcH;PQ;V5k{Le^B5$21DIq+y^-y+$IERo`={KuDdFx ze{Xw&OiEfW_#k`A?Jt7Fg(jgRu&dGe4r{-M8phxyx{Zf1W!-<7Sw?vC4Xv^HJ^;~) zz+VJKsR34!1@9Cf+z|W~;?rE}B^YN3L5mssU!0NU2b`FKvwsB{j9|7k`xC*M1r+`# z;o+9(XS2T}6y5#;OT}Dp*&0zm)N}^~*`+(-^Jg|}mj8h5rD&;Yn1*FW4B#M3REX*j z!rt{y11XPE|mL?NsXO}PrHtP+9~Dk>^CwV+e*rGzdb zZ)bURwfY2OQGjBGY9aexUKR`hKUUdb>xG7cC45x3yoj4*xTF05fcQbgXO3^8J?W~2 zar=qhbK#ES63HlEzol?UccvE002_ZA7P9K0x59w zfYSuId0)QL0lQH9mo#VWel*nNfeqooz;iM}`-D!B zBz(mZ?*3P(?}a+6$XBRQ(~*4yHE9CGUZ>l5X#FW*<;)}8!mOPJ9sVG75>Fc-Lm2_~ z2T(DlBUMP@?7N`Af(ICqP63L}kYDqG^cbo`Ztkp>Qh<*LF9&!y8-VVM`4i{NAueld zh|DqQU{0@`Lyzn_6PrxRx4iaHY@{U#=OHKudWy0N`tQ0D+vGw<vGOdd!&35Zu1tvda7HGq$*0z$sm7AI@IXY0xW`6?Y1 z6(ANy?W^FSayL-H(B?@KjF&r+#&irYL!cMUNoo}srIj53u`BY8;GZ2QNK@My zCQ`&TT?RiMC(oe2fGx+UpZj?&%pgjGMt0e1@9D8?8XJ4H`R6gqD-aCck(QP|dGcgb#|$nmE=ttyMGQ|P+iwIRK}|u8Lf8HyV-|Ep+2wqcD?kai zX8uhBSm!G6e4jw=3&Oo~5Cx75BthN*6`f0WmNVi378bZRh#^bw3;qzXRI>$V3_i#> zD#J@ELhy>c!r|sbMQf3Z@xvgztbrIvdaBP#^Wr(L=r|Jsrmwie&)+M?9{$*s*O@AZ8OH)IZm{v}*(lLPY2T zh8|PE%0m$V$n5ve`VUT?I;B*wVFlPZJTSlB(CjM34ScotqJT++ z+;;TU8sPGshpIjl{LWTZvg}Id0U{+zNM%-&d*hPZP$FZIkzrhAe)%z7T|M5vik4{^ z0=J+^*m0&C87<-W!0j%A;3EP^t_=;of4m4NgfG*MjDuTN1+agYhG+aAD?+8ppfB$R z10YU_YN4$F!+m+CA?4%KwISiG!s7Hc;x}K=7>9~QTWnMVmYKIhA&a9-vw~xN)AX5 zLFnNPv^0ERF7X@L`V&7{pdQIQAW2L#a1O`-&PNhsU?9|X?A8iH-UYZu!;p!=n_ppM z08CHL{g4T0g;B3ymJt;CxXj0a0C+(VdVtWjPz~%{jt6IgX+OXRabOlG_4Ne85HOB) z*!GOlO<=~BR}Bt?1nB0yz^%yrQE9Av68A!CQsGzHXM^gB5Q zSLX&P05J}##mE^%DR@wV?Jv|;fuGP5^5tBRT|h}DQ!vO?fG145y^2nh!{X~fAN1#) zUgu5Yd9VTkkjAAgE=>WlArgSF_Yv4`7w|<(j(llUYeLJ^s?wg4kf0^D%E9agoff)c zt0&gS0bqF^ifg=CEAHH)_8U`4{}z@0xIiOtGC%`EC{D-pmH1cB=WD{A!F>VJsjYAt(Q$Fw-gpQh z3&nA`EN{gN9WTgGB101#+EkJR zR7#7%bLLRoKw$y)k|+e!n)762P{P7s=8#{}o&+f$&>2r)J~-O+#3?5MV;y4vw~Ru8}Xq0it6R zus(nkgFXB3oj%gQ#&{nn*<{Clz+J2XwJQno)===iGp4pfjUsqR;fjj9mVx|{20ybs z-RcRqbhtl2WMSF8*#_dmyi1-{EQ}dIeK1naX^!76M|Dqj5de^uXmzY0s<0L1K%SPp zo;~0?Rngo5On}DLs1qSjZ+fp5&pFP6yf9Kxy>Z@IUjus5`ZYjzKL@*o5|1cF&`C6f zb`l96m>iV(;@@cXuYx!x%c&SZ?QDRFaRjJE?yIPfL9c^1YK?%!qY2rCQo%ez@tFtx z!i{K$zZcn>Lk`hcW;0R>$t>u6W~cRfwJPh9#b`v_bq+vGW8^6c^FWYwyN%&Q!k}1W zxx`InxP=$h3gNmjTcfnla)b@1kdwm?42F;=Sg5<6+ZSkY7^IUPz8w3&omf}Y5V~0b zffXM@2NtMwx)^NPDIS=DfCI!-$l2K$63EpM0R98I?#;)tBI~&U=ro(3_jl$6AwscP zgvqWy-^xQWUK=LhPdf{lQ83MHDT7bITY7nc$EpGd4JaVqF$Jzh5kEr87+2G|Bo!=g`%QrFs1{0k^)Uq}LxjcWA<%OEe>e!M<6NEqP1B-7~D{i0RBM^XH9R`GT z6SS1m1bI%w{S+A2`W2=ze}sgiui z$e>uwLH7&%ov5gdG$g3Nk%H-Tq=q{RCET|SVz2JjiD^umo}NY|y(0rT z;L#vn-)exNLf)I{a>oNmqBp+SoCB_=YI1vesF{wuyq4~{S~S52orioWX+UD7?J&VJ z=mmtfRcu`fdBTZFP{Z@9Eq=uUV<()YEx{Vve*KPZ%@W!MUVUlWTD=zvIU_7fvvfOhE}0^ z3&dTbA_ws;et%ad<7PkKJU9K|p|%3C>eC$x9=~gQ$dwo_>JYK3K-4yR;K=yF);~p_ zI8b1q=!c=e?E@vU;%O^LF`GgY!}mgKV~B{c5)5bR>}(+{ER>{%fu_M1fT1g(4_pIi zyo2g&!R54>uOz~n2r#m!;ScKHl6q<^AK=r$I*tJCjo;wbI7cS*c-jE9%E2bR-B$q}Gy|5skhQNwssL4?V8WaZtz2?)xJ~3R963CcJcSdz zR))*}57O`u-bm5ugMve4E>vzr9|qpa6$XYk-%0}SJ$ghA&=+^eI87)~7T9JyLWdyy zF`!iM3uqscOdrKnRz^5!-bA4lW7j4s>=i<;{#kXe`+9KC*U>$fxgJ8x4xH$yr;C)` z0Ch#08uvmk0do5xEt5CoPCCptXWLA?>I{3pX}h2aROXc^*vKpvY`# zWoP$SzuG+&569i@X0z{FM1+KgpDYsvXpVeecrxvOp`M+P?z#IH?DtqZ(+9+)R{O2%=T@h|v*5O#je@l<>P=u`2-& z0<$wZVnXx}#%SSG5A6gmYw$F0cfaNO_TzqXtKs&3rse+;_a5L>_x~U8X=y3#QdXr@ zQX;ZxDI+vdLdnX^$X<0$HDrweN;#$zV0!z~Xndm#6K$U*~TS8*<{k;)38 zI63A+Z5zThU{5wL@jOUH!_PAmHN>SBUte7EF>B=PbN>vGR-eiRG!1#wg(@W5`(*N5 zZV0WEvL9+{o{=m@GZ<}B6vkTJZPS}s47_t6LaO5P=aYDHMZ+c#i)-w2Z0d8g7#hK} zDD*InJ2(s_H2-L8D~Aw+uL=>vC5=sOEX@Ue+tHTswJdYAI&<@#gDr4brSQLxpeO>x zRy46}2~a+N?%X~iKkyZDl+wdL5@9P-noL$*y${a(p;1@R2TwQPIiSx{5F-8jnU?S> z!DHNl%g$RqjVRT-5@1-Y_3_U7mCFl?S7jY~({SO9%qW`>jPNSKWvoLV7WXIwrrxh& z^=?nlcyFrBowotaVHFLtu8QdMok^IpArby;6qB@_x{;D!&lX6hgYRq-AWN9SUS zRnv8ZtmJzLglFw-s}_-vc+$~fK3X?h_C1)vd&zVZlK#ig>m}l6rw#4xHHcmeo7>>t z5Lq{EqHut9cy{aEt_CX_26ORK4~Yz5rt9f(hU~arLD;mcvVd$WdmjC^{!efG>-Am2 z&#A<-Hl`Ma4>hG9*PI`yBP}J53gqO=98;s_+1^cO`EfSXp3U)}{|PN8L|z1*Sb>T- zviJR7wx%D+5*dzt5UhEN4}A$Db}WB&F(gCBPZCvjB3nWf7(kd>me%>?=Du|jw%_j( z=_(J8X~+Z=@2j=kn_&Q*$d|}kckbA6AEM2lVr5y}Pc8C{6j^rYX|ilUpDs;$XKK2u z&eQRGZaU}?z-go%(VLbmux#GufMAyz?AZRuOxOG2w5Pky3^!QdFAv`o1kJ3Q(^3Bh zu#iBgPkE-HR=r=vTj;~MErDotaCheY|Is^tQ&k35R`uD7vbNs1+F|2{nJDRw_tQVMdL5pX-#TM z&fNVEs)mxH4C2#j+TS5CpUIiG8A_9#39fDi@6*aGHs!Gf!URxF9kiw=Uw5+ahPu=T zfGHtdGxGQmKC5_By0jK-&1&fGnkby05vc)>PXneEg>Q>lg}CO=&-Jb$3g8Sib;W_r z5hQ(@IfD0GitVLh*<=Rg&;xfAT35B5>ihSm_$2R?eK#F{RSue3Vh!v;9v2p$cigQ*kHwPd3j-vDFPTeWy!GI_V=5! zf&Tut&#dYh9!)aU4Gj+d05u=m_Rk`RR8-D8J8R(>olG>irKlu39_F@bSsBT#m_`~~ zYtQ}n)C_4GXu9KCk3`>J>GtmD z^V91}U)ZV$8!Z&EUv}Q6Bw!N7L5CY#YQ|DDiBRr&yVK+Xg51C`@d)dNw8I!Vo{IO& z$M{!%z5@Hz``A{eMA7wQeCy`TO)xVdDs8~Rn7U5VI6p*r3YyP6i{f2f@TcG^E#`_M zp5KWbm7kxlAI7$61wSpscE>NTCSq6HGHqF)ZkC#0c$9%c}K!d!kBXKD;)A8tu z)q@zw$!fRCXPQ1Mr&+JNgJz#ABd(bOwJ8yhxj``HKZdlq^d}ALJK7s1dmQ{lNb?&9 zhCjj=0s8)K=SsKh1=jy0EzP;Avd=LcKABivzu{cUJb8oonyRG*??iBd`rt=dc4Z6Q zHWa$t>^E>ie8tY7-6E5hhK5W?!nUGSo6@xzm!{8B7_i1a6P=J^QXjuTQ6A5Tw`ySj zy`*f5?vp4Wb>7rGeFmgPH8D1<332SMaRY#-xD`5 zFu3QkkVl7UlOww1g!n6WKFs+kH#b{IO?Sn-z*NVjNws>oGIciZ#gl<6Ce{w15lci! z=vyy|U^He4ON59?g%KI~fA-AA@x^}jt7~%v$yTzLGFKXGgJgQZW%;f2X6T7 zQk+`c+j>z&s98JJJ{`D5heKi{R|v39?4u=y-ddT0?DDgGU1y zI+KIrCLr-PKr${m4$_6r?_}DMAqAo%U2TdA3(}aUi9{JZ(O=` zX<%^h-7~AixxHp6>6?R3ro-~}_1Wry%uOm6shf4%rr{PV|4`&ShN~e<5suqW_xoy> zgPfL5U9|W!&}9AI5jNf5_J>G2RY+tscuBqhvMrvu5y6Rpfjl}is<g|kc;b`ErUAE4++>=RRlLjkiiW9wtrGJq#Z_5X7fvLv zaZWccnp4x?$G36gUFD64mhhFAjk2?ED+yh0Dh|~+5v$31xbD*@|8;l%wsl66frQus z9_+f!zKROe6EP~7V2;+vw5R8Tm+ag3l2{8q$YlD%z*3PkxP8+BIMjY9EI>knTgy&^_!n*{AN5?jd zi&OXlvJ<`pDXr9dd$rGl`oME+n@+|v%o}Lrj$D=q?gxLg3A_aL1v1gJ1^%)o8R6nm zw~xJ&_4S=h3ZxBL8f6hL=-JpDBQxpG8UUPoxwF4QOy4EW_t+we~-r=O&POHp+@USz7KgsU8kQ-7YT9kGH6>u*FAJrWD;B zL~77_nl;ZNHFW<_cL|o@TfoA9!h)Bo>}!ICg!x&-9_HHzSs_+2|>)UA!J70Mr&bX3(TozTRG+NBQsF^!N%isY1-cG z+p3)RtK1&xbcc&`sH=;apAHJ2s@PHtZ{EDQtZ+ISuH2pFaoK2r5fKyHlq2{8Wqu+_ z{W*LGEC^wjBzJ&u*7~kT)&bM35l_5-e;dVH^I;BQVPOfY#=kM&BLHCL0EzLp_#Rnz z=T&QG477wx=+HbkjK~dg<&RLth!{D%?3TR9jvZ^EI|4=@!{e!*z zwSw`>4C1x6R{KtC^nP>6Kv*iN;4C()%hXwnx0#7yF$xVHIO|cl@tdaVI z^-2UY`Yz6njwb;kMZ)7FXyy#=Wt@o9CbC*&|In=Vd+yr<{q-%IH`AJ|3-Jg>h8Wl7 zA3|IanQ{3;Zy7XDocPi^faZxdn8uUoSY+gYXtzMPWvbwIufF~aKGFoX_A~l2sKwJh zZ5Gz(_~EJF6!^<_=sGO6`|7|qFt_n8Ao|)w*B@3ij^KYZ19meCoSr7E*qP~Qe=}U% z+mdZN7eMomq~zE3NstwhXipAQzVxwe4sPkFTxPj~WEz+Sp{FI$LNeW^!lzW6H2;0; z?jPH-!MLCM!-cVB?wQXBf1 zw8|XZn*=X6b;&8#dz?EFYs_NT=dt8cQ+1sc?eFm0M+ZAExZ-{pG0Ulsy5x?WPM=%d znK*w|5vPE5M~wJYSe-iS1vN5f#Tut~)MmZ5N70B9{vN}R0)x-*+_|$=1s28q3hr}N zSP5Td?RNYh!p%r+eD4*z2BM`U5=(plfeGO_$Ft)My+|Ul=!^{QGE>u0T%i$yvd^zB zGzf&{KuHi^_yD^qYF_hL7MT%A#hbdfatz<}_U7kUNIZvM3B4Tk;QMNuUOdYDM|Go* zgxgr!#*G_!6=0EItp?1(X20URV{~$F=?lkUA5FG<)q4{y1V2qUK%SK|XC%fgE(~{w z=*$V&EnMCHD{us^vzAA9n;;Uu6x3LI;fRSgE{uIS&VY!hXe2C6ODEEWK41{ULBD+6 ztX1D_|Kj||Ewe7~MxS0=gSTu21cc3I7m`>=US6Jvn0}Y69rA*d>O;s5K83cud2;p7 zmqgl=q+jIVqEbYHW7JFgfbTvLc53mgt^d@-ZdLeF z|JS-wn-j4nECn;IDT3;Px*Dgb5xy>Z3cP_Q@E@Y&;?PyU15Sp1abJ5)7glL`>{ zKhA!r_Ry*LR|ZUM4ec*?8ik0nmPj#fLL=ODFo*j)0Vn`c!L0P%vT)uDPjnnnYPnwV z)923*qw4kng$?L#+Eq_WG{!La=QM{z5}k#OkI;!eHSdyAgaZJJ5Z5Bzf1zKn!UeZh zflgichHXg0MBLWhd5j)XCV)5N981APi*~J>?6i-w73bWWmSq4_qnj7y zbzAkwic8IwTBqw@*_vJY1<0GPVrRd=46pxor|H6$pCnxkeT_b8q}y?>lp2U-|0mksqtW3LWEXxOx<+{V#teS{=en{QqRj=N*D$C|{4&uG@%| z(?Vs$7`|R`q?BZLT&u6D~1XPvgruPzmH$P zhBB%j&1PZw@a2nu0!~3W=Ivhc$2s+yY2BPAjM zyR8KUhfi<)R5#TjmbVKa0`tS%gYw$fE!!WRkZ^?P;UTl`L%WqSN@kTnFR{C^C(9d( z_yd%`!y7u{?p^@UA&TxqM73P+%$5BQj2G-L|K6@@Agy7}=CDCw_~fW2ZQ}_QRB2I~ zGv|~A9=A|s#z8WUN!+_a3W6y6y((Ti9-d{4Wl~G_8*Kejwe+Z=>dgh?j5;oDsaP%A z1K^`4bIA$-1L6ptgSk*|u8*j&^C|#qazqb5$5hyfm6sjLSAEuiDwqk1OA~k`)-ik) zR+0~c9WCe;c#qp5d&OmZxVDlTLUivM@{81(M+a&vQ#&*Gp_M|~S)dH(Q@;MpEdL2` zHU4$1uK`QJKWDFO#sa{$sCZA)cu@KnzH);?w|z~$v88af`x&!ueg6}7jC=EEX-4Yi};-3lFDUYHx0e+8siWrj37Yk$(QGS zS#vBM(@LN$TuKxT!3fuu&llFnZ8(45RB~HoK9{25^&25@Lg>_vGMird2swTg19>dVk9XASdgcD@=c0KQPQ0jGhDXl6$^RS6;;l z`+%8q0W}2q$oLZyi=pL^Nr_L>GVRYtkK2L=nSS7w0080Ekh61?5n#RV44F~XD$$)M4Ub4VJ~dc^0#F0S({ zXlgM<3QAlO=72{J!Yh<>k7RSBE|*^#5HDz*n!sy&ZRz!W<(jluW=0C)s0ma;U%<$< zuS;Y1e?K>R%<0q<;8%D=ygVuWBR(ug(+EV?+de7hpF2XdKVoEu6J^U`6#FpN5dT~# z7e3_QxcE}2lk^-hct7H7a)oy@aw2t$*ZrL*;?>^QlzwXxUq+q)Uhxlb#~fy)kSdpT zQ>qS8$%O`aRM|)GFqIxV(+5J~&`{>upKI{5FU~Ed({&&f(1GLF5WNpm@F?3zin5u{ zEU5Rm+wSpkPvQF~GHQD;F1<-C+kMAyW*AG+ub7Iz$2o|7CnJ)Fd@^2HR*N?gL{@aV zLE|hOUvw4_@Bgz^)$Iw%_fdNMj0YtZ`h!IP#Zn?0kCRJA3Zv80PXnzj{?7WwJYvR^ zD?lSZ@6}c)%Q$h#mLhjyE(>d0k!0CB8SVoQjA7lb%%%dLoWNW1oPe;S(Ico_Z{jK_ z;+Ngo9h$mxxzzzGes!R8_VxA}q41{3=8q@;6z~fG3YT^hor3Q#Z}|R#b6cNjRkGfj z8$qEArVU+cMik5}NTn98+<9%a)I5A3xvlOeG+u7crOXFq!zR4STe8 zW>NjCl-C#9KF?&Heyh{4*V+zE%Uy=6Yfs<~iIOu~KE$LanmF2T`Pm!8hHimiUDQ3l}O<5u#SDn|lEDfWqxu-fiO} zgNGLIif)lP9Xmc;B{HvcfF4Y41Vix58>y&>gkN1c*~%UsjxvbGj=nIK-4}(EH&!r1 zPRb@ZgJWrNAGaHeig7Vxycg0&qI#{xq5i=3({{|mEzc?#Q8Bg{9eDgxo;%q!BUv`T z?JGycANypvaA$31*sjU8aGuV^oJL32sRduan zVm11spSImG`Yd5+Kx|V8^Ez*{6&g8oteIBOJQCPpc`4JnU}?Y(>&X*@Jxxq(D=6M5 zJ;jI$m|^BJ=}Kh$H_P`@Hn9eYnjOJm;B7^d78-VMXITG8!Hp!_atUh~w5`3qTO#Cy zki+^k#*j1FTR;t(3v$2)gEH4OzUk)X8!k7O2(52cdw9y$)i3aJc||VDD(XK{EGv*9 zY~_5TMfEfjbhNd4tTm8F+dK1ZWwb(kramn_v^3VNcPiohUr^a2)ymo3g zkTnD+<<~Cimc6TtrfSO_piTN7E0X<8*=+DqqWu+t>1@|6Qnj!D4Rqx z0&hL}(i?xm%vEDe(s)LBL%6$toLO9`Q-R~H`8Y!Y_<_&yqXRF`40nRh@q#9OwfMlj zukdIEk@>gh1EKhU-8wov@H8f-sPzICfFm29jahg3EY>Vh#;ii>Gq-)>)uZG3ZkSSY zFX1tItLO>h+c&k&-n+hI#CEx!;fvtSxVp}f&ha;E66T?B?}HYyyc2jEHJcUl{q5R6 zziA_R$u(@y_@X`2V2R{ng&ul;KE!4++Fz^Q-h2&!=#_QWk_^0U3Aqe8F5!nwlGWp{ zD;R+m8E0GN>QR<0gIBh#%bJFgnYc7Os9Xi?RSUGUo71@0lVKQ3?db9ulugRb$$Z%M zdEAG6E1h|CisWz6D&Uci*z>gZs^uLeOQOaYwm$o?>}lr~(#eqB-i1CKo=Osw&*N+S z+Vd=izJP`G<+U_Lmyyo0lL`Z-zGHE2NqwvRYsmHHPiFWIS=|IDIOJMnPThFdDD64zQkJjJ;->|r9-tY$IS!6(VGNd5hJ^V8pi;vU04 zSANgz_KBJOLtNZkK{UhU3pVSZq$bw9T96bf2r|4M0TTY8tXRalY95P$-ce)G$=rMM zl0%YGoC#)|0+X5;T%M83=aQ}Yl%b&vBT0hl@fdvWYr~ABn_5bzN)tE>E0+P^rIiZJ z^P-szpk@hwTe{Pn7aD z$u*mJ-fwvUr&wLQhIQ3>HizZUMD1fv))g8J!I0yjSvexKa}S1lY-8R7iY*hKC>ciT z*`cceYiRBBZVM#~2ko$aTzUu+U~*iE!wb|l3ZFDL?(KRTHT?h)RmRJG&pwQXxnCxw z7E<2I)fsxH&JoOV8&mVlB2D*x9lqRb70-^TP@ldJd%kT-=g8?6!WAQI9ny6k9N09emUX4e*~ z&S*?RzKu2wNoke@T`McAVur0m$XHDrA}JHS1RFg`;%SqN@LZoJ@hF%kx!pETa*Ue4uYKm(dwnk1=Xxb4yoeN+Wu)Ag$MsGhWU%)9KGi%0GGx~mW zp@&UVE`XSbc}Q~vo(tgsdac8;%i4`v1lIndBWqRypr{Q?<|-t*MbFkfLy`dWs05e1 ztZvVUsm&~_4p@(BaB*RKA*|$C12F^OC8)98<&Duyd|Pj<_RK!^tz!OwQC0iJ5(iVX z&BlFt887%iA0LX>GD)&CIbIkPt-iFd@h*l*@>&~eK^MTNnYf{9O& z+rhLYh?ds|>>vR1GqEjFw-YSL4oP%KN5~~`iz^9E({gDu12|YAOjJoOGWev>m9+Lr z|M#z0m%Oh#$70r1CkkI2sSc227VnFyifb14R9U&grE-=Eo!EmG?ry9pd3CYRoCswb z!?9E)$tR391)i{Qv)Z2|Y{wOJ>%}LaYn$ZjJstr!O*&9;pT!$Z0?bv)+Ks>weN;m= zB_#vac&of^6Q`MCrG+41jZegy>Hty`eN#wfzRSGkdrdgNX0=UnDbMxAHO#t3NacmR zcI}=ZPml}EXRc!XSXEJ>!Ob*|urI}0+=3qvIxIbmF>ckrnIatc4W49X#|QjQu8^KV zt9lEKKinxc-RK2BV#-tgUwFPeDe>%vi6p9zmNq7bFav#~tv>o5NUlAyw zL07P)Zm0WBDXC{R5&|SnyVd{}V-a05UB%LftvK9ryM|2UL4 zYFb(zQ}e6FV^NYs0bl}R`Tp8KzJQ7SzA&SUJZ$n>5q8OA#3>_lIjRAuvsPRy|5>I9)5ZX}!l-z_SK)?3dEcP!wc`t4aXL zZc`voWRVo20Q>YCsNvK8>G=gkAk1@^3tmH){@o}8AI&Xzm|(`S8u-9T&%Za z0$wwHzIBPTv^3D)ySxBE$O)?QP`hg%yG?3eLBGGh|9dvqt{H9im?$J=fy-bup-}j* z$>AaJ*uj~Tl~rpz;YdCrsW^ZZf_@<-1Th+SVMhA@F_n&E7w9x;N-ZWoh?o0PX1y9m zi|io|u7g`@!j7PhRxl(yY5!x?E=O$=)tOFNF=h3^WmqDDx>!T+BFem+$U{K@R{0bp z?7PCj?$g*JB`0%mqYrvo;=P`tY5{M6=L?)wKmj>3{#&RzvvC_KMg7pMo z`>k$YvCzYWF1dI2+6%+<-|92ZH2pbd15EIf)W&XmfXE$P`!>l-snh+CYo?DXR6lGY z=nu=TQmd=2t;PV=G;>kQh=}+hfrXJfl@2)C{FxsPYl~J$u0ew+ zOqbl4Q1T$#{wOo2h8s3|PHyp^>lSP$?_*v?(qq!b$uW5zDfa~6rf=n!-D)o+MW?d{ z3Z{lE?oxX41sBt4Z_ddVq(viHqhy_(a~Hp6wQ}-U#-DD!XdrB`aG>O^$$#67;N6ox z9bpFhq=AZm0Gp9N7B8^m(5X8w9MZAWa1zsZQSz2dIRHvlI}aQVd1)?ZU4@Xz?~yp{ z+3O3ZioNeWYH*8RFn_b-$CTuucpmSds=4?T5PiVA#jNG75(?4#;{X>z+Bp!L8%hFA%g z7}rxJ^Czz|Z#(e;Vl9{fCwSMh2EI`H*V)FDRurL7+onE3HHMVrrZ#v3fE-e+v<0K_ zmN0L#^s1!)aJS7H?13)rl#tlM6f*8eAJ9fxyyGY87|l}ZvO|qN3sro$|Gsx)FM1|W zVSmb!xd56iu(t;XQb3<^2U+wddq7S#P@b!*SXp&or^mJNGoDYkyajp)qG z+SVOb+Nh0v9edPXYDFqamxGMNXQPf)b}gD z7WBS*?_RNkDVmcf`Xg}%YUrxPONDJ(xS;9h7x_Q?eMpju=?RVy0t!)tekBv1lS0Ig z3hEwQf*sR1Gc~z1=+hojnBWN;!8lhLSm@}ZpO7%TK>2&CDrp2;YVwf01wgMke@2w| zUTt4;NQu0S*wqPN+Wbv&FAi?wRGgr8_ZQ%`T=?3s;X_$rd2O#hOvu?MY^&hOi#;Dt z)201#{gk15K=$D6G#|i7_CSLjO+F0`4f9<| zfK$A7(tyQhD_W3fyh0ql4`7;SfQQsFW?E?M^n&Aj*QO738-H1##+}T_7hOxsy>nw4 zpW%P0aulf^(Kmqmk|-|G>Z_TQ9EPhBl64C^24Mx>m>ekDz$4$c-V8 z_eWTa7+;`L;|Y*|&}1u6(Iitsx3=M07IjW2+S7Ax8>WRnXB(TFYI0pyslLd48-H7P zV$JtC-5NPXXv!|Bl2bo?_67I>ShD?r-%=#d=7EsTm3)E*kpYneb zw?u9)&l;B+W)btA341?EuMUvC6@V^#gZ=)@sO_Qd6dHrXLwYiEqRir*h+E!GJ>|C- z4H{qmXCOD_3n=ra0*g($4E)CTLmFooR(R?iQY((SWT`#QF2b)rI=Iu!Y*VuE$%UwQ zWV-ymRr9IvEBxTr7a^p5UZ-%R_1DR+_lKc~{rc+agYqP^wSETNs_kpzE`4OF&YiM; zuMSOJ_kQFviR@h0hL0xg55R{pf@}(%UQ+-L{ z+i|~*aXdG38>To9C6G~rHhTzU5!@B+GO=i&GAN&)d(HKqU-{2J{{++9Fy6mZ@L|ij zKTnvcq5SS06KT`5oYo8O%Y76hn$x_@%*{7Wnor7Y+o=_MrB8sWtoWp|KxS_HPhppPH@^#3$@c-)r*IG8!%%*hH51}}-4+6?61%$J(f)UKHN3b337liu<7m)xICd7s~3 zyDc)cj=#T_aCOp`|NfF3O5DtR@AsD|d4WgBrG)#VyBHH0ZJ+22RO5Mo|B!||Dn@b8 zV+&+A?=%9b-2VphgD`!-oKjGWmfMKn6!I%7$%u zch*;Q-`JkfQX}a8Xndq(`~wqNgHs_H@suNch20NQ6H`uE2w;#-Zp(E%1EksgBO2Fu zqiHlvBxuD8|9ZfjUqMXUmRdU+`#-skiY_CG%4|LIN%nDXxzvpD(hFa2NNfe|VQX61IIVtz|zY*4Rl@cuO}E6de# z5@>ry@n?eqCQ9FzNNV^)>$hJd!D zD+cpkc@ke=n)qS0X?j*xNBC5Nyxh-DfXkR^`B+_T!nrgv+ZY1z z6=Y-Ow_jW;IO7Jh%?7kTbnA56wiDA0>Nb*#ohlH{^{@ZCwDd6M6x#gV+5OQ`j3!fK zBcmz50)w@I+~&Vu;r8)_0(Uk>G|@it4jGja&!XGa?e};wr*|!Cn$;RqC+jb!(w$?K z6z#VQS_)U$5pY3Qz4Ft3Nq+uI}Y4uGC_>a1JZm&k(w^8%GG;j@P9xSm8Ib zEY?FgFz^9%F*bmKx8T#KPlK2fJS!(lDOU>4ns7PPhExt5$Q>Lk&>6G3aE2#;e2{y5JsLO_sOZTvMBl?KzDv;s ztF^_!dBZ@e@8yln849wc<^Cv;cVc|M^~VooDyH*9(IY7!x@dX+%hkoP;2f?U>rc+j z4IBMom}t{lHk}F2QGD}~*8hHzS&x1b_Tj4=4;?CRza=3UjrgM2Xw$jW;fjBz#v2Wi>TgmaDh;nur9Sc5xYHFS&)E zo6fvhimxIz@;oxh`ab(^+1IbyHZ%Q2pVj+5#4I{^i|DMKx6?*?3fMu@LIoF)J}3aDo(v`}17OL$z2m?zg5aI`Wbg$#IKvgF z=(RNjAHyuZ2TMTK-FVZ4%(9=-UF|QyGJ7@yl0x`B4C?O`6N)iF&MRE@4PMaU zdvw&>+)Y!Kr-E3@Qe!k>553)$aiPMSSyBg^!$xsf*v{u>%gC=xyabK^zj(yAep5|?z{>di zbySRfP0?WFfXRy7Tr>mgco_2xwE?OP1|^e%Rgp;LIfyV#J##QZ^kClRmbcqzrJFRu z*;yMeMR&q8DS|eHdafu?ga$2)c`Exhkj0S%p}`p1=^UM%F=Z10BAqPKP5{#Zf=l=5 z7{fF$GJ4#yO3)mvRwLF{Ha0Knb_%}K#8cibQ=zA)H!ISkwVtkXl#G!CUsY^6xxjFj zsOZJF);X0Z5#fy%KOuMU>ve3QB$!q`KooQrJR2{`JHwPTNL~=odKEwQ))x<%M{s#t7YHOTLXvO9*@9)3}Tjd}IuC+E#K-L-#Wkmf(S2*4?A1^D?{pC~B{sz;yn8 z`Tm&VSqN6?_-w8{_`3y4T> zbV%-v%Tivf^|by6DE>?A%^`R)OG}Qaku| zSMks1an4QrxYq(+)GO+wlRp0O;5Pn0e;EI7%`;NN?W9lnZSMGYozbV$%jJ5|u-C|Z zI=9yBBGu!m(~1PoAN}R_&Lbw7{U*f5d3fr6AC?`bk3RxUqJkARJ{|NkTf`Ro=D~e- z;7uIR3i~z}b1#OVhSVbBI528Uh&qV}Drwdr0K$%bg~mv4HZP4q-A&FmGyyqs6Y8ohvcjg z?SS8YxQ>qXTpIcCq25Smr|<9SZ;ERu=!Vw1UdU|%51a5LVGHx^Jn@a)n3m{Q8Yf)9 zQ?HSAvkdC?wzaezq-l*sxYgo_H(vYYdMJ@Q$+sod4}%_{8oEkTFR{Idc-&h%oi{Y$ z`p#hx-sj$|$RLaeVP7~or-8K`F-~fxvk<6AnK2N!eRV+ClR|}f!L_>?xFS1Dh z4J#Dkef0KUqeMpGD(M-+9Zt0km?~mmh*o*eI)7LAcp;GU$v{SDo8SUo%v?0Mftx$} zNzbskf7`sY{Y?~;%R9LQ(_gZ}>Kt~s>PkxEx&Dwv#|6^X_pC8DzXKL!TfM!*(mBN?@H$czmi4Hwr$vTaR#=E7hq;+= z+RnW3{as6W>mJzJ*f`he$r@Gte)9fR;EugvbzgFeosEr_TKym22_WA|z)H-|_|v+9 zU|uU8+Yz%f^E1Anb#$Z5@BJqj19P_W$JrZsO;%OgelMG17{~5)+i)SX`SRBK5 z*t%M`Cmy>_Z+rV68`&3n6R&s(YpLvq_JXDa&|pu!j>VI7qr9NMov-Jy_f#)HwQMg3 zTHOn9_+@*g1egA(&6LHM2SAUo(L}csaBp0WE%$?ETqG2%&`8@13M!a6<kI zTh`2|L?5$lWCvT|VTgm3i+T=GE3G4??N<=v^3#UARd+W6w*+t^PNfuJ@*T|D_#iDf zEp@&yGuY%1w|WE%(t&DZYkT`4Dl`$7Pua)St0iC`+1WP}`-rg^Znv+X*jq6b)d&e$ zy|o7F|9C3Uc!C5#&;_hedV88T`xPubarM_aQX*F(%;DBR0`*tXOAH+ouJNU!+{)^h zX|4j3F(TO-=#B^p3f|_`d|`BWDuKbKMFN8ujwCRaF#d+wmu4wYK>{;%9f;!W-daO? z@j1B;OJiUL8z5JDs2XxH-k3gwiSOQwWMc~pRVSz6H?v6r zaN-r|OE%Qe>NhKHs>f;tz~iXcb4`5{EcgF=?sfF24gA+R1WE5Oi?f8JSq0loaomk=Z-y!l`+6N1X%rKN{GNk{_k zT3%HpE~AYH2K#$_%JmL;@>7{2Q4ftsOJ#hBBHX+hGS2F zokYWTBf|03+(eki`26`Tf{T@1RKay-FK&)-6(c7m&pjR=M7DVmPTDXnY3PTcY!IY- zeq~|*>6rhWF-+M-gR7Wfj?mi1r!dywHsU?>xiaH~5tsi$3~~sGiHXU8-*ppK1>|QA zolR#ZW-aHd%slFcu}$(bF=LgGiIZL|a*9$Su>TP!s;^!|vOD))ABfF@p9 zel}pt2?@2!0v0_Twx?SuI(fEW{i((ssf-0-bopd+)^ugFD=gS;OBYM>|ff;^yvhK6BoFu>P9$Pj1=m z2=0S0^1K{l39&@M5W<}`gM$#})ABHWb(hF;<#M|@I}>6EgML%V<*$dN#s(XZ@E@d} z8|rDIL6njhQpc9o29he>e`>fXb70r$A)i`pZJTA}_QEg0h4}r$`P7N=a(uXl>EsMSFw7-QIrFt#U zDI4<1uR1h99ha?I%w&_(eT%%4Tttu_!MV>l79>IxkvoATG|F~|Rg2K^ZW04kV#x&39It{9s$3*XtlKAOJNj*P26E2n z<(8X)7B|DsH8ddRN6+d?g76{U1ApKKh3_D8BLEvS55ZYj0<3G(d*}fNASB^Mo;{1o z3ohq@vdPra8YFZ0Y5x@0q^p^26X@crM?~s(Hn+2-Gm)5ogc;wgeS&?X=n_$!!j2{k z)eKB&%WU`U4dHS+$;lkwo*Mg-Iczrsc^|vt=?vg9zM130nI&#NRmV3g^u&$#WfohYAw3L95=dzqiEuqS zlE<(U=&~c%#&2&2Xa3S7k5+SX7C}S|F$~tX>pneo5xj#qf-{VRA=A@SXQq1Li?H!0 z&-Fp7(UG1Ek_2OTTo!Y`ho~G9Hk&XGbrx=_*dYi!v>OONZ*DHG6m#H`ouh=5m2inu z?UXXNXO38*jh?TLl?u9LLbM6kI`sC?wtpZ!M&wfnNhn4FeO$*UHV*m!QBO{P@i?S9 z;B}`*$&MPMCgaOXgglO`pSCRy`D=K1IMHov@)&nY_0f8R$KT zNC+!H<}Cr7-HeV;BSc}2-c_G7^s_QE6nK(z2aK;80UDZJu(c$)gBOP`u653WT~OoQurkC2q{(1-Epi(x85c*FRv{D= z5`eki2<<$JJcr;!nlvkYLWMj2Q)k?S$bn;F6iS%ZgSljCNKlK(jDQ0eWpi^eZ&(G! za3oqKv>6Pt99Fd8#xFe`sBt|~h_TMCVN;!vER;xKO}!a}hSH~_qYdR1gbgM{;BddWj2B0w!p4nBlSt7p4ipO_|YF)hJ9NgM^^4cBH75;34R5_6hyH zdf^8V71WinqsoDOhXXByf&ex=!WXY`LbQc(de|lqh1yhzW2Q0;19w9Csrze!%u_bw zF)|!F2Z%Zt&K{K)81oQO9^nT&ZE!9dEZzaxpNGlb#B)TyART0WXR*55dkTFpvfd2l zjbg&PUt`~Ji}{P7o6_!eURn<-<2=lB_!69az-@dW5zUCERS8WGls+?8bZJCluH;*0 zpyYGF!+~WDY!cXU!#Z6$ovPBE?10*fkI^yPqM2rY0hDbW&V5gH2%=pqkxR@frkgh^ z2w_r`pf7kB<+uw-e7pmL#1ZuJH8(fcK&@T#<@t}|-XK*k1ZhYpZR1e0ixHv?TalozjfC5!#^rMb|*m83H zYMVcwJYOF1j2ZebQzkcnb5D%w$B(`sCy&5$0;3Z#hH%f##UVjB6O4|G5$J&EL(l_{ zm)3OeRDxq4DM?Ij;jihE*A{ZV1C=+S*CrC~Br7_9zIZJ9B3u+Ha3EhR%F8x$x-0)^Z0Jni!1D&@CJ?a$5KL-si(&oCfPp2$`H8@{t|#!KBw{COL^r zP-5$G8_6nUsB}DZG5RR+lfTQG$bq*h zA3a)r_uX7&FTybdg3TjT-~9)Wvw*xP5VnvvAC0w%SYrYi_a%yqoF<<=UpXhjrnjY3 zs_(?W0tZ1v znlpR&Gp)XUxyuIE58khx$V5mjk9atLFlnx^g8;q$e;Uf@|lC*XGY7laB_;I-GX@3*=ma5yXG%n#NC?YOhoNsh=zZ%} z6V9~*WC6${Z;Q*6!SHnZ{`PaCqN4XOMchnWD>1@khlABMcUFn8CU7OP#SAflMa)A6 zR9U02G6elP@Eh=c^~iMKEj6*DL`~4Vz;Y7q7AZi$TP)xL29RSu? zfuzI`N0IjZ$y0(+>wM7i0S{FZ+!-57kx?gDHN9)R z^}r`96==;p=2ivLGhb!K(P|QatLy0C$+U+Yts6yPf2%Vs4f=AI$|+q8q(PBS4O{%i zMoq_=v9x9MV6@2GbwC zf_YC7VIR2wa&>TO^rBw$G&Q5{awz)PJF8&E#Tc+98<`8Jo^NH@SEUg(|EiRmf? zfc>C3a4XIa4V7q8E~SIdIghweeu7>Xs+}QkkCkg0Z?|VA8pO$wJlNi1fnjrytlQY| z*rkn@k=OLQmb|iA=Fh(m!7ou4Mn3}- zS2kg+KuJldU_0k7VB#RYGDQ0z0G4-P=p+}-D3*qz6KE9xiWs7zrJ3pK0&ipgwHhd3 z6DT_Kp%$8mppF=4gx4!=&B=NZp*_4G9;7}{qv)8J^vAU8?-5lHc!j_jvSaq-A|9;& z1+P)Ggyt14566ikivW=vM2l8%8HNyGGL-H|tjIKlm6d*&h9LM50B3rL8|IZ9pf4)~ zzWb4K1mERfzm8=jJ9NViJ@@Pg?T#6V?Ck9MAlPCQOLjJ5@{wufQhp;?K^69f+n$e+M%! z+et(&Q*5K7174}Nold>j6jVE6!1Tqop4x0QDT+ z4L3?$%CQXAl$@s=px!JH|OV>#Ew zaE8CJ>xBhjNWuubM!Y7jrTYT%TNu@O$}^AF5>YG|3|@pOso^@k6Ud})^HJT~T&a5= zWE2FKwsI;x%%jkQuB}M)V<{xyk;A{!n5d8G0=G)APd0sfZK*)|1CXY1FtO^Dy^h>l zO34GAs_G@;c%Pjyv7H1XJ_(&?<}!e_{jiQ3Nxz04i7}xRv{|g`9~7YTvoFss$1UPc z@%WtfG;<<9AvukOOWUc|@891MY3;;&em-{d3xNY^k^TqNsL@_PvPcn;mHnyH5OFso zOCn+cWF)nC!X`^}BiL43>^*218LqFd zS7Cmm7(~HAm=b?R$zuy_C%lr_Btd=+UB{^)^IkAlD^Q3W*59POXK?Wj7EX8aiN zDFv`6PXON+Hjxx62T&+_&~k7oh`zUCzXN+l zY;O9kU0?I?+yM^t5K~0#C-4Ec)=xOHsChJlEQ)-SfO1IDbh=zl96wGBFZeN$MdX13 zo$uQ*cVk_^xI-^>hF^{}adY!a%;QxcTBb}q&!8|>G%KR#>+0gdWW-UZEqOW)tn|-^ zeu+0TVA}Yj&6cbhv_>G-#{LA`frQ+ka|;EufW|B_AiV+-6@Q_!R4}=-@$}~MYl4{I z9N-0PUtnWJL|P3YEj8n!q&c~LZ)!^j}gQQ@~MAHq>$%VOQ~al;5HWq%k`%J;!2 z$gYrB<{z+n#a0b9(t0<6Uw!;YO4LmJ3YrlJjszosHj^s&{#rFB7=ndf%+&W#!P;NKa?+t?}Wk(o~3GD8Yq$r!8b}YlJ(Kv zMPNY!^&Q}H;DxRfz|xWdFnLTjoQcpU`v4^NY~G5#&V+#vYE&&l5K+UrlP>a<^y&UDx5+cD) zO2+v6b_r(JqOurHXA7|qAcD@#g)hp7sVEU6E380;p0@J&Bu`Ku`x5Vsjt7Je4OiN4 z^pT_nSr7rka7NzV$b&;LhG4pE2PEhm5NtEhc_9er=z#de3a*TZxmje6UL;7@ldKwm z_L%dZK-b;p4QK~A-~kxkWp>2qM!t%_x1szs;1pYVk0Dsg5`DkZqB2~7j?nzUC%F?X zfILiI03U!>k$>ASZBDnkfDTTisc-{!hZ*QMY9tqemZl!C#!0)4IsNH{0oI2nj%QZkVGvoOPl;?v z6p7wJkj)Qo`G9Gnv#uG;#zL;N)74Hg)g)jOFW|#9<5vx#6f1+Ktrg1|d(krb4uqnJ zZEvG?f4X;JA&KJ&2-yfYXPgS+p(rG~=xi+@Kp*U(^;dHw2V|2m$;Seuoi3s|%Q-uB zJ74Dte^vD1!kQ9=#*>{l7mx>^^$%PzT3eim{A~t5Q6VSZ^ua^oN3v!iSnwczn`A2p z_3*d}e1Y~7pR`kVztF4=abgm%moE9ZiopmpND6WzWrRP=cQyW3ZV*+2b6nx@O7lEyKy@`KilH?jG3+k%(|Wk zIQbMHt{Z?J!m~57m-Q1oDY@3wiCJO9Wg^XVb#_Lw0bntMRBmiX8Y4#PnmnWuqPnSH z4xCbI-w-r>S>s68=t`F{GsgAdq;IoFGu`@c-Ed0Y=H80tMMG?T=nq%h2MnP%pwCu{ ztWx>a=?qrV<&C$6cX@T#fHEn>Dyma)Yl=z)*`$%#m9YhGLPEMj1SABcBn73r1*99KyF@yq8$>##yHmRRt*zew z`@MI*`*FAk`|Q19t~tjXb4-KXZlMMc#p&~1PgU0K20GeIRQ6wf;i5y36`j2Nm1Soo0eGIPwHR5Ra9nNNHP-hcr8`-`%@m|g)1iKH^t z({qP;CXRhTK?-^HhlwL^1YBpx#6&svHiEMY!q6dWvpQ#E3vdGn4FK)(jDQa>A$dCl z$}k~|3~?cVQ3W>-#e-04;L!Gt0{Sx`zzW$GC`kT;L4yu?0+yd@0m|?vp>S<^&jLQ= z@}g5H6$G(wN1XviwgylDUY8S7$lQZVL5+C;Mj|`!$|SaUW6^ZEetakV4azTH5=6&6 zh%)y)n|K~|=YO7a-O=2eBy?4=Ox22K4?sDSt*>`a9$arcBKs^eKE@GaDdabJvv>p&QRTb^xaWa>YXs z?*BWi{;`pcbJ*M&pqhlgru8NYFa+7lz&Q$qPr%OS0=6nxY0%*coE|_SIR;wY*&t?t zdVT_@c3vVF#MhAP0Co&G$DpG-)n)q|pfX)~uS5A6k2Q4uq_`e29FP#CRaa2B|T&w0LieLg32M^Ahrt|%6)ZCXUFp#H9iV^lMvPU}}) zahXFLPd&;<^{-VghhXlFWTyN#$Wo*U^}MU&?9BOhaHUdGjwcm%wb z`*4dR7|pGb)35Z6S9a0u9+^@k3Y)?TCM|qtxej?F`P@0>+&S$W);(pSRrmf%9gxu; z1C4YP(2gJ?I{H_M**MUvX#r8x(D=9?)Rhpl-%%_WbGHZ&@QVW}Q>edT{C&mS95KqE z&0PN2GE|OXF5kfFCuDF8^6^e+KNT7f)mhy#?VgB>p>9YKWAZruI{gj6Vkh91#$fs& zi2$aL$AQn|MW9fu$cIPu@0Dp0-|_+u&|%Sl(}xVG?*3RpH`t&9B|e=(azITD53_b1 z9@MGv5NZOp#cm*3GGPFYX&(D+JV@kNI%>3FSCvuK1lJaP07%&Qg9c78Krn;6L5B@k z_zdN5?4UI$AhN;1Kt1tf_-jp$=zkgVP7zIeN*meWpwDhD35N@ee}{x%O73F2pGX+&5Y!JE40cP7^k zrqRn^Fnvs=zww@OO%9yx?MjRL>^9z?-z)JUP}L0pRK-;BY~_`v2f)9tZ^niHZwy*n z5Y}-_N3vzQ`ucn&vp#jaYXvP8{m#xDAYh~B{_Z*w5Jp6>V=y_4jR%qgfzt@}wse;T zH40#eW&yG!EhEzker$bnVGVZhaxYu6FLQ4|aBw?lt^u_le%BMj5dYKwDfd-c7|2zf z@q1LygaSD>=+VJW@l*J^n+LO)&?1kwT3AiQ zb6Y#2AJGQyx?AezjR zzIz=V3zk=xXEg19)2{D>(nlR5nI&RuO!tg~;|r!yi#zC>)(Q3%4grBbxFu0M2{3C^ zf=%Z#2msiH2br{B;1FR7XU~DQh&6K-phg)J9B5E3h25wpMr7(a4hGAhhk7u5^|Qc) z0MqOtx(@2kGDXyWzvg;eIh8^hs@BzV#0X@OW4(y;_#gr9Lh$2My(~oR%`#t#- zgizF!l(1MY4q%#&zLZd~vMOwq21rv*gH~MDy5%GKL-rOk5Beu{&cS?P@Tm>9eqvH$)Yynnv@Gs6ME-)AJl{O>uG`ksDDko3*Yrs+%OeF$2T z-NRN)g#edQAAnL9fRLAKXR7ZG$}V`Umk~5IHA}6QL_sMFL118@tiOc#|GiKT=~!`|AhK_0vo#sa=br**cQ9(y1aY}-y>^lYgzyCQ089H=dm5ozd`^E zg8@9JHn3};3HtNOTYxsT7zGs-v0D6h`Twpwk)nbm_Go1tB?g~K6p>2xf)9M9mKMCWbGzDdq$4Uvyj`(i?MgCeShOw)x_E z;a*Vh8k9pn17M)npx||gEz{qTRlsy+kps#J)=t6-5#iG>eN_Kg8iRo$0I%w3cO9Ii>wnU zXe$NoJM7FLWN((*5Z!>bvZRCrqVZsAs8ZG&xuCye{)F^yOrBcy?ORe%j^qPKFOR`6 zPd2(f2cQzXOjHaehS&bqHLy$XK+HO{We3^5r{?3#&|Uxc%7k4lsk#9gtnAJSrr4l2 z;UmEHZvmk50munJD+|7=1emyYz+-*W=)wgpR{$TRi5;h5T<5k-V-~joW&sIfQHDpf(R57{{&i2Pd)G4XlQ8}hzb5%+c-EF$)lqx zP~Z#3jk6F)1W89Bgm?M?(%lL$zdt}%^g!SONzO@vZs|bN@)KC6dH{z9@dP~*`@6Is zKg1zWn>|4ux=Wx{{J<^k-~F|Jk==p`KxzZVQ2$xNq8;BMgnSN}RZ7dswgJ#A?~Od* zQD6K@yYmIDLBWx>1PHZl;Pk=^_7Cv$1Kv9#RAUMbqr6|B`8ixN39%(BSm&8boof~t z_3}x0LIIK3hhQ;UjhflVnXiB#Q<0sRDszuU2B^EUc!0@k+jUq0wfZeUz3vl$YV<%a zC(wX+uM9&Y_7HeC%K&_Rii?YT0I@=_sm^5-6n_4CB@_ygIH2c&r1XDu9y{v)owZDJ z$PzF&>VyM;F+C>-vH5y#pB=c$tE;O|@CSi&Zhf#Q0^l}6A&}~|1^_k#J{k@N843!D zw6wG$A9|)j(;+x=psNwzU7X`9nKFI}`ur%sR2uNrI@fyRC}nVy73e{{7YZhihMpdT zqI&`Pp#a=^2i#sB+jaE24bQs=0Cs%5m{)(*qu%5VRp3JR3hJ;AKr0AzU^RS*;r~wX zu;TMSa}cCi^b=}KbaUV@B<|wE2Rw`i!5z;wt>1!m2YOyEfJ|5jIF^=yw*YHVyM{0L z@zuXsgx>5z0VilFQi@yz3@hk9(!97=zmK#CB6(0H^0jk!W_sFcy^jb;W>Rx-JOqLg z)ku7+7C*ztf`LlML&zrqf$@?R50U`Vzk$pML+Rtp1bH7!ki~J@%`FR2^8$n6OZeQW*#2$<(>kPsYn1P)HY5Z&?lt9 z+JU-+z611cP}kOklQm9TlbC$q1e+HX@k|4rQj+DIi@dBGrJBG?HZ-PN^YaQ(ElnJn zLN~l{C`}Q5qM(Ca;dJd@0Bemn)(e=?K!zbYEagras<*7wmd&E5->3B*+Guc!ji0~J z5iXMTmOSJQ4tSSotDqv5lDEZ8FPn*$=~*j@RwS9h69`t60pg!^_GhhGX=0>h(SvU@ zH?^DGh(PRz2$MHv#{8x%T{qMNc)%j$lEd6)E+wU5M{rgXy+cERw(#42t>8*zV-ZFk`$47 z9BM!3r-`mMDC2sRe!TDap5eF8_l5W}e98*yyBI`?Ql~GN0Rit?uQJOF6y!hMY1me; z#fJI~tR*DXv4LBKd-Eyb@1#GW`l#G6LJ7`)@X~gCL5>A5IpmhOmgIzlsTJP^L0Q65sw+j%Em6!hk;39v>hJi*BUK2Z?WjpRuX{m^df0wXH?OBrE%IT;ZWtzSs zDvvUF^axyb_@JXXBJl6${rzexedzR}^bK=Bcz7pZXR$jUtp@Dqg298f3+SAX{%ecf z1Ck2*a>;N5RZrZONJ`k_h|beXV^SWMcuFWD@-Ze?H}U2V(jAAO}}9J z`|%HB9>YGM5%KTqa50SuqmPe3(9R!-1Vtejn8!xJR4X-+u~$)-^^gVxRr{mINdp8_A$i8sejmCZ7}~CCh(;rv3D-t z4jJ0NoN&MgZCkQh1ZM!DkjD#h%ZQ_{!QmzArQP4t`uH>jbu?hV^J|J=#|4CL)S_G{oaS1SH-Zy}`&HeKDHC=wpp+ zq>L=rJ5;K&^`wnQ`*TAf+?z%uyqRq!p4VGmNRhH$lE3^Dq&lYZ&%ymm5wU4nok`?m zZKh?oSyE6DGw@X6{=4&GFS$RC#-Ei7I(D^ztRM`GStT*ZgzZ}=L5DTaKmGxnpr^LR z_Z*ubJ{q2$MlG2@(};zI0p^d8%M5RMWhFyd;(Vddn?eteEg=5`w6pO{Z)_yXk__E; zbej+;A>&Sx+j?S(@J;B$u_{llPUMHvQn?ydj#s`@5~ZZ9zB*gN#SfB?Whfh-W8+{n z>>Nx;gB_Hy0#E>8iRCvo07}b1h!JTi4|jw0Cl>r?)Iqh&r+(v|n->N@L1iMlNGn)U zb=Lq{J-oZ#hlhdULm*xsumf_*OWZ^78H#2B$(IDkHCuuHW%|Gh2~=@e%<{~Fr4EHi0P3+?{(%B0Ed{!VI51`8vA<*= zh*0~JRkbVR_z=c^P-7C$@kx&iw-sdYK1ZU;1o0YVArOHKJ}JLL;W5X(SW3*gLp|(l zo*f~yY{YMWHdhCT)&otGICBFKddch2Wm0Yc#JW_o2B5JZ8HE=2`2zvKXp0T4A>1N z=0YV7MS4gl??ofS1EO7d+<00UxCR)NCdNUW${IbPDVR=PoG1heB`-P&f1>v;rVp>l zWYeVkF(<=kmaKS}VquVFq-#~fPo@NZ(8xqIco|k^&glU$T_4p1OX3NT>^#a&y znj*|Ae)J)8SDx^oZIfoeXP$(I5%I!~$)Vty(&PPbUdcp5De+Zmom7CcvCA+bakq4e z)G7!!BJa~)m^>k!Wy|UAN9;)w{ z-*Q%F7B9qDnz?m`VR!UNNMBkwshH8cKV_da@>2LU7(jz^z^BJcEWLO9{RGbhxh$xp z194`_g(orD$`#iB9je`x9ig$=)0h(G=7^QoHmwdVaP@ND>{Bo+R03@d!Ro#%rUJh) z7iKf@qteH=o*Gn<56iPqo-Yg+-$o!h_&>BLA>KA*Iq}<@P{(uKoFN_A=M|E@yW?N; zehoKDjA3^rPdLKaNGgQ;mi|MY(3;nzb+Sx1nXOyNb)VFS?-_SB@X!gRC{{Eq`ZWz! zOcT$5zi*Z)wW`f#5*CMelOREF$ZzWWJrgsxzok5Ft}wpLw%-`o>c7)2;yqCB*q2kYQltQv|b9-P6VU7Ur zwgfox?QMX7NOKPe+#$7(_VcIc4^|!r z7s&ccab}N_jvaCKsbqB0|33` zn1z8smfQ7ibuV$Kb-w&KoP%+YO*<&{D5)wCI?AlNB4Z1O@xUg zcD>tZogG7b$L;fn?U2qVaVcoknNosUT2vdXBi-JNZt_Io_`R-Vsn|31Yxzc^o4Yr< zj6QEo(aPQzye@WSQRi0pNvjXWb2yR_ubAiJ;_XYbCSf|8~fER<(i{u zNo&HkL3Ti^F#5CNE*;70Zx;Nix%Nn>F!k?OWG z`cm%(O695Iin@{AZ_zY)4YWVM_52nNOU4>=x>US`eaoD5Y?$JC`~I>#M>W>S@x$^l zX-O2Cx^LQsZ#NR}b*;9Im~QwfaqQRAPgP>c!Gb8Mzg{1&)~RWnk+Mcth>GVD63sBntp-TkNQti5k_7QGL)=PA-k;+Rq~J#}39sv8@hBRH*Acs_}(*zga0>|L0U z@MtccimEQ`;C2xhb5vpuV|0s}CBFeSsvL>qX*tLpv`YR19&G=B3_S^#nM#~FHCWOA zRy_)!tSrF70QVQfcLElGJRJl&i0Xp#Ri!z<#}hyvPo6w!$(D&O1wODvFCa<*ko*Sj zvHJH1)g!l8XV84)o8XA zu6|jZ)D1jc==pI}bf!bT2otE<42z8m4|=SySOh!>)_WV{bL1X2G{ZTgc>9n#grvQi zVUJ08-J3L~$JmyIX4*Yjgr-CW-i z(~NcVVtCoh-W4`>)=0cnu*{Vjh9VDsMaoVriZsuI`Jr5DkzWz-C=xE|wQQN2HEVtn z6#`*9uc0vKxSqWvpN&rbCzifYw8Bls8MYc+pXS|6IbQ7$ckpt zeMn>dO1TK#NQzWqNM; zlYu#_jZXFFcn+U1XI{#b@(~qM(?_r)SRv~^gSr{FnF{BlSAYS zJ!o&75#cttj{}Ltn}VgfcSQTc!Cfih5l?S<8b!z!E@b;^Nuq0KRZL zuV2`OOg;qs{=vdBab%NzAn+2u{R0B|`ueg?`~>SX1~V`q4^1Y@3N&(oX#xFY*+C3P zUVZ4&$m6(2Dj7aA#rDM`a0BwU7YgLVi+ytJvnZcK#lDfCkNOCw!g542C z2L2Zv$9A86-kYrbn{TBxg!b!v3ln#;s|sk-;^i49OKX#ErPR)>yzsRpyAnRX;4h;d zq^e;hS2aG-Fgj?Ao!{}koMK-6jhr$-lgCfuXUZgYs6Y^r=W{sx0#8sqpp8DR9s30W zNpEC*6=_x252OBuw=uUFV?FJe0*Sm2=)VhuV?yh1=ft1lh#*+vmBmplNzi zrE;Uu-W?ipXBkS!c8Mv=8LtXxA{3}Eobn8CwHzr}+jZhFwaWOiIK&k8i(JZJJR6VE zi>rhkIJT%6Rb^H`u{`Me=$pvc9PJSd-K8 z*=Kn?0t5nwqJD`>6j-7H+0q?hMYnZEJcq!NCm-C3=XS~rKXUzMfuRtt{*JBsV4!W~ zu*J3;e##x+e&&dO18)lmGpXUV67NyM0Ua;wYNth~db}_6u=+Mg<>PBv2eqQBCGzLm z<{qJ6x->MsrX?4o`ujfMO^miX%bbxlcY+a*qqOwsoE`ZfvDMzIL~LfEgh;FCO8Z7< zKx9vWUKxMma-HcbiA6PuN%%y@@_U0t&G-3|!@cW6f!R+J#ID#kqzXEMGL3liUMvOc zNcV~^Rq>6c*|Y%+`1ev{p3^h}(6+=S<)1LP>ba#GL&MI=cc*`Q<5CF zRJ-ceN!{+=Ghr!Eg$QGn;ZlTx=*owy_t2hQKpio-9b;7!Xwc^}15)|x9_*|3OzLArWi6M26uig)({EBCz!6W0WV<;V9M0&?-jqKEt- z)OB0wS#ij0$|an7kK0FLdwrj-RJf0!L&7aoM?UtoJ~jNx*1}2CsEhnLw4k+qJ>8>d zZ4w};)gseQ+`4TP@xIh}Xfyx)a-cvKZRPc&yo&3AByi^|rRip`@lOJqPRaPy4Z8iN z*;l**Hut5@4uFK`LQxhvYHNF+%-na7; zm>6IyW+WpYj%cfmgs_3D9Z=f$48|EmJ4cR9$0>PLfM6B{v2A!MDMfTZsy*%O8j!lX zpnk*X!cCw|YSk08g)Il_){Q!rY13%yHnpn|#CQZytTj+Xe_Aha`8MGL9-odBYy4`E z`TQOEjjZEtRy|ci?ku%dDp~`bcEz)iI-KN^h?gmcglpxt6U9RmaeY_~Keg*KW%usd zt}xGVr{Xs~$Lb^p@-fMj+Udj=?a!DTyHnZwxjsBa(pgFU5F__tY5b(?H0haPsOMaF z?a{nNy+e;tFn^d>P9%n{U3o+zt@>np<<#k0Jx!ee?%Vq6uFnDud|HgN= z^?0M;%t3cJnSMuwY&U1U+rB7649%Xj!@vEp|2O}YfLP$}4IESUF~pKkb+93qr;l`N z%nbN7v1;zDE%S=p;w)WlDebWG&UiNFquU%FvhUajzhW|J9K)t-T0A786Fk@9eaGr5Axwfv8bYBVLTfPstA)LiKdt911hv8ZJ0)#4=}r6BU;3VSw(F9qcv%}D9+~*(qwHu|TsZR{89Tat$QQjF zKxX@L9#l$pN?|TXYxAqEa?4w6v?U_fM~zyznfXDk6}?!O@ZQ6O6jensHICo&UH;GY zkjfWeq;aXL6B2!9B|ga}VRVwzv7S$t?vQD1NZlsBTkS`mi*+#K?NQsJkP%T8Ri#wl z<&uF5Nn%vwp}(EV&1^J*&(ymOa~rRc3Q)C>6>RYCMbxSEA*u zRX4?Bvpy+#;@#I|_F9PWM+?l7l9RO(;SDSj>~vRxLDxM>&L1DGvrhOTytiTPsX|aq z-JPZgnVK59j;sA$s_WW~bwD~|8AY^aIpucvjkC+8ity*^P{Fp^BZJ0!;#JNU(dw(zF6UEWge$%icJ#J|eL$`_R%+<+ zT!_`1SHqa$GT^V7Ad~tat@%2z+^B8{!^ORGBV49AAK7^+jDE^@Idn?@r}V85D+-FBy@i)v; zL|nmspujlsDECzo7v=fz0g43BbcE%_GO;^JM>tMxj66?C^f{HIK8?qpveZzt6hiwt zd-nr3@a+h zYGdNBO8~?Ek++=S;-Sgzggf7_XADt;D}8umK8u&|{aKFqyR`(c;_huQhH zR25S07aa04SQun>zBA|&80Uv z%1a=f^%G>jgFz7kkv9cUpQHq=1qg@*WqCk=mJUkkfgI{yZL9gkN>Fg{&TF^fhk7+k z5fnzQyaWZ+GwjK!T%#cb-uaO(SF>Ta(gMk3oh*bQOH46H!-H~CvQo;Ch7}otqRsE0 zJu^rmla zC0s+z;r99MJzr#)K{_&$;ryd5N?4c`F6nJ~;V(#zg%U(*)AzTPhcc(73vD3HfJuY;1Q zZyTJ-2A_tI@#8~D<>8?rFHpG4-nvaDP?6AJOa(p zkd*KML~RO?{EWdv3AyH6WZs$B^dn9X1~aBfOO55C$CJN-TX{zvg7z%^75M>s+e5Na z@~Vub?|-n+I2vgk;Uifub?=$=02$Go6%{Lfg~{`T;n&ldqcn(7S&3v;obXGsdfT}> z)HFnXW^a9O0}!iTWAbP#)Ue4k{SdP3JgjH#QPswLHgxMJ!yt`P(e)}IqJyF?`BQdl zH{YfU9}1(u$Ue5$!>0b*pvT*iJu!nD13vKHg@oMAz~O-=dYBajmFn zS(ZaueJ43K+a)=ABuvYa7rgK$=NgSE{pkz7QJkM=UW1gktLS0-YT9X1q6gNfeA?-Z z_B7So>91i~+1xhDQBpb?xcT@V7Gw;IJnlb4V~|cjU!;MNw&LQ$vG{-neqGZR`Q7WG z*~CJh;;+sKe4EPrQmXf-$MZue2oor1+aED`-m>z{SxD<#?A7AJl)%TvrcQ4rIQ76v zZHRGs{W9~b{mRp*APg@ozL=O=G+8Jwp3OtY{_uZ2pUBLA*+ZB)+;}4mzlj|QH@D4d zmk^M90QA5gAYTy%XaXl@&E?EcPb*V%^LD^DO9%8j{Wb(pJdX*ASHwUD+%O-bhMo~HJ4&kWu@17j7zZYhExs$Cv zzs!6XksbJKDz7_a--eD1{q$>$P35{utl3Qd1Iniiiv66-ung09>795z zI?5Qsh8!Y_th~I$w;07!WYR|`e2TYOw0V0*4;7Sr@q851aj)2u5lyMW$Y2u>BdZ+6 zeiu$NwVt_P#x~5?BWH&RqNi9f3D1>;5&80F>(bPCFF(Y+c4-U%x3^rJJ}f?=kV&Wb z{;>tZD--Q??w5*>j-*u*!(1cTco%lVtfGf$C`aa+c4isHD?KTnqBJqj5^ioZW<;+F z_ZLV!aV|g_|M{teZ6A~Pm1(iar*FA&EYjFX66kM!3gQg2|IJN7DZsxk`E7j$Cvf^-a>fF6OUMFE&1qaHj!-mO!A1g7>Uu=bWW+v?4tVq);*o;TJ& zaG|i5@9^+2p358`6#dio#Xp4yv*|Oj(*aU!#P)EufZ+mN6!^ec3ZN*Al7-}v8nw*= ztJqYP*(kXULX=-4E~&qnl5-yZmn775T}`hjme1@tm@1sOzqLSmR1AYuq*mNp4a-Nz zpC%M0lmdp4YZPv=Y+vHEbzYsT(IL&v7#=umvw_{`vHzGt7;&1 zSSUGp-Dd9{wd%5(cm)xnTwK|TEz*yBA1$ihOASpEoEu6XelQ|P!2+LcXvdvFAIgMw zyb}S{SCa_q7Z*+t6BKN!9p%e1dSG>d$YYCbh;@fCARO^0_-PGezaiL7Xkmk}z)DX;iu6z$k~ zt;l9n1BpF<6us%dwq~mqvd0t2APWol>|!i?an&l`?~BLyyLSR&jECc&w=sA>t*(g+ zlyk?X8>XPt{lG48H7|2nRE+CJ2~BUdzb%7#ppsSg-6U}8|CjEKsa z9X&u?7UMnqmopJc3ZbA4pzLE{e`R?Yn}Fb}9;djtAfWa^TrtfeNn>N6t;)2(<&<)xGB1&^J+H4;Xs z&7X<3H-N=3gz(Ztrdveod9cWi#NwkR{98v%See8a(<;<&z`kW{j2fa88yh{Y-CDML z)Z^gz;%W9s%XcF-hoZm;LeebRg~ZkLomX(2zwCydJ`4}YQ@9uKx&L|21K?4RZ3A=&${?!Qy}S_*h?+KQ_v>X1(6%@P`S{1Qw6yvY0-kp-JU|*} z1yF!n0T;p5-Ytq|Df*S52=I&{YKYE9enn1>mtC$|n6V!LhSPMau?nHMMKy z@<6aS^~s#2z_0>le(KDsSH;)X<;sltTsJeGjsP{RMxnu9J6`S9DJg(`RkwA=B<#JS z;*+`L`)qUrJB2kuk%gDk>co0}>=l;9SIRmE?{oT1c51FtX%2xWhm{?$uAJv9_zy_$ zveRpl2pp`^sbrO^G;zzO2u-TT|8`SRJ$a7OH)liaMcfs>k1nnVbbBC7U z*?aE5fa2$X+3@e6`TN!Zc?5us5KZ?|6d)m^W(zwt(EbntBob*kx%SoWr3HE+<37U8 zQH?R5=mE9BJOGqK9KcPB z2L&dhopds|#KdkW#(>=dyoeB&nbvfz1pl?W;#0n*0DB}cYzU>mh-2)_{q+} zaiEd!za~6*F4}G8ms0^_%l8cZHqV~yMYYRrDcQchdmPa^`T9cZss-kYc&6;_^qmZ* z-~5i0bc0oWed5M8o##=A>rVzqaB%E9{xT$?nFvDpTCe(tejH#LKVr&x0W#)6pjhBd zky^5lCpjSX!h#J1LbP1+>c=3z2?}~K-`3h7g7U^-voydZX#th)-k{=n85F?(03slN zSf7CNS7WsVcL%n_3gC`OSXi(Eb%sZfKGhRu=HFx1GEu&Os`AIG@!2y1d~2a#*Hw;B zCG2!cF5=rOk#)H<9SatUZ;xwVEluO`F|o=;{E!Y5pz348&-giZ`c+_^;IrI(QUz)5 zd$NV0dzYRNOQ_Vax^o)u?Ko)V|dT%W?TWxNFBYXa!Xi4H?h1fLc zObbt$BQjz7uyG=6n%Eq8?RhS>xM%YxYuIu~WC|~QMjVNmHOzjyQM4R7I9Ky#k(7|- zXe7Kj633BUsA}Wt<4Cm!hdRfrQ*m0x^HV!v+(MFliFL68r4wU}5AfQQ4(S^acVQL0 zbn!P>d(zx0w?FaqjR?#f$6FkJpzbtjPG)Dfv_Bzg-F>52Nv+HeL&K5p@L;d^%D+4v zODEOz$5F@KxJ108%Bf%Wj(c!iot@?Bk5FfxKZ!A zV^^6I;Sf#*1@+9u%HkE}?X5J<_DXuf$WyQ86^YRXjVW8Bja;);!`a~Ew3tj6&kyr_ zBI2CMfNL8NAT6Rk>_Xy;VvW3yp5E<}2L>~Wz#dff>00ZN^ZjqwNwR>D1R zsL7ocVck|p7Q9;ZS^#q}0BCCH0lgonZi3wPcbU%P3Bb|SFM9)+e@?TW_qUDnP1Oh@ zzD6c2h4k8`77W5$fnD#PE~lD}UKL21{nD2XwieDO8hW+Q9EWzir|CPug{SY%@PN03 zUqAkF9xEd+nU$Y30xkmOLH@Pv*^rD*KKkm%1A0E$(#FJK@AGyOKH0AYk>}AiZ_X#u zZ>Hc>G_RwTY3zuqi`}`{{kywucbSC8!}FICqG21G6TeO%epN2XQ2)M=8O&y)k#4!G z6|Cq&Gb$+Y=DBgkqC3iTcjS()7#U}(_ybbe)7w&N;khYmOde97Xuq%8k>RAC-XCl+ zjwWK;$sH!BKq5w|VJ2vLH%aMWnUzOnX`GC1#73#KkXnCaNBGk3t;%yh-MPxIFtsI# z`g5-X`v+rMUJR|c!mLN+t>2iUNUj$3Z<@aH-aUPRM}{ikMLKf~hZP6F3lkH&j~h}V zyAAkTsZ6a`?{IovIk?GlQ(BHyHqV&qO-IZ)KgK>M$kLO#pnkN#COSM2=ApV3acqcr z72WK%JG(upu7~x$)`}y(RQ0|rwmR;9y6kOwar{$-4FZ+Zg z%{s9f6?nu1rm)8vML-Xcs{w!1Z1|3@DMN`#&Kr=(o>DTa%`w8Fp%)%$ZcC=Y==FuVKJ3B;bjutOw-tW#!d8^oIk4iDeA`ItAho%$T` zx@mwdhpNB;Ni_g4@-vHzF@ZKvu-OdoZJ{*-#gw48&f=+L+SXG*a|0w?7*K3?9||f; zGRn$uK!IQf=&1`@-Gl;dqSMQTepcNk^!m9l@JE=ka2&=PnWhp_sIP5VQ1P=t_HHe2 z%F-uG#`j4Owl?M@)_D3&0&SODpDu%<@Xzogy&z{qW0qJpG!?l==c|-EQeW89>_nny z0$w`2ag2S}_>}CYi8&<;qv)j^-R6yqG`*SP)+;wOz8r>cb;41{kPqH zWUWh6e3Y)vMen!^ie=%BF)>=6Pm9Sq3xH=;@*bsXvmOoE)?KIIpnfp+)xE$BpCIF6 z*dxbVq?tKS*35v`rUF&by$iNX!h7_$x4S17w@@UC&o?|ZO0*pQpt=UXrfrOZ67Os{ z89CWAElzZjpolSzgOQNTj;%L$A9&5qH1q`wCHv3%-!uwit*{lfcvIn({LZkF%4dzZ z7=QP39V1DpVi5JXiCAU7tb)(@4Fn)God)GieJ5Y5?=Rgek?6;?y^oTomf_62sC==> zU(7a1RkrOyK+G-(1@`3viNl@5yRn4P~-Cn)Af&G$-l5$>V%4N>f@DI0!u zaC@O0`iG`ai8LNv+(K$wij-r{q2I;m--rlm5jEyw84U6o6g8E z+p0VmV+Q!zaAS(~X6_SJN&Ip!YUk66bvC@*`&F$=k1eIllxnScM=*MooHhL$CK$`+ zu}{3l!mhhYfaJ(uT>zU&&EoeQ)2{8m-C~61h6!|V#&wA!6I6YB+_`xY-LD-}sxlnR zabisf;Zbg*D-;`s@yf9TGU3Cb9VTB*>s#VEKc>pW`8auRCi!1%`R9G&IUv45WrC@$ zd!ObkI)Uy?87QujFsK7i9ngFI3>d*HK-WS{bDF|1R3y0YxtZec9?@YB0*Yy+;~tmM z2Hf`~uvc7P@?56b*>Q>(C5IKzP|t#!exyEEUzvYiU-C5}Iy`@2wLQJ8jq@YNZ+cj# z-6x(;5WjfC%<*v$S6$@mq6WvcbJh}%y@Y9C9c_y7nT~VYCFJI!FjtVGijxg*a5SS7 zO#Ynd&MIuvacGP=-^|Ub7HSe^9y0B@gqL(|@=`vcXm) z)i0;5{;RK7O4VLaS*Kt-qj9ZE=Pkl9IgS@X=KvM+!j={dGpmpFwx&6fd*`l}W2y0u+o6aPiCi+^X+ONtWc|ywsLC&;)iBG$W_U*GSx;t>0$mK7 ztI%k%PK3H`rQ?%BdjQoX!owOF2cBPFMJ zM}1LVR_qQVG1U6~8>*_goj&N6aB-xg5+oM^uv-~0oIPgox*BB0w_%g>Jwg4XT)YHp zmKyql#V52<&$W~;`)pJMZTnpqS>!EMGKcEPRcG9Vq8d=YPNGWUH6#Zo{+8vT5jHE7 zP*VGN&MT55Hf~<8SgwLqHig{3rx^hA;~Xs_RRuwWJ+rTjptgInqftcoXD;#YsPc&8 z{70GU-tOndh4YQPZZ+TN@b(Ku9RkE1s4{mjnEnq_RFbcmEt2&Yh8F8Y8OlRCJ*{?w+)&pdM!`KU?=!PF!v;@%IjN{FC6p428s2UpK+3jH|t z1EDB+4L%W5aM}5R4&J~on4y-FceJPk4;Vv5qw1R4JlGk=EtUMLYY<}FT|pKQ+1*Cb zj!{?MS!-LdxfvnX{7Ue|+BEW7lJ;oB{uL}9ZnU4m=V40edllLqHKO!dhdXH%ET`rz zHMR8lbrSeGtIGmnvXF3mgNY>+o`U2()BI`jFaGF#Up>0H}hTI z4(xKIKW#9#`ja0Qb!$AS&@457eR21zZ$R|UlDSl6!$Iw4Ptshp`_ARJJ1@b{_ag95 zd7L$d+DfS&KYFlTcD@y|7dX_a!e?k%Am#q@Y5B&E=y?)AT0OXf7QRWjXHQ-U*B8RY zx*K(+JibbPZ)}oL^V3_~{6ty?lP?Ni=8&;<+UQZ~C?2)BaR9j*$`DJB#8eu~WaYqf z0@KGVVrzBj3ojdRX});1@CUirS`M|Hlp~%2lFmM?`#JA$^V}->!u|{YbEJH)hdA0B z%Z54kHuRY|VqbqjXFALQpqZ>dHRGJ*R8-rIA0KlXxXx`*#x;UsUc%fklGT6!KUP3Z z4kuW!U%I`wrCcpf8I=Fb&EOG1O+{RXe{+)+A@p3H%zt8hmapp%t}}d^2TGGbwImy8 zH0lks;S50ObMbZ zf$#1wZ?>6+VUzkXr7Do~IEOY*q|?5kMQ>7ze6VR_f!#JF`=0Tvsey`AYS-#5+^7uk zrt)dV1e(Q|k^gQDyuvVnPrA$}g%W>3l_={%CkdXg(RPo4b7Ch-3BbW$y4E#wXkmcc z{()!u;90SbV)lZIh+XYstXH-n3+Kd1fpfdc>~$SHOuB16rb#tn`*$jl7w@GSe_>Se zp(KuG*t&_O0F=+zvF%}+FJ2L5-TTDWm-uHvR>^t(bCjY-aM+xH?Ek=h^3o`Ki?AN^ z!4G^GMv+=)!I1bqO85BVtPsrNXl~AA8_^gTN+lmWcRKV5I(aFP7azrL86Jo$!QGtC zOkG7_9f&_l=*3K$gEgr@MuFo5>6HB;vA7op>hYt7K5I4bnaC7M@F{|1e(&2ef}A@q zzw<90!4bbiwR0qF3$Mf{AZ5j(0M!42PeUIEHrpFT>{=Y!V86chMHY_E6X`jz+kD_^ zK|@811f{v3wu8_%b157pL40`S)aDixEGwP-%YVy8)1W{V|KlaP;gBZd6Glb=Jph%E@nLFs`Sz#1^)4?rCq91H>DOTI!6T{sGgl{KU{spAY}cz<#ou!K2wF#n%( zRJ@D=84gst20-O_Ku`t~6x9lCK84DE0qoNXiu0h#P&&4U9q~?WA&I+dlQ$n=QLARC zOJ+Yv7O5V&m&l4-k%E7Ru8;BP{|A<2;!yMQ5&;?sDO9TqwB8YQN*ssISbCp90d`h) z_MgIcaD>;2%sd}HZEGw+=6zKtH7u9&#Jvjn%gd#4Jf-?FLauk6oukZ#M(D~Be{O!1 z`u|PdC^i2>nwK9u#f3cYy7_M^jM-nmt^kcYS|G(p24(Vq0IW~>KB)RK0Lqw?&7MM_ z)15?iP7X$oM_@61ofKLGSM7>V0n!cuOXqqDca7$axwI8ok;ImPB(rBlmS}}6{I3dU zc2raZKr96>%0Ch4-*T`&UnOIpI!Mr{nY9TNel7zI?^a0ic=7tf$B&=;jiDZghd_u4 z8_1`T9Ju3Z$3;~r-X)0|(p(G5el=G-vEoyX8kJ6r@ujIGX7HnZGO6!_0BrDq;Uh-% zEj;wZKOa(@qs#{bVvC(AsA%;*t??QwY`JOw;+|75`U}glDl`4pSWdnm?SWR7uZyE! z;}v-P4I^YV6?CIS7!%%2?fp=G5h@{Ikj=xPGWlA|<{7t5F1L5!>u!#9rbu5AJ5l=+ zt$;9w;xPQ4r%#tmLu}*T1agbKF}F2t_DuF@OYxxGqHz*1jvtnBtp_swdnT`Dcjm94 zP68R7f@y5QV*%L%GSE7R-1+3OfGe{P;^alo`*Tl!@&zDuzq-C|TtpVh&QthH9>j4f&~}-W3EOT}bXk zhsx%xaf(IS5L50=_lG!8Elg!Fw68_A)d)(kvp`7)&?HA?5AL$x1%}Mo3HDMrUrmaqbmsAx*(mX1E9z|(8Voo$Z4PvarNAL^!x|%V>H|Cw`^)@7_9KW zc9+O?pWYc6SM~ncd6DRNdic=Dpg6DJzcj2z0N*FHFE_@OYkNaeE3Nq$^umBdV*%q5 zQi}<(6cc~eb-t*()0(!+_h-!+D*w4gH&tA32hfO&-F+tRSM%1z`3ZQEUxOdFx%~PB zZ<}bN=7FAqq&5kVzqiFNfTrWmE0W~PyZ`_}x-)@{btw=V`VdF?4ALCB@hn>~tVf4_ zDbhT5p;~;T9`p~*%ggI>AOctZ`?B$Q?WOVeE)pND&PDCwimz9S@8^7oV}F0>tadCP zVoftHw7c`y%>4Vro#;OkLiH?rm7}_%{xw;=MDZ6b*maVh&vo4SXJ|vr1^qt#j|zgg z`07x#cJPQyQ+MQw*1Akup(8B)D1pU2r zFcdiWhV?N29;CK!qq`ei>NwG|yXYczHW3W{|GW$_mHrKmxFLEIZFRnDVHaNQv4#Gz zkK@0Q{qM2~25+ZW|2T!B>j8b_3%4d_b(&|6?=hRLX>d^hql*2+36#PA-KdeZP)9-Va~L2A)B~y6 zzKxs>uq(lrDJdxl2k;lVfKI&wi$%3y-hZMeR8$pmu*P8UnCk#dK8{uU)?`znoHjuo zGbK8XO?SYCi^?`>{eYzNOXsw8GP4@>Gok;7t*-!!>f7E%K|m=1=~6&YLb^+&krI@W zPU-FvkcL6JLAr+=y1To(yJ2XC?~K3yz2Ck6?>o;k93KW}&e?mNwbx$jUGE#}E(<59 zF{&l5{j#gY7@4}xoe9QxID&U1|8vZizMg*uw~7Df=m`@6OiEO=d}keCBmYa>t?A$M z8?NRel2QYZ;S4dTP_b6SZx7BOlL><85~>x68+gJOO0{x>=Lk6_|M!b^2>~YnaLEe* zqx7$%CrtXE`(c$;^2SV1f)ix{u7lO;2mCVu+7x$y8hZ$MPR^xub#<#gzZ`8;r}hQt z3B*b){%s)C`~TOJ{$&UMbFQ^{*TV3x8~v|yg*g0+|360p2jHasb$$PN?kTb{{FlZ4 z&;N_4?WM61l=H%|-uzNJ)6wH7HT|3~;{;<^1{=Fo9WRO zsG2G#VNMW>k`(eh<>>flFC1G9m-xDz+#gljT{l7mWy&q-x%7Zl^34b%f$(Wpn$A!Pa%D;*LoawA{|3Z0kG$uLyP~+Ih%`*AQ zu57De6o)+yD_mk0Yiscd(54+>l7R{L{{MNf_Uo~GWXJCzPVHFH9)8W${5veQ;P?M) z%)GZ)#whdse8-RKkfD}lCcky$B+JSOF@8BR@l6(cO@&ah7yoECu^4oRRpf7|7 zI7j~Mr7q2x1^qd<+7^(qg%qJ2K zXN@o}BgVd-9ro-3ND>ihfM5S5XWI-G-TE-N$^`;y;kE!rVR|>9zsCiqw7qgt0V2xZlGNPp*UZg;$bj>TH;U1g6Nl4VMyqdfkFH{4 zrI(XmZXu2bZFIcLbHXdUUR*+sMIqNZxtoUHD(`EaG}~a%^N)Y}W{tL*6@Dwp1?kVt zl$J89+7=(|JP(xJNq8acM9a)sH9Akcq5i=Pn6cU>&F$thz|sdSnqknA8=%a?d!cHT z_qhttzkVP9GWiHAY-u;4fM3@iA@y9phEpT%sXmTUJVXG$TZdEcoH~q`{xt5hl~>>Wqz8jf$|0rE7fMTv!x9&5mL@Y9p1BCi z3{Gj`Km#RKY3j%xM?7F+S><=K>;Lny4K!E;Lhp9KEyMer;ZlJ8Ky37$j&2Rk>OR}q%pf8VH)R&^_Ajn zxY8IS!0o&6%q9 zjel*RhQ)?iFo1dF>7N9g;FW2_#l@Vs=vFzveVPI^tJ(q$=_de(m>n<-xesXE$4z%1 zN*c~yNPtLJflezt%j%@%N7xm0R4-9}f0c#g(+|v{Hk7d*&ogr6vEAm|s=PH2D_YtG z`WtHOjI;PlaYe(^C@&p-oVA5&Y<#G*rbFv}7vAcW8 z23hLp{ZN;gf7;*6*s{*pR=psQe|wnvEe9PzWcN)LIlI$FU;^fcBnL6nkY4)c}uvYp^6yFHjVr?D;8gftOqb_XD?Ja}+AF1PqbtP5;mcA`>* zyyRQ{+)N+9Urn&=A;=%~pdqU5(^F=tx4nKrlW@kvVS;EU%pUt^`iQo>r`_I7ak>ZT z^3CCm32h+h5oKa23;rEy(WRaiC2`1j(!d+q<*;cdD3pi1o>u%qG+LEXt^|Y7<(2!`=h0xI z{m4{84hOXM6oe4i`z0mhz4CV5IuxO#-<4%|$mBBDb*ZU5@ThR>xrC@e;wyZ7-k*rv za13RICg?wGd;qb^f)5DvAGf1pW8vJKw(w%wHXuw?d=9MrIhrtn=4(HI1$Z4!STNKr zc*(MTp7z*q4)Fg>)LO5$T@YMdV$$klE#0-evvKSiXTle17|&PRwp;M+*SZMl}jBGKizeS=v+ zGFd=3@jUjt-A(ds;5xTlvt3o=)O)p9&&I8@KT69iu+u%E(Y1*pC~wYwp93MtST?5O zT-6lm_PZ~L<%CUNB!sP|+gSSq%R}fvsQr0^v!kPtRo z(gTQgT|PRkkBltGuvrX=Kf^BzP8jSS3DBor- zLw`UZf7D^fk)1oHPyiIM%g?p|@=|K75aOJwqhZ+&+f+ zf6@~H!QmDFg}Db7Z!CCr046Jd6_o=ZboW_U zm^Jt2>7lu8R18)Tl38y;ea<(o_nh)BF%Omzj*=Gs+oUW=`k**xM!V~Bx}Ex#l_9z^ zh|DzSHl#DUkyy4lw4d-OFrjky`11(N`Pn?y+pZ5Q8hluHA$iVKDU$vvRdP-v*9t6R z+9ou-lVnHFzf{ll`-XGj^6F!F2|0;MtYwK^=-^HkdhlPnbGOeB$McB9jLsY5dgO<$ zm6+$QSH@ftP4znN`8+AW%6jDa>0pi4SxEPT|7B-g!IK)<107tfk`Fnq+E4q5wZe4? z$H$~5m|J+uQ(E?35MyF};oa;l7$Kjz>u|f17M+?M7KCq$zzGM-p@aWwj5gk+G%WOCjNDzcYjC z&9kUCE6eOoDN_pUrt0AG%}CBBN~;eWtLKaTF#DOoWR-rSz%U8rJ}kib<)t8z-yD5t zrFH&|6EmtI9nnx1O0(l!6yJhdyt@sIv;DGT-+eYa=*xWNqEb$ewd`;*JRm<0|7V-{ z?{G4b15mGOfKGjH0QL^801K&Q03$juYU=-TjGH-}mLTkKe@`ybGrA%0!=sl&z{Z*x`;Iu*f$#Od}&%H9J z=VQ-6LvtjV(9zaG{R4L#>8;y(@@=o2sdBv%8nu3<(3jrJs9hCfbc~cRyjkIgRHO}8 zRP%z2%kPj0&rI|*p0(#5x_eV9BkrsatgiCckb2%-PkK3i^6i7NhlBe79DZ@rlrn+I zXaORGnen07tyl}p-x?G%dlVB?hcTkP zEVfq}x+21JZ~DqazFHJeC0{5u75fe0=0EIs+`ZDYnow$Tx8~!FIGz}Fw>)@5@!e-i z;`2vMP9YhOIJ<9LQc}rZ;eD$ll|GyY zg&n0^CGC?SUsgvAwZGX@mMtwZjLC;SWTm#O9Mv^^J=!Bx*Z%QcYObY5m->fWWn@ki zGHei|l1xzSeo@PHIn0i3;?p7T@W^?Qh{MFOtQS7*rLxlP5BgC-1jOMwb#=_N?B?b) z7}^7Oqw(&-HxVgaQ;W-9BRb9r?4eh$QeNK;9wPN8`40)7!=xSUlPNvZ(_l+l0JAj@ ziDkNHBNv3C7m4h<@7Jc(En*@fgrj}hOINDF+*Z{C+G{AWY4f+wgIyUD5KiF;WBR-$ z5|RakB@Ae#-|*P{GH~a{yRMn3E4EP`-n?|FN3R9-_(P@4Q6&AUP@3iD>;+VWH&eNv znH4CW>jPG~q&1YfW3VlR>_LS^wb)R#TgvLiL?-@OY#9WIH z^?qj?=!HkkLWcFvDg!lyUZ9}`z<%`up~K-n8>N3epyw?>J4cGYKk_ypmt%{t4Jd2m zodblB+yL|a5In)SZ7g(`01r2ea%-xcxS!~+$j^|x9U7vCxq3_sIR`9}*jSm`xw3)t zmUnMsmsyZwIk-TOgBfwlsO)b;Fd6#2V_Q=dLXm#grls8rZHU6cY?+Y`QQYpevMXsO z^Ugu2R^!GWrQvJ;%XU?*P5Y)K&)SN5AJ9Apx1(S#tRoM?4ZXseGUDE}(r9c{VnXt- z67g&?2{b6kU*28XavEqgBv8pAio(8o4$@sAyqe}tA?gBGL)>c|r(+Lt_8c-xSt+;f91sGnly@ z20xM!nYzcBxSli$fl0x`n>KXwY$b(4ipSRymRFq>CUN_>ImXwwH?G^!W_G0AHXk57 zo3;8BY~42E;T5{v{{4qY+B`8^bJnEWV?F2W4vSh4jbqQ;a%*Sp#_$6tR?xt_h1^Y` z;lprp;@S`|Xg%4Mn4Iv-{GMxWjzvfHzpwy&>xLvwbDUV=9G?r5htO0Q#+J8`P`Zat zc$)D1^}#0Ab!>x7>p+}Q&nV|2C^COxKE(Wipf33qMFu5ql~AO+^O(JXqxTRR&J803 z=@NpjA~Yn&(i*PG7vkWhy~pj*mc8q zeosz-x@{_;IRy|&cL7=rE`Sos&5=`cKk)C_YAXsrZUVkWXf(O=^v8Vf7(#aHpnUgrP^dgQ(IUnCydyWj)IPSPnsAlAP_VO zVKu?#S&~2TGop*j-d91Jd6TFWlvNi~C*$*d|M^C)_C!T(>Rt@uei>C|12&P8O&Aq{Qe-4)Nbnf7Tl z85Sn2pXLJ}P6ZX^C(kaRwOpKK`V}biP+8q)cxL|f%xSzf zrorE(M=ni27mRc3fD3ay8~N79x`K)KxUf>!InyGQ2X5kC4XH`a?oJEO=Ghmh z24j;<9IB+WkDNdx_;`1S;k0e%P9W5-h0EaqDFFYLwC!eeW}w#P9K$ma;7eG`O;p zd=tX=%cbc8z-%Gl_C=+oFey8id{?mGy2jR$s{G*I>KyOoL30KP41Gz7rnO6Au@Hmk zn0Bj9x(^xaW8FVS!}w1o`v2zr%m68o4nT4A<|0>U5U%Bf&mh_8M-(Q0GaByM0VG;9 z0h0b}AdVOWxB|!kZu=V`OqB<~^O7_b3BjZZ_?1B^A%+?_KNk=0ZmZj{$bG#z9w?c6&UJ@t@sdT~OL0TW*j}PnES*g`ssUbZFJ%Hl8c{3pjmKAP9k0 zU-i`ZNgJkP)6}Q-IJB<$+nvK?lIuB!blWK7gH26Ax~4S>Zc5H{4;B9laW>^|inV%0 z&l;TLFe$VPw}T`2C@9^Htmnz4n-1hDe##yqybV`bOUfBJdv_yTzzO2uq*=;t7piu} zk$Hb=Ls_^(&rQOqx0Q|UqiBn?Q8>^=?4*!EG1&Yio+)y(WN_N z&~c=@D+i3Qd@KF8-V0@1CLr{{)crr}gYPFWM0t7rpKf*qv(hPp&VO}gBR#YWPmOqk zS%#n4X}-k^$yFwqu_rqsu0sy{CfwJhK3y(d(3R+vqqCr2c96P?V8<%gupOMX9Xs-J zZ)@VajVn{fY%S+G9wyDwW;=y+8BP$(cA5!+bgoC0l}W3OfSM8MFe zD=kXE`G{Cw4yfHkxctp+|4(Wae(FsG*q{{^6k32vX)l~##K!4z3pg^sNuqR1F?UuB*~M3z_O2VFBoVg8 z;#)P!RUd@qPZNi?N=9q9qoyJ<$W@rP@Kvt2uZ*gMsCpf3CGBI?sGAq|GepRI1nQzb zDavqPhRxF&mw1=<@Y@p7njg_hzWZG6ufp&e5LJ~w^_JVjCOlnVTC?HXAPyP8PI2fK zLKzFT$0l;m_##^7Rn)Ta6R#7U(P(%SlQv-jy^dol`KGpwq){RR` zOa?k}Re2S5?u`-EGG{isgr|{t#Zjz*tKWfqXvQxvDAtv?Z(db%j23#giW)x5#m=SI z2|nT!Ac|_pm5JVlt(|UfV0&K_{a_TK-hE^Vn%>~hli(DIDaQehF33bB8Ye)_QNwT zFxJ9TdMXx2758;%UpSW+GFmBPhLt0>3%xj?M0Vwq@?!0+#R2t95Ln8g=VD=#j7^l# zi=LBI^)4&G=9W@k&3wZ#5LbYZn94jsFRePj>^KN}-}@qn+t-JWmOMwUTe>5_cMr%L zcYW5XYk0M2*3xStx45~@qNQ!7PmJ?qs&+=<59zqC6J@*cD}_=*ZVa6$Zh`L)DZ zh>6(Y?!dQ1N1ym33lWCL%yt5kWnRjoPpdF{-^yrXYpL)>nA{*pk{|JPhl^~>Y|WMG z{R$W3cAyc@$c=-cA=;Ub`De*mQFB`8E(NijIMZ4m5D=``MC{F^gyPC0_z}gXY`OJy z5WZUAX(X!wYB2_|zlEoNJ3(Lr{(*}t4oI+{=gWHp18e9Rzysz3lsJ>L0lHxLE@~4{ zhXu%}{Q< z)#JFT&uk}Qo?SxFk8C^6Xrl8W@vE@PG}oGSlKv1q;@RS>ns}hpDLllkNjx=bw3lX* zb@S2Q(qWq7cbt&7ej3nS#Md}OFvh?}brmgTtvUbCt~Bm{?MhkqJpq2J(dlV8K{Q;R zwGSu^`}c3^0Xn2`Kr#G<0N<@P0Q~5rg6{Evuo0m4acOlAP*`mN#f^J_v3Ub%KXJdv zq!^U@NyHo*Q^7|1=L|}AFf%FLJvw7O!f1laHz#~PikVn#(OPebhQTzUsK^aHoRz3n zs%ru%=yh<(Vl5ex^E)Nx>y)9{YVhbdj8`$So~|s$zhNa2FY0DCqT}at-)TA!FyMEXqu61n5Bv=x_KinORfEj`CYU!!|}jBYP!!MOzfqGDO?@|E1BPS<_L6MiA{+!mo%$#2^*4o z9L15f2gCSw=kVh-YDQy3mezK`W-~nvc`20%J(2?p&V&5=2BnLsGcX?k-W?ACPE|6Z zEl&3d$I34^y;5MRY8~m;#fT^C6SW*Lb@O_!iL#_#8IPe64)gJ}9Bc zT8=^rBI{073QepY->+uQJ1Z%q24I3RuI3WMC9{pW@D%ai`e)>~UV}(L$p#Kd*Z?Mg zgqKzbP%8d+^%h=)$^^$6al|jvU4TG*e5WZe=1@Rg z3eL3-PsZ2*thbT9)De=u0Kg23#ZMwYBJmlae=8vB)tUBqleTV~y|gvZ+uO=MSmdBB z*KO_g-24n@<}2b)hjQQ8IFfuX4pGYI$!5m=xP#HKn#hYUH3LNgvX#k1&cF9_J+(<7 z{oSY~Zxgycrg-x$BPmL8)zgBW#gA9PRuAKku;-<=R@L?rlor+OY|s5EE}%Je5ulr) zdf5YacmKjf9+w*`kZriwv1n>^uomYpb;}DYXtphm3W8TpwGpVNt1{Glcxgt60scKzbz=m-G}UgRlnC$fX;m$e zJ8$IsT77KvchU?CwF`xaNGq}|umwP}i^FokhUehtH8N5mQ3sq}v; zkh=Q1j4T8@DZM3q8|>!44k~+BmM}XIT}u$YljtTW?%p7(&HBm70M-Q?sONV^ZU=j? zWZ?2R-RX58*Vom_@PEz~+Dmn?WLj!nl4cLF$UFUeCuG zMyPr5j&L+ZaQ^BqxCPi5Mwpxfk%i#=+rR-nKR>_wO>LNARsTz(vrZ<@h^u8Uil2ah zl3^`zL~U_t>2ILp$gmzg;n~g2P3F-w1)%dJub`p9e=$u87pU7b-4M@qgGjo< z-vp35a1|#2xf4M$2~bV60Gib<0Qm13(1-ox=_x2CCI$yHtP5TN?i)a7039F$fOzwJ z0GeRAaMXLrGK4wYMc0>VnY&B+I~11>i-CMwDpOTepq=b1+6#g83yrYRDq8m9bl&jh z_@^q|cp5r)-%}%qAGspn9JM9~1udU9*Obh$uq~bNBmNPwfBdSsImZO~gQZd=p8Hq8>fE{A# ze*D#|!EExm@s4l5hOJt(NJ>#D_S&>4;{7aFX*xZbx|&cqf1?HjQX^h>$#`|_@bZ#6 zGS-w34u?*v{Ji>r2+ETCxpQjC;I6N6_k8ZsaWH+T$p**w#t@zVb2m|bD&`!fx;_(| z$Xa(@;3~zrYL}e2zesn8$E!^&81>!Xd5fsM`vMdQB1l?*VY~4ay7o=?qMUUE%9!XW z;XoZY)MB;G@71eU=nql*(=k_Oek@{LPVjdJ!(VhsRqX)Kl%<$yf35jINltj*EFc~e zxUirBsAkKb`Z2kC!#Rc+GKIxl6Cl?4A!BX$q4Yn9Py@jQNOZ=OEjj6$sg&&JT)1`Ln zT1H&R+!})}JL2Vk8bo*Luw-LRj$XUQcf1<^v*cjtjDpyo``tv4e<)b4Y7C!TwQDoo zAjQg*B=x25+PBX3#W}3%@L8KB!Lg6)-UmoO$JvHu@6`+|_e^_M z_)SIWGh%1zFI#gj98wV3r}??{X(aUnKF46_-$<(e@jymlx`gl+yi@0QjEsQNcp@Ov zZnIxp4Z3Lnn$J&<0a=B6V0*o3mv%=A*S}d$s3p%>XF(4E3y}Sir$ucp_3Mh#mzXN@ zD7HuUzg`f#j+J!{ac*2nmk9Db{KdMlhl5i6(!D4K76V)Tt;$wMRwB% z487e~5cux-o2Sj3EHBe?xaHK=CGT4N8C#k*XAco^3t`#JfvDsniD@1o`utU;()kbE z(a@wSQ~^z?hb3mR`s#|!1WrArhosql`h0aRYq_`j>{i9J3vs$?eA44l80cE~T@T;B z7AMXMj&9ApkVfWvP$x6@s`Gd^BG{LpOvlBA?cioT9Mep3R7X20OpK5;vV=J{EQr4f zB$l1ugN~mpTkG(VlN>qoj~}37$Quc6Qi+=!+@IdVE5uv6}hzv)V+*AnNv7xuWCJ#Rc)H@OZ z6w4Wqr3I;90uL&DTQD>v2TzRvGi?QAe{YhSZ%AMl@{jEGUSj5AZyiXG^%4Zg%+4Ph;3|IDOb*e?V)kFVh#r`uhP0#X-lxgE$ojJxXwCo4K}<=8`uB=y6T zj{KtgLdpsUC4ZnYreEx2$)HI_f*2`_FE7x~~=*X9TGq7vNIV}I@WahaJ+V)etbw+v%+T9>4XQkE-1D{I? zij7vt`Y@cf`yl!2#^1pE5vmiQKQ6!MRNya?$JR+^ z&_5j@(pa{Lcip5ayN<<+N``?eI06`_;ews^v*PU+dG0yEYYBs2<$aRMq3tPd11) zqWFh5dI)~HJI6!vKjPB?gVP-kcZ5@e+@yumjkyONwlJ&AEwa}Y;zyd4=a!RuCCkE6 z0&xUVZV5hL46Rhby-?ji%y8*{Nq+QTv@oLs%8Ft@9c>wQxD4;vkvB1U4`|F2P~6RQ zs{-LX0vbNU>j+8fvkj@XRb~Jc{n!r#^|K8wY=FeINWWot(n|l~1g*~mne9^@s7M3WnoNFf@AeM z6{h=XSSVTd##{eU+S+l?(d9Yv!$dPt7xKaS;8&C+C82)CTnl|2ZXMpi0SMnrbAQgo zs8NQ84w+RpxB*CO%lAMPVR|GOW+f~$jg`T%0{Dg`d#G;}=NECz4bie9U#s{VpFd1g zRVmfmaz?fx!-^RXxYeYgON5-9K_ar|JQMbvdgMM#Rb~2`(ZStD=|#_Nt-!gK@&w;8 z)qYo^dL8SM-!Dz}C(xVya4AMkBg!$@b$KlD z`@hZ>Ua5VVPSAH+J8nK`y}qnE4AZ~MZ(K%_kxn(qaU8UkkTEB*4IO~Ub*#PSYtyW> zpzm(xen=d^6E@Y_&nSf0=J6e7C3u?hW!N7UyotAQ$5^13&U2{^>5<<93J#h-#N*9~ zcX+GPZU>(<+)x$RWt$ebrbiu#U_@)!6pbARB=yB5<<~y$)s#deIazd@)z$DvAMfSV zH>RGU@b8-05;>E<%Y}tm)|G6|$a`NU4Ia!Kv^SjH_6;VSo}Qa8NI6kEd~jynWRu16 zmW5W5?dKR)IH{YmQsiZ`jdg;oqF2aVj>1uyNN%*Go63B_xSA6s37v!utJ&p^Nh90w5K5g8)GC*#Hi)4rX+CWdM$I zf@h5J8RF{&5)V=dN5@&#j@4DG!gS-~pOGJ_9d!yUwiaiJ9SmA#Sbd-Q`DG>hhuGHP zi~!3T{>BFWiX6e$B-W&kUDVvAVEtL0jl@>~6i$;!D+$E-HbYddBk((ZjSPAPLiluu zllqnMUXiGe7RlM!V!R4zz{vV%=aXzggj6d>+e^QX{*W2f+)Vp!H$WA&ogta;&gm^5 z_FJ4V?BlXh7UpvS=VRzv@33WKe%;!|a-@X!ysvRSPyLe<;NlFpM&tcbkkF%i5sKa_7A?a^I|~*WD-@S1`bqZ)W5ZRVbxBGtXy_?YMjb{vHb?H z1hlk@|6+^-&_-NEQExtVXNWEbkGiS6#Yk#QAUJwHie06oUH{^pdj3hd#`Xc>s;{nG zN)UFK@XD^b^cfoy`R*ghs{`omXG9Kp4rA*iVt= zDj)hK?h`m@x4cYT`?Z2<8_2`rE2B!AP{q6X2eAn<$P?c)E?1M;Kc{f;`OW9QEdc+z zG5DFLS3^^N$C?B};vVly)CP15vGF#TgHaXl#0fNCF!hIZY^Ik(LPkPjkX}gqGQTSt zUES2c@|JKMAzCUqDF<$%2Sfb-`Bbo&eCSCTbM6pS4?3GKH(-f%bsc=l#8#o1A{jeN z4RRWFpcHTDZj7 z?~>d(J!2)=5v41QcMLo8qE_%!^cScBMyuhiLGc1NjznUfSD9}-M%S2hq84hwozKAg z%i5QWCG6v#%raNIgh7JLwu{cnuW+wz-+t3(YAt+JjV1xfu1WF@mOx5{7E)XV^nL$6 zA-JmAQj=Q<(oW)HGGMlxNpN)&ny6|No$|V} z-g^rO5F_4|k(0FBuh%ktv>wN=GCxaK4brG~<()YL_8=P@X{HM*BK_4*cQ%XvdA5L` zGPFP?)WG#Z^vCkN?C}~xjG4f0T$z4lrz#r5zpwy8YQmdWZK?@N482grS~DR&E(6to z9#VY18JQgo%&Q`%?lhsHHUZtlswstPw`*5xq4KmD`nRqk3Pye&KyJ=DncwSKYo%A@ zAkCTLGraHfL6?SF;bjbx?fZ;hi$@aZr+txDDGs(@kxO$u8w=PjVh#&eR;;ECPC42} z9EkbGe!M7beTp7KH*R!)V~uW{`2PC?^WnA2 z=qNC7R9Dkm3~lyw(88E7er?!3Oa#>DX$scgy|$Gta-?f8tWZOC$&v0; zxjTv1N!iah+@w(t|DNB8)^EZ$^~t(nrKyM1m}2(R=$^P9J?k%pVrB=kr{-R4c|%j6%u3JF(*HO{v~zj>w&~P$errWdTmHedktX(e;>xk^R4XHrPnhT}p{GTC zSNOJEX~r9MtskVQoFvz&FGiuE+IF=ApY;d(r&n`Ykd| zw4Z7`yFU7+AY#;eYLtknrUT%jxCWC(fV{W6>+1#$LWAxldOn7@mkVFTzexRL3}E1% zmV3COL~7nlDi(N|@C2WXsrsd?k4s5-;UoSpvF@p0?~`)xs|cgZW>t{!Ms^vE6{y6F+0W6OH6qWY{m9gy z7>aT+K5&`UQ0gDz!2PbIx7?0&nWc4gn`W9WylVJw+f8_aR<8LoaKLM7iAH@0;R9Ba zJsAYVr3g(y<<#L;W`qL%p8M4Y>)RtMH|h9G#fTa4^x|p^X4$)T$-8W!@_3zUJQME zKO#ECx8;JCb?IU@*P4)y$%3gZQ|c3sUUAz*~Wp(CgMit>G_%H zjFn~XTDnmNr!yz#c#|wy@4q_~4UF;-D*|OA#CB%s66I$)Kn}lybuMw{l!g7C)CA|b z*ZO}1i{07rA^TWs6{ME5#+_{p{ouQQDmTTu{NXb^Yw)$l0}*5uw~h zV#@BHO{j7kmHbR9Dw!K4LVOba59Aivm3=5ulc2Z5W%j3jgoWK49o~Js1Uybnx1=8) zi^R~znFvQc1pl-Qi~Qq6V6xQs${<}!Agl!v^cRBp^!h^yC+^OWnWGnUsTlgTGEe8{ zerQqT-UhW|QMo{Yp?V_YzLZ5Py5qceYkh}!eW9+B)7#;N6*79S$QMLSNKcnPpGBCX z5l+Lx6rRh}b{Q6v|F}=jkh=?2zjw9x%ewk^kk}-xD1v%kxx91B3Cmz(oZwG!6&Yy+ zr*_FAdS$RK2Mj+eYdo}vJ|T=YFCc6->km|udU#3bFyRWF8a#(56l z{5Vc{)14j4wD$Wh5_XPtyT6<8m?I*0hAW3-j?#`k2KPDWyJ`*7{P1cBt)s%Y)Dq3<+3ae56LB7TYg)x6I7i6#Lq~lparX2t%RV=>Erd zFYU(`6`uISbOR7uT--|y{B*bZj|-kQKZ6H_?{WE^G9ys&e-{4Cz)MY_Q=$e6BnH0W zBdv)O`t1@c>9#)oIW>axq7RS5OApP5&R6=!*VKud&i$_3Jd zbT`SSWNTkcXpD51bk?s*MW65aWhD75Tm`n%H<>88il*xM7-18rMQ)Tm6g+Pfi;Jjg z_3RRzyQ^Pzy-h~v?OYV#EbG=nUvJktqTs97X$znAOG%maXr%tEt>ek>+Q%DRo*N*#j&3B7Q3u{{=OJspSRDJR(wA=W&R+?vAZ{vQ*u1C za-2Ac06*;H`Cr!1#Mm0LHcU;%Deh+cJnKayGEE-TRIO$qNm4~8B_T7j*E$;NyV71R zYfH`x%W^kAD`(Ce3W0<+d`)RMpv$TB#Oy+D&PhCL%~wu0Q&Jb`kIPr7*vAq|OOar! zZFzu@%~GBSqZCpw7#sM%nYb;p?VIGX<(2X%N|Xj3xwOT&)pclAAuXa;9esUsmGB>k z#o!-u(BZItnk(g9cVt@t#qg29e9mKI32E|N=tK(4fs?AtS))ls05 zQ=YVOCp0C_pY7s7z~z?7(O{p;X*(f*-2D%c$^)tLAj~V7A3NQ8x$6RUa=!bxu9=_Q zu<`~MI-x~A)D#y`aXjlWd%D=@a-VthiFe$5t73fkVODAOcJm=$mf9oyU;r#s&VvUZ zv>zBxj8=$4H&4>V5$s%89tfO@-CU?QyVi7$B{(^L2}lm3p)+* zucqJ*ymH)pd2_)t35I?xsrQu!Sjet=!UTh|&IP zuWjn>MCL5iRzR(hr@pD43UOR}4vmWnIv?7RVLMsJWi6t6>}uS~@Vp=vCc9D>f8$=Yx?zp{sKeY& z8&$NFXxvo$mW~BJiX(JS2U-qfN#$y>TNoDR)7H+eU^c~yQVx_-FW!T-=R5Yl**cp( zI|J)Y^*xL{DF~n=N|B5_di9xYN723^@@!_q@G6v-tDS?Jmvzwr?4PGjy znLGYLVqZ$diSvGU>EQ16=QB%Q4S~&F+_$&mU*D(Y8EohrW-J%c`W;;?DfM-^$?DB% zu|cgf5(T`jt*aiD7ZL1+(WdWV5%uWJDtfaWooGyP5ug+#gI-K3UMk>~W#m#C6W*|0O$zQh=w%~MkV!+46cia9yI(yBGS z<-5{&rIk7rHK;u|cYPxw5VIY?%Bj-sU(1?wV;)KB${YUpjR#6C5Pr}DlArqps9qx= zRK_B(F`Gessluqfqp5x0dxRit?U+Htui{cKE;&zKg#>;_bnVA@TD6w|!)1}nyXePX zcni2NUt@A&DGy4(hNgx#oKav3~&w&|h=WNQRn4d*c?mSRnsU@!a zI!SOT9!)+p$Mvgyw2{Vxo$6u7ja&XjEp7RYwD*wPbk5AXHK-Sf0EN5197|!H#vqvK zIDWx?y79fQ_WZ%NHGEh;_CIGvtWbWhqWC!yyc8`Rhw6~bzgVLhd$g(I266TGWOSOPxeJTB1-@zT=I zo(GVOKi&%8w(2A96|4_j={1ochP9_h>pXB#dxUo{VF64kU zu*`(q8L+%eyt-&2o8%9H$t#vQyjJb{aBJo4ObzL39G_N-zkeu8T;WAqb|_4Wa&@cE z)y~us^62dT6qy4!r_@^)QNVmWEA2O@_vwel6R_dK@q3ciUvaU~l@t9n2sg3s`f8wj8ES;+f;L z$fY(nHVl{RAhn{Qk7G1++u=@)h0(B_G}P%of~<@AU~4NcX%*E;FvVOs7SQ_sdY( z&w0#mjbGB+P0sH*JJjvlu2$cUZRcj&$0tm0nmRsAYerppT;=e?Ix&3i;8WkyFyc)V zpMr)M?-V!Y6=X-F0^YOGXpAVEi_x|`m`$1Gi>3B6zaNNwRkE(23kLiI3EE`brf{?I%009VT>y+C^eyZI4^ z?9}YN*VQinX+pT+I>FT@-FSjQMk?2y5=#ROr!|WZ_$wAIX0Bp_2i9g=9lg~{?;$5h z9nVetTz@-}>u$j}wq8|CiUK(;M`*TcLkG&|8cDXac2~EdNB)e{jllz zQWjv%{>(Th4Kv()_&olw6RLY;bnQGh6ix&lBs+ z%pY&erb`+x^gYkMatc%mh|oqZK;HAE^8H@)vObh(7nx7Y%TY8L_~IJ;9tI>!*hQ9S zQgfTxqF0ZB7$UCZ%(WZKzfzFtq@fVcJ?Z%dSCUZ|XvK7{0ag}^a~)h1?|ua3)2>xVh9s=)6jw5KD#j06Ml zq{A@Y;_CC9e7ZSf;`}lMZYEE3Z~XK=T+o1zgKVqdd^TjV;?c@Uerg-sWDXmkNxOpE z#Q$mUJ-nLAy0CE^M^RCk8BhkL%qW5=5Cjn^A-17NQ$Pf1N(sG43lIW2hzx^t>5#}E zV1R)1o+ya4&`a4-t4{4v-f_^Is2SE z3O)ViFus3iU9W7ToYp+=s5kRiP<1d*rgnwbY?oo*Qhv8;UAP`f9Fnm^jBhdDE-4?V zsjsw1Ofa!OzBQ~KmGIk0XLFHO$F@S!$O%G$`PD=k1A~26vhfA@_pXh@>TSIP+V$#* zkrrDi`+WXNY1fkj3Bl~BU7LGA<9jDV9MA8j zrgD8@DWUxu4AyklZUHy69xyYjcd5vi%F3u`RD6d405g6E|K@3Te?1em+T|2!-R}a= zMky>VfqVuAyJh5^+ogTht&?OgvNcvneW9D}sp=MN`u^(0%|a=Q-ocD|=x5h>lNuBW ziDB8Z_OwqmQNuS*)pEu;oXYOyX7$CH#QvpEd^-u0cco}5Yt7ZR3?1-(CUv6w!wq?$ zzC_j^TU9oZ>y1)`k{v9~A|v2ZT-#p|%owX|?LnRbxUGfVwXAsowK zZ5ai<;>&pxA#+vs-Cg-%bvr&Yt>nFOJ>x9f1>&`nr_FK1T9wdHhmG8DI*R4}A>~Nv zqTeTlo3-lHRMzwj#TbW@m)zLdc}i-mjGfc?dZG7tfC9jq5RT@S=`5FlW7!1bb1&(v zORiC;W0owKVbu6jb`X05_Ko5Cb9D3q7)4569gyl086cSPx<^9&uAiC2u7%V^I6D0a zP7TQJ5rTA;!ojSI2aKTq;bP9G0IeeGoMA@X$CT?X8#nwAD(^D_1X|ze=81I&GuZgCil> zRFI7k&M7WyFF5fq^z$4z-hp6#@}wbVFawKx2?XDBs#xn((Lb%5X<-RJ-7E9Fj@;ZD z6D_8kmGcxoSz25ia$9fu&R+4IPX7o-pSO4e%S<)>S`*Q`r_OihmzbF7jLGRV>H~Ax zbMn$&Uj57RMK6WGaR#YD)!UEX9_BCv#dlV&Y!yjqJ-iyySek?-Pp8Q79>}CcirPbE z0W!MM)|t*_2x@#LBk`1=>D1|s<;C{iXu`=V<}#$K>-A?9$+B^PjJ`~nnHlQty%u>X z{6>g4ADNjBn#y~LFM|UwpT>opwjRpC!sC`~f}%STf%t$6yj(EX-NQ1~iO?K9oL8cg zzV=yPSMJaf2U9Cgnoj-ww3WLJ(;_nXmo#EZ8l7%PZo)FGs-Mo^IMWWnP~zKq7|dhl zwulAqJGD*=79|Ct1xQg#MiGnV_$M|?^I6ydqO)vJz+dUq{F@~et;t(AevM9xA4mv( z?XL*^qEQxHliP!fr^Lrz3yUm;bihyML#+-#FQfMHC3h424$uF)dtB+Ax=jA+Yu_#$ z7v2N?`=)@v3zzRR`54(f9;N?y|7)LR_v1a?M_+BR`^ioGe-Hl8INy-+KjaAf&pZBq z2_5%;gfHS7*;3yf!5)8OtD&W%L%yC_X(AC&tcjqk0@rJvYXH;0wQiENSn#IiSG=~| zB?1ZXJ~mHhJvaep-FMzssyDA5(+@5k>tiM9ug&q;8@>`h)7xs#upn?{jnuz zYdSY%nSXjkEFyC#@XIn9U&h9Be~wfywVcYlQ?Jx*Z0MUw|5fp<2Vz?T@mff~h zl+~R?9<${hB!(36rK3el2dP?6(8x*F1Ky&l!kv>|oKBSs7|B*^T;Ogm!Y>Q;TNrDH z%`UP{c{7g{Y{GiOh24kXoY7Kt#!zJcs(R!vu<1I@dh*U=w$$+NYyDXPd{J70!c>%P zT0EDu6aSD2Wv8hcq-gm%qyUm-EeBT&h;lexb;Z`JnR6%Xe!e%h zS_VcliRAGwUq%xpy3t||x!l$>=PmJbe?aLgn;|Bxn~o$6e;GqKyqb}qWoA_k#l{dS zN8fG09vIu!G18|(C#h3GHmJcFwFbWt((_}z61rn1B#i(i+zweJbb(oIUAgjps%d5a zI@$BZSUsdxiZA*{?LE-@xB2R5a4D57YtSHUOxt0rk2$UA!L`^gFv+2*2TwGhbU+a{ z0Zkm;I$AI`Kmum5gt`GyS-=?D#zxU=sBt>!VQ087W_7%V*l27*36 zB|^V=OBT45#g~VktC1t(>k`IorjDHqD1F1eb5IdhF67A>)z#S*%F5{b%*XraZBFJ( z;cXIkVKYCD&lQvN=rextPc*U%#y|?dRrO<^5Q|;OxsuW-`b-Tz`T+$n*L;zh=i145 z8a~%`gw*E0g`ea%G?He)!{(4HWbNM-wMH-O?7-G6Qtq7h!I#)%%oi1^<5`0fe;UJu zdY6ms`+zg(+(Eu=UcWk^yjLjY=#982=O=}6=H#+kS+ zi=S#EW|}uGQabFHzp}|_<459F$`Z+~A&L~`nA25a6&)uiKiso#IUbPdR5JIO4+(mH z4F;{euBDgY>|Ss>;6YzDTWT!VTtuuQ&U2RUd3NEU>Ge_Oxm>luf3vX!VB>`1y+4ZGJ1i8Q&_!{K`xXBMz;3`!pHo7YZ1?Odrg{DX zEJ1?b&}=D_&dXXlT;v1qtjhdNT`jzXN6R zU9u~a+9VRXio}H!@%dvT&j4&#+@+XcnAduV#Q!uj-~_UUmSun#eSgMFT%2QM)vtpJ zc-nxn{D9Lr2H4*1J)2FRN6Y+IWXbRAIqz$^UTR)}X4;PN{gnSGpu5=gK?{D%ziH!3 za#-?@hU0lBD1J9CRTIz;j@BYQ`3BNb!QY1X%eZnmWOInWGd8B`{yzu+P>^!$y#G3f zRs0&-7cRV9;x&K2PHDx0Y@jw&1TOE`b^QSo-+4F>qaOSYE#m>M4nmt7kYMYA6WFn@ zl+p;Gixb(Ws~Sm~zv5^9@G7qtYL@_F#jh|D_9doG!UIgSk$a+1q`4Or_N9X@)$>;X z@S8Goz=}G4m`LB)fG$bGYVKr?>mDtyHzd4k_F3))+691l(RfWK^HRjt^fOdMy|?L^ z+slolBGWV71Cw>TUv0bc6j&^y5hLQJwN7~4)n>Bo#ymv}2Yv2a{BeAhlnkrPOsv=r zkI}G)Fg+4*p=Aqt&ZW%N2Rdz<>vqe<*Lvv^8Y$ItbBb^>;Epvbt>qb(T%Lg}Pg-$x z)ffP*LhD>YIu@paJE;K#FJ%X{F92Gy>&*=)o+HRc-)$?eb%$CcdsCy6kEHTROW3<_ zZNf)KO`1dQ<@pa5lxhB5$OhNMP%{X-R(ep+S(RSYCc!t*nS3eW1(%Ld8e9o6_so{b zK&D8KNzdYkQ+|B#2VAs%o-=xbG6}q-hGCI%H$v?KC}-p2HNK7cNYNszvtma0X)WU6 z?4lyMMo=ufgvlz~O1h%O$H(BM^c^;TRpxmEsi!kP6 z;GX4jMwwMIU)J~J&3Gf=*Jl+&O`*jE{u9RGoKa6jxM`*eAqz|2P;0DxU3G>YIx>9H zA2?OM_^d_B;v?N#EuUtjIxnS=yD-tT+)$R$dosFq9z1hRY%FZXg|EPiyib5JG3dEF zHsi^(jT}hQq;EuIFDbFtbAgEPxIjnVS-!V{%m6ZCw+X(YmFZ)sr9uwfPDyVS%OLic zOqu7$->I)tstMOvA4)dC_)5oBj-h}!m^Cys3an@gfCkpM(BT0>dmD+@&udwlMyCsT zjyZS#c}y{Mz)%BV6fF@{!VVSC1``V-jb*qP`udD-KXfl1$n{_oIS6$e1h`DBVzoTy z2hZ60{<@me>!aF#uvtJBwb`)89948kxQADQ zBlhgWHs3|Kk)n)^wq|;H^js|0B5AdJa%-Y$?~p}i!Lj@?a^qr=1_F`2-cun<(SBD+ z9Xrz)G=9W7$a6b-jIh=5H9YXi%pwCkaR$)YwX>7&`u*)qK>X=iP1II#t$>Jm0Q;Ec z?r#B{05>$5QwW>7;7V7uF<1MtnbS$p{=`6W+xIqdD8l$9xL;5ODol+x7YT+G(}!qk zU-*FBUkcNi{CPXCu(5w9-P_ro*cqX?61)bE z`8urIFt}4ExyP-oO1C~!%XhgKT&go#wNK|b5*^*bn%;R_=g`vnHSZwo8dVqD@tBoc z@7soyrYYsRn8h%6){%2!_o^I!^J(O9r~G*wfcqiMLD~|hd1x->Dz?Xu~;ajMd4~}M! z(D?FYMvZ@BoUY<~#4#QlvPjvc{|&Lln!R5fRS4ef^ldtdo{#SVoY_b)rO0CzNJFT_ z+e7`D?jxkasT#)9shU6o%jxVT<#kWrR;|V2l)-ULml4u}5n&5%iRtAh05Q1;o!uMm zQHS^*@@65BV#?fe3ja1u@!ioIZ4$Ny#WCq1z09cd)_>GS07$k5Y<9?VY<^|4L3v%l z_#cF?gL9XmC97^LOK7-jjV%~Q>L2AIEh_YsV5rx$DwX)f2E_U zM1U&-Yygm96JTG8fDn-d_3DQ71}AKcYB7*^Aa_I(aiMs$Ox&PjNvwHs$`l(r{|#(; zH>(aPjt;IBzG50#8-1e%wtVW<@f~?~WJ%B2LAXsK&a_xM8G#wy>Ttc_eXB8-ADIA? z4=A$8C{QfCHh3;cwKbJjSc26_)0&; zBA)=&U-6Z%HBN001B_FTfBIknuM?Lv<^bCxxa#UH!mSk5{y{}e8jxC3jEL_Ffc70I zm<@aFP9OfpNdPS50Eq2p4K^G-zFpMXo5c_D_cHiw24u1`g_aR|a^&1sEI2yt6Zk62 ze#t+wiPr;@TxV5ODM5is_CA6rdqO|0c!xcBue|_ho!#19+C7<}koV z_f2U=#Y+%re7Egq1ugWm&H#KoS5t6O5xZbT)Hie|35P;Y#nzt9*&A@jgI z*T9SQz{Vos!Y;b+BX{QbxqlZM3RYOb$=-Qr&RqnUG6+0vjM8;XwStE%+!aZkadAl0 zC>X2HK;Hw^9OjFmZ17(rW?B51|Nk6sW`BM2_1|_c)jSgb`ip-bgDU?$YzI*Kzi$Z$ zC<2t?KcD_Dd{E&RCLNq!%L-SPZgKV2;dyyuWA$}>Kj8R4&oWeRr47=(tLO)DV0ECo#?rinVb znIgdS*4o%gcw>Y&Xyi^$9ZniATd$dSW3|{0|F-o2u~Pys;vuMV(bj%{qoUCpY4=6c`+&SUk8gwBMgi|{Gd;0BdcQGQ*{>iel z66K&1Q&gww*OUDUhV)ML_m;vF@!9yl0^H6v<8Y8P&%?^F$gpL0cKI%Y4V2geeH3c8 zOzkZ)^~N%!k*}P2>uKHlR+=w4uRkUAw)FIPO$?4S(E5vfch2UN^KQ*-l@LZa@SJLP zN*sY{;qU>qW|dM-6P5m1|BK4`foQnku&?a(nEw)Kxz2??Sl1{HvK8c8q7|!B7;|Yc zh0`XdYtH5Rm53M|LX3ZoH46i+H&)P73q^|}^1sQKdlJ}aALfG<-17!bKq4-;+H4de zU(!vF&S#K6D3h=MK9+gb6^@3OO5UsrH^<)LT&*k5reD44`HE8`#5(2OtNr*lePig5 zMxCnkd7bq9Ftg213C|8gB9>n4;$D*eo(**Faph)8>IuS1FDf~Y-UD-FjI6;}M6fGzXY&qidTx8|-Q5jn z;35=?uG=+tvE`5Mp+i+kME zMPkf#E~nwo7L8i`j7guNul6A6gw%x`mCt>R62IW{sQEq4uN0$24Li<*G*Jq!i;Gfy zB4o_Prs2H15NiW=$e9IcT6aG#QU#7v&)lPjAL-{Sc$nTni}l!mG|Sb>bTp&7Ql&w5 zGedx@O^AeUX#wu1mBZU`pK*aY>#jeMkJ)f#Rm07)^#6o`We0U#vmO{rZF5D&cN&XT z!)J+H8N!5BNzBtKK+~#)9C-C|wQ+>-RYQWAj#XC63f0&hVH#j+{&gflKyx^L9f;ma z{x!MnsjE-TtjH)w)$_h0Y0r!ly|hen67HB5YO9Fr(y09tL3cG3LKNU!KXWP1CmGF< zCbcMd#Pj4R93B+;@bc+xTw14ertL~OXT&^|VYq$5uH}U>no|=ePKt}3onWZdbyy}^ zMtWcGhD%Ijy`>ukdn$!9Vh=|&b>I3)CTm=Krlm3}%>r})d|fZ=s&P4Q1?@!|J^%vI zdy60lS-8W`-7^k5DmVq+SvU@Rrendt#IkBJv7WMY9kVI)=CHAaikS~y_D~_C!jtCy zt=U|MAB(@}8x>A4l8&ElE+4gZZQHG^3eL#ZHaR)bcSCI3h(~odrT*uPnb4merXMXT>xZh zOn-ULK&`vb={hj8Opp{Wms>gqog_-Z22@m4Gv#bQeYW`2c*}?vCbCDO;u}^{cfsh{*6QObxDqB9C~q77^rhPQTT zyfBH)wm4U?v^_gVKLRqf#$MQavZ;FAO)=}|zE4&^d5+h}*P?<7JB0XVl$@$xZAR|pyo+u5=QFmSzTj9Kl|<%}i;}ozm5oQj z{!W%Z-QVvfCvqB?43$w$2g-qbRZUBZZOe_MGA0OQ#>0t0pZ7=8RVNNuh#D4(Kb@qa zQLhRuO-kJz2P=x0Eg9nCIhc1;$k3REkOwrx-y#}2s<=j-;w$cdGX zAebH0*vi9^FxUpy?<_EZZ?N#miYk&38S(&e!Lu*S?XCx8)$tO`F$I{7jTcyVE9vy; zjvgA`@(T|4HU-Mj$|5dCIgkcz)qiW~dPX^Tq&6yT={58r;vsFnV8DZ?YK`1A?h2_I zw2gu!t@RQtOh-YykL4s$Vr=LzRQ8;>#s~dVVt*R@4*ngXGR_KLIf<5*=rXN2AlxKn-}=!`7zfT-n~bd%}DoIoNnZQeZ-#S$I>n zKs>rkk*Usl$uBkyI(aTFQ0=8^UfKL-i(eXxGl%UmLZ^oELKz~7E?kutV}`fwO-h_(9itI?kY~DHFTU?FU9nVTzFN!Pb+gVy@%a zTAAoXo#eLz6F1uw)U-@P68}|^*myz$A5Zb{2P#s+loPpk&M;-7346yk(&Va{`SJ4Q zO>V)rq(b<%ID6!@L3!N2uCH5)Iq}RAwRfxnTyB23nmDRGbBdY# zT-Zc*<`8S6*tu9xvamaQXRX|e*WCTtKkU+C)*=fE(7l%Vp_ym7nJr#A5{EG62z1I2 z`bgMvT%Y$psGInj7f%3ybXRC8ymgb;1VvhyHcnZ+rrpaiOYL;O-i(%1D4w{y)o=A8A2dA4UOj<(8YvoI?Z&6wyb5};KNV#WwZ`?g#5H>sPtIk z9l2%p2jt<1fHi#1@XO3nLtw4vibtI&#s;C{aa`+P?75H4%bM3?Wwz-dX89iA} zN!s4T3_%k_8=**p&X+~+0p-e}9(z4tVA(WY0ZfUVMd(77-%WLH^zW>S8e33Wx4Z^78-9SYWX$%-F`0TKJxQ>ys4qPw3q#$vj|-&KHWK<{Fm?8n4tj zEHxr1xXiZy(~XqC;t%tHI>Giz#lx2s8vsmjdu6AasuxNpRbP9o-6gm}P_;Pb+cJ)R zSOE=Nwl0R1-z3t13T%H}dpGAfN9`?LQJ-VL*qJ4Dz^g=@wGB1*~+FE2!;@~C38Ra1BN)DhuwocQRxFeF(L<^6rGXL~3W z$0)4-fZ{Txjp#ij29LY30`lskffHR{6jv^wb#hmMg%*k4Tj9ZytviO-&&NyVW|L(* z%u@epyaYL*@s9518))D$^Lu1`Dpg!w8fp7MNpytF*V@NJP|wU=!ID+JJa9~yYsU)N z;C{~X;`q(ouJt$vIbZBwhNNxRIs5S*uW+tih$bXbx*_8FroVRIPy`C?&A_cjVz(yZ z_$-mo8j^hNLI-?+oER?HYb9bBD^kNZ})Z1a*}Wp62tqB z`)zc-6 zE)PKUr-RQ@ozO^q%MHd$oBq^&S62lavbR`L#&il8U6}M3S5DD$a67kgIB#{{>KuUl zpcZ7?_VzHYJS3Lw3$C35%BV`!5n$QQz)RoA-FmE+Kw!x|jng3Y1VcNAo_ojgek6c3G<#BYQQJvmO|JX*ZTCK61s?9C(MLf?$MMR*S7Y5U(c$dQS-m>@6_3an*t? zc|;)K>h2J@)d3(uX%1U$gu{ISz7oiE`G~VE6jBrrdNd*Ir^ZBqQ|&+(H3_~Sp6|gx z_Z*klRpkByzfTvh2%>eiZy-0hZfm~n<2+L*17M|9z00!RV(5JVym+nj$8)kz*BP!{ zUNCJ?tnG5b+-8Q|eJ7FF`X4X;+0&%TP=hKMeDxK!oPU|3G zv!!|gcY8ZVtJbY=&xxLmz2VCv6_>=-33nSEXU~q4zS=dp`$cMz){z^*)}>ORQWOC?tG?X6tT?iw zgOA29@MbB{R2&xc@U!>HrU;EcdG#bGsUi~_jj4jt-`Dr{oh!DFMVLtl$6K5{q;8FG z%f(dGt?vCy7W!Ij+*Zak9;sF}SrVUA?!I3w+2l7%Ya(=f;u*$@EqVb4eEyOpD4)Fc z?+++-u1}c%{=k}r3HSWZt2ydc=)d2il!I9>{`-UMz5o9Y{{LC}HyZx0(9o&$q3NHV zPIYs4UlAbs&)edLF==gv$tWm>l;s7oM)kcLCYApak1sXDSTCvgu{3&c_Z94rb6whMNtfi|-{9|L1Kz(kc?u`9o7vC3llu zL|R*0dA z#Otv5=60S6gZXH&uG>mc^)f&Ezju&?+(GBOo!ik;jw*93os=;C;!vKl+b_Qx|L40% ztu?b>y}BT9_IHPYIK(mG-&yF<^ChUs$Hu`iKi*%1G5(1=iIx^WKG+xyr{r7a`0u3} z;8Lo{rS^Y3n|GazJ2525FDZ%0O8C!MQgM;7VER0|`y{b{e{H&(AxwIX z^V9#ljkTKqriG20J6Hd7J9c?vgZjX=Z^vQo3qix_(aIn{yMagYLSA*XIvN_bYXlm7Z;6_lM{w$>AhrJ(<{Z^@Nthkk&hY}9nDEOS$(!ZIS6x|lk8@ZV2Ylo zFPJh4gV=jN^*4J`xrOnQYe0OeQr=?oE3~7%67M3Tj__f3-Z;9NQ)I>W#7SNi_$;_C zFE4-7wr+5ov_16DD{0tI2&dqAAjgiz+`}5`CV!zEe}QtD30u_9P-DZ~fOzKUGW_jO zfbPZ>)Vs8%CVhGSEnh6ZPp%z@jU}@k5i7L|$%8kV{&(!BBcP{)Ejf1Ku{Ks!zodb*C&y2zP^?Ps{ld(W-N_zRxT z+l5abc(adEI0yRr<2nY|JT67w?EG;3yE*4)riq$cS;nDHZQ;fYcoj%(FJZPS1mIDR z95kJIIyyKk{(f)WSU5}Se{+z-adTQ&V5f)O?a!}(=w8#i=2e3%Zy%dY)Hyy|BK+$!_11I?!bjrN96w({ipooK5fZjuhUj1{KOY|&1$^`e*rIZB za&{C8i6uOa%TZMBt8DW-t`qJX4boXkv7DD%S))3QD{N;a)_#;rM(}S3Hg1Jk>+IWJ z&`Hp;!H~WCm2XIU*Km84sUOEjL7YqFN7%*JW#suP6ETuhl4-(ug!!w(`;vXC^$J!@ zkGN^Ya#e4Jsu25Ts9wxC#=i8+ELsF#jQVU;#Gk#|kR+V^R&G_vk)B1wYtp~o=I>^g zD`w3<%q+Py6~q~J;Vlc?N7iqjCNxf>?WrQNtC8_0aodWBii#%iITtq`_F7x)Ef3E& zW-HJyR*vcou1|d28!quuy-Lg&7ghVcs_5(2CllUhCr9hfO$Cr*qz|UNg{Yrg7|cye z6MoNS9b;*KuYLDdeXA^fNLz*7yfl+`m29VR+2mmDZDIO(nO9izkNnC?p3NAHOg``Xji_G+%hCt{_>XgXduEX6Czgg`Dk&{?qQ)$trGde7ya_yN6HgWRuY7~Pcu)kQ46Ny z`zCwd7nmeE_c26P6sPsM_ z9!pjU4{_ZLOt>qV=F^UT)#x=w=g#W^8$E0w6`s>~Y8u2LMHs~P$UAMS4^xpMWk>M?(4sK9K)@V?kVM!(3f@3SLVRH4hSbGMx}1p@B-i%U5vBTUsl)1MdDns)sz zciDPcq}QMoA#_@^-f*C&>wU7Pyj>0-bEgY0v&E<6)hDw+Ruyaxoo&gB{vJG7r2Zj_ zbfVWu#AIk{sWHjwX+o0=Ft96sckewVQDl7+NE*!NPspZhJFfCG$j4`_(f8UVtRRhD zolg&m3c_s*2j1NLE%xh`03mUxRhX8^OY<*7i}wBmewW)x`;ux)swi2+SbGL+e)W84 z<_KjML4$#yNW>x2K#qYmgz}w}oqcD*bs=dsoScekq{RE=`Me#Ez-BYrf~AdTt(KNn zg-JK@$!37i&^38}VG`I5*y#gueEKIP5LH{9uDzLxax$&1s@~x%!E{8T#esm z!>`OeXf$%w?t}_@J53u9pd(|AYr&+=j^8*&O5>#WnI{xEub=J1uok;ZgJZS!Ilp`2 z?Z5sWd6zZPo!-!(Yu$L5{Un(`&voaw+)^Jpjcala0J0xdMY4C4Hi+k4nA`de80F7NkjUKk8np@yL===%~3 z7OF5TB{@$jlK9tcwUc+Oq5V2;to!&8DP@p4bd|M;6yJ3kJGA0(EzZa4k9^!{lp(nw z`}+T_g8h1`TAv$vlWR3kXyZ8zHB%DDn}dvw;pwy)47&nVEUQYpmOath$;GNF4yB(C zm1RqDzwg*BvsA1Ydwn(OD_6_wf5STbhBf+$hV)(8tamYFGuhudOOGvxaH>qgeXk6t zJzG0ASX3CF>H4&X2jkCW`4ng#(>=fYcc<@u(vy{{aVv7?&;?gs*X>NZ+MnVq@pH$G zlkOV==Qa6Y!r5fJikFwy0YT5S)Q4Yq^kd=9#x1LtwmPUsp>E|sVmwUuVty&}>_axj z^2;6E^Sq6Lm27v&{>iUC=aon5X}$W|0RES~i>meX3b`(Zm3KwC%lfX0_}wU#R-z9J z7wTA%6@@_J%wpusvUnxJDf@V6UEAU@3GGc$CT^R;T&Z%)Fg3>SYC|7t)EX47lCU1z zoFGxZ{F?P?!rtEAl6uoobPS7r@z<|kZ9C?6T-ScqD#w`U4iU;hsd8JdUD*9@6tR^3 z-s;=Q!Bhz#%Dw&lWxpGG{m300Z!~%TJVS+a%r394Mj4Xudi>d>YZ5|T8}08;?S0P` zG5(n*xT;>PPaLU0j`*gnZm%$}rYvXaQ)dG!TKWt&g_{`kPt&4(kZY=(Bmh|s} zWtQ5uzlBs&6pk=~ z%a*wcBk|tx)S2GAoo0c0iJFW|cg<|qd|6#x-O$ibW_EV=70Qna^kx8X-F62g_oiRt zEdw)B)Yg6vAS2mxUsGV~^EItHhrEZ@lZ8C?U-htBSg|=dIC4u%6*n4>*G(GaQP+&d ztH#F0mIZKn9wa)e$I?Xk2YYcEZ#ug5Q%>NzbrGe1NL$5V_?U5UKUu{VO-}8r0hy9$ zI@xWN`=kjLEh1flvtAYaN-7OdxWX;JlyW%fJ9gjr&KCb)O28I|aryGzazP10ysX9A zSmnZtM0Mua;faYN2VQ|RYb!s)T;-f6OPzO9RJ^^L1o!gf^J;4~m4>k0&CDJ*G&GFW z*k&l@4e>-6X~rn!MFF^TGPlM@p=5)CZ{$B~9_+jzpJP}2np)HzQeMJ4uQBa7L=tELX7}h|%2Ca$qEHW! zu_Bc)>B;jSWhM(RWY_A7fq7LrEGcQmIJV4U2&V#_ZP@wBM@B~WZELn8`tj{3_>#R- z>A0eXAa48LJv`PVhT~N*SlC2#O_C^-jrk{qu2{6B#RwmNWghvv_Qg+dU6#qWRp>7> zxTkeRKceGO$s^;|`T9UQ90I0dD6t9>(Qgcy9~D`$ud`mfE^5!riZh~D!y!sMI6BzCtx05=h9tlg>&nE@n>Rb(AhDDysXP@cb*!$PPaa4$i%3X*m};?eVI4 z?r?~l-F{KLr3~tmT(v@tG&-3Wgg*@9aQ(DtG17?1YHycF;&-+Cv~d;cIfc+0Hw>L5 zvd#Ro*9Gr*)H#xPN4qGj z>bEgPC8uWBLk+tZ%538#SBNCm$NeeT$IgW&n_5WtQnflGEw3+g^79uG-B(NG3eB~p zkj!@dRf)~mtt2TKAh;9XXExR7>9&*=Tj73S#rg1|#bmu}9c zcg$|{Tf=~xvvxf7YjvJfS*F zh5q_nU2$Y*CSj16?(bJW{Qjo`WWpu{&J~%7=l!SE;>8R81&vl#W6cS_7AGGzEu$pr`}u_Q^l>c>|rzh+Wg5M!UiFcz&y3eO~W8*>TTRJB%c0< zlHUMS1Y-ihVCoF5^|hkcULlY+4xn>}m@|18~hjUl`SM zFIume#VyjVej*?sz-u=bnCx|AelmAgXyATHeL5oXAX|$+X5+YPVaLMEEH3H*$KWY8 zv6dvI&7^L9@Qr1$rh?g%;_w62>XYIle@~+Bfp5~4&1ot@WK#Or-5gPJ+7{2tBtQAr z#t&pg6S9e3xtnhn$Twgo9i(xcS10HbtBT9L=kga~gZ^10YADmGBL;2|Pp~{g*>dma zT$3kV7bqKczsVdGG#wSN%^H=)5i@EaBzWqe&-EwVkGj66>eT6eHJucm(BBV84!v}h z*sR6pl2)Zf^zYvHIdH>EP(g$?N;Bz0>4`&@7Z+>(a^Xz-Kx(J}cyi^y|H2)#g$X}k zmdO{aZ@=IkQ6C68&CL-_<0pG~y`Y;>_r)T9IZkiy_k__^GrjVRLruw@gpAFbL?IXb zYmDfvB*(>i>X*sHI-ar>0nzA=VN!k&UwBS;|0#JPO`mgwN&Ml0N{~FQ>bE2+D=Kn9 z_vsTjNCaf}l`Q4)?FtY_8urJYGsJc;@LPeT)6LRUsIKQKE)&Zv@LUS?vFsNQ3uNzP z3>T)M$%#VJeru8K&U)IDw8<{p>nhZ6Ct|?q$Inq zrlZ;B`B21?l9GbbB{ z&DhFLqDi?ABa8j;I*xVcA+icoaTPc5^H(vj?ojZONOOOy{~b4`oz4(&iK*)MGm6T@ z(h8+pYFDY!EfAFog)$`v$Yh`ygTzYZ^U?gA97(8Ah z(s$lLw#XKQPK5b9OY^RGf15cj4%`>C9c%zL)dp z^IbuZU;4N9UBC8dwjY^haZ(joHXnaGQH8$-&J{-(7|vko|op&sp-R ze$G)H`<5(x3=E9j0{s)|orS);p-?{v`1N_?3&dJPt%t_bKCO`EKTZ_dk_0WVV45awdvCs4Ouw*uK0fC`86 z`cK=A5r%teC3-~-?gtRl02f?;mTtLtWGe1KB}=udrC=g``GVw6x>z? zB#AY+R~I*(x-se1|0$bdd3p8Ug7L2oR{VK~89PgaN5NTNTvGny^18iaVRbs>T2XO* zI(3E^sC|vW(Lw5basES5WkZuQxfz_<`-K_dYLfQvDLFsO(LK$0B^udpsC4On)U>{j zQMXw&i$9-dA{)+|p>cQo4FQ4Kiky&Ow<(?!a?yM}6 zpQhihDFOuCAGa=m3bXUO7m`XnK_;qTGc1Q4=TUvXmS|v0m-j{b%%*w4rfnNOChDyaQUX&>*6E zSpFyz2b=*E7zu!Oa%&{J*8#p{){wejV7FzByT^L%D<2CcKuYz4C3+WbyD?Rm;geP` zN7pQ^O?;+u4uY6_oLt|R%^cfR_o%c3{=tED+%2DgNca-4N0}#Rl^F+7d29-M9(hQ2AWE#UTN$G%6zUYXi9kX{u>T*bR=7WUk0L`}4E>?RR=RIsEBv*sKwd-A!O zy_bw(O6s+NATH45**!n9K~k9GpH0J) z-l@M~2?+^z=4((de`Kus^G;G=NvfS!lciFb=kUOa;aA+Q(|H1##u6rBYi)x{ru$Ki`s_~!(yrkN z&j6gDw{IKLmagZvL?>|Y)Bfn^f?y8h)+e7{TtKOpmys`P=vRDJT63z`+EOU=9o}qF z&m*+Bb(KjoJ8eYbe!i1gfj=Hocv)DL5-m=a934fB<~h!smX;*3y<`Rjf313|*nzj` z)A^UeJy$sI7E`MS`1MczrS76Fqf*L>$P^OFngkNRhyD2 z`I@qONJh5tb^gqm>_}VD&Ny-J08IwWi$qwLYKse?#~^k~@f_G4Fr!d|8UIl%?Cr~A z7&Yw_OV-xbRMpjE5lj;v9)2(3=1aGmp*23Y34^3+@yY$uR2Z^U7&xz#U$n{d4+yCA zJa#g9K#GVPNV6np%=He zjO>zcp2{bc2d4Qqtr!T{O_VlY=Kn7Y+H0cfaq(IkvYE1zSL%?0b3LL1;kJ6aEAQXG zN66XA;y?x{=M7WL}e}as41`4uGr8l8q^ue6*|<{<)?+gVxPR_tamOS7w$UaLe05M>sE7s= z(MCW#UP||lG0{YbES2Z3A}}l^sP`zMux3?X=)EuBh89PwKh6WWk-V1qt0Ly9(=ha+ z4pDJQcilZacaVmO?x$_j>Ca22#?`6_gQV)dz@KdXI6f+iZf8d8!QE^+BnsaFad|II z$H@6P1OH-;M)<7R)=Zm)wRMg)Q8rGK^95852XuY_p|dpoEz@(ICptMyIjda3CwJ!mt$sNbGW?_d-=w)$-}_#wc);v&FU>`a^ex4yAwt*IJ`BV?R2dbIlks za&nNhbzb?<4B6ZpIu??YXmo)Kp^25bOfXu> z*8x0oRZ3T6^5W9`#Z>kTN=FFqKo@Q|sJUVmiP6~XygVsr37o5yNVC<#(o&#c`6jk# z!=ITDSp2$Q{^Z8vv8Qh{3`w*aJ!)YfdtLWS%m5|=lj)sr#6hv63_)OI*C3G=rPB{^ z|Cw9sAg?LuexFxh@xK1PYN4;{NkBr49MmE{cjL)Df+&8vTEKYG_RJYTVB`A$7pj{Pu6#z#%G&b z%(jOeO&&Dn0J3|}da*_tUjl_<75yWe3-T9j&VAl*+9PkN)H{xJ_HbRhVkHVFv2GCX zYh-h9&6+7{tE_!6ej;HKxRHp_IZbbA7N7TUT4i$FgLoF@-9Af^@!vo8qyRMJbVztv-IN-ith75pKGnga)9B%6wXYu;V z%3zvk002Oad#VJSL1H41P)9>p8goIJS^Ubkkyv4bmWv0M&3y+f3RH=KB_s5RbKa9#<55Lp4w9fF@GFjM1nSYRo z(UfkJr4#I5NYi0nnZ5u$uUP0XudNMlZhp|x)*k-(Q|G^#E!GO@^8;-Vgsx}G@asHi z{{rwsK*EFgo=XvkCVMh#BlL6AE6erPD1OnZGf#LwfuO$F(hO?l*!n)VEIxu)xiaj69hGbAG{ zpu_1)5J!xNe>EIgN>Us3JK>-o#V~0*so5_B(L{RrOiWBb3l{jpH;&!@Zgo^zPYLQe zPdFl=@!r${QchJFh$f&}1I=tBy}_|Dh7McM5Q+TLLZ$LIslcI8-E?B<=wD_@|0!J@KQ^B9}ON#B7jl&hW1Di=%FqQr>^N^31)6 z!U_?AU`BE-EB=+k^>r%{@MZ7VPku-(D3FmCJj@&^)-8a}AJP;oX*#W&beY8=3K5T% z&MNnkzxz%qKKtIN<6WjuZl~3_#+{@M=&DOa>bd;7#H3TBP(A6kVnR)hXkw^GNw*2F zSbqN?oGmpweP8$oj$`_is`FI543jE{3WX)3uC|r=j11GT8^74A*7Pb!4|h}xoIXT_ zl1sNS{&+Wt77o?`pIL6LdY96%@p0&po!91n)(8r~aL~284jq)vxfvO=g$wTP?j|Jd zn%!KU{TtqA?hPmV|_7wPPF z&2Pt@0DHY1ipstKX=^CRMDxa9Bb-4N>?{O&DAaxA%6H?A--%+;KT?v3x!2n}bn&ue z$O3Fv!abMA?LBWX2J>oMrHJsZwSh^anM00_FzCM&o4I!&LvsGO5eSsA<}+^@5M3UZ zYOMMU2ZV)%K}?|OVU)%Q-|)(U5T zLZ9>KozUUCZr+D4gKh%X>(TO}0ikecLR-<o3Y_6uEQ$io>Em)PG#% zeB0zHCu$+BsRcmaP#cgymbhg&ua;3)W`2w4Ei9@?wiO=%Dg-O0>VeM)v{j;rj^VK} z-gT1hGGon=OR)-L9}HhNLQ{5GQt0Td7hwLSXm!1T*$AOx7VpFEqfa*)Q=x2?>nZd7 zo<}EuhAq^rAW*`8l!u?h_jyRbZW*P6@MuE@t+RJ7%KoEe3=in3cevf>lm!&)kNx$D0?*@pbMPA= zYP-i&tRaa}jDYNILSUy1*RdA(pX8}TnrI&F<_Hx*WJAP)s;T$wpz%OJ;CQvX?(p~f z4jfvL3-QruyLojPM;-UR&_!Z`!H~qhD`esYtvXH*W(9fTR@2%?0jeCC9+M6U~1K8^jXrF9wM}~v6Mvs=&oASr4 zn{*9HEZ}at=IxHwti21A@;KI?-;WOVp&@a0&AkdHtD}+X#w^H0&ON8lUpd*+KdVHb z=0FF!jVpAYQ=k0P#{g(|NV`agp2nfE>A35_>9QD+Px%DL1=`1kqIqP3Q4B4<1(dR_ z3cQBEwbdGUmd$KAs(&c*8iuRzb9|O-qnr&caDtAX?6hk#$n=PuJTfw3`=03HyD)^a z-q_gu)%rkAIfR%=iJvNVmYY_9!h)Dd>vk(EVxVEg?#nm$Uimy0DF|jD(9+5X08s+2 z0Gb$5;dh+v1yf=-j=`jn&OrN>NUSG`PaTm1L0h}y!H9YnfB?8m&}=%wDFKjr(A!Z7 z<6GojUvz28ne`;1+;E1hGu)Y&^U5dZDUV7gPC6A{v;olZ+nuG@y`5sixRgZ$gfeSP zPbzwpeyV&5B9p#58#7atCXPN^pb6a?fQMjSt!gV+{p?GKXvVDf{CNSwBwYB5 z5h)L96BrUG*-b${v#_!n0SgibOh$WqJ6oT=`&y;j^sCDby_};6CX7sf^DB&NQUR1e zC@^0SKOTbF4Lo6x2(IDMN@qnPX*H2Z%)!ZNIW2%n=|Ozr;`n9O&hv$%=uiZC{@ap6 zL(T(Q-!u*#-27Lf*ZC6{ogM9(m94(34-~2LqC=gBa&d}2s__8lUJ?f+DP?y~n?+c? zk{@ckY-3Y5e~EQ7@$9R<;Y~#Qk3*u<7$hF0Je6~_{m36HA9} z`^h1Q62*Y%!3TAhV@fG6)B7mLTS;AgH16d2Na27eo`8c?x4?xs{_|=Nzy_=iB!hpR zKiu@lv;IEVnW)|1%FBr_K*jiHcs}~mTa%bBJ$h>&8Ad6kpKKgWJlU6+oK%+HI98;# zDOROvt>Lpr2ggf)#-^j#$87E=K?fJ2I2zzf{ z_D%)Dh2$~8ers4tkk>L`E2#tg1BIDn#{(>H;Ms7T@;q1qZ3y5HG(jxP%@vJ|W_i51 zMq@N|K+6ZE>*(s&Xqt<0hv)0Y*v-2_POJV7nr0uX)02gTuqcmoA!j?(PpP(r#HcY0 z=TrPNb7xC?Z6f`nqG-R6U1{wD%}Q=Vo8nKlsL=P)yo!r&LgP82i|fYv_;g5R2UTvp z%{|~??MAw<)8CBCHBHKY*b9P!h`1sIjutbF2n%D;|;=I#S zFHaC58mBilpO)rYd#-3dyF`FgNkp#k!8GuvLGtqhA=T*uTy~RP*n{a5MP zvm9J1{#@8f^3vYfTvHy(l$4Z6$G&fzC0&DYnfh#t+HrSrfbICot(Wo0wzknTq@V9@ zbi?r2!>(J-!@$eI;NQb`14V{*7$-}bL{&iLV(ksZc^Yv~$^@mDbJe&u-eR-=MZrB2 z@nPIjdY8wavD+*~W282bLV?=*%^hB4HIYyKclt6I8x~9g2p|K4VRaCZ0KxZaA5I&H zDrSW6LtR2rA~cutoawPhp$!KYhCI)yfiA!-DilZokZivKner{h}G`*E6zfZ8FwtwcwG=W zs|8%(Fet~>S=Dj&=i3gy=K|l=T-W`u zJzJBZJ%i}zUolA}s`S8B*VXj>v+%&Sbdg-lZ<9o`psZy}y>>NTLy6u@N_$Y(*5k?+ z@A1xO@6@AxZQJ38*1H8zQfM$h)+$ECMkJgJEWpn(ZuLtjUg&gIXcvqMVL#;YFZ8_l-)OyI6;GUBNTn|o+y~cL z=e8S<{5|Hk8{GoZJKBOvg2|aO=8n?3hL4F@-mLiD(EUXt<$sfoLfQWPnuXu%44(Mh zlvXIG(8wnZiP4be_9q-h`G^D@#rN#s)~JBe2o;9cZ8sNqge1u;^A>Pcyv&Q0&Z>ZZ zFo-V>yq*Ik)t1`Y)mEyE#LCLbgFGGQy)bada+*$oGK6{SC22TPMn2n8fFDw46OTiv zKkiMM_jl#94<)A_6}|JG^D>IB7qz}jAEhx^(Tu8BOkH)nqS=bs9W|ElqSw4^cw`RR zM@6;0;lE8NOa@~RJCU|@A}Rl8di%JbJ8qK~lsh@(K(v7YsW7OX+hjmTZQccStbT5k z%s&m%%}%&0z>?k7^1kpNqmz@xC7x@~(FvNdB@wPqD1X~wEkLlaSoy;=zK8FG( zxKpCL-O1?1gj;O})WKeJ6scWgOj2a_hG8;`DZ^pJgF>_@Y`FR6tl5)yMLeY1mSI(8 z=I)v14nOlAzA0udozsZo(UBqy@_qQ?JI&y2Mv)Wl@Qk*Q8wFtVDb*+h!pL|&o%g2@ zE1~|`o<6iq8aKMj7(voq{uMy2#!pppu#3_`n7-@h2@E?u=cTX<5mkWl@BI%@h`+H8^l0 z+eLAO<(LIeU7D;i>C8J{|>(ix4u?pfPbWeNH!*Q5*ZN6K$?jw=q`Ox0!p5PS)n zvD=ztQRPoar0KY@h{0ERXc32h346FXZS}slMDrV#OWUt=6)SFty%Je#)W;#IH{kHt z{M&hjG}ElN2Rf7E2KiY7ig!#TRB_C;nZl|P$YsGAcQn?WOcD6Rs?YTiAfOIPDDw0rN##A7JOtEde0zX{C0LBY2?fbZO6 z5iME~##iW#gF+SSKo7p@?>x)iYwEv`oPXK|Amxlnt0H%D@FHqRlf?h1+WVMmZ+AEJ z$5{>_2=EHN^Y{0!@ILbb_bw=|(b9BDf}UDPe;=IbjvxUNNTb*>4bflLUG-7$lg@og zr%*}}I-z!OqYJzgxleyYsQV$0YuK=(U2-ADXgr*mYz1iP`_s(|4m&*IEZNt%W!BGpI z7t-29yhHj5XB!KY8G6iePn+Iq&JS?nV0*rZ~cVcIiLCO%N(aZjOireIFG?cCCvRu`6k zJ^f88G5sH5dLc|AUx~fb?+Y1Ok)Nb=ahE)>Ti+N-fq3lio9A#VU(M`soQ3RnFoj9q zWy+e(P9RG+?eF|<#^TRjKxQ%ixBq4GM75;Eo8hi~)xmASmjE(AoPv(vwjsrGyQ411 zJQ|V_RKu_*FlkwtYEE@YrL(?$*)v4WhQO&0qyb89RU@2oG?cRoeO=$IM3h0ycfd2r z9^0L4$A|=n5PAw%4+K+#=;(HKasXD2_Rtdp`cj);B9=dE6sb=)13=Nwo)A|izOUA?gk(%ujhxk|5-BRBbLC{}U1+C;Gbo?7-af_;T^MeU^b|9-q54ucTrHT2;E_$^e$7Zp^A6f!nnVn_-N|B{ zQR{^;YOF*8;!wfxWIRr%)kA$gqO_KI>cIzD*_i@&xXp6?u(vE~SP8k~r0Hbo@?X6& z@dqPPwykM14Nuj*?!rrWk(Ti{ux~J{-Fn;ak3(*pP}t(T)QadPwiM7F)_{gcaNE=W z90gHlo;nzY<1yg-0zZyCs5Cwx@afzWD*i+R`N+hOR$&-@9CSKzRZJh%|S6@!_Eu5cL+4J}g&2^5|!=vR-rlSLx_ zVODISE(L`mj6jhK8FfNO{X+a1`Kb>Dv0K?MzB*F5CQCFJ$Z!?%zpoL4)%#!`#dp7J zXaTRVb*TIdC*!>P6xd@_V7xSUMmLqX>eco*g z;PH>X{EQ5vpIb`~T0lC7p<_HWJeZOkNaBwz`XJ0Kk9P2l?BE-7>5(s<8E*PzvdY;6;iTX^dwE|SA04!XYgE+! zzv4~_KRR!WfQ@+=Hl?;ztvDd5tR{4n&MQO!LXKM*?N7MOhSA~_bQqENBfd6>)_ll) zk?rV&m2A&22;*fXoF`p#tZL_p!AJIF{XNR&3Cz3&lWv{L*&q3-0sYgxvjQ5-Wr3u7 z@DbR45Avyd$b$vJmbS<<$a>rFLBXu-V3eT>wR#8nZ_*Ow>sTI}HI-ZJ9ia)>P~nzu zV_w9;#m(1X?Bb9^oN8Yac^J_yqtxSIN*9IBc7!@spIcjx0@Oad+W7E&uLVdAh)(?k z40|Ix)Y!M63uA>?v|&5arunVZfoNFO+mY3*@=O0lu~w(C64#Vh_31RrpxsHg{!A-PqsN$pYbwz%s~UVM z`%3amHHAI@prD&z_;>d5Uy0w^I5#1$N;DGSGi|AmtB-ST^NI$~1eTVNQ_3TN;$^2g z{dGhZKbe?1nGkRITE^H5`UmuABLw$LBM?U$^q16SWI`Cb6ViWNMBRZ}ay06FqF!6f zR|Y3{7C}CUoaMgZ(O{l{C|DKG`jX$WrmIofn&J zk5S6L-kLS}z1DIoXU7Fhv?rv@!{5I(g7x}%7;g(ll$Lr?l6p5_*mFSguNr4FYXM6r z1A&ClCUu@#t}3I7zIuU9;JW&K3R9h|i_B`ZI%<%1z?K6Fl+u43;{Qu8Qsd;}8g-YB zyHs=9`vS36lt1h9?HCo5ty`-aN4yUIITT@{c?VS^B5*kO4h+(Bai02zUFt*MzCHM5 z1cC&z*^xi|^3D4h27%J`r_ahY!D}0O zWqdu{a+5d0dLyEP6Wo^WwE8{m#l!A^TX7E)o#U?Pj8bYYc>cFNQ0#%k!cUvm=K%wp zO{?lfJg~PKe`Jq>MuZ$;>{$Ic8_ri@+M5u<3l__tiG3KN#jvI0!YAEk_Q&6rla8! z4p!DwIQ9mK7|vuUP+pKFIBzkD-AcnDfB1!?*G>LXIVK_{b=X$G5sk{~>OlkILI0Jh z=vfa>ni^A7^YDCW2Niia|2spHqwc1^-BA-P-2mM?<`mgnnP z-(*sNr0S$Q>MWW4ndyW0c-ei=o3C!;-+c5Ysf?B;FsogQnaNDmthQ=+#?joJdTp4w zYB;CCQq^~oAwpI05qcgbJwEZP4}MJen72vFB2Dg$8^_qMQ{P0R<&*l29lx>Q>M@-N zrtIpaUvhR{JB>n2V63rO?7vy4Rf)wMdldlM8xzt;?i;~C($nhe6WcJ;t(u>r6TFq? zAj9b~Egxf}Z{BRA^`;5F<>TWs6fS(he>UZe{e74i!`tk14>)l-kNY;iwYi#v;^Jiyg*$h9SYZR#^a@$^Pj`pPM>h8APo|DSV%4&I9 z>cDW7z}1M&C-D5GV!}$oYC9t~H#heI51l{}Wy71~0!IPr_uD>yo`zQ1%5LqRn}9zy zsZXQlu^Sc^WpBQ=mX^)mKekcP(HCk|0vBC$6|ZwAJ-JRyoDQcH871%?*@$WX`Si!C zWMLR@-@XkD4OQX8A|N(iyaD*9lJ4+a-*=RK!V1=IUQGkvOxjDCaiA0MDu z{bIZd{FA-v*KaYaD=GP~Kl_?0pCXtzAT#7wW57W0@9R*^)|Rd6#gCavYdB8wSXOqm z?D?VtFMP?TrInQtg8tV6S}1%dzrd|xHFy9(K7|#3pH{xH*Oe#VK29^P=ycIX4Kf=UoQX{;=RSh#Fp(pPW)*)I~FSO z?Ck7}6ZCYe)*Uo0H-v@x(%rqoAg0qh-xdV@)!CkScAHwAiI_0@{tqO=Vwr>=C&JUy zZ+U(5@d!SkJVcA__FG=Ifa|qdROV9#Ttx2>x^?T;9ze~3=dO3cBwm9*_0jc@8w4gc zHmo2i1>954)+wb(O{Z7q_^@tJJ&vqwRBY_jkYnPLyG|REVIXnOz*UpJ$_-sBeTKxA z&+FH0#$WJBurVq#6i~lBB~Kp}4Bz76Ax%q53k(ic;=}#-w#u}MG$5mmHj=WNIvn@C zj=X)7jg8=7(wzl~fKQ)9RwoTx}`K4Nhf17-F%_XNkfAKaT1wTYNeRK4gzHY#xZ9Qj$K{!0RI!W#4>Gg1vlrTZ*8khf{+#=hM%am_E~$^>`DS!66|H zSOlm|M2Qq+5<{&C;gN(%+`esBLsO*{P^XUh25Q66~L1PZGw~>)PA3m^_oWK!3aaUI! z#5$LmljFYM1VShYs{yJ#lyr6_R}i{x!O&H>6d|xrLU`@kaJZ=M=QSsAB~5OP#lC&} zYIXHRG-2h9X_zedZvs-%AaJtJ!g;Oljh=jPIP1#CiFKZ;;$mEJaq%x-zC02WLw~vN z?g%CqsDmu217@ryUDrcN*)awN2L4W?4LBn4{?BVp6t;q-lvL1YV?qKML@O;HA33$x zpR{L9gG-!hTl^b8E!4ANi9LIIM|@bQf+hr(h)>UpH5MvQ?+6$&@dYQ|yr5PbmW ze+H9T_WQRfswO?&T3GniXikND8PuL!%2#!9!xn90mCqaY<&t;Wp?+3IaT^j6*=q%sgEkuf~gxj<)DXL$z#01X_(kMP;@6$^E&#{T4kvW`o<_ zC!+`f|CyPY`{Bc89A=i5ZSa5vKVM&Th#G7XR+M$aUd*WN)G8^P{cl+~E_BiC?0PK? zCL~xfD=TJyTuLmI3uvh~F)t$i{61HJ%v;cK!3M(;GBu&0pTXQ70l-1;tz3-B-_wI8 zNraR;W|~e{nouanwvZ(L><-G8{5fibrx+}b zmQX{0xgD&BfhOpV#WUxvR;;t+7~$vVX9$7HaHp;`JpD6h5n+ohJ?Z-pS^<`x&X!`3o* z_@02Ayuj%;7K-95aM9`SFFfz&@;<>3y#}{m0AxiTKgI-_6b@A4a*Ef{J&;0P{`uq5 zx5b-;3&5`(9(@tE;jzGHW@XhLKEJP${@E6FGjmwVU7k`oLxpAy2x-*}st7z)oGAd9^H3;N&^=H~a%g=_LkBs)Y$LGqY}{&)*=F-ENl zOlVQIg7H#PHj$eEXp^X^>7AGRKd9c_m2U?_4=VtHpTPM)Xchf|6E<7W@`a;LRPq9Q z*HP14O@}x!%(}r~p`3-2T4K`DSV%*Ut8Qrri-q&PfX4ARa6c6LLUY$~c^C&qL>GNiaNT*1X{e{)mRfR*IG z`=CfIWNyyb*WdqW{<`OKJohQVz#0%eE(jo7aPq)^xa~IqlKcaT)k`?LFdK9?d2^M8 zp1v7snk_)7KD1HIa#O?o)gOOGn@$~jpMEaXEPs=f6c(%Jc121`%4NIru0V;Zii!cO z0*QcI#po$ST1I9jI#}c$cpY}@yX~JXc%R+{jlds@>ok0BzZpkvUS114b-};CUtx9P z;|(@8Hq^_r(~Yxs=#Zz;cgcAQ@CFkjh+-kdI~*QW(y^l@D~p}%GIIslL>)i^GfRwWyQRLxk1-f;ooGpiyIU6EJx=GV2h4p8^SJi)&7ohYQYc z?lNhz_o*u&H6(^Ks$P)Z4vMJ#+c|%hg0?1CU~gxqB5l6{g&yE_L>M{OCyUA%@bew) zhSH>ux0)otjz}L|dIQ-UCi%a`K4XC9&K(Tc^!|w3>7Qcnz*netUrez+{mo&+h9@3W zR6Re;)RSNH@a&NrCGuX*Jx^-J%AQmgl$H|QS1%UR(V;*%Psu2fS2y5(xSiK2wzs!Y zDDeFFw*Gnqot_;03#iE3x?8932db_0OGMC79`J~m0Q%rR(0|}RhVA_t0Vi-ObCdVs z{rguTgTu6MS-kL|MUJ+NhIZA|a2r2+)@oJl&Xgj$%;&I(-__N{KYlt?abya7>?s_$ z&?q;>k(QS3hX-yL8ykO^79WxV%t??Zc3pgN&kexee{UNf{c$9E(v!|`9=qEp1Hgo+mw^gIHvPW1?O z;!i6sga82G)v2**VIQ1ROR&cyf4Ca#Nx87pRl?#p3G3ca1$)@NqbIQP#|r>o0+0?a zzwh;j7`qI}SIohoVr(FA-Gy=CU)-zPMs8jIs;cUt2N=e_^!EDQmLlP_xK8CVeSsf3 zw1B$wI`p4kxgm^i<#sRgy`r)*8VWx6#PL`_MNJKQQp?NWHd&dN`dY?5>J|ZG*VH71 zapDsaUPK}L9&u;EksNg9*p-+P$BY%HzZ)CKXukpls5h;D9O;W#o!i8?N~)@eQ@l@k zfZtw_ie$AM<3Q>^ph|pkuk81^`W>ilC=So5c4z(afbJpcOb$5der;pZ$N26}^_q)r~8>ddz zoxw5W_3HCyvHHK;-AGjdkb9xxpq?9!_A=?e|NEY?`_G@*h=%d$c9%%N0|4*0uIuC@(4|IF)jzM%fgE{iM!kBHkQ*!#o}L0;r#mULAeXm;6EYCm z%Y$%?IwmA2B%~EiTY0q3^2Iz@j=O1F8~)>3^~@)~tLhU|wx@u_0FfZiXz918M6i?F z-txTT>TpbKI^R^XfP4Kq9?X^Jkpt1S34Zv_te>Vvhxv0yhtcMAi~4TJ&GfIo{=$?+ z15Ggi?V6sRUV#tm68@y~93Jd^K$L)z8pqvGA`X1#>66=ipAiho4f{|-e_4AUlcT1= zy=w9K6Fku;ZE(p3KDJ8zKk0X!=fRfwDS_;1_LKXly z1Z{8I^_2oybeWGUdWDEy)NdO>Rla!HX3KUO?G$ZDQ3=B5%j_n)Wq37Sj#s<{%)*yUooV zmr_NOGW-8UpB&)C0(CeXHK(Tb*t`JeR(>D)Iz#D(z5)&a$!E!~+2i)cCMFk9;Adpw z;NqgCqq_tTfnq%U(;@T}a=@Q?7VjXa?*^X(2|#RZPT+iQv%ji|5Dp+U7f=Xm_<0`8SH>p-IJn7dM1PhS>*)Plj#rc@uEqE!=iXg+)Y4U@?%|S4!{g?VY;S zU-~3`MGmkaxw^a8zB2@>A1HU@JUJa}V~hScl$pumMvYm&zO21;=~6%f{8s&JTwLK8 zLNtO5rhf3?`jg+gvtE+5At({qSXf48IoJ;JtqC-QE6^4RD*$RiQgU+lCYxsIkC+x= z4?iX;%SfGO&YSY1tgcRFz+>~Hqb4S7R}9mr_S6YUz#W&Y6Oq~3LLI5Hi{8C^cW}Ef zGgIgh$;*cq!YTg2tcSGR9JXAI0(kQZO-a+FwzrS;nHUP7|dmT_=60o6rTHwKG z5Y5eDPZjtQt=qjHTvUa_$aOt_2tZ~G*a#M01*Ye75B=+6T(x^nD9Qgr4pAs$%0wtd zaI}TOJW%SiG(kW$X0c!p8yeTNEG^Rqr_Ih~Wlfn=kaSWN+|I;AUoXPh2Un z>V?EEq^4#)X`xLUw(MH;A6|$;xh^6l#lk6W*icw}E5_#M_};e0J@{T@~UAPUD2MxUFq(Ul9Ekm^Yua_8;+43I3J+ykL}mARag8kglj9J6iZ4^ zkHH3hg&@!hbV&Y&3MNpI%E%Nsec$=sgm=3!jI9BGNcE{@(MrrbGneh^MQLUST2{$x zgy#F#$#zZpq#ZX6Il-X78Axb6QiT1t%uv2SP|*0qL{e(%J;ub>oY=~gJV~Zdn%I_5 zz;9ukaEH5bcfey{R|^Vl+a?H~;l?9AKI|)2Ts~@+HT&io#WYvOYwq|tIf;=lRWU^-Ossn_L-MVusp-ay z2YSZF&TB&T#L~HKf~IvUwAk1ggu&VLPq5=Vqu8o=WfC$%0wKXz;YjV;+qXB_Zp`D4 zrlTPQ);KHbC-49~DghfAS$IOwKI-r%+iO`_@$cHTi*4n~D@Qv#OAhv~55jA|I0^P4 zPH>xby?Q^2Q9?f8o30e5n2AbAxpA`RYo2!kEr*4@V0@K;Il|LP#L!heUAFIhPM0g# zhn@s&+7PS+yPqN`HkizL$@#!IwlFZ#wgWfp0^XOj5{d%Rp+e;7DnKllqFFtwo|a8P z!y)yHxuK5suY`rV^6_+=ty;K<&C5RzNue^u>n<|o`kTD)L$JyM0tvr<{t#Kab}=C3 zENW$PykA1`(9_dX_w`kv*D%?7@G7`?T2LkzC;y3NC~=$L`Qlyu%G7@y^*@LtJWdxX z)BtV+NfmXow!OVDHbhcNN|aUY(L0kzbN3copM3Iq&Up(TtJMBV7UQekWmDKy_=D7# zeCaJgvm4Qg$f#q=#?F3+N}nWX_m||wo?Pmtz-uA35?hO87f=^q=*W3C&Qv-@p)fVK zv}l|Wt;l^=O6p7ChKq;Fp2XpF{AkhojR4_+XMo>CGax_-FYl&`NRnXnXI+)Qv52}g zR{f4&Z0R5?~^BNb)=vJf$H1cM6h zwY6#BuLG0yCg^CVyyzfF1NeuW7(YKhN_@OIsayVmK!E>VZ#q`tr6jjq`lqy~=xv}% zG`cE)OIwz!8z0)`+6)OZ5vvCt@KLF8V7>KZo}%yfFK!-# z>^->f*$6LuX>-_}kd6++d30~wL2tDpwzL5DeG{ym)0oHe3d*brm(FBrKWPpwo&-6N zr}m@aov%G4+JQ2cyaf=)Qf*Mqc9WQmq1k{x`pccpWTnMfGx<& z8#6ZMN|;>{Q<{<4?b_PpOwuo2EV6Fh5;URcqHZJn27wj$8D6!+IND#^8T%pF%wpRw z*>_&`$E|PmQ)`5UHCxQ^<`>_IH5^Ia7GMRBwr8s_%?LVTiu#X45&i}|qM2dO^`fF>dkR+|Caqbs zW^w+1Vze8IRP&fMG_#b> z(nUu{6WV?B)Q|5o6W)M$kG^8zWpQw_-U?B-uKrIpJDHtZwFktEZai-UmXB0rP_$Z6 zMhG#{;j{$}WVVc`a9$TrR99C6Do*c z8U3&cuo&bGUpxeejXshe1s$D)v_#h_$z%HQMa-fP{0P2Je?$j?Livdp5cYv z- zm~r^r{W&JXXqn$iS-D~b(S7m?3L2r+0_inni9~cnGr0VS^n_pPd`{5S|! zf$bApp5e-9k4 z78||j+O_`s!X`kccJ2#7OW&t~X4RV>t2s%e4M&7U6MAvYGz* zHLQW<#Tg>x8?+GA7_``77a99YN=oq16K02_z_b^OrPFIP%+Gy3aZ6zrKp|$X#6j_j zTdl|n=|IcGByp!an`!@lL=A0!9#by-j8jWE#j`Ouj=*}tQ(`zD54@Rop|EardB}%y z=vm*~x5=k(D=ws^<==m-ch&fUroR3XMpnLiqiK{6UjJQ)s57EV@CnDBR>_bu4eSZw z;^F&ge$f=gjxc)ZlBnL}q7&lBfc^7|ie@~XV@Aao7)b7`w@a`LqGDop4I#98J9fPM zWT@@G@eew~TR^x3J-tRuOy@8Cd;=R@N{W1AKof-Mg1ITO>;q8~rr z_5MlOVl*JCqdq>9oP4-u?u%lID_zKTfn&{Y4HRfY?%1k>XKZY0I$WKtsr_s8D|Z5R zjj^}#1ytwiMn>^uCoM?E?Q&rBz%+L~eoXy)pd{D;&%kE~{doHP?(^Tj{0U`@&`%1$ z8!(O6p&1g~u%gN%1paJ^7#Hj?tBTPidW{g{s}5^I^A@w6ZQs69SoqT_)OgTtpulPC z>MjVCpeQ>7@4oYAdhJ@El55@IRHDP@@w`LQhoKC zGuwkft(aO^j6FFCKM5%;ZFJUB1!73G_~#c@;J#dwAF_;E+ta~8=BlUhD4rfh3XR(h{I8tJBfG%P&hFm* z`;F+Q#Y%;e00xo;jfXr4JV}X(Bga18hRuzOi!0z+*7@_1`pM#RQd1!1rn|NaYM62X zDwPOn^n`u1k^g%TOqYxQ8@32_J3l*3O4QAsLlgixTLjJkw7e5m7C-HHz5l($HEQkq zAX}ip4B?C=hMMK2lit`N;ng9hJsjE{z;kf_w47no*YAz@w5F z^3TygjhuA$?CY}72J{wsV{!z*GARyGt*cc_v(F{u9i(SBtzj)|q zE&uiezB|BCCcAe1yZA0mvzaQ3D9zad&s^&q3p>oPY?fZf?^G11oi; z-)KUAUy%HfO1ZhO9%W(PNXiy)CP3mRU&aT;kaDGKh95~CjL4lkcW6T3}a_31~myVXU8`?=fZPb;*UDXD642PeQNpvCS{~-nakM6wJ0U z)Dfg5YXUXicC&a`81;PirrrGSDWd@sxMg7S=%dOuM@Mi|7W3^w4rqUj8#3GKi@Ww4%?|HeJa^~u@k zSJqF5t>PpkCAF-r1+enSu_!$#p7jFkbBiB>Dc%*`{Z1Q537p@*auJM16_&(RaQ^(t zg`YzpuCE`K8YLAT>f6-wqJ9~ zlYalFdXrFx_k7U3c55sA{?Y#eE6tY&V(EB245sfdK9XL|!U#5HjfzTUnJ|TpYvK7yo_G+c-o`E=;147Tj>q<5>-v97?yhq|Ph=p=lQJ7Pl!=*nymEpq={NRKpcE1ZDsbXB zL5VS`q`emwBjm1-rWgOx+K&5BMd^T!0K{5wg)AJ5b3yy!*yw2)!*ZTJ+^PL*Cn_h? zt@Nh;$j%VQBuP$zE282Ro7EjqB3G_3g2(})TM*aDYk4}U3)l(=2VhT}ZtlOnl2798 za)i2Tge35lxZ??*eMOjhF-~42uN8`U6FhHSwf=`!irkaYKNAj7s=~n}WWhI++tpxS zg0DOh_ZF-=hu=QR`nFyh2eph%LwmU3xbkDR{Eio1+2Fw#7#NfSzeteDwns((9=Y2u z3dPbPYvGj*Z+I(C-HJWcBZ6Ym4mvARDFKoY8L$86Z+PR37EgYV(1quU5L6boFoJmL z(%SiXZC@8`l)y{i?03>qfxu8;@7eMlxXH_gTbc3+SA8!ciQ7 z9`kYVaE0YGW|(B7^Wn0i_TD4^e~^eGJ@<95iA{Yqsf?dkOhgZfjV2G|@xnYl=-WWgfazPi{|N z-^<+7YBl5Tpg{-_j%9zXD5^jHY15Wy&jn)%c&XSHI*eK(`H}FC z@sJ(;Yg@EXu3eK-;$sCsAmkC!Cgff0wgxcJdkOyo$dIafe6!024hFWb zcyqbAGR+lz7mwBsD+T{j!F>r+uN?8H3%`El*2b~}g7C=N(-XQ7&<#Fi$3{?TNf{Zj zz@2sQjv(u8Pq9v+%%ec=aUh0AOrGsmy#hl6$foMk9Dld{9CyZpH!~W>7mWKy+g+GL zX~OQ%)LSptU{m=aA|f&kSwa@k$I7P+fLRQ6dP&(ip7~==VM(Ar;mx5neXr` zvT4D0<79l7Sk+ZgJ?x3s0m=Pe5~x%vH$Q&~#uMY%{`K@w@`e>%bWle9cs~e*41^L! z>^qRE=pw$iwQg7ps*gl>2C^n}AiExc`; z&7=gE`huZFiI4c$a8E^xjY^x#!r7^q`0%DzkqX~c(5x3h)&$=mauH4ydP3G4A>rrn zc?O2>-**x--brNm@J3r(aq82$LhW17<$A72Fq4qV$RI?L7S|X;Uwvh5DGzGP&Y>ab zo65YFk1`aO2i6M^vIPnd_<~xgrR;Np4{!o!se^0AcHqog)E?bH_!5**3*_ot5$ZnB zY)jyQ5OCag>&0}bl$I$M%PKi~7&O%M^nCr0rZ#V02_ocTq_y^NJaI^&=HuWXk`F?u z7RboIR78&_N^pRRFCIHnH_~ETT~I3q{vgr?PEC`2$++S~0ZlIzw@e;MOy$=DxvIXA}-ZW*;7@8#<-a2RZj#-2TUQXGYae>d8P3qr?j zf{~FxZxU?9#73_?bE&W_fnOhGFC%1^2{T3ww$6b83g!Zdz{3fV3b=HlXG?9YL<~%@ zq$GG>aU0kgZ5%ovY{4Up&ZO(+zVP7uC$cjuJ(tqOD*Lw`GcYh9=n77@p)ZejV!wi6 zz+44r+1wwoUm@KHK%b=t_gE{+%|5q$rO13D79X7(YxFsE6ZoPLE1rK;CHyz|O&Bs+ zF-(CQEZc?qAgEBb5=EV8lrdByyq~PT>*?qyO70-AD!F~*1{?W|9v)KY@{f?T{?`8z zCgFu&rv9KRT@N1o zy{LKXSABrgftXbjOEgr77hWmX>iPKi;;=sI=bh@{*uoG0a{rx-uQERnlwZrq!rs8) z{=Z<3P9OAB|53!Wl*}q*F??PU(LFrg8_9I{&lfFh_76=Bbx z>eFQ$=K|h^qYc}P6mnpG2oZ$T@-`Lt_x52>5Ogbd!&F z&aaNw#iNOU*ZPegQCIL5ToCp*4(P?kRY@}ckOUY5Xkuftymt8dUy^`QQ*5K%%3%bO z2*Sn9A|DWe1DNC)WSOKU6#g?qcv=jk)Uh2Jf^762L>!y1l5K0aL3N_xpbjYPcNPw_NoLo3`l!KLK{_=I{sUE!)`h!&;aGeUvYd3KG}^ zEFZ8A6V0Sf4Cq9{9RPrUovZn947MwRuR*YY)dJP)>+Y$+#s*ChzojDRz?w1~sQOPZ z1gAON+fcKWYhf8F38 z0Hi%W=PXNorB(WCJ<=k|C2g2;aLz+86K)NDB50C>+eN5P8|=eRqXEeld4Os8^41XA zMJhiSGzdcouO@A7S3uKeQl$au(()E>zd$Of1~C*VU-c>SDY5+*njen@h<;DU@^ z{nb)T_;-_i_;M%@cpFqm)VSztyP4V9{)sc9!(Wb&VIe@58m_Jq_6`n*$5j!VP#_`l za}x_Rj3rNZ&q5$*#4MtCzyN5K2R23N=4!zF4`C1`$dim3adxW=)O9fKZ20+f?fAkL zcig9IV6YU{C>V=>=qB!5;MLXphlbu)@bmEv<$s2JRLY{3WRY0?D^}FR>ZK*W@ zz=Gg^yZiTQ%Dt)q`Nk*&$Hc6x@)$=ZM7e2=;GVOOg?dm`bBOI}t4#pA%0w(SR`xl!goQ$j@&3i`wNr||0|)o8&1 z`{}*Ag-OR0Eh}9>FId$D>kJ59S#U@&2ocK;p<0lo6?h+PdX(Gc3R7@#-WATSB6;3; z;z1XU){>oLCB!o}B;2Dwyb*V7P5#n!Tw^tX&e~wo$$3N*28c)h@dJvnkn;L zPFLGsw1*Hes;c$7-zGb)!k*m7!=h*&2Z9wbRR`F%AN>6dO$hmadA)z+Xs~>w3X|yc8||RLB#%XdV|H z*u%Rx#Ner3ASZ$f8AIZ_DtR|lNIkbp{rqT#nwqpUD~SMrMMNt>YXdp01GWA#x4w@{ z5@QeUN$6KSO_e~orf5zB<@V37-<{`LC_qCv-$KgDyr4hTtQeEX!ygEuzF!nWZGc-C z-wF?mv={0UI6Jv{kX?tJF^m>(SkXKYp9XvjVvR+)EBmvc&ql-Xr@(b}$|A^7S7_E-M}Kli@Xl=2WTiH|_~8IWhnx;$5r?V6?}-?$jZ^w6OV zpeT}dE%-z%TmZxkZybb_Q#C41~|K{O^*p3cE5Q8A! z3BFmkZi!6&7Y-an;F!~?si_kei!Waut!ZTgm%5I5#7ojk$w_ILIa50O!Ds)`m+mnx zwXZhqa|=LDEF|>$=GwXrc@@IwiHpxGMC!xT41f{%xsCJKav*+_)ihMp%K0 zTO`!EXyO?=ndlUF*{L)XDqa37p7_pNJ40Odi!_wkh%hHA(E0BA5p1a+ZoFu$T-cW* z%)cxd%MLmmTZ^FkfPes(+~M;Hk$pge#1&4)iweuhaex8eBetA0qZCp(sP1TH;~k3G0U%b|I8tDBET3mO}+~<1JU>wJpY$7K-a-> zm3Zb1ohjF03rFk@0BB9pyCkW|ZuJtctg{oI0kF2<*s2;fNV=A`yB zOQTRrH`YqGaJQ~OM%stY_Mt$mkr#EJan>W=j@e`W782>H>yoQ2PV>mp!7hhG3LXDK z{L!ZiCk~a>a%?wrf#RQ_*g^OcHHoNyh-ZfEQ-J8Fz;?mrnL^oL`Th7aV=FQ{x%=+}AMnB#&$4jUe z(i$?dzY$ty$hgcuv^k6)FHK|@tQ`szGnD7&71o|pEQICCvba;gWWWH{JuT? z$hPOZxAIzU`*cr)bc6f@Lr@8&AcoGfkmbgcBhX~AdT4dANBu+`wvCOA*N+<^ zpA*RxM;&xsbY~IsT2Y3sP|FH%Wo{TX}gOqx+CsH72 zTxfdnaj@^5?|QL!f#9DA#ftthcftb_12h{ye|(y}i)L)<|F`IYH)Os`uet)!<#Y9w|D;!?uvP`dE&>tZ|04FH*N z9RYJ3w&?Qo@MwmCvlA)+c$jBLj|v}LtIq-brZ>TRyH~sViL#~K*Q9$k*O>Ib*0f4q zz0Amy{O0*<&#CqiMn2ApH)fM~l)5#V5%gR;XRu3rs z$oRR@ag}TBwcxv>zk@ebwYhru9gh)zaFijw$W!6Tuxn}6x0hbScYjA4r_i}LS(-G>90HP}LI>nVx0%QWLTG+B5pLUqDtD$&kv=Jx{?u{6atJG!+alf6H)vh%>QQf2cQfsWrfCQg=APDGo5NW-FRd<( z&DLtH6~>~OQNjmIHrQ)cP?mHH4^mI9)B9Pxi7;GUqeGrkPg<&W$H6b91NF{OynES? zgn~8F(g|eMfC~I?K>sHW!ioOkRx}C$g$*AvKZGy=b{Hjz9lD)WuLl}y-x~FmlqmKI zT(Nrn#D%=dn$9<7o#S4)51#z`_~gUct~ZH?k2{Cya*MfrMdo#5{uAN*Ik zIhRkJaoS($v3B!jeZJC84^f`SjQ5u_EjgR{HT-c?4(+b5bZ!Hh1|cT*XpaP1Fh39X zTyr&1Jx7!+JyE&Em`|qEX@BX_eeHT>Lus`?f8ESY+Mcn&JuT_YPvzEC`ekFQMsrVp z=n}tFUHxY zw(fIN^5uNNml3}=mNngx-;h;z-iS5RP`IgFuIP$fbX@tQt<)PaDe98NE^DRY3{!d1 zzO47S>+rU?GId8}b3N0M>zwqjMa9kbh3s6BQ%I+Ia!G{~bAc9fL6h7;Vder&W?_wA zKZzbkoli}RvvBns3&JgGA92_D8aAd804wN*-A5v-q?9_-^KQtlDv4Yd6H1J+hYlZK zeKBx+9faYR)WzF6KHx@kAsT&c4KsV0W(6an7xVM;&&J-KT?&LE_2Zimb*9bxfFUny zO;q<7zkcrF9?dB|-X_kK9P1YA4o-8hy0sc8r*fxwcRJFJUY1*L;A9rgWp-9CkHx6! zahG|q(c=U9jAHVqbJU%SyXdZ*(MS*au=@Mw+tpJw>Vrq^_DMfZ+p@A-UaHPdab?!U zO>*Zh@uZb|Z$4;mpHOKmFSyOAMlWr%I7hY2d&f2dL)RD@t7+%mV=;SA?6$d{ealee zM0IE+^NLpt@BeR>SaTc$HlbFc79X^!+ zHjEZwfx+eGd#yS95*{+8HN45L?w!$Ldvp3OxspSxA#^1=RSUK6=WfRei1TL(80Wf6 zM98}seTlmyD^QlCwvEzE_RV&h(wVd>Hb)x+%tNkNuXw2Dj zoF4A!=Mv|2wmdxHxh8Z(tUzI(I!!}Ib4!o<`|@-8W)|JiF=pbXn={jP%Vp;0DQ&fT z@jhHp=tRzDlk<}mXVVSeoV4O#m^G6zmEGiWsd;UVvQ$oqrk26Em@7M0_&Ke=)RL7~ z>8z9xrY%g{t?=UWT=qoZEiJ0BiQx}o&p2>CSI*womy45=lcFswv0;PN_0IGBi!C`< zh>MH#DVcH+7m;H9JEK`>3kgsmUOqOEv8rsXl3Ln&TCkOLj)6QXl5!KV)Ge`K*}3hf zf@TgIW-#3iiYjw;Yj4TF!)3hua@VHJ#xy%lm$h|ISfe{`I}Vwx~nze0lK{+ih$FF)h7oa4>x;F^|dXH`q@5s-86VD{l5d zL3~%-g!x#T-hSTT643r(=u{t^y`fU=YynqzO|6Tv_EzY0OnrNWiyWHUlGje3{ylqo z7HzS$Qu>Qpy%$!A`Z0=&Vki5P3%IM1uJzoC$b-rK3yaPL%ErtpM zDXTYQyTlJJUBjfV&S}bNYQp)IgVp-6hVH&-7ONH6lES{`9hEhvqZQLWmXdwv)XP?ej3GuKnWQ+HyfcqLM zqqYH!p+YqLC+Mu-8&aFs3iBm)S>)LIT!`E-qvnyf=f&>+hf5{R&Aa;gpbc*3nqTEt ze)7-eQ1o$bwtt=~$j8?V+wz?%S7ngaPu4tDS#wI_cYx?EV_;xN8o2h0pVIouK;RyX zzlbi-m7>&zLeN+26mynxWq~4y35rT`vXl*nK(l{J~{L=hlz6bDf=S_Bb6Bd}XIvGV7eF>x8H38Ex8=Mj z2X%7MJ~+3&vS(u8z}4L99r&P)#W87jYUxCiTrRL#Noc4$OVoyYsncaQ_$B3M-zdAC zrDeL5{{*9QV11>Ve3WCYbZOWtcAd>zrf;w1U>bj>{=P)^7f(qh38O|Kfn6!V(C@9X! zN?o%0r-OLHS03`r?{XCE@4l}zj(pd+aYN<>b>}zQ%rZyCO{lRHdM9l9lFQGczB2MZ zFh3}8aUDT&Md!P^OkvEyJ-jp_REe>vsqI)$hHa5o+&UEwUDgz(3O6`nw9>_a%J}JN z?|Y?nmri|tyJMfU@$xHPvvJ?Voxa_OjyC+X=6t!`;L^2%zUJDyBVzh^vEzKp&GIEA zlh}J0&d!R?Zb~}0+tZ1Sb}H@ouF} zsdvXNo%0Fqk5Dw(I%%uKOwn@Vo7nWRR>b@4cQLa_$MRmcfxfY(Hsds)(w z$rPb^6XRxN#%1}qc`lTD0wu&eINva;gljC68w_Bk!vzypg7btjK>+Q6h zoH-{mW56^fOqbpt82wqGFJ;ui|Ex`S(FI4dv-h8Qxwp4CWz17nJ)8RF)zcV#a?yn_ zw@f}gJFkxB>U_Ocoug`ozf+?h($YrNoS7ZHqaVJAgZI99x#Bo^uE>MS?#sOufBa5? zbiZKAV|i6oF1&%qZqs)0-TckYZYs-3Pm9ELZU^nhgjVOuL&CzAZievR;$rZ2_*m38 z@*L>-dB%-D&}i*r6ik;iKRa7@ zs!C(HFv#}l<(WzQe*P8G8Z^E-As6+HX`Y$9w^|)Uxy;vmhV`Lws?uOaW7kDd<1bg8 zA7tL};C|)38ec9C=~{p68hD^j@vJk{YJ<-Np!Iqnb zNSEP2^vf@4&Izv?{J5`Yt`)ZQ{PW?jPYl!__kT$H;y`Kdax4A1BjVAoPOOV-xmqCT zaj9c&xsa2-x=wWXhGqEXSDqH1oz;FAB(aOT=7Z~@-A=SlVsiK8|6S=m{WJ7chA?UomN@>~mjZn*5G;asxXL3ZhdMejV0*xO?36dUk! zQ=FZ5e_?8vK1sXSm{(#ZHc#SQ30@?gd2sa!i5aVbj5?~sCkCk^S z+PsR`GRTmeMhrrL`8V<$6I^OE$v6!R!bwNG%3B)@te(wB-SOt+TvANesI+rN%Sv10 zcy7P0lS6z$qK#(0jiw2A&N@Riwk`#YkCD9-1(bqBmZ#H}RaRviLR=f~G^CQ}C84P6 zu#mIix060rLQXY2G3h)pbXOU>l^#2c+_p*AJ{BE!e*KD+%Gr{7{q2Vw-%Vyh3#GUo zqfnJ3SC#MpXXfVSdRcMDG`><1u2K54H74jd^;hGt1msIbJE%VU_-^`U|H-z}w`xk6 zyejpVjmf*K+&rGg+9ok`d@_YDy}8do+xL#Bse1HIO?;i$awC6F)8!3nNCj~%9=@zs zyl-wjg^&AP*QZe2qg6-2Q-rt5`;7-LqW#I|N$R2!0NO2L50sB8{OCN8uVL@PM^aB+ zTA@*LS!cr?AN0A|dU&wlg)=dRl?lXB#xxgVe2hnH%e_nSVOKc<-ucq4UEIwRyN@D{ z)APB?28q1aZq-v>KM(gWcDsub^h`8yUZQP6g{N&3Dd(fsFU^yfiL_JPTkTrd@7=p+ z+uc{JjCZBT9?tn7s=PREUzzyJ$grD9y1#ikwtdEa#68?3&gv)j@yK2dmxt** zr}tCDJw$i0zS+uX=0v-HynZ}t!;CWT{S{}O2W1!(STA0QP2O?2v$vPQs2ldG%qg$D zhUn0cY-ypq!aT`En|o_+mg}@?Q@KQBmjd_lsX2_?OB0P;d+q(t1Kb-Qv&NN&<>W;q zFIvYpzT;*7?_?9x^$rI0G3O}}gB**NZE|9YYC0Bl-c0JxN!zN(PAlc<+iU2o-M=55vYItvhBx5y)79##8$IoW zM6Zk{8j6=-61KK5`>j>mV~=|FYR4AZ8C*!{{~&QEphI&iFIo$c=JBDC9$V(VEtjpY zOxim>ZoGFXq8mwPaub^gAN{7)MZFF;?K8rWI%h`TZ!?sPBGuK3S|3i1gjWZ=ezd!pF4sRb+W~!M$9vI zloWMEonOD~MMyY~mpbyThNfH?DJjCk@@6ZS(nvf#dg!B_@C$P- zzIU>CYb4yJ8V)}B;q=y!hK+$;)j`~Pd`qmCy5@X=t|kHc-=p>2;+D*4uwJL`XQAQ8<66{p zqsX*1eyaf%z>B&qLMv@Y$uCp+NGZib;3y&I|d-ev$gM(WhjAM;#w$ z{NBi2{PRq>!T$MyXRiSemL+BH{b@3uvgUJ#jit^RQ5bkdpWAgRuZ@0oi+jlq*8;N} z)yA#nlNxcYhl($BzoWO_lHA;OimSu0D}16xZ+`=_H@;BjCS=Nfd@f@|y{4_}UJ*HI zMDm-$SsyRq4FU^=lrvT0;XZ!vHJC=?g-e|@xO808D><+qk{0#@?fFUjfX2q0>!Pe# z`cxmG_>$C!=lYCY^LKW?41mhOf@5I9s5A0N(wM$ z#=%YR4^FR1zah(4;dQAsL*DyZzq*3A=hn5hDxMB1p07IgabimZe6Zll38BJY+cwOIftSm>WyRi+xwlz1rQc4A{wsV+~XzqfW6PKYhK%D5ZQZev=x zY?^OkR1p%CqIT_uvs(IX64U$DtB52zDyRm5?5_{VeYEG4f9?Q{LSFE^`y< zVhn#GFT&SaJ%X7md3ANT_Wl9zDYsv+{uzYOIM`F15QbX47N=8!l=?E78&cB_)t}X?_Ik5LVz(3fhTip+n}8IvbMtrUC<*2E$OvZ} zuyK2D_FR8XbMIbm1tWNjKFg_YrABxUo36PbwG_@_N{hXOjLdc=zDNmXrZGCYw4=s& z7YCGkAG$R*mRK)BZdK}Yw^dOae%R)nq%UyXoOA8>-2v5-(HvQOH86iJRnh6lA0sa_3CHZ zM9IW3;73Ir*Iq9?(MBUqT*p54?%f@<=drOyxeV*>KJs)+h2q%FUuQVt?n?PCyX>vh zy`$J&Vp)6IvnHeCH3z9bu7xD1EqcTskM+u-n(6K*On~y{zJqy7Bn#)t*FF04RLP?2 zt{Np{M0C#;H(Og8IE97b=7N{s)XJ*Q&FF!V!iet#Nui-B5vMTG9 zck8RnUw!uPdxe3ScMlzJy6I6SnBnec7V%n4OqfP}As6Hp6dcq)tyRu*z~78X+f-YE z3j>K}80rU-#b}W_Km=~xKY!D0@462)Iedb@e;=HFvUS3%f7$3jtyoCunW4`fe62b| zUY*;VUs@EOdhXvmE%@m4tJT|9H@f_?*{1e0*LwbAn(6#hG`+6FSC!`%`j-9)z%U?+ z8hzuaJoF><3_ErZ=`1IG5EfFEXVyq(Or4lIesjE_(8SV`85{v<6b#nl26Wp}b^Q5{ zXNxu1h=X+q{}IVOU}FFCbf00&gFNSxwf15F9cC(TnLoJ=u5E9~V-6tVa5pK&l{Uaa zNE0A0f`3C#d)c=W7!!tpkYwHrpRz9#+|*i1e7Z_}cX0_-7(B2?`+VS~xkE0FMwNuL zDGV08v|YN%9|~veuemQ@zF?*Rxgb!<=MBpemRIw)x^itq42Eu3auYz`AjxGd1^7!}KjeMR;wN|7IurPRMS+>rKA; z3I-vLvo|hVw^r&34vs6Boeey<{PM|TEs;AX7Sih5%nO?3k8gg+W0Qypg&7q@oQ8R? z&hTC~n%m+a`0}D@iZ<~g4&0P|XRBiOs^f`5LgsX&ZI-}}x1yOFp0)%GJuE*a=Y3$M z*T-_grf?;i?7d=ZQ2))}c6Slu?YqyDXTld?Oj&GE98Ofe8S@#@qUclo&A=bh$pWnjxvnYs}CN1A6Pv^4V{qqa38_MWJldvI9y`0*cg zr+;Ssp3Az4QRUfgyw5P1hgwj;ObA2ITXW82@G^~pQO37lyZh@g{fx|p{z%@#&57%^ zr1^0u`1jA7xJ&mVI9FS^Luo<+R1z>Vj(ssJUjtlLQMl$~MVBiVX{q<_xAM0G1{a)d zSiJJ5e0ogo?c0KwXQYZtz5-Ri%<^Dsq}=)*Cr;WI0x%*+R!*+;lIYT+WvE!X(jA{jKQtZ~8A6r^S|U7X-qWF}a*dxW)B{@(eu3v!b9M zcQ^xNt|+Mc6ujDX^bfS zwZAbqzdryi&L1z!oLE8})ijQhI>bTpA{du1JbHR}8m42V1N|+xe?Gl!w=iGuQP3Ot zo49-UBN+!ubL8Y*c_XWD!&4`@xBYy#v+Oi&fPNPF!!2Y|?9QNcPR=1dhL#J>b`CeiN<4 z&L@78M`^{+H^HdEhQe&}J;;Yc6Z@r+{#6^6{hs3JO1ItG&~P&v{FE`vC9n0#L8*q8 zsS13eEH2NgmxuJf%-u}2bq`B;;K#eUZ%ksTv6vtr@xDJ8tQe>({Y-l@W_E5;9pCPV%kqEf1an-&q0c5GqXL^zhGxCi5lsEUf zy5>L5E;bqEBPebM`aP%;&QW`JT1kI#KB~a0Bek*#o~os4`M;Y4f3eXJ_jO0i4E}wi zK;YOKGF9=3V{^~vTbPgfFoQy}CYelu`?WGfp>)hf1(!ccZP!$?w;2a{8Ji@}lo+!@9+{J~lzcL@mRKMmR{e6VukhDuadB5X{K#Tn_|HxkjQPD6tR zJk^OB(hz_?Puvm7&Gi-?N6se>tv`0;!+Zq#3Z3?Eeo`6V)~0W9e($^0tWmVK`eD?G z@$ol?j${*~Q4n^}#ki_325u;l%xGx({n%q$5_ept5&GeCz>p95bnaTQk!qGt*0!RZ zh(M;#wn($ZKP7y9zX`LIOZV88jJvKKxUy@*|j|uzt}B2)jG#9kuq?N47tuOEnDe0f@PbnAS*=+VabZl~;a$ zP?Bbo=WAwJ9Cky9nGXCkmQqxRQ(^r?6 z$k}h$0%T8CdVuCKB{CJc5FcPEHb&@LRQSTgdQ10|5oq{%;p7Q{=HO z+kzsrwF?ifpYD`@DaKb5*{$TWIX+2WW;#*t$+NUPx5Y~*%L7=XT^27A{S{a-mA}tZOxaq5lQek1j5$NPl?fo!P$iP2N@>`TgGJwP9_S z;=A;hUXAKj>U&k;H@?Na@yJ6Xppbh;uPD9y*l(KIPQmWSh_2C@v?~Ev$`s)S2JYAXVb)R;GYp!7m4Ixu;$S~s@mz45uUW>O1r}T-oAC={*=-g^g zh3*Dc8PXQ`G|_I>GwTj_`pQ*!wTm^lSD5mj@7i_Q9>gJ1&&=rh(3)?NJ59LzhitnX z<)Sf3LWCpwqY=C1CW2`VyS4rO6$1kU5v3FAL`9rA7-(s&)YZB1UF`N2x*qQF_B+ld z+jKXe<8JgRE)oxp2tkbR-g1uf`qHVx`vaAeuj|oSkMBSo#N-MgRUK6kcC_-f?9J5d zD~1~8`Ek2`e^(MIN&Lfwtc|fZUeRpk)T{|*m<$oZH4dR!t4z_Bg!?!hTwR&4#Gq$m{}+dys^5GH86Ng_cbAQ|9-zEZn*DM6_iW6Xw4vD>$jOsIOnKNW!ZnH4ymFV?EjLg->kx$YyfV6eP~w4b{YA&5~v z>#7uY+u7t3Vd7~=xjm{Bbj~p-?9CrADYDy*g*><-Df^qVu}KP>MOa%@8kdd+ro4vU zvAw00Bi!h>JpxmZ@YYhVq^Z^xcIr_R56vu=@H&uP-xbw%X>Xh2$|^7C0qwWy%xf80 ze3!p{m`Ov^eN}ELoUE6GX-FS35B`*C&Xu*w8J$21f zRW8=@|Ln;0RkEX+XV_u$g=!ck)h>DD>+d6hGle$sX!7Aj`r$*nL$c2>6m!yh?eY8; zzgpJeuG6ZUYG0twpzJ!Cjf`9MWTeNAL3@sikGI39$ubW1pFe*R1eP+divQcy-ya2M zOJ?y-^8*Nii)heQ#Xxft9y%Y-w>8pa)TPuG*7ec^Z869{mS)Tq2UYsz^krEkPePW1 z!qdJF6G4*URuGUZ-5U4nZdeD$NP&CHt=i;tBF%oi{jvG@H<%RVEz zA}CF=XxpEV_#HV`%ilg7ve#@;&C7~okGa@ugd2*ZC1lQ-@_*u(HMf(|H(l}aK+K%i zZ%L1YS3)ae?{oe(nTP!b}MhWos`bI$MFb^mwWyO(uV>zvN^9p3kOpXc*@p3ldXnThb) z@{D7bdG)15y%6vPezu1}DGUzqS%{j){j7Q*FTOTAcJWR()TlnN;4L@juYI|7r|Zhp z2H(4ojh8_nnV#sakbtU4r1$`TZT-cOR}vGKn8-=N!f{_K#NYX7ZqGK0sW0paNl9}s zn9~h*NC_q_AB~7L5orB$Ufa5OE&BN9dV9k3yivtvwyUtmX8kL!@LKPVkJ>?$`n`Gf zH#t}x0DDK}N>d<|B|%?$53DBzHt#{gTEeF~KwI^^@U2rJU?<)M>z%xYvUaI<@`$q)N5>32yTVfNR8M>h>gbm$`@AI&_>?%zG)!YZq-oNRi>a zC&_W}&_>mV{J`=~OG7hNjfQZ5AS8#m%uAZtS+Bm#{W|k?kiBXko(~#*&nd}fMw`37 zvyM{K$p^>9LBa)OqMS;f%VG#%hb|eAHthUf=X~>d#ha$QvHP%^#ER+2FspT{x`}4w z59ShenLZtdNHXS*t5maL3EukZ3Ic*%JFJFb=N_^m4cz(C3qQrJL4|vuUO7(~9TQp8*j3 zW`S9)*b0*12$^^?8NiMF>@b|PbGlxaSrB6{1i+JyeJX3Dh`5dXY>4G2O1w3@wU#qy z2ITGXofD6PBmm6Vqrp>HJKGwqon}5s^DSo5H*2I_6tcA6Lh{xdwO$Xfa|9tP3h-y# z_-X9DGy967+~?Y{yp}I~Vg*R98sUsgwLEZ|9@+9~kE;!}g5$`aiUxZPE@6ITKURcn zIR555nNOz{W&z{*Ry#+EIXdyWG|irQ(P+Hr_Z|t_r2Bx4UU(BnQZ1}%0_4bVXVY=3 zG8+w|S2nO1HQ=KpR9?U-hzY*WWTJmgNzoi&sQBA@NF3Y^k;ds-{tzlaD!W-3#eMpnC`Agp+PF`M3VdmaI z1scUasBzWBS9~z1b7Fc{|E8@YxxsZ`D*+cp?IKIg?Acc=r;g`3WND8BA0<`tD*(UgYaXPClwoZCJX0Dt@c*xojZ|h_(SmZAJnm+n&o%~&wcU^<^QH8~E zg~dlp&&^q8tYGR?nL*6%IcDILv4fN&Q}ufz%i?Nz)8jnPg(b+cOX9;K&)tb-eoFgP z+-cEbZB<#4W1>!4Q86BP8$8OFSz&&m3p6&6n!tSHa(O2-cVWIhYZV&@soJSj;H9#q zW;nLjtpt0WfCb259YhLHUj3)){^}#-@xw4Qf>632AMX5e(TmcQ$?p0v^ni&z27Wd; z1r28HWx}1=R!-bhm05tNhJ7uSdXT&K4Bocnsh`XW-E}<+DT$sak3Dts9RV`EQD@ZK zt6w$LNR>yuwuH{BSzKiNIf?}lW^o+{U~`EbzG=XoX7G{Yh{n;VPxs5?^@Urhs!RcQ zva+%ol%<0Rv_l^gPY&z@vi@qUj0_-+(ZHs{Un9s(&QXyRO$&Hi33xPQo9WV@bEycm zlX0}ie6X=`7e8fd=l!n3=8bvf!qDb?Bi3V;e6Ixdq5(677<0jMySftfUSTN*gD_#T zRAE)-miN(T*=C0BeL6#PM;!90wQ-Z+Z~F|*B1whCymL->{h9iA3B`QuE}UFHL#Nmia)Y0LC2n`A#B25^lfjV<5wYM7FT0 zi5q4`H18yAzqqIpf%5Y0kteND;7)UV_bYNI1@c%uc+Oaq|ncR7%kxrN^&y{^Tx zB5iYAif7aB%Pt95GkolkQ`@RN;HGM9d}zD=o?Yg4)82ZyxAeQ(NL zPg@XS|4WAb@sU#$9Ca&Btq)RyL*#Gyt=ZMwPXACK=db0Y`N1$%O+7d+wP917$1u3D z#P;Ls-M3dduVj$CyNI%ktNge)d65eqE?-$$8P)xS144fZQHB*!4zf}$ ziXJ4X_%4_o&^)I1;mlFZqJ<&-HyzF|o&gz5*3(|%vypL9cgw5A<9gXHAM3lYizn>A zSf(zCV1*6BBy_JyI5KmD&+x{?;%9!cG?Px^XY{T~Q8Ug=ny^Y+)fVRE)@QlOr$2nJ zk1I}1(RGN$2vB98CR{mV#+sttAL4A#~1I))Qo!JZ^apXb5b6e zY$5+8WPY%CnvqEo(2bOZ4^M*^OA~-j0DPI-dKFD$%pCJzB+5#(N2vJqv4V(Hf#`P! z!1+YGA?RWN)^)8_Ls&dW>0^<R;s9k@m>Z`lNwZN*wC9jF~BMM`Q zkxx{7a+OM_l1OaGgnD1NaMWFoc=eP1_m957jM*xegYY=Ex3}@1k4%Tep>rN_h1ctz zw0K0}MKI>MPNG6*h8$$-P-#}c4nNBhebP?EPy)v7TG6R%L$S^S@Po)3J+hb(6#B222iIis|HBaC(+4Y z`ta7JzK*I#ZWcp#^60FNsO6pP2aBgTU}!}wK6Mpa{2V<8MsnK`5>0buJV|kC?uQ>W zZ3S*Ftaw?fcHS`OV#YHRcIr_A;*7%k!v)kB9b;3;Oj1Zs?ZL67$kyZc#&TJniV$#P z#L<-(lcnaj+z#YsOYvWoIs0}ZI24v9q>&Kuh;-S19$c$Zm?TquLF;5FOqwIEe*A$+)oABi z?&jiyQ~oNtFC4OYy|&3MDZOXLUE2Hw+V)x=_%@wTL1lA73z#|P+?JGK0%VM&YF|{? zarN2B6l&o#q~T)0qZ&$!au`b!Twfm7$O^_$5$cbkg$|#VF)M4$nB3b73$@SuWG=Om z93N5~%4w83e#fmb>doefRk_px+YLwgndmD!&-`0On5lmJSUk}a`fc(_@$OEDN;6o1 zK3lf_rf3O`Y0!?_13VRl8_}`O^yqd&;N%>sElCMa{^25N`7N)tJ!|ar+hutP%I6KY zQ+ATWK2!h)PQU8|j>31ZWPEt$djUi*qLEL>X6XnkWM^9sJ#J39J)i!QXK16%X==ph zo%>|Z8~>#Fze1!)D8CESS4xopRSGm^TMH({Yw zX?dZqt0hd0TN_U?8c5F>$d|e0U~KFYGgh&HZpJPt2@{St>>(+r^k-fGkx>wWL=e7r zC!KsjOA9aLVgP|el>Alkl7oq0Uj0^17v=#GV-gU^!SV4%E?^QU_7EAB_s$*k^Y>R9 zk_C&9#p68U%&2yQgd3PVFlhnP^<#Qb#uVS4);eu^Y86Uv@%3EhS>PG4J?ETt7q;AlX6u0pIfzP`ysG78-Q|@X;o#i|BX{ z9w0GVU|SG>LBu5iAVEP4gCpPxnPh+X{EHJ6=NQS2?=TUn?SP^qcJ}`jL7{p&eTNuy zp)3T>2+YUw?>s-L02ZdsQ7_zw{93b_G8|`tiqHdcM@WSZ@QDhoEL=?zVt}O`fcE0I z&y$RrdP)z5(FH;u_Ya>i>EZ;TWcHWITUp&sklRl>E!7Z7yw2yAdmeGP4!u{P2fe*G zl%;XYxg+98M#6uXg*)^S@w6yCGGHx)Igic)Oy|#vN?oHfQR;;uG3vM)&)#Y!H>WQ3 zbf&P(N-V8?`#lOKLe!iKVk7+dEWfinA|xf;D?r(y6RnBUjD)ZM`-AuQbQSn&sNUgk zb?@B6;8G#W(U;bGp=WS4tbnl~wlMmzk!l+FmIwhk^~}%!GuOs6`;I;Zh4cXa7GB+Q5hn zX5S@3?;CZa7ndpwngw^kk2O_z0o@ZqX=2$;_6x>iKv@tRqth<&WAHcr(1}4rL3ij2 z?_Re3D1{0ac%OIkWDOVb*9P~-X770fi3myaM@qgYP$>{?0{%RCJO=w%cW4I@ll$ZT z^FA=x(HE5Tm7@4z#M=A&W58tUo-2yMFLV`o;c&sJ+QKM-CnqBX7pfzu$eC%pt8SAc z+St@2EhiTZQZ8@aym^0ISe%S_?M@7pa=MqM93nj?kfVqXxQn3e2hukdW!O09+jfqK z?adi|9dTU!{TGh2ievuX!-Ip2&=X=x)Y{;sXQM(K0bE#-i@wp(-C*FIDBjNBs4HKd z17RQZ#nK82_2wupJnKW7c769JvIq!Kx$rMqN!$~HJoNB%Wr)}P3)E5HiwF%sHyTzh z+G4lA$>DGu@x&eQ=fyCR3r-j6GtI(1LVg5=I%qafol5=k?-f11#RLV#LqqXoM3c59 zt_>hE6uJDnchnet_a0y_+e^HGsZ&7MQfJjvNP>ADcxvtw`TnWT8>m7=H{zU+d4mq? zKac%pmYZi+h({JoN5HfH&-=KURcbU8qVb5-E2Vb1v6P96sqE5!_X`!Q$)UzUY{Icy zpcaIsQp5Gfzq}k5`$ZUVIFQZu|L0h1UFA&_QvH*2XQf!ZwKg(uJk<^YbexEj{$l1F|t=hu1$iHWueBoAW1} zfezxArAC!Q`)}&pcbe2=BnMx*IcT(l?#S2we%Il7LEH#?F=?lO)4uQCOGw5^*3n2~ev4`@a8=TS*CkVPnTgmz>}P zKo%$v8#x#gZ#OWA#Sgck4ai8IZ+o&d32phCCr7`U5jPQ(TYCS|M>iC98c5ISV1E~BHl&i4nt%4#S>>mZ*7PIpT@MTGS>Mvq$Lon4UIHG z3xeU3vk@YQfo(9zl0ldRQG@^d|5u-$xESjXbSGO*;@ctp_wBUv6I@Z4fvI(e?3luu zM&kO^&CO28@^b289rZU6lE9cR{>O`{IQGSGkxOeIr6?xWxnV6$_TNJXGqS zj6Z=MNHbYQai2eX0=kBj{UN#7p^u9v`SV<0!;ktytR`-FD6xPXjqW=+cH|&Za_(d4 z#10Y&*UQVx;Y`(xL=+51Gfplp^@|{fL~tfa<^W#g|8@|~ zZ|wLoe?9M!GjJ3zrt)$r7z}(A0IQZBt=fOKiUZm8w%`d_T_g4SavFHsM^!N9*8nsA z=cS6vTr$#nar6jSywzRA;2qnYT3}zx0R99NQu$8A-r7xj*P7hpa9`8H+$fjxBOYakXHbcf5Hn?cF;Wjfo z8ZjAxQ9DeIhm#C213Iy^V5Iw^QIdrjS7Z3!V?q#e&Lb#Z{6$+e^~8(6y!E>)WboRl zX~~Rn&b;U(`)4aqzT~mvh2}rd)9#$aFu{`viPXX^r(~f3@%P91>(0+#dBFPs34MGz zn&JBAAY;mb{+-B8?e~Uo;gSdHTrilvTXAtz$YcynLVCE9id^rIlEwSg%L z%nGOeGeL{Vkz}NNFDx{-9yEY{1Mx&O$cJ6`>(|wLLm&R#Ir9p!T6f_KR6$tpe>+D` zcc@@l5zgg#1?>kzSlT^F^Qx?4`cbhN9K;~QOdaJ7E)VJkY5#svkxTvi)YFy08&2dA z?f;%Y1ov-_ee0qY84Yo1 z+5;&(1KuN#@BHrGpCoH8)@K?0UWvbr0~2$x^$h*fBbV|wS}RuX8j8aR9ZZoU&cQZx z(h||}0R~qPQWLFZm{x3QVT*F%G8}=BD0_MT8;77Nf+wUfbL$H54DV*D>k`R$gs++y zCg+@J-v-*5FO17@-nz@($j;vXej|9hb$TY9nPA;>`OrW63@^$ShhwCUa{X-$nPqq% z6$W3{f&Je?IaOBcVt!sK)8L^YS3L$ZUcvdlJpSmz(|A$hAl}mVat^IWM)2D`M55u0r?Z=oV`pc#F*7FK`6BPi-uy*d ze}6W}-2l;c-}Eg$g_vrX#@1TW5x12r+D_H`=N{HNeF?qekrV5Dno=c@1%r?F=Gg}# zuyAJI29d9SuA;vDhFuk9Czdf$3m{Fd7Gc*vsjufJL=4$@b>f2Ct4$C9oquw5`HB8R z!<1KxOvyd4y2;cSxth;m#`{qv@*HK27ONy_<>CB^F(T#K~frIaIeEs%Q?cs**+=NqyG) z*Gq-*ElIYJ`A5KzZHJIvkZlNj%ZHSu~j-jF*&*s8bFk3gFA0k&e`Ou~AbH0UJ=-;c8+1d&}UhRz4c* zrt3t(&3YV+W~%X8@ICeec#a(Tp<83{mH&iKlcvkDUx(9~+{bXZ+-^DDn!~~QF^1w% zh~WSn=jRSGOE4S0S^dxJ3=lB}9zuY8NLVEenW^rv^lNAF*)R~ zj*rvPcD8MAD?s9+b@C*%B?gy73|MB+F<(R6EbyP-zU6HF^|eBXFL^XHId*9t-pX#$ zyh2uXHWG%S6Ik-u9&R!`aw3E_W+!yO)Ku%t&6){0Y~ zL#KQC`lzo0D?`rN@t>TiDYwYQzbuEHgF{+HCCOcm=G6vQy$oiYffMc{wSQr)gXXa1 zw<~Usg~ikR=quuv%v%}KXc>lFSZK^3#{8{=*jQvVgrvI=x1MM$KM}CUL<_e|y3cgg zw{=y6G1B6f^$~Ga>LB1`fEca!Z;HBvv>mrArc)*r-m3?Wg5Ar=0W~tYD9+S3x0po{KQkI47f|s(eCu| z49N_Z%k6&rN~IqgUUz%tdsaU*pDAWLU!+EL8*z(t()>DN#W}Jd?^`WA)3SdLlNHX8 zgDF{?Q-{30OFKDQ<2ILH`mB(LwaT3yL{)|C4|@0Yg#JQNN6x*^dU~LG#X@>|{rYvS z!*Mx(()!${M%^KElG$CAPD;$UtabZT6d>}*)E*Ix)$X5bpP3Q3`YrI zMZ;P2mfFdaJp&R+IqGAZKDLA|hrTwy@s3Zaaqa{Sg13Q;QkpJ9-IaNH&!lDh+D~@1 zJhXdRC}!Si?jfW^7E9qpB;Yl4!~M?Qi*ApME*^MI)#zX6VQ*_on&Ei#^1(M(H>`2kJvNU^GzkyH0N?FbReA8u`kd8WI1_?CH!P-T3l9R1?crCd@G!_P_akCa$(O7+Ha0epyDhSuTp9f6{B%7;z{D5U7B;;an=Rw*Gp04x%%fr`!SGq} zaSKjO)sTZQhH0-1eNpk|+tg-Afpd@;m-WgzzqQQT#~2J=kV;aJsn?jIQ&}-Om1}R4 zkzaSi{h^oLkV^oO9!?_^f{I+Ykm({cxdHV1-8DILqiFN^eX4vDBDsO%|5nIz5g|kF2c)`^&A#)gSJ< zUpBS$7ocp5sgC=dD<;I1$~dGcY|ch2VnlnuAO0z9!M64jW2Kw1pd0fVmn-uB%n)C? z{xE)D%(%rBn0?eCdoM;n|F~x{*be^n0xs6bKdjh8fv78meQ) z%oUhwLd{E4Nl2#m(N09zUU|+Me(WIsOYZHLX|cspg6zx$zFX31gV=X>Z50X&Gc~II zh`BoRj+Q3afSrv+lx-LNmr(xlW&F8^$h@K(#14@oOJiU3xrdQQE)KL|Y0-QV8dV`~ zng0HM5E*gY*G%?;*Es>{ug}tKr3w0~Bd+b0oa>$6uja*F?;1lG&)eI;y8Y8-h zOzJ$f1t6TPgXh9sODV6Vbx3J_e3%Y5uaUK`CwjSWd~|-Yp~O$o*=g9wrD9mh{Kb(& zq*L>udE(4v`Kucul&WVkv03`kX>YJ;gWkobHBXzC(BI2o93j`9ON`JsMQ$fZRh2?s zb8szWX3Ls4%5~yF$XNINgv8z`0fB72+~?`<8tqM!7)qBg7PPHWr^%+8^wngA1@TnQ z$-PUf=cHfXwHGU#(|OOK5vwjm(Rh# zkO;u!J|Eval%&CofFcf5he$SO`^mLkdE}0c1_$dlkI7+jU(Q_wctY~$3piWzuYPxl zX3~AW9s()`S!c4d%J(wTm~o2?F?8(f)ac%hDID=YMtDveGd`=?s>;giIAv96TMo&t$67_oco&p=&Ig+O7~v zjMyMk^$VHtHy!kqrQenf=L58ZJ~_#7qRYSh-kKc4cbO6~0<3lccTbLhRmDt>REMDr z9_=xqZ^VXZe!!R^wQRNj4Vus>?Y^k8v0ppYa5os3EJu%0On+NP(_(O#$cIRQauj$X z5i7;VCw7kj%@%9`A>KB&Pk3$t^4zkpiI4LfsUT`jGpr3G>NY|V@(M-PaKu9bO( zqH#|2?<#hVZ9Vj)FIt&D_w1QrUzXYd5dP_QfVVo>ej_-0WG}WFj_@+4S6fNErAQ3cD)ixSrd-|hk@))an@0vbV$>9sV zC_4<_h&$Q|F26DI3!19csCs23v*s#RJmXAtT4AurrvCdCdQn5au5FpB>34m>Cu^*f zUTHK~!czex!C&%VTpbND70ZR3Egla9<)Hk1)8Bwa2P$Hyju{F{cZq?-8e(M2`3J8>rKBuO zC9l-l4ml1*%$HC59()wX`Dw(pvxvd}U~J6&g2|gw82qV}``mnXo$=imL^FX31l+_v zW?ZvAPwpI_kYu{%HL>o4zi_g5Q~yzr=|ROTJ&RgzyMW&C(C*c%3;LgGr+;?dAe-XM zbiH(-ab706)Z=zEGgqnyPkhU$$5yk@ICX|2x@?HFNb(-e@c-1UfYU?5U0g!li6tRl zophflZ?erGru9{wBOS3YHnO?3H3vTE4@2R>%_5;|m;!G7v2b|Q<4fzR(5+r#^c#Kp z%O4t*(`(0IV(Y~VS~Nc$^6~r~bwIf5e(6EcW^Zqg*#2P<8b1Ybs=e(08uEy>#U@F; zuWJ(@*N_l}pDlC<63bTWzwiG{S(TZhMhizPQscT1krc54o2j;BAE~WXhvGb+oJZ+r zDFX*m4}<+4!*jwtUwwY)7he_IN{#AGyB-%MkY`GR39Bu9t3o@`?yJHXUv>~Pl~XQ& zkBg1M`E|WFk9w|suJd{TMRk{--QhVa-8asytCu)2N6G(W_6Ot7$+NtX)m2CuYGY#} zTy4kN#h7J8K_Z;i?})V6YxUbVlq4i2ZLePCL!~GrP^RB5b=xs{HLvdl6`-Rlx#h;< z>1!ZMEd-$lIGJ5_-!`F+gg6JC1O+$)e{CoK4zjqDoRhh-U7uD}a)kNJ3kfq*%i4&U zLM|1~j3=L^9Zsp9tz{$FsCV0_YXn+q8D_d3;ZpxN@In_-Mow<-iMsYxh*Oa0iAazZ z(|3O!GLXTDjnH+=N#B&gK6bV`!a7l-oK+W--mzfcDt}%Lm&rJ+S)+-g751Y&02#s2 zO@AM;Ezc*Di@XG_;*xkYoZ#)vh$>@9hTDlKw0$|f5MY}g6Liq*U*QNj(Ao*`45A7{ zb8Q~dpW?}E5lS+M!$@9s4%vAWm8DAbqbS94R_Qv(xp_=3LSm!<)>bff3+9<#E}_7N zzO82;5Wt?ULjnB-z&BvvYk43X`l+0Je9wTpv!}oMV>B;QC{OF^UAvw7%AkgqgWZla zWBBu>A!51KRuhHG1S8U)R$S4y#G_Lczc(4yXhsAx*y^g{G7I_=8#K;kI6~Xx^V^L$ zGPrA;KNA&sI^#+D%k{s#$u);G3O`}eFJYy7X$rWUdv)q6jdmaw>XS{*$syy#UtnP}j zQbW>ny~qVjTDGG{(c+oAad-}V*SlAqOeaCJAr>DC3ory|!ic~Ji;){2a@xJ=AO*Q94KS7|BBvOy~~OeANFGK%sGpO-NaBZ`0A5p0^j%h)10BlXFJ3 z-3@T_a63%q6k3t3K72eKRUI#Pwq6ZI91qc-MJuqA&#-Be(bN<7O`nS1~2)k}gsG{UTIqPD+j>nzGq&OR4 z(`fhVGWfY^*Y&j*xUBg0i_}F=af0^9Au>OTrQ*GN>q=*DMcA^6OX)<%oM~_OQ=~jl zbWZdy899juSH%K)p(uOzQTqDECCn5jgSZUTB60NzP=3wk3&`r!_=?F9fdGQ1k3T11 zrcgR9hB6U~q!Zpk{Yd52x+7|6)D4sm(2{Iicr_agmcJO-YcLdFT}T?*x@zz1%Zw=b zkuW1koJVzWAtjNJlA417zAnIhCHfm@rD1{}i7>=x-MKSeJsq=^9KT@ebTI2H7OM3o z2mAX=1rBI6lr|NID(7Gdo@lh|%VZf~vjz!#bWX~TUWPau_TT@hbCbMAOSncW+`D5v zByWkK(1v^#SH5I-S$g}ozYH5~ce&|TjjBT#G4Soj_{sVBPqkT`XT$k1Ri#7@uHGurUWZix^kKz4*qFVo*&TpXro}}sAr;Fi* zHw;-$5K!b%L>XzBfrB*!#&NnJ$4-RNl;6=Uq!env4S-SA>@!ZMuX2nxDZM(`zJ|@N zhP#9xpM&;77h0NHO&fyyMbt>}jgjp*ED-P@JI##GNHOKk=OJin&rP*BuQW>eHoR*z zGH6Paus+7h?XApza(C0Un3c9W->Q{I&r&=0xk)+gfe=&r%5#2|=N|E$C!1;!5X5sZ z4vW;B6xj?cRZ}3`oz>5zP81x<7`p*j^NIY$LQ5$yfsIrz^awtS^E>({SX}x_;-os+e}3!qpY%V>`Y4JC)SzWwmVNhkPWDz7xc#`4qksm^d<2 z2(k3_F(XTb-=+2O&v%v0Bc5VR^XdW)h+s3apW%w zawU2$t(TO{ZB2OfD1UnwVR9jq4G}!op~Z*?6a{%_Jv{$lt>INDeX8Gl;bXiQ1OiCx zJ1RpgE$gti>7}r*B(k5gzBBK?pX#%baXMaN#-=I0@Lqi3$L5%F_J<>$2k~)(!++J! zG~byTq#_Fs=FOq(itwJ3JHQ!lC8NyRCzbIVJAfXFxJw zCBsMvuhWyXrBe2giN4~OAbgb8uhcntec_Yw%7cxhEz#+3!GXO0q!cbW&!D2Nkqr9k z6a#$>C}sc(2mAqL=M$IW@K7WHFW@DAg3b0O9Fgl#!8{52EBhkx6acTsAb9EPkWS41 z{*EK%&WNhVB0{-JL*45C+WPp9$MgBpQU4BA$4EU(z3eJoc=E*s80S(JL8vD zjiI0oUlS}8kIkkxq@?waWUBs*GU_hvS0mn-hwqFzl^%VgcuRY|d$5q%MhV z(aClKxPPalL;?JVVGN9kI*JSR4~XDCEC3L&0CXX6?l^$+@amD{1P}}$L9C_On($e- zP8EjZE=1*NVeMEQou+{|U}&}=Gzk)tCKIu#h_2Ua9ox$Y)YKNsXo>t!Vg&;+{#a z%g0%}TxTO9D@E-XlCQjFhEwD5IvE-Dm@=VY*Y#?6W=jNf{`buXz z-}W|#@s1aGs-f194l6IQtzfF{mk#@xtV-y+Gq7pJb^baZ6$V8wi3J!vhSpV6EWUo0 zS`XT1|K?O+nT;2t6^0^(Q|lAStBsUi2RPdKVMuIt=*}-$z~te%K?KWats)3ApvDh~c84pa4+H{tInyyD@ZrkOjxt0JCpA@?ixb{)3KLD0n4 z?J-|pk;y1#@v^L@>a|RB8os?OT;uq2D;-{@EWw4DDsl)Af#WPzm^COr`EIBRU;Rss zsyWOBp9m6<_AUoSg=7=zuO1)VM=QAFCF9in#p)mw;@oi03iWE)^&l4fbNWRJgw%td z$h-n0IVt}6E8rp?g9I^bF<2~JXDyT;s%?M@0Y^w1=1;Ms2&4INp+}(Tcv_nc>^CEJm<$= zPsgdKyxLc-xeqd*TL<@?KghCS#vN5{ar^7cUAtiK(GLy6)MVxzn7xgMV;Dkji<@_x zI~v5uND$EuIjcT_W2J~ZN@}Z%3$&z}pg&)TgbjE#sG7 zjSm3kDsJ|GJcxVPDtg#RFBUjh^2vI<<@@1J%@31BftJr~)H}V;b*rj(UYEOX{FRaF z6y-rO3n`E5wTx#o9P8wpD8fmWKr;R&VT`#sfkLB7LoA0co{iyp6gu6NaR zJx#7+bsq{HE^C`4@63vjR$MdG!j&33)*R&2bLG@2;nZ1LnmV9S6%4(4Z%0i>F;=_Y z6DyQ|vV|w?+V!4;)T91Z_2m|$t#PqS#y$m!kE?iuie#YYyt>#!Srow7?5q6cmB#n`2385UKvltD{F!mOM4|v%3;O3e z_0>Be;-8dtu4SdoWiLD^apf&NRKduD3Q$g%s2*Ng_~ZhAU0L+5GW(ASpHQ9?_wE{& zG9JBr>dhY>qeq_bDSunoZqN;P9;%P{L<0EZ(-DzXoGitf(Ef zaJVBz!-{&&wjrQBT{1I(@3&K3z66zXqPBBcojIH-ZwqapYFJA-)KFjV4vXmgUMUHn zU}pXf8i}^MNKG#jHRIOT92Z!0sJ4Lxu#N~Sw$3;kY`}%ZDX#dJ8%bO*zlClur+;Mf zU?DCV`9S|tQPAmE7-*Dij*In-1}qUoW8-l6krJ2VVAOE)CKCd+wjr-ZkSes>mQ{>d zHKE?5>A%%yHvBn_#-fDyLj>9-AqCnjx^R#gWSeLtS)9(t5b}N4+`TCd5OKQ zG&Q{xG&f2ECZ#Q3ooxMtxe!p=BkS`SZ%``Z3ee`;@`9%p(3(qvzFd;&e2m=&Vji$+ z5}Q#GIkZF+D)E+MgH+oSkEW4o*!=T$oK{UW3Q#$J08U+6k<|GFpL zdS$GsSk?|BK~s#mpD)%^i!m%k9CI&z$(^b-U^^_jDLRz3^wI&D9an`a8ykq1(C)o5 ztpBONx3`S0Tjc}?&k^=iMw+;#q<+rN1nD%&U!J!-`dT^vuKafUhdpve_L_pb(caG3 z&_@t-9_ZcfKm)`m8X*wt_579mm>V32=a5p;`the5$LoLp+7*m%UjB8NhXVjH)cZ6< z5Mk5~8;wZk$%o?sy_F$B%bS+W6a_~y_5y{l`o8*?#72b&oQ7tvHk&}zA~PXlkd-Ni ztmb5d{7h2mY!WFHLpM@C*xsM9yG-cn3cvm^E$T+UvDMeq)jf_w8e^L&2Ng)d)h4`j zO`tsLQpYIT$wa4$N8eJ6zQsjfb0}rM0Fh*25Frh`nUyxI9siI&FYFW!l^<&wAs~&= z1JkZ`e$D|^rfABwP>dP|#($B|dI$9iymSF9JtsMjSt$Snrm|LCr1d zD}JS3wfsHC#Fz9fqvp(~N7td);Gzys*0|lS`l$e;Gr6hnj>us_`7yw1o2Y|I158T( z$4Pp2FrG})!1Z?kPYmK|aKS3nOBIF_V-{(59eJe`0c=saWR>q?k-G2nRu$+~zAp)( z<_Y4-pi|5=mUcaEb0yKW@_Xbo?t!hJmh!JXXX75?ez;yv6}CFRza15zX0$>%VG{iczV9g!fxiDs zQ3O!W08Nak2wialCe+yIO7_U**0YEAvN1rm`1mxtalfa(epyWXhvBbrPxEUtPPg!8 zu6nBs770Lmd4wG2A19faV|pYi_$7`ptWq5FD1Iq{;=*J4?fOe%3F;zmHL5ikSZMZ& zo^Kb}-ASNZEGc{|a-_Jr(N}ECjXxc#Xm1Rm#OB@s$^*o1z5Leefq#xRk#D$($ldAB zfE8L_SvmRxEJ1_-1c^p6aN960mzN#HzT6P%erbZDkM!opVq zPJVEp$;il%JT~PycUi?ao)0ao`?{9UJbq;^X4w3(c^?B?f5dXxZ?Z=R$-XNZ(TdcL zSAN)XW>g?gXJD3%;*ZR=`g5c?WLx+=)^{XzHB`6Q>}z0AjA!G}>^xbwG}D1ceTQBY zP(*2$ziU)wRoXAyzE5G(s+q)qNSn;y0le<~aUWM#DAr$BM?I{G zdYE=STZHCx@FGB$Le32}`L#`VVp6$K977O!xqAbv;fcxxW*`6{a9j?UqN=b9`7#(8 z_IZ7=I@?*LA;_9279SlmoEkB9-zGW75^BX>T$OLb+0xZLMJw$!$_~`@VFGJGi|YQL zBc$2r8c9X(hR3%XBL&Ef5W>reHFXd{@}RWcL0bIfH3AZF6V$qK7o>=(g|@5PG= z;7`Xcwey~8W#Bo+N!u-De5f7@ESBMHmRmHU>?X^dR6Sp-%mb>->7!r9k$FQx!5u%z zb(1jq&}K6%>87j2F{_1qEgY_?e>`m2Pcd<0@zp$7>28B!$8+L^0*Sv7+p(bpELrrR zou@4%jn{5vzOt`-yLUrWGLu9#@&@CV*!a@exMR3(B}~x`Z*!cjQCC+&q**q{$5`jU z%DjT=L#{!b0ZPJb`!y@rG@r6*o=A%4k4iqIg4-_MyT5%Ol|iNV=hUzv{*3SuJub#{ zo!C>ya4DK+EThPq44(1<>z4}jdjZUv-t=i*1;E~%<7mRg{ zQ=oL!IJp}s77sF9YM_p*a_8hjL)Xnz zXMSefe)DFIo1Z&VzOp~kYYrQz6T1)?cyRigSMcF_LP#7^bO2QxQKY`&Ipi7_yLIAJ z>c_ptAdJ)FGqMAG>Rfx^PFic<@^;521(T44h+&!7B931b>JV4=B`wd38FFe{@rrWe zCk-k3S@UzGgR;N6vc4Y3T7y?bVpD3xge4iwb{T!eD5Sxi??~kR)TC7Y7>jQKs$nz~ zg-I?47ynEjV40ANIV7#H9xD1oN5-&zKW#% z?2Qx~qf$N| zZJX+|iO>fj!d}ozTq4{>BGYq9792}XF35UV6S^iJN zb*#-I;gGSs5FN+Z$EPnv{oFEb?N@c=+k3G%%V*k0^8iCwa-W@`D_IQY193Z>2{~Xr z_*p&OVK6wq5h`%OM;h88W_0{gWpBmOG+D)|``p7g^hFvs%s7uVZ$Xhj zoa&W?2gg^WswKR(HRK7#4d0tt$We#gx!vk4ieJU^zk~o1;V5^Ibu0EwM zrNXjRsP7x;(3b5uy$r>^aDka-^5&yPYB&x8bH*TVCKh-^3Wc`CCp9qTsy0&Z-atnS zk$7dCIW8&lXNTYDrCd}-*Z+ThmuR>MrLgjLwhkfP(dkt_CD7M1zq92 z=zO_o7Tn7LpHK-0-ZMqCXC%n4^xI9TRm~MTkf&P|wfvgQY81CAIPT0L57aU&VDaos z!y-VNAut{`T|El93y9beW!pc#ImmN7fHn?C25M>gMzw@~AhhRi=AmrWgk9eCPu{5iD)p7%`xM4M6)9XHVP?1#f@E@YscWBt#F2oux zo2^To8SqWsDpv&`)gJA08fTlxZqAYuTAfT)q?{zqNM&W|?3?Y>A)qFytWp{sqMFk1 zg_A&OqR}f5!uf#!?PK5`2$t+?*Dz&i$o!<1w+G_)@mRd6N$_96d_)2caqNQ-O+|)U zsL)tA?H%*xW(3z~E~>kx>nVqufUW3#wLCnI0)dlbcA*NkO)9=3PuR_$!?}Eh!oW&h zLby;_6gb7U_fB^HL)thLkGqn-x?60jQZ%HdISj?&r*n*!8MKEf`Oh$XPTZ?Pl7b^$ zuQV+yJ_jg;Pk|L66d3%zVFp1XhxB2-A~9;9at8c(IsJofQI(Nth0Mf6D=5DQojK5# zL-Qj!qE1dupf3&5Jj4xa5jsT`PNK_Ha1f(t->!Lbfu8M$bgO~-X;+1;eyrW! zT_m1dMdbcQFg?9hDI_UUFYz}7+fh&jpb`ZXlT6b z#!U(bj=Yf(klq4q{QT0;w0{7p0qgQ!(<4x(mbJlnN3oiCIyLGfK-<`wwUGDm~a!d!_}AnoWLn0&0~Eq2@r{6`maaOF7Xt%xukW8morlg?<$*uFmvA$;rW$BOmeg5_ z@8_evGT&J=YJS+iOKKkjlhyd<^f7elYK)99V}#~tV1}ZjcF!YHm{ma}K{V*`Cy$2- zuS9F=qc^qk0s%=B61^+L-n^pl36&R?bO$UY7A6aP@#C$IKEvfr&L1wT0PhhpFd!=! zkWbw?$~b%@_9NKK%6xA!O4xMfTp{=rTSPtcwle`b4v>=SJcM}Y;&7X%4f;wr|RVz#R?MX9)xe10JKqDgYqTp$bg zo=dvQ3x!MJ9Ok_D8lm}mudBk%zH$GSzpP%JB&-?8h99p5pT|H#Tg3_3-Zx@T3UB(0 z!-JFdRqfGN*IZ)1@^WZ|S(B-;T>kQYKVBf{xPQ;m$<5L+%QD3RVY|aMcom*mB2h@e zQz$Y#;()DT^@v1@PJR`;&* zQ*oQ^i}!i84^V~F4}x^6tmGj8u=wx$VzygKA+hr{BisnKjz*0w?k46}&GD@JUcoy`~_!wcRhc#v; zpsWpC0ETJeokwx8T;R$3;>8QqA=%Au-(dN_5#E{)J`ks>Bq7L`0WU>~zlVV$okdMy z*6_;ozG0S2`%69Fmapz%>(}W1Qki$5G!N_TgikQl#z_bZj)~j9598ZxJ6jAHiAC{C zAbvwX3mO67_zNnZ9-FCKbe&(Mn|KVB&)ho$Yxp^PL`e(~aK_$ocNRVAyh?;~>xRCX z%T_6d$I3d~9rSXK3P9 z73;zJh7D9B%tJLi59)89xjR)_+BURp0h(L2VH$)e490bO-}?s4oA_x%E_7 zmc)tC-=nb&zrM6m)GCi*fj6$q(Z`|f8dGxS&tjck6PaR=_F>1+&Is4TI`Q{zUAm`K z-B>_~?dj?=P>8&hvT9 z9mSPmD43v;#K}9Jk>v3#xza_Mb{RS1fbRAW6D?wb(=CM}0v@TyGm0-AV^I-WQTn#^ zsX3i*!Q9bB)M17G3oDqse(9&sw<~Q60#6|N`F)-bxxdZV`F@{T)jP3a*{dTcL0NxB z_2V?s&1|$>+^c>4bZcI`tNk3Zk#2M9T28Abur6D5mQuECT(hIIV4d#Q8<#npUYSts zQ1fS@G7?PqWSC!Dzr_2fGP=6n(0`p`EF%6z!%B{Osk$)T=DmA9hg&q1eDRYnI|9va z&gfkju@tT2Sg@!OWeG19jzspYKIQCVt44Qw>Bnito0I)J8N|WvgNJC@zNUN4i}tH) zu5aG0F}vbm+r(|I+&6c1Df}j~#U2MYNlC&tr)^g7AMXQ5s%}c)A6nLBs*xs&@=jtR zQEz^d7v;Yvd|}yMnAiSQQB+7Z zmeX6h$2Q3=WZjhx4Ez@%;Ie3G1HG9U*Oh^zQj*(RV>X}?&!4H9C$PS{>CutfZp+R} zpgzRJo!p)n$}EWc-HI`m-EnKC?)l1F3Rb5KSNwexnx~VZ0Yu1GFPN-oovo`6Nzri6 zE%xc1&PmoRD`zKV?{Km$k3K3)jhlc#gz9UPrnaAzE%W#|-RCC!MylVNW zfPM6cjx2`48gn8H)^bvMn650gn+rUT@+zr~H7G*?$AbtLNoge&$ul$^Y_|Vev2%*P z>wQ0K_KGbni8H&m$K*Qq+b?CT{9@I~(R|y~+b%5ow8ZSH74t%tFk70o)bb@x)mK9O z#^=*rdu#0PPR*7{xK7@dW<2@qN#(ugZ+~96Az$osYU}=}Lp{pA+ z-OnO?@fq1$C*N&zwO~jXePfzlJ~G9%`T8y{u8IM>_iuO~8458(E{%Cg^+AtOa`gsaPPz05;7Ut&4 zW@hmmyXdK?6WJG0%r2TNrD(mf$>!qZEF0jtWz^@|9bhD56VH}i7ge519TJzIbwr!L zB*`#GK&YmkWl*PaSG45X^_kA4D>95iRd$A|?Q9Ku!$Z|yyeh0yusOymJF0z8{LD@TIe__*sL z;jg~OcT5z%R$cQT^yF9Na*k{A0i6Ec6v~5elLHB7coStfwkdcVwfkEOAbXr+gPGuB zib4S1f>JDair!b3+T6j$*5OFt?h_r_;#@i}l#Vcqt;%$IrLM|4T;N!=Kl!c}Ied9x`Z&#u$E*X#V{@~cj3j>$8NwdD8IM)^Lynf0ok(LX7F-*ojx zA;*Fh!FAOc7djbe(vRzgp6sdNFc=9up|3ge>;!Gtatejw<9ho2yzn9lgcidL5Ikq)A?$EhIo)=Z`Y*evz=&IC~EG!J!csbXl zl6%6!B~2&&n%?fWj{55+)-JF2IOE@E=P1Rg9kbfEQZ23Du3oK{NqpLnKCr4o$I4y9 z;PAKaN3tE#-Gg=BPAXY3;yEbqH3oL?0#pX zm!Ik8+@Ge)bJRnmma6dguH!B|0aBtvxis5agow4X5XHgp~t4n*h zwR+^h#X6fafmKnmg`Gvl_Nv$8J$~ME9*|dHvgk_=R%)YHmfRZGv#V(^#$L6?Q1`qc z3dww3SgFf<_Xl-nCT%T?I_Y`!>dEakcR%M#KbKS9v$+l>oX)>~*zeWO=z9{lex%W3 zWm4Au#Jn#u1_gex7e2)vVShYjn9Z>JU8bc*+OhN#Vxh`CYULck&pP<8$txNX?V$K% z%1Bdujy_O`M^mhxvFRt&%NQ0ag5$4v_G?WyPs!Y!czV) zd9NaaG%dN4Cr_5Vp6zs}nLWtbsWZaXtZ6kPH^IW>B6)gRp>oeKSF>J^%Hf-O;;EA2 z0T4n-8_sgSt2ak!@T^Z4BmjBNn(v=0PN&;1qUx6{x>)aFFTSrW<+)Y9+ScuXwJ*P4 z$}15XSUs_wlkuf+b9ER+u!d2+E2u{bJ6RwSH934K_WoCX$)7hT-}I(c^kya$_g0VZ zvZ>rPaYiHUMBQpVhso`nWIZY>)U~yD2Uj4sT+}IPZ7h|!wpU~1aA3QF2Ek^Wjooa>#94!a|GGwni;y(nCI z$QGtV@ zLdK};6#Nc_^5iId427~p(8?F?Z2Cj`le(AYEY6qj3{Z16u=o!u8B47g{2910d4K7K zC3iNK$JRG!#vB<)u6sJKB_*zCtLJMKpm#w2vazXcfuD?u*r!(vgJSf)LEUNQrfHn& za`~sOooI=Gox|?wXR~c-h=Wa|80xYyoL^=6+MmH4j=5**XEOCNiqD$R5}Ta@6)Ejc zI(wvQoh&=m0xozSjal*{hg#sMhnWIAa>jPZ*ln56C4n2+PiHfP_N2$JK3%ojC5fYI zS7cMfaVwMDkV)KtLg{8MUn!@Ro0~gR?I+H0Q3M`}UY%bOU%VQ7Volt{=2z6d8!Sd- z2dYL+Huj%6G46kmWv0biMOoiAtv}?bP30b!1d~9nyKdjkesvI;wjq1yvt}(WdPX6> zZeX2{5xUx-#aQ`}OHy?7%K^JvY<;fuYh1#jm{RdaKD0-zHt5UUvnu6R54j$3u2g2W zxYDO2DRoRynih51oRDzUHM*hdUu(ar1ip_uk#v zX1%klE$q_Mw)@jQHD&*b;D6wsrxz-3or~z~stx4j`=FE+l5|K%H{GGQ<>1emcXkOYqxKPr~UnTO$%H8=fe{R3-ssXv;S!2|JlgXSy(l3FXhF-~F>}BhSZfHbiZ`SUtkSf>u||V(w}fdZ&Ei#Px{tFhX1W$droDy-Mw?i*qQzf&$x*H3fMoEfCZHFXT|Jw*8P2HdQ}egzke^jzYTo| z|9oE4^08Bjx1mu;Yo=xJv-I>#r+yW3qlX`iL{V}n>^}Z@@p+#(h493#u2V^pN0$G2 zg3@AzPnH}@otI}h~rJr!m$S^4ksnVddtUV3fQclQDfzYA1H z{`&==KNsD!d9yY%^?{}T__y`J6_4J&Jj-@2|ECrs3Jb*-Fb-cbHHxcgYq&8z%M5)%>#boejX z=(gt*5J<|((g1;^;dhbh#UG^!A>RARlRe2=X-D)^n|?ZPGdOz}(O*!T9b7%%&#v3`F#0e+R)gT7!y#@k?%hY5xHR4j zPG~c)KCqH#_wO(QlMU3gw9b%S_!mv+atCA9@o9SBziSQCuxZn#gr`rHT=F~qx%z^+ zYqsLg?XXEIIpiA!x#ppgq+TH*d0YR_1t0&b5C1o-QF^KXdlnJFGSr%RqNSxpJI^VB zX!}1l;QXOOXlJHwZ=cq{## zJjjUt?^+vXx2dbC#X_fA;939Eil(>pxa22OFJXWe97U@OA*NqcN8R`THsaAR;(tEG zhVn#NcRoLfF;W_Se@!UE4U?riGDta4YoTZU%TG@mqW*m0(Ccjkkzf`tw4e?hdY;_j zRD_M=kwJ{hZ`1zRx-IMEA7MW%$kd4GN13N9HZu!3y!zkdxA;;+kyIVdAV+QFRDh`P z$n4pyDk*spJs|&@f~_HPP%240*g$`O+CPSoI%x^z^${L=CLVUu%~CtZF6x|kWa;fi zBj~G{hxxHRPQn06z~gxLAs5ThuF}whX4D@lWw!h=+<0j=Ykal1RxV7yRzqF=u4z?- zwUJu!A!zH}Aq{N~VNZ6m1n8{W^yh~r+=1)wDIe^O0Y7C05UH8|; z9ReuXaRrNvW2R4 z@0r(@D0yA~_m<4f&^=?~kzu(YzO zM~|;$Lmt5{;|nhyVydURM*1$Fn#Puvgd1A~EYOSluY#kKPbS*STemzrio-(x%0C`p zjXn>3J+yZu5d>DFhbugA%SL|dlhN>5KuFUi`6_s^s@N`U1;Bk-d!%73jc zdK>`9C>a~aAawl)t=%&UMc0#c#ag5{R;JgiJ62E$gQlhuXwKVn0!2Q0bQCrU`kwXI zDoSmO!n)fD?uo35M^CnYp_KI}7-hebD9nof>!O~v4M9QihrHs;|AyKWO6@QZe?GNe zeapsdSbO>s9^UlkN1qR--|c>Mi3R&{i+cg<-O@!}h z*fbNa;YZ>#lchGx@c)Oj3mo^vrYOAxaQf7lvL@kRP=+uSe!kWC79cNve$+T_gYFXF z(wAwmf#Z_oC)QeVt2XKjhSocZwBGgTiG|5qf+nmabm<;FQ@PzyE1%K42KxjtI|=#J z)Ia-(NI05TZQn5R-d{_IQ^)amyMxHuH8B_m$h5NmvuF5fX^;6eCiLS1_-R z7t4;3T<@BM8%XZF#W6c!Z% z{I>WESK$amvrDR1XwKZ#(K2-2Sxgz~SY_>zeR`~Py#mrzqI!3C^sfP6j&B*)2~U#5b-h% zH8lulDj^o+N9QtpVIhFugND-!%Mh4BKt<7qRLu51OyX4Bf{EJit4ltu@h{1lzxP-G zouBN+_14|gf>XOv@<~Zn_9}S_24A)kLye`i*GKel@nY@z|9F)@uSKuAr;b+v#Mn?v z`Z18f+PMyoU>sE1@G=8~gJ_;*oAB(J3YvF6Yw4`y0+uodF1;qTjr=0^a+Bg8w?d)F zzVoLK#xht~Sd3TA|Eik7F@R*!Ou2aS(AI}IZld+!$7_LcjKn)0rF5n`4JYy*vYh*N z7$LEvR4=c*Dk4A(Md)SrhVh5TlB+|e=FekN=)?opcPsHSsyjPp!YC!q%($N|=&a|j z<85eee#{wpP6Y?oRCyVhdAQKWbAZ?z00SKFV+$yAd_9I9yyOLGM8El*d;lf=WKTaW(7R}td;p$_6O@M*W1E;TX=YKtr+cA8&jL|nrJxRm7zxGkQn5HO8 z6SAG-=)q;#^6WH_w8+Sh0{v7H=gp(55(dhL1neC)NTiB7=Xynl7GLjNBb^5B@~BMhHcN76`ch;HT53^?gcbaaC^MTV7Z zY-}uaTwSv70q0Tv-SLTkyTA!zw>Dt z2#lf50-XS{$@^Hd48s=}ls!{?jUGRIcnE%eV0gIk-d-K)OwT{^UwrwZi4-G%G;VVg z%82K35DpI&u#IqVaNwADe-4Eb4Jms0ypCVwl24{fE5sjkJ_l_vIZ{G=__$;sL694TwWhezZYSBX=y15x6pg` zB;x6S8KJ+r*v(pgg%^8+@H#O$`EFHjT_~TWO8OSSaOgfQ)$&aD35!bnTX7mx8e?yi zjvl?7k~fgJD1FdEU1nM08`Xy5l0cP#_7Z3(iTm^=CgwF7OJ(gvT|oZCx_@$KIPrg-$eiqTrfW1d~7q%ZKBRH(D7E1HydqPuJD_F&z>#6iQ*I4~Xe_MD6k@ce4*Ajq`jCiW1tJqbt<_g*{P zhMyCA)^WBs{Nhb9bxqA+jID_ga{ThZWqGL*RvkXCp|&;}+p=u&B6P5=W4QwcVS20= z2Tuqs?!R$FZ-6lRaGp=X=Mwp(^&tFf_C0?nduNCF=eKtg%6?uK^X_41t%;Srvz)ni z)NLFSs1-3`S=Gg5(#INNhw)7_ea9pcF`zke@>k6nHFWjRK+!GY&Z_%4eZg`&h{cE7 z?Z@~(C;^NUsI9k^l?~`Ko8dOv#TGE(UZDNd@Vs1|8Ui-Cx}I(H4?C-Tt9n%(X0U%q^KxU3Dd2@+8f5(cPm0(?(kU^}#f;F|w3NoI1oON?)XZ7^I` z=t?{+2xOTUI4!~-W07#;QQX?W=m{8QW>GgKmVjeILPG4qXo++T2)z!Y(LKa)A~_Fs z6md2hv8%!C?$yacRu;-m9pZn>ea%U_&6@#cNVfO)$Ams`y?H$Vq{OdJG=Sb00g|~kn6Z6WYyvDDoDnkyI1q%L_W-t`IT_%^B1{(lEGT}4D(B^e! zcEme%mulRZPcJX$;VKXo=hr7$X3MX*iE`KR9_vn^&^-sR`)v;(EU*XAr-iuTB2}sF zBCYcy9iw|0Z&(16%;1cD3|wwPV&ZX4J?Fb$-iKQ{pTUFDZ|7jI1w}Q8f^FcbP=4!B z009eGCQw8DPRALiFH^8QM3TT0yQ4{$6J82BIfzNj^@FKJDT?R1Hj+Ww$If|C3Sd_O zY&gym9w0V9Uq>g~2E$mI_?mQ$LEB;Op0VjNn9FL5BOpfZCC*9iY>n>!(K7JVv9f zD>veT-qI6S? z_frf-56G*6w8TQy;cFQPiwkh%(H$M*GtW&s=waYW9-7F1o(NQf4CPec@|U@Y7XY3d z7_j*K(NK_7e!|qftTtZv>O9^5JLaloOl^$c>2o4C_}e?QzJ>p)4OCbuYlIH;ds@A|)^|ur5LXRB=!F9hk-K42#D5=SA)J zQ}_4S3G$x(ZbHy(cQ)lo@zn6;y|-m{u3L#eeK_+-vJw1N&4)Z!krdfVc=^74jLbKr z`Ou0SOfFEs;8f9kflXe2T*hm{9pljl1&XF`2n!4QcI>+?gK^^W1ObbC=D~dnor$y) zd;<0v3S^E+X7OUSaJMA64QYOBnjStiMxTJ)1aCP|&Kao&Sk?M|jla~^E_KU6E0RuM zvPkUbSA|V(zKXPqi>02X<{r8IhIV3}))R*u>%ATxwee_gE#`?DEf6V060ZQw?Acod zfWbg+A(E&MCML&+$jqGZT4WGIdCdd=fRunT$k+GZZ*lbc=3PMVNEo2kfo;g8^ROw$ zj~{oMXwV#FXPv&Xd7u7+*2c)kZquKG8>*`xk}hHyd_33^L`a)fU&fmDuvH0YAoc<0 zIDvl6ubv4r7u$Ums#CM;5AJyz$u0|ER6Fl6Ilrq>-_qWM!jt6?{OiUuGd-?+kz;}5 zXx2B7P@-e<`oiX8zE}NWJt}!C>)yAs4Bw9$IAPWN^f2k->WsI(shokA5~PFeDE?%3 z28H?B**4)8mX?`DCCiZj>W8hgYh9BHR|Ov00*P7Sb3dM<{lwGqDsac-^&vl8G! zcY=^E;X%CNjKeJmF*?xNA@4`mbw!W&&qT!+MHX9q7{$d z7@78H;gvl%a+9QW;MN=Aa9>~imYQP5)Cicafw#F$yV|U+b?-OR z&%e$_-om;)M>(}{X5dNytR!*?O=uS4HCt-%>oNhEU0q!nRj*MdRQv`~x)Cwl$#m0% z=g)P^O;ix{KRbPq0O4fqN6aEFXE3!f54O>-y=nm&V#+6WZTp?_`fh4JW2w=wIARv_ z@`NkHMKoc~nHqWzYyi9ihq=3arN4;YRgI%DWr!7S0W|I2ySHInCFQlzSIlK2SBCTY zn_HQl>W$PC7=58x4tYDj14IHL|=1&zF4d4y_42? zyyPL~mE$4~Jy(FdVR1~-!#fUmA>VlyL8iU^=t)*ENw2BPuTY&%Z{f9U+~fKEPGmj& zX$Hm?>v>Kz#JJca2{8Z!F*9A|or1O=T3i}W=*Kl1}@00t;X{q57LXqHXYPOT-}(W zmvrsg>RFtWR&{lqI-A{s+!t!Ec5k?PW_D%*>SQKFYV0T_2dE_VQ-h^mEp0SV{N_E^ z>pc!bhw9C>t(;(kT#J5&;{oB4&b~jfDqoko05dF9fnN!egeCxEYf;|izt~jTL@=x} z4uo)r`(QFA9@F3D4_Aoa%&q&F_~rkgMtt+hj>mHCz5Vj2 zCAoDT*#OJEdU#WHuZ8YTk|OpK53WW14xL^a&rlC13P>_HGc$j%`0e3XK!Nes?ARq#-e z(zNHT(;%%p7<{8D!vq3UOyaYFpYdNs;Ib4erg=uKK(OJ9WVC^5z@vOt<1S>LX!AR~ zIwgK|wrxIfa8dD(Qu?)9Rgv~QV($yW2k`OoKF0GyFk&1E5skwOB&MV& zz-_RM+Mhms8ZSrh+Fc6HY#e=YPcpy0l;J(^MWP<#T9?Cz&!db``tz46)f=bV%?8nF z_?8j9*)IXxPSGSuG0u>==`9srq7US}D>--HGha-(?pB}=i^?};=gL#diQFoz1CsZv zD1%6G!`{g*7zl}CZD4)kQBh~hhw78V0xt_NYxr4<6&BX!gX^p5gH)0PO9M|v;{Z1y zjo5{UvGz=N#{#m@tX&35iBS%I4N-D}ilU>J$TWjKJRbc-R?$SVZNJWkna0Q2TsN%S zdo5mEScbgd`=@Q_dK3EkjI?5$_uT7etTdc;24h#R8FVcqFlt;6U%GBD!wMh>cS>px z+THT&XhY7A(maI%<(z*lP6DSzoVCJo6p@TwMXk3B}hr|2Q!LqknUURiWN2Z@E#x^l6L5_@QD}`Q_aC%?{ z{22}g1qTZlwgI6NWMy6#mynb5BV!1IZ3oLF<_P8Jgux$u6$W$9P#Oww`Vf5-JgVm) z7KF6}n#1X3Y1%<0KK4$x?zJ5b6?-8Vx5~PeL29NH&AF3sg5APVFpS^27Wfv322%na zp|)ohod7ctV%}@*jhC2B0JDw&O2wH^A-U)q`n2~W2rPn^2N2)9N9&=j_s_PA1N!5s zKMO6JxINJ@4Ln|iP5w|;{Uj<&(f!1r4kixxBq%&Q8JWBR!Uen^JWFjBYwtbm7nQZ%7u;%2prPt{OF&w4zN<_Dk<s=B7{dkaw`Eqzh%Wb0Pj^f)PmxXoM zp&0Q5Yz4EhlMKei)q{ZE-$xIy4WJCtz)n!~vE8H$X}?DTLxhtyxt}-VffGOkDvD3X z>Yp1uiiWk0+Ng#)nf(*Ctsl)g)nL(V3a3rwLwRLWi{|oJJja!ZXcJEhDNV`gTJ1SI zXwc+ZIK~WftO#Bp6_TVfbZ*4sL!D;Pj5-#8Tqp>v0EAh`6Z5aCPwXp*MVKCYuW+EK z8$+;In_>dQ6T@r^PononFbClfLoHKkU_~-aD;Ya5bRCJ=>QwJp%MOg1#|F=!jgEI? zm7}29#_YDCd-WdcCllf$YB4S2BoIR%araeTlLv{1N1h^KHqv8Qr~|w>xTHMvY2-Wo zmKG6SI^NYfamQ7FFVKSHF|4yPAJCZ+jo6Y|e|=n$V0~3;gvteK>pa*a`1nD6IE}&UD+C^RkK+tnz67#Br)Iww*H;>l&^pigjB^z}Q z(@`yVMpQ@QZ-{t4p)Cj?0wH^2a;S}zPCG&qQ17U$s2DJZ?k&p5faP`H6yZfkEURK{ z977@y6pu(*Hl;McV%bBCj}*-`qypRQ0QlcOkvr(!i7W=WBrzlqww)8L=K$n_K+WPC zqxHE4nA)I+W?(qFFw@?(jAUjboQ*V&hFTe+LVMA>Es{lNb-p^eQnLLkI~17 zL_MdPqX}8_pIGM(OU%>+@OsWTp%sVcTcl00tlP$+)Jjzn^UsN4MFD86zJYmPRla#B zaT623bOV7WxN9bw3{nwyObj*!xQU9id5JO_>mLZImlx=W#iaPd1b-4~xO{|d;fc_) zK8i3L`#3MBn=IZ~j}}_S7z`8&cyy44MHCfh#asQtwteB8n|OM5S~Ib-qDaNMb2>&M zjF0oBhTk%Z@$iQTTYic0Vo`aNMs>QhS+m=uW3cr^Gg{@ym+-s; z`LpP!7lfE^dx*qzxuQw{7~1L}6DW~OaUmR^z>rJ6kaa6>dQ=qKgxj{;Jhu5m{HnD+ zO%v$S9k{C;lOgy5n1l{IOhyuQo_Bi)aRbXm=g`SI3{`e}_Uz%kQ{H19S%;btZ8_O5 z*EVsz7aArV3*$KIMyA3hCMK4&7Qw#A%YK0ns|LXIHV2uA!*?WlH2!|^;cH}vm@-oU>dmymE#er8HTYGInN zL^Co9r;Z=cOw|{A*a1^_P(Yw*+`Yhb&t?(hHp$WgxN)_1GV#sFIuhU=&w(cX_uao* zeYpPV9ITYU_7KvFyDG=F2+7fqz;|GkW=%OZFgzVfof}A9UTT5+A({)tQ|{TfPoR4= z$2@eTP&4oy#EhnS{;sAz!?-@8-*gmgXS7&-fwV6FI!}m~Ad^n?>_{l{{rPKcFJXys zbBvG@`8Y~?V8wBaAqaBYJq(`}hDzu5bh9cSPw%m?5BCG#p;kttNK}|C=otz@#?Gmq7uaif<~KZY4OdX>98VMF>%HPhhp%niw@s_ zIoVQehALhm#BFsp*)$fc-D@g%7x^5;Ij{knEnD?K7a@yXW2-Vm}U=KIY=stBxdU**1DYoKt)nj4M|(*^!u)p zH}%_RhYNq&pkRZ_?JLZ~Z4Q{+;{$q=mdMzW{3|lH!L3!F?E0eoSX4w=B$Bj@)9!mA zja||26vr}HSq7ybOg( zdfdTW6K+UUksJ%|+6NV?^)cqo>)X}=)kGn6-^18vvoMG9N^t$s@lCQot7=3$(a zNqT|D*_@1w@h4_K{bN}J8t*qr)OCRqn)4CAg9>D##l#Dc{?!_z>;(&Fcz$#HPf#ow z_nX;ofRK_R#67oVZuuW=CE*i~yecSvb<~9;*XXC)`HIJX5nYL|D(I`CpZP^~YX#Z~ zH?)x607#D}{cKwcJf@zOO{B(qr_Aj8NNnQ_k%{LAHZJfR&OB8ywCS^h=)Yk1yY=YKu*Ym znIyh1JJUcT*px%JM~mmo{M_|tvx9Y0sp&;vVh{i1*2((n?<}i;Y}x~DmH5b}!Mhco zg^jKK4l>+W{<*leo9f zK>Xu2*CK!$H5J?Fu>vqFz_GE50#MG6qKx$tW{C1(cy=*S)137CB8OBEDUCpW9!20Z z*FF<}wcGw14AAjFAm^#IEse0T9I}Y_gu3StdLpz`L2?ig_zJ5n13;HTC!d*=KeUz{ z@)lL#GQu&(>-^|tR0B~=9*#}Z2vKz3(9ipfTUc4C;UWNOq`(|Z zejV?MbDL3NPgNpl9W9KLr$`{7Oaxh(d*Ihe7)MMCIcJk`re+&hK7mZ>84rYR-~b)< z$L26&sRr``7u4bwzDeX2C})bW`%C_ zRLfVi%Zix%dqJ(#kpx-A;%$fwpm8<{_q<(V>4Y6ofLGk)!Fls#3o+AUS}r?IyjAjL29 zqHIM^)?+j7sM$avU$Q}w*Q=obw33QPGlWF`^8Rt}Va$B>YZnK%zUb!-lli!~9iX?@ z-rvPv-&;`BJfUPy-PG%Mu(oOTT-o!vCVs{n5&Y*pxkt9t`XQmI_3D2XrU-W*SXr!v zgblK+BxU38?ZZdSD*gnGZ3sO{%p{VI2qy`T8Ck`dFm>vF(;)L?mn*OzhTIyF=!?Kj zXT)(yv9VGhWt30}T?n9o{I_NE>H9MyS)MX|lD5Q2Xok zMkIwMUUn#@mV(gITL?K(&N6|%juvyjrV}0|kPKYx@OzfEy^K>b;|9N&hPO@TW(eKB zG3jAX%ovx!^xKoAb{5`W1I$r#oCoH@Pt4|V$XfQA4|4>_A?&Bl|Ii<}+suK#;^o?4 zw*lMk`ldOnDOO1Nhu2EhH%h6#)XhP)8RcoTQV%5`)pJ9lA>3Oinmew#f)57 zN!NW#oZ64w*>A1kreQh1O@tET<>T80>I$J8f=p5gim)2l&d}EQoE$B9+SQkjz-3+J zj&*i%89-F00WhYN{bI-kMMReHGTP9uTj|?o0;Z_@6~|j*L12dQvJ^IlqfrDfS{^ZYjn0`-*saorDP|0`UYf1-n%*j>2!q zh8k*|kT*Q=cx_}=aH3hYH=QHSj1p{*F}`O=B!l1dv-|Axk3G6Rsr%q>^AY<=HX3q-X5+j2Hhd^-oHE* zTu$W2KYF7SeU!k&x z#$k5GS+Brd9btS`@Rc05(P(I=ZqNN|(HULbGGODkZ+gx!j5f(ulfQgCi>?PI8Wa`k z>gk~l==|apiMH)Iqe`|T5`7VSPk7$Fbmz{U=;&ytu`iY9JX+{|qY#X|$g@2HZCrB$ zO(RJ}3Q`LxM;g(2Xc724RVk@UqN1WK^zo-R_Fpg+1r0KEK5}15ZQs~C({x6DtH*8G zwu7iFoWA)X*OBvs7lYfcg<@T7m`hEDx#~oJ-Lc-P$R-2=>dD%CM~@wAdtQU&`4ddz z>qClT=93@m_l8gX{Rt4ZouZ<;tmnR+&vWXJ_L`kB2kstdPK!BZY`jKK|I3@(>;M+` z7B60WJi|;1#6-lo@3MpynC{Fdav2I$h!ju8Sy?*sZzKBfy7xE`j=S=ICP64%)sqPw ztv~_I6x}qTBA_Oeh^d@A_k3cn#dWN0(vi!nadgPTP}IxI>-+e)nuSH8*W9$3PPO-dlyp5RYcP!Dusz3iCXFX4&9mMzp2y zar0N!RU^@{qGDp3wrokN2;RpfF5dY?3r~)hk44#@9!kliCbDfhwBdO{fF%V51(`U0 zMT?%srSV6NB)l*8cjRYtn15|fj>r#71hkB+(!-mq4;o+41#;?!(`1UDLHU1_M zi{j!#D2D1st%ruTb|{>!#@EkB@?1w!;N{8j^W%z&n#gx$qSOFE)qE`^X8hg3sy^^H zHJ4UxtWP&ngdD14n_IJOBi*Nl_tMbN5ON6oL1T`6H!U4q{F^s26MZ!}(O)R+)JImC zmXI#%w2rd@<(Q~( zs1%Uwu~$=SFFid1AtLp#v9TOCSj4npZ^_s2z~p3BxVWb_Ikd8P$&wRl+0gJWRgtNf z6On)v$v{nvA8M2SL(~mLD`-C+FTyK1Pm#g97;U$??Eh=X3 zA1I$X6}?;I$zwdr@jQ_d3%uz-V{({wmQ@030(T1vYJn}UMKyhbj}N8t{{9keTLdP2 zcxO_D3De<@99a+c4N<91WX)5fl568sWPgCGEK$*7QUCZhDChW$3|^3Ia-?Dy^+*1G zol>*GO z)(@}PUWS99cDINz2{Ku`eFrnA3`O8^&UiQ zb6ria^vQ1^~6|gm__gV@Wwpp0G4EA%a5al5vdF&*|VM=leL(S zneRHn{e8#t(a}*xVW-F3dU>%>0`ee`9#Z(nYw~6t-fHK0E`8mOK_@NdfjLJHpX+F`@$5g$yp%o5Y4dA~epn0msct7p&QZix)G^ zs#w-C3#*a5E)2&6GC4arIHUlL=i^b+D5f^MfB$}x=_3mJ>XnrIeV)TWcFIUMWS}_H zdAPmBeR$SuZZ%T<(V#DPadRs$FffoqN?EoaQZPCTdt7N6;QKyY#1dtY?&N5T-KQhq zEIddB`*JG!hhiR+TEWce_mS@)3?j?|gi#VjD232SKAUzyPn5h)4Q(9x3}1t(HqxkL zsJXm`juZn!4HbcG>u<41awMpgaUD;pIv7@YTtxHRPZfn4 zPCd0))*H!B6?6|CXxIMz%CK>oP#z{`>bH*>R?%fzj5wb*{lL7`ZFZXCY}LbMOVfGh z{A~67q5y%4ha{t2pQz47%Bem3gk8TjN8zYZB1$1h{B!l5`O8$r0{00g%xZZQAFmS} zxtJo#_^WgUg}UqOSKXfM%|5kcbs>&AP0Y)fUYH!%lvBRbP;uP5xVzGdKgquP^={3S z2Z&2myD~rSP0=q%#7>=ccTY4b@#Wa|_I`I+fF-H*bL_n-f7aAA4plYm5)ws6rf{&a znZ|qBVxNmSxw#3txei3t{PXkk2^xTEix5>aO%E|y$|5u)@o}{G)2ArHYz4+5E74|^ zsEuO2GuYMD)YOeA0pG{U8d*!Vaei5+$B5Vj9w*X!E?0gU^>?ud-V-3orJcP?DBr$m zNv)wUy(%xi`a)3DK|w*`JBrPn=y!Ji=w`inXnw^n*T>2+zBrlS3aZ1spR^HK|W~)bTC(;Vk0BFPWV_#>Bjw@^Sy?fq_I==DR<} zzAmHm+Z;Jn6MYm5OR=MoeoiSqOx2-R)z~$Vth@bd;c$-6g4d-`MA)zy)Teqn8^cAi znQI$aaFF2PJ zrv~L;k77J*v%B|o>Z7Nr$Vv@$_{@<5R9t+|6rdrk3k)8kSc`m=>3N zC`S&)Qg^{Ye2@|dYO%T(A0Ho6a+u+ESXh!j)xK6{CR8vex(@%?&B=KzB_+kd<$#bd zN6@0-;bDvBZ^QGXAeq7#>D>q3u z5~f$BrAOiXH4Yu}`TLDxEB=b6CQV2gQOSk7L!M`zBc*U4M2_%HF_LF@nwy*Bzbx8w z(qbfc-NQbGpz1qGbL6&x2izkllR!T|KMU+Zv@m+E!HfmnyQlHCMvRfBZEo)nx3F+t z5IdJHY=+5!5E23$bE)k5VQagw*n0^{_OGyab=55KU3;4U4&Cb*NxVogo)m6Q-OlbQ zA_``ht(7wp#iQWt}N`?f{r^V}H8MQ>^UuN$5(B1{#upLlc=Gqb@Tqur!nQ$o51 z##H!=ApJx0Mao2- zLP(~bgc;a*=Y9-12}z-R?E*L_mBnyQ@tDu6S5s4ifCW`7GyUJdPRdxo-yRd%t|KfCB(*zPelO@m8d;FZ=m%!5N2y zge-e)htT2%laLCaGAW6$?m`C6|7A(ZXXq|=cw*#(0mS_1wbRqzKhF%=dUF{V7+~8U z1A8(`c%3UeUk^`GZgRkUer}eSMiiQEQ&d!3wqgYrKfeZ`O@-zZ@JfBIquKP#%v&e` z3i|3%2|Ixod24c@KfOx)4u|?#BRyq?-bFE{; z{MVNBP3zaQAsA?QtSrec?f-O#*zny451xQ=;@Z0P5KPhPRjX5}x9N|9#&+)&a} zF?K`;^|7)Wq0tJ^Uq(T@heSVE#N06_vL6(7cI<^Ie=WQ|Zr9b_O^WcHzcwqAFmr57 z_4?+$2>F6W^iy2pK}wVjp$GVQb7(HXL!Z05 z+4t?+SNiJJnW_k}?Kj!6riv1?865o}S#Fn`)RK_&{Vs(tijpX47(+gfxM5l`xKBw% zCGbIbxO(BavpBj@ZpE*&;x5hFr+wy z#iCV4%Cbo;2yd$a3%Fet2(Jcc&>3Y)$-23>=-U%fs#wC@h;w*h!qwNz8M-m#8GZ`2$m=4MMlUUX;wfY zi>X#SN5?x(uD3jh^pOfm7!PtrF;vVWEAY-8=dM?)2B#rp3ridkkpgu5`0&N$p!c(J zLM#QbOl!T6eU}so{qRI}2vp!G36j_D#%Kd|*iqnAA?T$%;`3V6#q*x2-kO`22ZF_m z=G+&6dtWlw2nJIA;tHC3s3s$9CfOmFIC7ik1qFOS+I&{cN7jL&oUe68}(4cqw6^cq zL1KcV+RGCkPwnm~^4w$s)?lV%#ETQkOQ@DbixvULD&dVLUTsvAnW>u6URRMuimp&t z!pLLjGcz@kiq;_J;P4Q^)yzh8jw4h)(JidFhcFNNBI~#DMx* zR`Flwt74xDqDFuh6$&K&ko2V@7vO_|$pnYtF*V$P;W{V33gRaF0G&vA3(Sp*oSZ)+ zpM{CzY;@Kt%63CakqVb)3NIA%26Tn-gZF$vOv$3}3lN65>7QEt5NBPDEq z{Ti#HQJ+V$+f?R2#5hhwL}@Wh|a zG`Ob9iBqRe;W|*v%&+7mB3ro|B;NWxGi3e~7D48~+}u==PKC$Bz-gHSE?=9C#^g8{ zxVgEdA*eS{zo->}6SwWROt6b_56i5KVHA8h*hNL#;p==W)1oB(7z6!5Ls*7<7Qx1! zHSD-tYD4c!C_21!yaIEW*@Mtfi=6!YEr43mD8VtJclCB%g*lKQ`qI!1B+PvdGx2a0 z5FmGF3OZ9gXP?b(@imf?mc~B-;ax27ANJMV!bL`t^-}jIA{e1TS^+%tNj2ZL&o!>dnd7kH- zX^Qc*Jia@c!@5&#vcjxojJNzBD%;OqhH{jb4+(&h%X~aT8qMlA5Z6R0f(T| zF658HjFKx`&EulPj|{g)w__QWAs_K4<7+&Hoc}{gzKz`$F9m1Za@Hb8@+w!Obp218oBWPm$d@7S7%Q}vz%u9-id5>rrbmK$UHw$_P!=87? z<8G27gXn|zM1{T@w|x2X?xLA1xf?hBx_@Q3G%bxOHcN?kWRJ>3JG;>P)I4nf!%1vz z{1RRbn2ckgjl2xE{2zhMzT8xU1_`AG6v;1s0yT-99CO~E08}8b2X%*%)ZWSAd|lDg zw~Qq&>mM9+#OG>#z`!`dyEl>u5BzNK@{R0DQ$*G5u3Z>btsi}z!aA&%0UF z%xA{ypx&^Wb8u1c8owiThI&{yRMx|DkhSHvJkL#_VJC_0s-k|C1zyRW5j}T+yl&pS zX%;?F;MZ{NBedfV(aB6-`BnFb$p5P?Fk#P#Rz*&pisK^+6~E&TzrfpsTyDIx7JS76 zDUS!9$HCwKGQ}$Jm?%gp3d16k7SsC=y^}v+}#oP+SV{BrgU%cnK)h}G@ zqZncLhh9L}c3FDc={mWU9$#HuZmx>~OU`=cJ*6=p z3w*XO$x<0k(q9kIrb#*THSlp(p)$2Sf1Z8xs1oqMOEjRTJN%&)Gz<5v?vwn2=i2k< zXLok)v^%%Vo?8NW);2X)#D+*S7A_;o-aBe^!nU zY>ImFQ^7mUnNCZ9X0z4>sQn^3eI4e&gT>{T2g;}w#(=~|PP3)Q%GwiC@~_M;_1Y8l z<(b%N2nx~-fTn}fLY@UkXO6g+LlJ*w*1HHO8W8FfK1iHqCD6t`)LLRK-@e+wgdL`5 zVc}NQC~LF7J>|jx%W__!3u3gE;3Lc)Na}YgAJYk}I+KG|Ex|F2&J;eMbw2oyN+ zxm<26PSm>nEQXhfL%cIS;fRTO#|IF?gZ3HNHHD^{T+>e&RbrewX|N$hU6T-c=XSRE`Qs z;Ls5P%9C%wNDRgR`quJ_E;|)pCq5buVm&a!P=}&*ROKY(LZC0EBdQ*{W10xq_R`-O zV`mq6g%<&r$SI1hz|q6QBONBYtKJkiNFL(e(>q#Qcz$(bHvb{*K{&|i`G8X=?kKEA zQDIjB5&FjQX}1{qvYydj_Q4+22AAgWa8P%E;by6OwzB$SrjgM_D}kDhuI>gfkwD?5 z?cgZ%Se0AZOgC(Bxm{~ui;e~i%B1=8nxN=u9e4!>8-JLgU|cdwh?9pvg(R2@UV&{| z3~n@;)~z5VBi+6#sO{_99eMch+wsv{a}Y@jEl(J*^oChuV`FU)EkHDk1EJRR15@A> z%kz5I*@wF;`(y49&r+INdik{w)x%oL(mS^UMXC$k@WRJa)TWYMj%X)6z#8a{$}?t6 zreFd)c&D8xA9=wqQ^7;_=4+U8TnH;?VjT$n(3A1;@i0kw%?~Pviwu>B+FNSFkiPu) z86|ulMT-_t#eV~6P6b?YU7EcTV;!^S%uz>c1T6Mi762XBlDK@}OX_YAYSizPl$KVb zgMNTE4_MD8u&1H&=&Xf3uC>%9;+6OaJD-XR2T4W(lfncWjunfvc;wyjU07pCggqdb zp0TlmMaV#mR4OHZ|KY<5C}Q4Fgcun?3& zTr9j$hqUC9WrkacM3I25YBt7|?W46V)HF0wV`J55h>4(4V_p5NrXfv8g=i_$5f)vw z((|~mSN+?q9W%IWa5D7;!F!^*CtySRTY_PZv=V1Hj?wT6kUQCkBQi2Wri(j&{ye$S zW*2XLnCt~r4xMV;nzd`Q2i1#V2qXcCk0pn=sSI9q9K3uKdp%n|1bIYWcwF?SZxPj9 z%vb;-;dosq8d!ePzwkk+BqjqpaPdEQYf_2}lzYiOyYTRES`h>| z=!9n>OiV%vf+7TR3-M{)u2qr0Lw3ZE7z-9GppnS)VI%39OZ~Et2s4ooy6ST?jlQ^c z0c^#BwXhv2%27D_}gMqD^Ojo6^X^;+3oxBgFa;wa5$A|VvK#ayE;MjH{ z9SuIIvTqdce4A{ayg~Cb|CE63BUF7#Udr`(U|3nja{3gx9f+EruHyJXcc$ZUCse2J zP@w*q)KJ`*rM_X*>_iNiWMKE|blr9>UyOv6_>=-33nSEXU~q4zS=dp`$cMz){z^*)}>ORQWOC?tG?X6tT?iw zgOA29@MbB{R2&xc@U!>HrU;EcdG#bGsUi~_jj4jt-`Dr{oh!DFMVLtl$6K5{q;8FG z%f(dGt?vCy7W!Ij+*Zak9;sF}SrVUA?!I3w+2l7%Ya(=f;u*$@EqVb4eEyOpD4)Fc z?+++-u1}c%{=k}r3HSWZt2ydc=)d2il!I9>{`-UMz5o9Y{{LC}HyZx0(9o&$q3NHV zPIYs4UlAbs&)edLF==gv$tWm>l;s7oM)kcLCYApak1sXDSTCvgu{3&c_Z94rb6whMNtfi|-{9|L1Kz(kc?u`9o7vC3llu zL|R*0dA z#Otv5=60S6gZXH&uG>mc^)f&Ezju&?+(GBOo!ik;jw*93os=;C;!vKl+b_Qx|L40% ztu?b>y}BT9_IHPYIK(mG-&yF<^ChUs$Hu`iKi*%1G5(1=iIx^WKG+xyr{r7a`0u3} z;8Lo{rS^Y3n|GazJ2525FDZ%0O8C!MQgM;7VER0|`y{b{e{H&(AxwIX z^V9#ljkTKqriG20J6Hd7J9c?vgZjX=Z^vQo3qix_(aIn{yMagYLSA*XIvN_bYXlm7Z;6_lM{w$>AhrJ(<{Z^@Nthkk&hY}9nDEOS$(!ZIS6x|lk8@ZV2Ylo zFPJh4gV=jN^*4J`xrOnQYe0OeQr=?oE3~7%67M3Tj__f3-Z;9NQ)I>W#7SNi_$;_C zFE4-7wr+5ov_16DD{0tI2&dqAAjgiz+`}5`CV!zEe}QtD30u_9P-DZ~fOzKUGW_jO zfbPZ>)Vs8%CVhGSEnh6ZPp%z@jU}@k5i7L|$%8kV{&(!BBcP{)Ejf1Ku{Ks!zodb*C&y2zP^?Ps{ld(W-N_zRxT z+l5abc(adEI0yRr<2nY|JT67w?EG;3yE*4)riq$cS;nDHZQ;fYcoj%(FJZPS1mIDR z95kJIIyyKk{(f)WSU5}Se{+z-adTQ&V5f)O?a!}(=w8#i=2e3%Zy%dY)Hyy|BK+$!_11I?!bjrN96w({ipooK5fZjuhUj1{KOY|&1$^`e*rIZB za&{C8i6uOa%TZMBt8DW-t`qJX4boXkv7DD%S))3QD{N;a)_#;rM(}S3Hg1Jk>+IWJ z&`Hp;!H~WCm2XIU*Km84sUOEjL7YqFN7%*JW#suP6ETuhl4-(ug!!w(`;vXC^$J!@ zkGN^Ya#e4Jsu25Ts9wxC#=i8+ELsF#jQVU;#Gk#|kR+V^R&G_vk)B1wYtp~o=I>^g zD`w3<%q+Py6~q~J;Vlc?N7iqjCNxf>?WrQNtC8_0aodWBii#%iITtq`_F7x)Ef3E& zW-HJyR*vcou1|d28!quuy-Lg&7ghVcs_5(2CllUhCr9hfO$Cr*qz|UNg{Yrg7|cye z6MoNS9b;*KuYLDdeXA^fNLz*7yfl+`m29VR+2mmDZDIO(nO9izkNnC?p3NAHOg``Xji_G+%hCt{_>XgXduEX6Czgg`Dk&{?qQ)$trGde7ya_yN6HgWRuY7~Pcu)kQ46Ny z`zCwd7nmeE_c26P6sPsM_ z9!pjU4{_ZLOt>qV=F^UT)#x=w=g#W^8$E0w6`s>~Y8u2LMHs~P$UAMS4^xpMWk>M?(4sK9K)@V?kVM!(3f@3SLVRH4hSbGMx}1p@B-i%U5vBTUsl)1MdDns)sz zciDPcq}QMoA#_@^-f*C&>wU7Pyj>0-bEgY0v&E<6)hDw+Ruyaxoo&gB{vJG7r2Zj_ zbfVWu#AIk{sWHjwX+o0=Ft96sckewVQDl7+NE*!NPspZhJFfCG$j4`_(f8UVtRRhD zolg&m3c_s*2j1NLE%xh`03mUxRhX8^OY<*7i}wBmewW)x`;ux)swi2+SbGL+e)W84 z<_KjML4$#yNW>x2K#qYmgz}w}oqcD*bs=dsoScekq{RE=`Me#Ez-BYrf~AdTt(KNn zg-JK@$!37i&^38}VG`I5*y#gueEKIP5LH{9uDzLxax$&1s@~x%!E{8T#esm z!>`OeXf$%w?t}_@J53u9pd(|AYr&+=j^8*&O5>#WnI{xEub=J1uok;ZgJZS!Ilp`2 z?Z5sWd6zZPo!-!(Yu$L5{Un(`&voaw+)^Jpjcala0J0xdMY4C4Hi+k4nA`de80F7NkjUKk8np@yL===%~3 z7OF5TB{@$jlK9tcwUc+Oq5V2;to!&8DP@p4bd|M;6yJ3kJGA0(EzZa4k9^!{lp(nw z`}+T_g8h1`TAv$vlWR3kXyZ8zHB%DDn}dvw;pwy)47&nVEUQYpmOath$;GNF4yB(C zm1RqDzwg*BvsA1Ydwn(OD_6_wf5STbhBf+$hV)(8tamYFGuhudOOGvxaH>qgeXk6t zJzG0ASX3CF>H4&X2jkCW`4ng#(>=fYcc<@u(vy{{aVv7?&;?gs*X>NZ+MnVq@pH$G zlkOV==Qa6Y!r5fJikFwy0YT5S)Q4Yq^kd=9#x1LtwmPUsp>E|sVmwUuVty&}>_axj z^2;6E^Sq6Lm27v&{>iUC=aon5X}$W|0RES~i>meX3b`(Zm3KwC%lfX0_}wU#R-z9J z7wTA%6@@_J%wpusvUnxJDf@V6UEAU@3GGc$CT^R;T&Z%)Fg3>SYC|7t)EX47lCU1z zoFGxZ{F?P?!rtEAl6uoobPS7r@z<|kZ9C?6T-ScqD#w`U4iU;hsd8JdUD*9@6tR^3 z-s;=Q!Bhz#%Dw&lWxpGG{m300Z!~%TJVS+a%r394Mj4Xudi>d>YZ5|T8}08;?S0P` zG5(n*xT;>PPaLU0j`*gnZm%$}rYvXaQ)dG!TKWt&g_{`kPt&4(kZY=(Bmh|s} zWtQ5uzlBs&6pk=~ z%a*wcBk|tx)S2GAoo0c0iJFW|cg<|qd|6#x-O$ibW_EV=70Qna^kx8X-F62g_oiRt zEdw)B)Yg6vAS2mxUsGV~^EItHhrEZ@lZ8C?U-htBSg|=dIC4u%6*n4>*G(GaQP+&d ztH#F0mIZKn9wa)e$I?Xk2YYcEZ#ug5Q%>NzbrGe1NL$5V_?U5UKUu{VO-}8r0hy9$ zI@xWN`=kjLEh1flvtAYaN-7OdxWX;JlyW%fJ9gjr&KCb)O28I|aryGzazP10ysX9A zSmnZtM0Mua;faYN2VQ|RYb!s)T;-f6OPzO9RJ^^L1o!gf^J;4~m4>k0&CDJ*G&GFW z*k&l@4e>-6X~rn!MFF^TGPlM@p=5)CZ{$B~9_+jzpJP}2np)HzQeMJ4uQBa7L=tELX7}h|%2Ca$qEHW! zu_Bc)>B;jSWhM(RWY_A7fq7LrEGcQmIJV4U2&V#_ZP@wBM@B~WZELn8`tj{3_>#R- z>A0eXAa48LJv`PVhT~N*SlC2#O_C^-jrk{qu2{6B#RwmNWghvv_Qg+dU6#qWRp>7> zxTkeRKceGO$s^;|`T9UQ90I0dD6t9>(Qgcy9~D`$ud`mfE^5!riZh~D!y!sMI6BzCtx05=h9tlg>&nE@n>Rb(AhDDysXP@cb*!$PPaa4$i%3X*m};?eVI4 z?r?~l-F{KLr3~tmT(v@tG&-3Wgg*@9aQ(DtG17?1YHycF;&-+Cv~d;cIfc+0Hw>L5 zvd#Ro*9Gr*)H#xPN4qGj z>bEgPC8uWBLk+tZ%538#SBNCm$NeeT$IgW&n_5WtQnflGEw3+g^79uG-B(NG3eB~p zkj!@dRf)~mtt2TKAh;9XXExR7>9&*=Tj73S#rg1|#bmu}9c zcg$|{Tf=~xvvxf7YjvJfS*F zh5q_nU2$Y*CSj16?(bJW{Qjo`WWpu{&J~%7=l!SE;>8R81&vl#W6cS_7AGGzEu$pr`}u_Q^l>c>|rzh+Wg5M!UiFcz&y3eO~W8*>TTRJB%c0< zlHUMS1Y-ihVCoF5^|hkcULlY+4xn>}m@|18~hjUl`SM zFIume#VyjVej*?sz-u=bnCx|AelmAgXyATHeL5oXAX|$+X5+YPVaLMEEH3H*$KWY8 zv6dvI&7^L9@Qr1$rh?g%;_w62>XYIle@~+Bfp5~4&1ot@WK#Or-5gPJ+7{2tBtQAr z#t&pg6S9e3xtnhn$Twgo9i(xcS10HbtBT9L=kga~gZ^10YADmGBL;2|Pp~{g*>dma zT$3kV7bqKczsVdGG#wSN%^H=)5i@EaBzWqe&-EwVkGj66>eT6eHJucm(BBV84!v}h z*sR6pl2)Zf^zYvHIdH>EP(g$?N;Bz0>4`&@7Z+>(a^Xz-Kx(J}cyi^y|H2)#g$X}k zmdO{aZ@=IkQ6C68&CL-_<0pG~y`Y;>_r)T9IZkiy_k__^GrjVRLruw@gpAFbL?IXb zYmDfvB*(>i>X*sHI-ar>0nzA=VN!k&UwBS;|0#JPO`mgwN&Ml0N{~FQ>bE2+D=Kn9 z_vsTjNCaf}l`Q4)?FtY_8urJYGsJc;@LPeT)6LRUsIKQKE)&Zv@LUS?vFsNQ3uNzP z3>T)M$%#VJeru8K&U)IDw8<{p>nhZ6Ct|?q$Inq zrlZ;B`B21?l9GbbB{ z&DhFLqDi?ABa8j;I*xVcA+icoaTPc5^H(vj?ojZONOOOy{~b4`oz4(&iK*)MGm6T@ z(h8+pYFDY!EfAFog)$`v$Yh`ygTzYZ^U?gA97(8Ah z(s$lLw#XKQPK5b9OY^RGf15cj4%`>C9c%zL)dp z^IbuZU;4N9UBC8dwjY^haZ(joHXnaGQH8$-&J{-(7|vko|op&sp-R ze$G)H`<5(x3=E9j0{s)|orS);p-?{v`1N_?3&dJPt%t_bKCO`EKTZ_dk_0WVV45awdvCs4Ouw*uK0fC`86 z`cK=A5r%teC3-~-?gtRl02f?;mTtLtWGe1KB}=udrC=g``GVw6x>z? zB#AY+R~I*(x-se1|0$bdd3p8Ug7L2oR{VK~89PgaN5NTNTvGny^18iaVRbs>T2XO* zI(3E^sC|vW(Lw5basES5WkZuQxfz_<`-K_dYLfQvDLFsO(LK$0B^udpsC4On)U>{j zQMXw&i$9-dA{)+|p>cQo4FQ4Kiky&Ow<(?!a?yM}6 zpQhihDFOuCAGa=m3bXUO7m`XnK_;qTGc1Q4=TUvXmS|v0m-j{b%%*w4rfnNOChDyaQUX&>*6E zSpFyz2b=*E7zu!Oa%&{J*8#p{){wejV7FzByT^L%D<2CcKuYz4C3+WbyD?Rm;geP` zN7pQ^O?;+u4uY6_oLt|R%^cfR_o%c3{=tED+%2DgNca-4N0}#Rl^F+7d29-M9(hQ2AWE#UTN$G%6zUYXi9kX{u>T*bR=7WUk0L`}4E>?RR=RIsEBv*sKwd-A!O zy_bw(O6s+NATH45**!n9K~k9GpH0J) z-l@M~2?+^z=4((de`Kus^G;G=NvfS!lciFb=kUOa;aA+Q(|H1##u6rBYi)x{ru$Ki`s_~!(yrkN z&j6gDw{IKLmagZvL?>|Y)Bfn^f?y8h)+e7{TtKOpmys`P=vRDJT63z`+EOU=9o}qF z&m*+Bb(KjoJ8eYbe!i1gfj=Hocv)DL5-m=a934fB<~h!smX;*3y<`Rjf313|*nzj` z)A^UeJy$sI7E`MS`1MczrS76Fqf*L>$P^OFngkNRhyD2 z`I@qONJh5tb^gqm>_}VD&Ny-J08IwWi$qwLYKse?#~^k~@f_G4Fr!d|8UIl%?Cr~A z7&Yw_OV-xbRMpjE5lj;v9)2(3=1aGmp*23Y34^3+@yY$uR2Z^U7&xz#U$n{d4+yCA zJa#g9K#GVPNV6np%=He zjO>zcp2{bc2d4Qqtr!T{O_VlY=Kn7Y+H0cfaq(IkvYE1zSL%?0b3LL1;kJ6aEAQXG zN66XA;y?x{=M7WL}e}as41`4uGr8l8q^ue6*|<{<)?+gVxPR_tamOS7w$UaLe05M>sE7s= z(MCW#UP||lG0{YbES2Z3A}}l^sP`zMux3?X=)EuBh89PwKh6WWk-V1qt0Ly9(=ha+ z4pDJQcilZacaVmO?x$_j>Ca22#?`6_gQV)dz@KdXI6f+iZf8d8!QE^+BnsaFad|II z$H@6P1OH-;M)<7R)=Zm)wRMg)Q8rGK^95852XuY_p|dpoEz@(ICptMyIjda3CwJ!mt$sNbGW?_d-=w)$-}_#wc);v&FU>`a^ex4yAwt*IJ`BV?R2dbIlks za&nNhbzb?<4B6ZpIu??YXmo)Kp^25bOfXu> z*8x0oRZ3T6^5W9`#Z>kTN=FFqKo@Q|sJUVmiP6~XygVsr37o5yNVC<#(o&#c`6jk# z!=ITDSp2$Q{^Z8vv8Qh{3`w*aJ!)YfdtLWS%m5|=lj)sr#6hv63_)OI*C3G=rPB{^ z|Cw9sAg?LuexFxh@xK1PYN4;{NkBr49MmE{cjL)Df+&8vTEKYG_RJYTVB`A$7pj{Pu6#z#%G&b z%(jOeO&&Dn0J3|}da*_tUjl_<75yWe3-T9j&VAl*+9PkN)H{xJ_HbRhVkHVFv2GCX zYh-h9&6+7{tE_!6ej;HKxRHp_IZbbA7N7TUT4i$FgLoF@-9Af^@!vo8qyRMJbVztv-IN-ith75pKGnga)9B%6wXYu;V z%3zvk002Oad#VJSL1H41P)9>p8goIJS^Ubkkyv4bmWv0M&3y+f3RH=KB_s5RbKa9#<55Lp4w9fF@GFjM1nSYRo z(UfkJr4#I5NYi0nnZ5u$uUP0XudNMlZhp|x)*k-(Q|G^#E!GO@^8;-Vgsx}G@asHi z{{rwsK*EFgo=XvkCVMh#BlL6AE6erPD1OnZGf#LwfuO$F(hO?l*!n)VEIxu)xiaj69hGbAG{ zpu_1)5J!xNe>EIgN>Us3JK>-o#V~0*so5_B(L{RrOiWBb3l{jpH;&!@Zgo^zPYLQe zPdFl=@!r${QchJFh$f&}1I=tBy}_|Dh7McM5Q+TLLZ$LIslcI8-E?B<=wD_@|0!J@KQ^B9}ON#B7jl&hW1Di=%FqQr>^N^31)6 z!U_?AU`BE-EB=+k^>r%{@MZ7VPku-(D3FmCJj@&^)-8a}AJP;oX*#W&beY8=3K5T% z&MNnkzxz%qKKtIN<6WjuZl~3_#+{@M=&DOa>bd;7#H3TBP(A6kVnR)hXkw^GNw*2F zSbqN?oGmpweP8$oj$`_is`FI543jE{3WX)3uC|r=j11GT8^74A*7Pb!4|h}xoIXT_ zl1sNS{&+Wt77o?`pIL6LdY96%@p0&po!91n)(8r~aL~284jq)vxfvO=g$wTP?j|Jd zn%!KU{TtqA?hPmV|_7wPPF z&2Pt@0DHY1ipstKX=^CRMDxa9Bb-4N>?{O&DAaxA%6H?A--%+;KT?v3x!2n}bn&ue z$O3Fv!abMA?LBWX2J>oMrHJsZwSh^anM00_FzCM&o4I!&LvsGO5eSsA<}+^@5M3UZ zYOMMU2ZV)%K}?|OVU)%Q-|)(U5T zLZ9>KozUUCZr+D4gKh%X>(TO}0ikecLR-<o3Y_6uEQ$io>Em)PG#% zeB0zHCu$+BsRcmaP#cgymbhg&ua;3)W`2w4Ei9@?wiO=%Dg-O0>VeM)v{j;rj^VK} z-gT1hGGon=OR)-L9}HhNLQ{5GQt0Td7hwLSXm!1T*$AOx7VpFEqfa*)Q=x2?>nZd7 zo<}EuhAq^rAW*`8l!u?h_jyRbZW*P6@MuE@t+RJ7%KoEe3=in3cevf>lm!&)kNx$D0?*@pbMPA= zYP-i&tRaa}jDYNILSUy1*RdA(pX8}TnrI&F<_Hx*WJAP)s;T$wpz%OJ;CQvX?(p~f z4jfvL3-QruyLojPM;-UR&_!Z`!H~qhD`esYtvXH*W(9fTR@2%?0jeCC9+M6U~1K8^jXrF9wM}~v6Mvs=&oASr4 zn{*9HEZ}at=IxHwti21A@;KI?-;WOVp&@a0&AkdHtD}+X#w^H0&ON8lUpd*+KdVHb z=0FF!jVpAYQ=k0P#{g(|NV`agp2nfE>A35_>9QD+Px%DL1=`1kqIqP3Q4B4<1(dR_ z3cQBEwbdGUmd$KAs(&c*8iuRzb9|O-qnr&caDtAX?6hk#$n=PuJTfw3`=03HyD)^a z-q_gu)%rkAIfR%=iJvNVmYY_9!h)Dd>vk(EVxVEg?#nm$Uimy0DF|jD(9+5X08s+2 z0Gb$5;dh+v1yf=-j=`jn&OrN>NUSG`PaTm1L0h}y!H9YnfB?8m&}=%wDFKjr(A!Z7 z<6GojUvz28ne`;1+;E1hGu)Y&^U5dZDUV7gPC6A{v;olZ+nuG@y`5sixRgZ$gfeSP zPbzwpeyV&5B9p#58#7atCXPN^pb6a?fQMjSt!gV+{p?GKXvVDf{CNSwBwYB5 z5h)L96BrUG*-b${v#_!n0SgibOh$WqJ6oT=`&y;j^sCDby_};6CX7sf^DB&NQUR1e zC@^0SKOTbF4Lo6x2(IDMN@qnPX*H2Z%)!ZNIW2%n=|Ozr;`n9O&hv$%=uiZC{@ap6 zL(T(Q-!u*#-27Lf*ZC6{ogM9(m94(34-~2LqC=gBa&d}2s__8lUJ?f+DP?y~n?+c? zk{@ckY-3Y5e~EQ7@$9R<;Y~#Qk3*u<7$hF0Je6~_{m36HA9} z`^h1Q62*Y%!3TAhV@fG6)B7mLTS;AgH16d2Na27eo`8c?x4?xs{_|=Nzy_=iB!hpR zKiu@lv;IEVnW)|1%FBr_K*jiHcs}~mTa%bBJ$h>&8Ad6kpKKgWJlU6+oK%+HI98;# zDOROvt>Lpr2ggf)#-^j#$87E=K?fJ2I2zzf{ z_D%)Dh2$~8ers4tkk>L`E2#tg1BIDn#{(>H;Ms7T@;q1qZ3y5HG(jxP%@vJ|W_i51 zMq@N|K+6ZE>*(s&Xqt<0hv)0Y*v-2_POJV7nr0uX)02gTuqcmoA!j?(PpP(r#HcY0 z=TrPNb7xC?Z6f`nqG-R6U1{wD%}Q=Vo8nKlsL=P)yo!r&LgP82i|fYv_;g5R2UTvp z%{|~??MAw<)8CBCHBHKY*b9P!h`1sIjutbF2n%D;|;=I#S zFHaC58mBilpO)rYd#-3dyF`FgNkp#k!8GuvLGtqhA=T*uTy~RP*n{a5MP zvm9J1{#@8f^3vYfTvHy(l$4Z6$G&fzC0&DYnfh#t+HrSrfbICot(Wo0wzknTq@V9@ zbi?r2!>(J-!@$eI;NQb`14V{*7$-}bL{&iLV(ksZc^Yv~$^@mDbJe&u-eR-=MZrB2 z@nPIjdY8wavD+*~W282bLV?=*%^hB4HIYyKclt6I8x~9g2p|K4VRaCZ0KxZaA5I&H zDrSW6LtR2rA~cutoawPhp$!KYhCI)yfiA!-DilZokZivKner{h}G`*E6zfZ8FwtwcwG=W zs|8%(Fet~>S=Dj&=i3gy=K|l=T-W`u zJzJBZJ%i}zUolA}s`S8B*VXj>v+%&Sbdg-lZ<9o`psZy}y>>NTLy6u@N_$Y(*5k?+ z@A1xO@6@AxZQJ38*1H8zQfM$h)+$ECMkJgJEWpn(ZuLtjUg&gIXcvqMVL#;YFZ8_l-)OyI6;GUBNTn|o+y~cL z=e8S<{5|Hk8{GoZJKBOvg2|aO=8n?3hL4F@-mLiD(EUXt<$sfoLfQWPnuXu%44(Mh zlvXIG(8wnZiP4be_9q-h`G^D@#rN#s)~JBe2o;9cZ8sNqge1u;^A>Pcyv&Q0&Z>ZZ zFo-V>yq*Ik)t1`Y)mEyE#LCLbgFGGQy)bada+*$oGK6{SC22TPMn2n8fFDw46OTiv zKkiMM_jl#94<)A_6}|JG^D>IB7qz}jAEhx^(Tu8BOkH)nqS=bs9W|ElqSw4^cw`RR zM@6;0;lE8NOa@~RJCU|@A}Rl8di%JbJ8qK~lsh@(K(v7YsW7OX+hjmTZQccStbT5k z%s&m%%}%&0z>?k7^1kpNqmz@xC7x@~(FvNdB@wPqD1X~wEkLlaSoy;=zK8FG( zxKpCL-O1?1gj;O})WKeJ6scWgOj2a_hG8;`DZ^pJgF>_@Y`FR6tl5)yMLeY1mSI(8 z=I)v14nOlAzA0udozsZo(UBqy@_qQ?JI&y2Mv)Wl@Qk*Q8wFtVDb*+h!pL|&o%g2@ zE1~|`o<6iq8aKMj7(voq{uMy2#!pppu#3_`n7-@h2@E?u=cTX<5mkWl@BI%@h`+H8^l0 z+eLAO<(LIeU7D;i>C8J{|>(ix4u?pfPbWeNH!*Q5*ZN6K$?jw=q`Ox0!p5PS)n zvD=ztQRPoar0KY@h{0ERXc32h346FXZS}slMDrV#OWUt=6)SFty%Je#)W;#IH{kHt z{M&hjG}ElN2Rf7E2KiY7ig!#TRB_C;nZl|P$YsGAcQn?WOcD6Rs?YTiAfOIPDDw0rN##A7JOtEde0zX{C0LBY2?fbZO6 z5iME~##iW#gF+SSKo7p@?>x)iYwEv`oPXK|Amxlnt0H%D@FHqRlf?h1+WVMmZ+AEJ z$5{>_2=EHN^Y{0!@ILbb_bw=|(b9BDf}UDPe;=IbjvxUNNTb*>4bflLUG-7$lg@og zr%*}}I-z!OqYJzgxleyYsQV$0YuK=(U2-ADXgr*mYz1iP`_s(|4m&*IEZNt%W!BGpI z7t-29yhHj5XB!KY8G6iePn+Iq&JS?nV0*rZ~cVcIiLCO%N(aZjOireIFG?cCCvRu`6k zJ^f88G5sH5dLc|AUx~fb?+Y1Ok)Nb=ahE)>Ti+N-fq3lio9A#VU(M`soQ3RnFoj9q zWy+e(P9RG+?eF|<#^TRjKxQ%ixBq4GM75;Eo8hi~)xmASmjE(AoPv(vwjsrGyQ411 zJQ|V_RKu_*FlkwtYEE@YrL(?$*)v4WhQO&0qyb89RU@2oG?cRoeO=$IM3h0ycfd2r z9^0L4$A|=n5PAw%4+K+#=;(HKasXD2_Rtdp`cj);B9=dE6sb=)13=Nwo)A|izOUA?gk(%ujhxk|5-BRBbLC{}U1+C;Gbo?7-af_;T^MeU^b|9-q54ucTrHT2;E_$^e$7Zp^A6f!nnVn_-N|B{ zQR{^;YOF*8;!wfxWIRr%)kA$gqO_KI>cIzD*_i@&xXp6?u(vE~SP8k~r0Hbo@?X6& z@dqPPwykM14Nuj*?!rrWk(Ti{ux~J{-Fn;ak3(*pP}t(T)QadPwiM7F)_{gcaNE=W z90gHlo;nzY<1yg-0zZyCs5Cwx@afzWD*i+R`N+hOR$&-@9CSKzRZJh%|S6@!_Eu5cL+4J}g&2^5|!=vR-rlSLx_ zVODISE(L`mj6jhK8FfNO{X+a1`Kb>Dv0K?MzB*F5CQCFJ$Z!?%zpoL4)%#!`#dp7J zXaTRVb*TIdC*!>P6xd@_V7xSUMmLqX>eco*g z;PH>X{EQ5vpIb`~T0lC7p<_HWJeZOkNaBwz`XJ0Kk9P2l?BE-7>5(s<8E*PzvdY;6;iTX^dwE|SA04!XYgE+! zzv4~_KRR!WfQ@+=Hl?;ztvDd5tR{4n&MQO!LXKM*?N7MOhSA~_bQqENBfd6>)_ll) zk?rV&m2A&22;*fXoF`p#tZL_p!AJIF{XNR&3Cz3&lWv{L*&q3-0sYgxvjQ5-Wr3u7 z@DbR45Avyd$b$vJmbS<<$a>rFLBXu-V3eT>wR#8nZ_*Ow>sTI}HI-ZJ9ia)>P~nzu zV_w9;#m(1X?Bb9^oN8Yac^J_yqtxSIN*9IBc7!@spIcjx0@Oad+W7E&uLVdAh)(?k z40|Ix)Y!M63uA>?v|&5arunVZfoNFO+mY3*@=O0lu~w(C64#Vh_31RrpxsHg{!A-PqsN$pYbwz%s~UVM z`%3amHHAI@prD&z_;>d5Uy0w^I5#1$N;DGSGi|AmtB-ST^NI$~1eTVNQ_3TN;$^2g z{dGhZKbe?1nGkRITE^H5`UmuABLw$LBM?U$^q16SWI`Cb6ViWNMBRZ}ay06FqF!6f zR|Y3{7C}CUoaMgZ(O{l{C|DKG`jX$WrmIofn&J zk5S6L-kLS}z1DIoXU7Fhv?rv@!{5I(g7x}%7;g(ll$Lr?l6p5_*mFSguNr4FYXM6r z1A&ClCUu@#t}3I7zIuU9;JW&K3R9h|i_B`ZI%<%1z?K6Fl+u43;{Qu8Qsd;}8g-YB zyHs=9`vS36lt1h9?HCo5ty`-aN4yUIITT@{c?VS^B5*kO4h+(Bai02zUFt*MzCHM5 z1cC&z*^xi|^3D4h27%J`r_ahY!D}0O zWqdu{a+5d0dLyEP6Wo^WwE8{m#l!A^TX7E)o#U?Pj8bYYc>cFNQ0#%k!cUvm=K%wp zO{?lfJg~PKe`Jq>MuZ$;>{$Ic8_ri@+M5u<3l__tiG3KN#jvI0!YAEk_Q&6rla8! z4p!DwIQ9mK7|vuUP+pKFIBzkD-AcnDfB1!?*G>LXIVK_{b=X$G5sk{~>OlkILI0Jh z=vfa>ni^A7^YDCW2Niia|2spHqwc1^-BA-P-2mM?<`mgnnP z-(*sNr0S$Q>MWW4ndyW0c-ei=o3C!;-+c5Ysf?B;FsogQnaNDmthQ=+#?joJdTp4w zYB;CCQq^~oAwpI05qcgbJwEZP4}MJen72vFB2Dg$8^_qMQ{P0R<&*l29lx>Q>M@-N zrtIpaUvhR{JB>n2V63rO?7vy4Rf)wMdldlM8xzt;?i;~C($nhe6WcJ;t(u>r6TFq? zAj9b~Egxf}Z{BRA^`;5F<>TWs6fS(he>UZe{e74i!`tk14>)l-kNY;iwYi#v;^Jiyg*$h9SYZR#^a@$^Pj`pPM>h8APo|DSV%4&I9 z>cDW7z}1M&C-D5GV!}$oYC9t~H#heI51l{}Wy71~0!IPr_uD>yo`zQ1%5LqRn}9zy zsZXQlu^Sc^WpBQ=mX^)mKekcP(HCk|0vBC$6|ZwAJ-JRyoDQcH871%?*@$WX`Si!C zWMLR@-@XkD4OQX8A|N(iyaD*9lJ4+a-*=RK!V1=IUQGkvOxjDCaiA0MDu z{bIZd{FA-v*KaYaD=GP~Kl_?0pCXtzAT#7wW57W0@9R*^)|Rd6#gCavYdB8wSXOqm z?D?VtFMP?TrInQtg8tV6S}1%dzrd|xHFy9(K7|#3pH{xH*Oe#VK29^P=ycIX4Kf=UoQX{;=RSh#Fp(pPW)*)I~FSO z?Ck7}6ZCYe)*Uo0H-v@x(%rqoAg0qh-xdV@)!CkScAHwAiI_0@{tqO=Vwr>=C&JUy zZ+U(5@d!SkJVcA__FG=Ifa|qdROV9#Ttx2>x^?T;9ze~3=dO3cBwm9*_0jc@8w4gc zHmo2i1>954)+wb(O{Z7q_^@tJJ&vqwRBY_jkYnPLyG|REVIXnOz*UpJ$_-sBeTKxA z&+FH0#$WJBurVq#6i~lBB~Kp}4Bz76Ax%q53k(ic;=}#-w#u}MG$5mmHj=WNIvn@C zj=X)7jg8=7(wzl~fKQ)9RwoTx}`K4Nhf17-F%_XNkfAKaT1wTYNeRK4gzHY#xZ9Qj$K{!0RI!W#4>Gg1vlrTZ*8khf{+#=hM%am_E~$^>`DS!66|H zSOlm|M2Qq+5<{&C;gN(%+`esBLsO*{P^XUh25Q66~L1PZGw~>)PA3m^_oWK!3aaUI! z#5$LmljFYM1VShYs{yJ#lyr6_R}i{x!O&H>6d|xrLU`@kaJZ=M=QSsAB~5OP#lC&} zYIXHRG-2h9X_zedZvs-%AaJtJ!g;Oljh=jPIP1#CiFKZ;;$mEJaq%x-zC02WLw~vN z?g%CqsDmu217@ryUDrcN*)awN2L4W?4LBn4{?BVp6t;q-lvL1YV?qKML@O;HA33$x zpR{L9gG-!hTl^b8E!4ANi9LIIM|@bQf+hr(h)>UpH5MvQ?+6$&@dYQ|yr5PbmW ze+H9T_WQRfswO?&T3GniXikND8PuL!%2#!9!xn90mCqaY<&t;Wp?+3IaT^j6*=q%sgEkuf~gxj<)DXL$z#01X_(kMP;@6$^E&#{T4kvW`o<_ zC!+`f|CyPY`{Bc89A=i5ZSa5vKVM&Th#G7XR+M$aUd*WN)G8^P{cl+~E_BiC?0PK? zCL~xfD=TJyTuLmI3uvh~F)t$i{61HJ%v;cK!3M(;GBu&0pTXQ70l-1;tz3-B-_wI8 zNraR;W|~e{nouanwvZ(L><-G8{5fibrx+}b zmQX{0xgD&BfhOpV#WUxvR;;t+7~$vVX9$7HaHp;`JpD6h5n+ohJ?Z-pS^<`x&X!`3o* z_@02Ayuj%;7K-95aM9`SFFfz&@;<>3y#}{m0AxiTKgI-_6b@A4a*Ef{J&;0P{`uq5 zx5b-;3&5`(9(@tE;jzGHW@XhLKEJP${@E6FGjmwVU7k`oLxpAy2x-*}st7z)oGAd9^H3;N&^=H~a%g=_LkBs)Y$LGqY}{&)*=F-ENl zOlVQIg7H#PHj$eEXp^X^>7AGRKd9c_m2U?_4=VtHpTPM)Xchf|6E<7W@`a;LRPq9Q z*HP14O@}x!%(}r~p`3-2T4K`DSV%*Ut8Qrri-q&PfX4ARa6c6LLUY$~c^C&qL>GNiaNT*1X{e{)mRfR*IG z`=CfIWNyyb*WdqW{<`OKJohQVz#0%eE(jo7aPq)^xa~IqlKcaT)k`?LFdK9?d2^M8 zp1v7snk_)7KD1HIa#O?o)gOOGn@$~jpMEaXEPs=f6c(%Jc121`%4NIru0V;Zii!cO z0*QcI#po$ST1I9jI#}c$cpY}@yX~JXc%R+{jlds@>ok0BzZpkvUS114b-};CUtx9P z;|(@8Hq^_r(~Yxs=#Zz;cgcAQ@CFkjh+-kdI~*QW(y^l@D~p}%GIIslL>)i^GfRwWyQRLxk1-f;ooGpiyIU6EJx=GV2h4p8^SJi)&7ohYQYc z?lNhz_o*u&H6(^Ks$P)Z4vMJ#+c|%hg0?1CU~gxqB5l6{g&yE_L>M{OCyUA%@bew) zhSH>ux0)otjz}L|dIQ-UCi%a`K4XC9&K(Tc^!|w3>7Qcnz*netUrez+{mo&+h9@3W zR6Re;)RSNH@a&NrCGuX*Jx^-J%AQmgl$H|QS1%UR(V;*%Psu2fS2y5(xSiK2wzs!Y zDDeFFw*Gnqot_;03#iE3x?8932db_0OGMC79`J~m0Q%rR(0|}RhVA_t0Vi-ObCdVs z{rguTgTu6MS-kL|MUJ+NhIZA|a2r2+)@oJl&Xgj$%;&I(-__N{KYlt?abya7>?s_$ z&?q;>k(QS3hX-yL8ykO^79WxV%t??Zc3pgN&kexee{UNf{c$9E(v!|`9=qEp1Hgo+mw^gIHvPW1?O z;!i6sga82G)v2**VIQ1ROR&cyf4Ca#Nx87pRl?#p3G3ca1$)@NqbIQP#|r>o0+0?a zzwh;j7`qI}SIohoVr(FA-Gy=CU)-zPMs8jIs;cUt2N=e_^!EDQmLlP_xK8CVeSsf3 zw1B$wI`p4kxgm^i<#sRgy`r)*8VWx6#PL`_MNJKQQp?NWHd&dN`dY?5>J|ZG*VH71 zapDsaUPK}L9&u;EksNg9*p-+P$BY%HzZ)CKXukpls5h;D9O;W#o!i8?N~)@eQ@l@k zfZtw_ie$AM<3Q>^ph|pkuk81^`W>ilC=So5c4z(afbJpcOb$5der;pZ$N26}^_q)r~8>ddz zoxw5W_3HCyvHHK;-AGjdkb9xxpq?9!_A=?e|NEY?`_G@*h=%d$c9%%N0|4*0uIuC@(4|IF)jzM%fgE{iM!kBHkQ*!#o}L0;r#mULAeXm;6EYCm z%Y$%?IwmA2B%~EiTY0q3^2Iz@j=O1F8~)>3^~@)~tLhU|wx@u_0FfZiXz918M6i?F z-txTT>TpbKI^R^XfP4Kq9?X^Jkpt1S34Zv_te>Vvhxv0yhtcMAi~4TJ&GfIo{=$?+ z15Ggi?V6sRUV#tm68@y~93Jd^K$L)z8pqvGA`X1#>66=ipAiho4f{|-e_4AUlcT1= zy=w9K6Fku;ZE(p3KDJ8zKk0X!=fRfwDS_;1_LKXly z1Z{8I^_2oybeWGUdWDEy)NdO>Rla!HX3KUO?G$ZDQ3=B5%j_n)Wq37Sj#s<{%)*yUooV zmr_NOGW-8UpB&)C0(CeXHK(Tb*t`JeR(>D)Iz#D(z5)&a$!E!~+2i)cCMFk9;Adpw z;NqgCqq_tTfnq%U(;@T}a=@Q?7VjXa?*^X(2|#RZPT+iQv%ji|5Dp+U7f=Xm_<0`8SH>p-IJn7dM1PhS>*)Plj#rc@uEqE!=iXg+)Y4U@?%|S4!{g?VY;S zU-~3`MGmkaxw^a8zB2@>A1HU@JUJa}V~hScl$pumMvYm&zO21;=~6%f{8s&JTwLK8 zLNtO5rhf3?`jg+gvtE+5At({qSXf48IoJ;JtqC-QE6^4RD*$RiQgU+lCYxsIkC+x= z4?iX;%SfGO&YSY1tgcRFz+>~Hqb4S7R}9mr_S6YUz#W&Y6Oq~3LLI5Hi{8C^cW}Ef zGgIgh$;*cq!YTg2tcSGR9JXAI0(kQZO-a+FwzrS;nHUP7|dmT_=60o6rTHwKG z5Y5eDPZjtQt=qjHTvUa_$aOt_2tZ~G*a#M01*Ye75B=+6T(x^nD9Qgr4pAs$%0wtd zaI}TOJW%SiG(kW$X0c!p8yeTNEG^Rqr_Ih~Wlfn=kaSWN+|I;AUoXPh2Un z>V?EEq^4#)X`xLUw(MH;A6|$;xh^6l#lk6W*icw}E5_#M_};e0J@{T@~UAPUD2MxUFq(Ul9Ekm^Yua_8;+43I3J+ykL}mARag8kglj9J6iZ4^ zkHH3hg&@!hbV&Y&3MNpI%E%Nsec$=sgm=3!jI9BGNcE{@(MrrbGneh^MQLUST2{$x zgy#F#$#zZpq#ZX6Il-X78Axb6QiT1t%uv2SP|*0qL{e(%J;ub>oY=~gJV~Zdn%I_5 zz;9ukaEH5bcfey{R|^Vl+a?H~;l?9AKI|)2Ts~@+HT&io#WYvOYwq|tIf;=lRWU^-Ossn_L-MVusp-ay z2YSZF&TB&T#L~HKf~IvUwAk1ggu&VLPq5=Vqu8o=WfC$%0wKXz;YjV;+qXB_Zp`D4 zrlTPQ);KHbC-49~DghfAS$IOwKI-r%+iO`_@$cHTi*4n~D@Qv#OAhv~55jA|I0^P4 zPH>xby?Q^2Q9?f8o30e5n2AbAxpA`RYo2!kEr*4@V0@K;Il|LP#L!heUAFIhPM0g# zhn@s&+7PS+yPqN`HkizL$@#!IwlFZ#wgWfp0^XOj5{d%Rp+e;7DnKllqFFtwo|a8P z!y)yHxuK5suY`rV^6_+=ty;K<&C5RzNue^u>n<|o`kTD)L$JyM0tvr<{t#Kab}=C3 zENW$PykA1`(9_dX_w`kv*D%?7@G7`?T2LkzC;y3NC~=$L`Qlyu%G7@y^*@LtJWdxX z)BtV+NfmXow!OVDHbhcNN|aUY(L0kzbN3copM3Iq&Up(TtJMBV7UQekWmDKy_=D7# zeCaJgvm4Qg$f#q=#?F3+N}nWX_m||wo?Pmtz-uA35?hO87f=^q=*W3C&Qv-@p)fVK zv}l|Wt;l^=O6p7ChKq;Fp2XpF{AkhojR4_+XMo>CGax_-FYl&`NRnXnXI+)Qv52}g zR{f4&Z0R5?~^BNb)=vJf$H1cM6h zwY6#BuLG0yCg^CVyyzfF1NeuW7(YKhN_@OIsayVmK!E>VZ#q`tr6jjq`lqy~=xv}% zG`cE)OIwz!8z0)`+6)OZ5vvCt@KLF8V7>KZo}%yfFK!-# z>^->f*$6LuX>-_}kd6++d30~wL2tDpwzL5DeG{ym)0oHe3d*brm(FBrKWPpwo&-6N zr}m@aov%G4+JQ2cyaf=)Qf*Mqc9WQmq1k{x`pccpWTnMfGx<& z8#6ZMN|;>{Q<{<4?b_PpOwuo2EV6Fh5;URcqHZJn27wj$8D6!+IND#^8T%pF%wpRw z*>_&`$E|PmQ)`5UHCxQ^<`>_IH5^Ia7GMRBwr8s_%?LVTiu#X45&i}|qM2dO^`fF>dkR+|Caqbs zW^w+1Vze8IRP&fMG_#b> z(nUu{6WV?B)Q|5o6W)M$kG^8zWpQw_-U?B-uKrIpJDHtZwFktEZai-UmXB0rP_$Z6 zMhG#{;j{$}WVVc`a9$TrR99C6Do*c z8U3&cuo&bGUpxeejXshe1s$D)v_#h_$z%HQMa-fP{0P2Je?$j?Livdp5cYv z- zm~r^r{W&JXXqn$iS-D~b(S7m?3L2r+0_inni9~cnGr0VS^n_pPd`{5S|! zf$bApp5e-9k4 z78||j+O_`s!X`kccJ2#7OW&t~X4RV>t2s%e4M&7U6MAvYGz* zHLQW<#Tg>x8?+GA7_``77a99YN=oq16K02_z_b^OrPFIP%+Gy3aZ6zrKp|$X#6j_j zTdl|n=|IcGByp!an`!@lL=A0!9#by-j8jWE#j`Ouj=*}tQ(`zD54@Rop|EardB}%y z=vm*~x5=k(D=ws^<==m-ch&fUroR3XMpnLiqiK{6UjJQ)s57EV@CnDBR>_bu4eSZw z;^F&ge$f=gjxc)ZlBnL}q7&lBfc^7|ie@~XV@Aao7)b7`w@a`LqGDop4I#98J9fPM zWT@@G@eew~TR^x3J-tRuOy@8Cd;=R@N{W1AKof-Mg1ITO>;q8~rr z_5MlOVl*JCqdq>9oP4-u?u%lID_zKTfn&{Y4HRfY?%1k>XKZY0I$WKtsr_s8D|Z5R zjj^}#1ytwiMn>^uCoM?E?Q&rBz%+L~eoXy)pd{D;&%kE~{doHP?(^Tj{0U`@&`%1$ z8!(O6p&1g~u%gN%1paJ^7#Hj?tBTPidW{g{s}5^I^A@w6ZQs69SoqT_)OgTtpulPC z>MjVCpeQ>7@4oYAdhJ@El55@IRHDP@@w`LQhoKC zGuwkft(aO^j6FFCKM5%;ZFJUB1!73G_~#c@;J#dwAF_;E+ta~8=BlUhD4rfh3XR(h{I8tJBfG%P&hFm* z`;F+Q#Y%;e00xo;jfXr4JV}X(Bga18hRuzOi!0z+*7@_1`pM#RQd1!1rn|NaYM62X zDwPOn^n`u1k^g%TOqYxQ8@32_J3l*3O4QAsLlgixTLjJkw7e5m7C-HHz5l($HEQkq zAX}ip4B?C=hMMK2lit`N;ng9hJsjE{z;kf_w47no*YAz@w5F z^3TygjhuA$?CY}72J{wsV{!z*GARyGt*cc_v(F{u9i(SBtzj)|q zE&uiezB|BCCcAe1yZA0mvzaQ3D9zad&s^&q3p>oPY?fZf?^G11oi; z-)KUAUy%HfO1ZhO9%W(PNXiy)CP3mRU&aT;kaDGKh95~CjL4lkcW6T3}a_31~myVXU8`?=fZPb;*UDXD642PeQNpvCS{~-nakM6wJ0U z)Dfg5YXUXicC&a`81;PirrrGSDWd@sxMg7S=%dOuM@Mi|7W3^w4rqUj8#3GKi@Ww4%?|HeJa^~u@k zSJqF5t>PpkCAF-r1+enSu_!$#p7jFkbBiB>Dc%*`{Z1Q537p@*auJM16_&(RaQ^(t zg`YzpuCE`K8YLAT>f6-wqJ9~ zlYalFdXrFx_k7U3c55sA{?Y#eE6tY&V(EB245sfdK9XL|!U#5HjfzTUnJ|TpYvK7yo_G+c-o`E=;147Tj>q<5>-v97?yhq|Ph=p=lQJ7Pl!=*nymEpq={NRKpcE1ZDsbXB zL5VS`q`emwBjm1-rWgOx+K&5BMd^T!0K{5wg)AJ5b3yy!*yw2)!*ZTJ+^PL*Cn_h? zt@Nh;$j%VQBuP$zE282Ro7EjqB3G_3g2(})TM*aDYk4}U3)l(=2VhT}ZtlOnl2798 za)i2Tge35lxZ??*eMOjhF-~42uN8`U6FhHSwf=`!irkaYKNAj7s=~n}WWhI++tpxS zg0DOh_ZF-=hu=QR`nFyh2eph%LwmU3xbkDR{Eio1+2Fw#7#NfSzeteDwns((9=Y2u z3dPbPYvGj*Z+I(C-HJWcBZ6Ym4mvARDFKoY8L$86Z+PR37EgYV(1quU5L6boFoJmL z(%SiXZC@8`l)y{i?03>qfxu8;@7eMlxXH_gTbc3+SA8!ciQ7 z9`kYVaE0YGW|(B7^Wn0i_TD4^e~^eGJ@<95iA{Yqsf?dkOhgZfjV2G|@xnYl=-WWgfazPi{|N z-^<+7YBl5Tpg{-_j%9zXD5^jHY15Wy&jn)%c&XSHI*eK(`H}FC z@sJ(;Yg@EXu3eK-;$sCsAmkC!Cgff0wgxcJdkOyo$dIafe6!024hFWb zcyqbAGR+lz7mwBsD+T{j!F>r+uN?8H3%`El*2b~}g7C=N(-XQ7&<#Fi$3{?TNf{Zj zz@2sQjv(u8Pq9v+%%ec=aUh0AOrGsmy#hl6$foMk9Dld{9CyZpH!~W>7mWKy+g+GL zX~OQ%)LSptU{m=aA|f&kSwa@k$I7P+fLRQ6dP&(ip7~==VM(Ar;mx5neXr` zvT4D0<79l7Sk+ZgJ?x3s0m=Pe5~x%vH$Q&~#uMY%{`K@w@`e>%bWle9cs~e*41^L! z>^qRE=pw$iwQg7ps*gl>2C^n}AiExc`; z&7=gE`huZFiI4c$a8E^xjY^x#!r7^q`0%DzkqX~c(5x3h)&$=mauH4ydP3G4A>rrn zc?O2>-**x--brNm@J3r(aq82$LhW17<$A72Fq4qV$RI?L7S|X;Uwvh5DGzGP&Y>ab zo65YFk1`aO2i6M^vIPnd_<~xgrR;Np4{!o!se^0AcHqog)E?bH_!5**3*_ot5$ZnB zY)jyQ5OCag>&0}bl$I$M%PKi~7&O%M^nCr0rZ#V02_ocTq_y^NJaI^&=HuWXk`F?u z7RboIR78&_N^pRRFCIHnH_~ETT~I3q{vgr?PEC`2$++S~0ZlIzw@e;MOy$=DxvIXA}-ZW*;7@8#<-a2RZj#-2TUQXGYae>d8P3qr?j zf{~FxZxU?9#73_?bE&W_fnOhGFC%1^2{T3ww$6b83g!Zdz{3fV3b=HlXG?9YL<~%@ zq$GG>aU0kgZ5%ovY{4Up&ZO(+zVP7uC$cjuJ(tqOD*Lw`GcYh9=n77@p)ZejV!wi6 zz+44r+1wwoUm@KHK%b=t_gE{+%|5q$rO13D79X7(YxFsE6ZoPLE1rK;CHyz|O&Bs+ zF-(CQEZc?qAgEBb5=EV8lrdByyq~PT>*?qyO70-AD!F~*1{?W|9v)KY@{f?T{?`8z zCgFu&rv9KRT@N1o zy{LKXSABrgftXbjOEgr77hWmX>iPKi;;=sI=bh@{*uoG0a{rx-uQERnlwZrq!rs8) z{=Z<3P9OAB|53!Wl*}q*F??PU(LFrg8_9I{&lfFh_76=Bbx z>eFQ$=K|h^qYc}P6mnpG2oZ$T@-`Lt_x52>5Ogbd!&F z&aaNw#iNOU*ZPegQCIL5ToCp*4(P?kRY@}ckOUY5Xkuftymt8dUy^`QQ*5K%%3%bO z2*Sn9A|DWe1DNC)WSOKU6#g?qcv=jk)Uh2Jf^762L>!y1l5K0aL3N_xpbjYPcNPw_NoLo3`l!KLK{_=I{sUE!)`h!&;aGeUvYd3KG}^ zEFZ8A6V0Sf4Cq9{9RPrUovZn947MwRuR*YY)dJP)>+Y$+#s*ChzojDRz?w1~sQOPZ z1gAON+fcKWYhf8F38 z0Hi%W=PXNorB(WCJ<=k|C2g2;aLz+86K)NDB50C>+eN5P8|=eRqXEeld4Os8^41XA zMJhiSGzdcouO@A7S3uKeQl$au(()E>zd$Of1~C*VU-c>SDY5+*njen@h<;DU@^ z{nb)T_;-_i_;M%@cpFqm)VSztyP4V9{)sc9!(Wb&VIe@58m_Jq_6`n*$5j!VP#_`l za}x_Rj3rNZ&q5$*#4MtCzyN5K2R23N=4!zF4`C1`$dim3adxW=)O9fKZ20+f?fAkL zcig9IV6YU{C>V=>=qB!5;MLXphlbu)@bmEv<$s2JRLY{3WRY0?D^}FR>ZK*W@ zz=Gg^yZiTQ%Dt)q`Nk*&$Hc6x@)$=ZM7e2=;GVOOg?dm`bBOI}t4#pA%0w(SR`xl!goQ$j@&3i`wNr||0|)o8&1 z`{}*Ag-OR0Eh}9>FId$D>kJ59S#U@&2ocK;p<0lo6?h+PdX(Gc3R7@#-WATSB6;3; z;z1XU){>oLCB!o}B;2Dwyb*V7P5#n!Tw^tX&e~wo$$3N*28c)h@dJvnkn;L zPFLGsw1*Hes;c$7-zGb)!k*m7!=h*&2Z9wbRR`F%AN>6dO$hmadA)z+Xs~>w3X|yc8||RLB#%XdV|H z*u%Rx#Ner3ASZ$f8AIZ_DtR|lNIkbp{rqT#nwqpUD~SMrMMNt>YXdp01GWA#x4w@{ z5@QeUN$6KSO_e~orf5zB<@V37-<{`LC_qCv-$KgDyr4hTtQeEX!ygEuzF!nWZGc-C z-wF?mv={0UI6Jv{kX?tJF^m>(SkXKYp9XvjVvR+)EBmvc&ql-Xr@(b}$|A^7S7_E-M}Kli@Xl=2WTiH|_~8IWhnx;$5r?V6?}-?$jZ^w6OV zpeT}dE%-z%TmZxkZybb_Q#C41~|K{O^*p3cE5Q8A! z3BFmkZi!6&7Y-an;F!~?si_kei!Waut!ZTgm%5I5#7ojk$w_ILIa50O!Ds)`m+mnx zwXZhqa|=LDEF|>$=GwXrc@@IwiHpxGMC!xT41f{%xsCJKav*+_)ihMp%K0 zTO`!EXyO?=ndlUF*{L)XDqa37p7_pNJ40Odi!_wkh%hHA(E0BA5p1a+ZoFu$T-cW* z%)cxd%MLmmTZ^FkfPes(+~M;Hk$pge#1&4)iweuhaex8eBetA0qZCp(sP1TH;~k3G0U%b|I8tDBET3mO}+~<1JU>wJpY$7K-a-> zm3Zb1ohjF03rFk@0BB9pyCkW|ZuJtctg{oI0kF2<*s2;fNV=A`yB zOQTRrH`YqGaJQ~OM%stY_Mt$mkr#EJan>W=j@e`W782>H>yoQ2PV>mp!7hhG3LXDK z{L!ZiCk~a>a%?wrf#RQ_*g^OcHHoNyh-ZfEQ-J8Fz;?mrnL^oL`Th7aV=FQ{x%=+}AMnB#&$4jUe z(i$?dzY$ty$hgcuv^k6)FHK|@tQ`szGnD7&71o|pEQICCvba;gWWWH{JuT? z$hPOZxAIzU`*cr)bc6f@Lr@8&AcoGfkmbgcBhX~AdT4dANBu+`wvCOA*N+<^ zpA*RxM;&xsbY~IsT2Y3sP|FH%Wo{TX}gOqx+CsH72 zTxfdnaj@^5?|QL!f#9DA#ftthcftb_12h{ye|(y}i)L)<|F`IYH)Os`uet)!<#Y9w|D;!?uvP`dE&>tZ|04FH*N z9RYJ3w&?Qo@MwmCvlA)+c$jBLj|v}LtIq-brZ>TRyH~sViL#~K*Q9$k*O>Ib*0f4q zz0Amy{O0*<&#CqiMn2ApH)fM~l)5#V5%gR;XRu3rs z$oRR@ag}TBwcxv>zk@ebwYhru9gh)zaFijw$W!6Tuxn}6x0hbScYjA4r_i}LS(-G>90HP}LI>nVx0%QWLTG+B5pLUqDtD$&kv=Jx{?u{6atJG!+alf6H)vh%>QQf2cQfsWrfCQg=APDGo5NW-FRd<( z&DLtH6~>~OQNjmIHrQ)cP?mHH4^mI9)B9Pxi7;GUqeGrkPg<&W$H6b91NF{OynES? zgn~8F(g|eMfC~I?K>sHW!ioOkRx}C$g$*AvKZGy=b{Hjz9lD)WuLl}y-x~FmlqmKI zT(Nrn#D%=dn$9<7o#S4)51#z`_~gUct~ZH?k2{Cya*MfrMdo#5{uAN*Ik zIhRkJaoS($v3B!jeZJC84^f`SjQ5u_EjgR{HT-c?4(+b5bZ!Hh1|cT*XpaP1Fh39X zTyr&1Jx7!+JyE&Em`|qEX@BX_eeHT>Lus`?f8ESY+Mcn&JuT_YPvzEC`ekFQMsrVp z=n}tFUHxY zw(fIN^5uNNml3}=mNngx-;h;z-iS5RP`IgFuIP$fbX@tQt<)PaDe98NE^DRY3{!d1 zzO47S>+rU?GId8}b3N0M>zwqjMa9kbh3s6BQ%I+Ia!G{~bAc9fL6h7;Vder&W?_wA zKZzbkoli}RvvBns3&JgGA92_D8aAd804wN*-A5v-q?9_-^KQtlDv4Yd6H1J+hYlZK zeKBx+9faYR)WzF6KHx@kAsT&c4KsV0W(6an7xVM;&&J-KT?&LE_2Zimb*9bxfFUny zO;q<7zkcrF9?dB|-X_kK9P1YA4o-8hy0sc8r*fxwcRJFJUY1*L;A9rgWp-9CkHx6! zahG|q(c=U9jAHVqbJU%SyXdZ*(MS*au=@Mw+tpJw>Vrq^_DMfZ+p@A-UaHPdab?!U zO>*Zh@uZb|Z$4;mpHOKmFSyOAMlWr%I7hY2d&f2dL)RD@t7+%mV=;SA?6$d{ealee zM0IE+^NLpt@BeR>SaTc$HlbFc79X^!+ zHjEZwfx+eGd#yS95*{+8HN45L?w!$Ldvp3OxspSxA#^1=RSUK6=WfRei1TL(80Wf6 zM98}seTlmyD^QlCwvEzE_RV&h(wVd>Hb)x+%tNkNuXw2Dj zoF4A!=Mv|2wmdxHxh8Z(tUzI(I!!}Ib4!o<`|@-8W)|JiF=pbXn={jP%Vp;0DQ&fT z@jhHp=tRzDlk<}mXVVSeoV4O#m^G6zmEGiWsd;UVvQ$oqrk26Em@7M0_&Ke=)RL7~ z>8z9xrY%g{t?=UWT=qoZEiJ0BiQx}o&p2>CSI*womy45=lcFswv0;PN_0IGBi!C`< zh>MH#DVcH+7m;H9JEK`>3kgsmUOqOEv8rsXl3Ln&TCkOLj)6QXl5!KV)Ge`K*}3hf zf@TgIW-#3iiYjw;Yj4TF!)3hua@VHJ#xy%lm$h|ISfe{`I}Vwx~nze0lK{+ih$FF)h7oa4>x;F^|dXH`q@5s-86VD{l5d zL3~%-g!x#T-hSTT643r(=u{t^y`fU=YynqzO|6Tv_EzY0OnrNWiyWHUlGje3{ylqo z7HzS$Qu>Qpy%$!A`Z0=&Vki5P3%IM1uJzoC$b-rK3yaPL%ErtpM zDXTYQyTlJJUBjfV&S}bNYQp)IgVp-6hVH&-7ONH6lES{`9hEhvqZQLWmXdwv)XP?ej3GuKnWQ+HyfcqLM zqqYH!p+YqLC+Mu-8&aFs3iBm)S>)LIT!`E-qvnyf=f&>+hf5{R&Aa;gpbc*3nqTEt ze)7-eQ1o$bwtt=~$j8?V+wz?%S7ngaPu4tDS#wI_cYx?EV_;xN8o2h0pVIouK;RyX zzlbi-m7>&zLeN+26mynxWq~4y35rT`vXl*nK(l{J~{L=hlz6bDf=S_Bb6Bd}XIvGV7eF>x8H38Ex8=Mj z2X%7MJ~+3&vS(u8z}4L99r&P)#W87jYUxCiTrRL#Noc4$OVoyYsncaQ_$B3M-zdAC zrDeL5{{*9QV11>Ve3WCYbZOWtcAd>zrf;w1U>bj>{=P)^7f(qh38O|Kfn6!V(C@9X! zN?o%0r-OLHS03`r?{XCE@4l}zj(pd+aYN<>b>}zQ%rZyCO{lRHdM9l9lFQGczB2MZ zFh3}8aUDT&Md!P^OkvEyJ-jp_REe>vsqI)$hHa5o+&UEwUDgz(3O6`nw9>_a%J}JN z?|Y?nmri|tyJMfU@$xHPvvJ?Voxa_OjyC+X=6t!`;L^2%zUJDyBVzh^vEzKp&GIEA zlh}J0&d!R?Zb~}0+tZ1Sb}H@ouF} zsdvXNo%0Fqk5Dw(I%%uKOwn@Vo7nWRR>b@4cQLa_$MRmcfxfY(Hsds)(w z$rPb^6XRxN#%1}qc`lTD0wu&eINva;gljC68w_Bk!vzypg7btjK>+Q6h zoH-{mW56^fOqbpt82wqGFJ;ui|Ex`S(FI4dv-h8Qxwp4CWz17nJ)8RF)zcV#a?yn_ zw@f}gJFkxB>U_Ocoug`ozf+?h($YrNoS7ZHqaVJAgZI99x#Bo^uE>MS?#sOufBa5? zbiZKAV|i6oF1&%qZqs)0-TckYZYs-3Pm9ELZU^nhgjVOuL&CzAZievR;$rZ2_*m38 z@*L>-dB%-D&}i*r6ik;iKRa7@ zs!C(HFv#}l<(WzQe*P8G8Z^E-As6+HX`Y$9w^|)Uxy;vmhV`Lws?uOaW7kDd<1bg8 zA7tL};C|)38ec9C=~{p68hD^j@vJk{YJ<-Np!Iqnb zNSEP2^vf@4&Izv?{J5`Yt`)ZQ{PW?jPYl!__kT$H;y`Kdax4A1BjVAoPOOV-xmqCT zaj9c&xsa2-x=wWXhGqEXSDqH1oz;FAB(aOT=7Z~@-A=SlVsiK8|6S=m{WJ7chA?UomN@>~mjZn*5G;asxXL3ZhdMejV0*xO?36dUk! zQ=FZ5e_?8vK1sXSm{(#ZHc#SQ30@?gd2sa!i5aVbj5?~sCkCk^S z+PsR`GRTmeMhrrL`8V<$6I^OE$v6!R!bwNG%3B)@te(wB-SOt+TvANesI+rN%Sv10 zcy7P0lS6z$qK#(0jiw2A&N@Riwk`#YkCD9-1(bqBmZ#H}RaRviLR=f~G^CQ}C84P6 zu#mIix060rLQXY2G3h)pbXOU>l^#2c+_p*AJ{BE!e*KD+%Gr{7{q2Vw-%Vyh3#GUo zqfnJ3SC#MpXXfVSdRcMDG`><1u2K54H74jd^;hGt1msIbJE%VU_-^`U|H-z}w`xk6 zyejpVjmf*K+&rGg+9ok`d@_YDy}8do+xL#Bse1HIO?;i$awC6F)8!3nNCj~%9=@zs zyl-wjg^&AP*QZe2qg6-2Q-rt5`;7-LqW#I|N$R2!0NO2L50sB8{OCN8uVL@PM^aB+ zTA@*LS!cr?AN0A|dU&wlg)=dRl?lXB#xxgVe2hnH%e_nSVOKc<-ucq4UEIwRyN@D{ z)APB?28q1aZq-v>KM(gWcDsub^h`8yUZQP6g{N&3Dd(fsFU^yfiL_JPTkTrd@7=p+ z+uc{JjCZBT9?tn7s=PREUzzyJ$grD9y1#ikwtdEa#68?3&gv)j@yK2dmxt** zr}tCDJw$i0zS+uX=0v-HynZ}t!;CWT{S{}O2W1!(STA0QP2O?2v$vPQs2ldG%qg$D zhUn0cY-ypq!aT`En|o_+mg}@?Q@KQBmjd_lsX2_?OB0P;d+q(t1Kb-Qv&NN&<>W;q zFIvYpzT;*7?_?9x^$rI0G3O}}gB**NZE|9YYC0Bl-c0JxN!zN(PAlc<+iU2o-M=55vYItvhBx5y)79##8$IoW zM6Zk{8j6=-61KK5`>j>mV~=|FYR4AZ8C*!{{~&QEphI&iFIo$c=JBDC9$V(VEtjpY zOxim>ZoGFXq8mwPaub^gAN{7)MZFF;?K8rWI%h`TZ!?sPBGuK3S|3i1gjWZ=ezd!pF4sRb+W~!M$9vI zloWMEonOD~MMyY~mpbyThNfH?DJjCk@@6ZS(nvf#dg!B_@C$P- zzIU>CYb4yJ8V)}B;q=y!hK+$;)j`~Pd`qmCy5@X=t|kHc-=p>2;+D*4uwJL`XQAQ8<66{p zqsX*1eyaf%z>B&qLMv@Y$uCp+NGZib;3y&I|d-ev$gM(WhjAM;#w$ z{NBi2{PRq>!T$MyXRiSemL+BH{b@3uvgUJ#jit^RQ5bkdpWAgRuZ@0oi+jlq*8;N} z)yA#nlNxcYhl($BzoWO_lHA;OimSu0D}16xZ+`=_H@;BjCS=Nfd@f@|y{4_}UJ*HI zMDm-$SsyRq4FU^=lrvT0;XZ!vHJC=?g-e|@xO808D><+qk{0#@?fFUjfX2q0>!Pe# z`cxmG_>$C!=lYCY^LKW?41mhOf@5I9s5A0N(wM$ z#=%YR4^FR1zah(4;dQAsL*DyZzq*3A=hn5hDxMB1p07IgabimZe6Zll38BJY+cwOIftSm>WyRi+xwlz1rQc4A{wsV+~XzqfW6PKYhK%D5ZQZev=x zY?^OkR1p%CqIT_uvs(IX64U$DtB52zDyRm5?5_{VeYEG4f9?Q{LSFE^`y< zVhn#GFT&SaJ%X7md3ANT_Wl9zDYsv+{uzYOIM`F15QbX47N=8!l=?E78&cB_)t}X?_Ik5LVz(3fhTip+n}8IvbMtrUC<*2E$OvZ} zuyK2D_FR8XbMIbm1tWNjKFg_YrABxUo36PbwG_@_N{hXOjLdc=zDNmXrZGCYw4=s& z7YCGkAG$R*mRK)BZdK}Yw^dOae%R)nq%UyXoOA8>-2v5-(HvQOH86iJRnh6lA0sa_3CHZ zM9IW3;73Ir*Iq9?(MBUqT*p54?%f@<=drOyxeV*>KJs)+h2q%FUuQVt?n?PCyX>vh zy`$J&Vp)6IvnHeCH3z9bu7xD1EqcTskM+u-n(6K*On~y{zJqy7Bn#)t*FF04RLP?2 zt{Np{M0C#;H(Og8IE97b=7N{s)XJ*Q&FF!V!iet#Nui-B5vMTG9 zck8RnUw!uPdxe3ScMlzJy6I6SnBnec7V%n4OqfP}As6Hp6dcq)tyRu*z~78X+f-YE z3j>K}80rU-#b}W_Km=~xKY!D0@462)Iedb@e;=HFvUS3%f7$3jtyoCunW4`fe62b| zUY*;VUs@EOdhXvmE%@m4tJT|9H@f_?*{1e0*LwbAn(6#hG`+6FSC!`%`j-9)z%U?+ z8hzuaJoF><3_ErZ=`1IG5EfFEXVyq(Or4lIesjE_(8SV`85{v<6b#nl26Wp}b^Q5{ zXNxu1h=X+q{}IVOU}FFCbf00&gFNSxwf15F9cC(TnLoJ=u5E9~V-6tVa5pK&l{Uaa zNE0A0f`3C#d)c=W7!!tpkYwHrpRz9#+|*i1e7Z_}cX0_-7(B2?`+VS~xkE0FMwNuL zDGV08v|YN%9|~veuemQ@zF?*Rxgb!<=MBpemRIw)x^itq42Eu3auYz`AjxGd1^7!}KjeMR;wN|7IurPRMS+>rKA; z3I-vLvo|hVw^r&34vs6Boeey<{PM|TEs;AX7Sih5%nO?3k8gg+W0Qypg&7q@oQ8R? z&hTC~n%m+a`0}D@iZ<~g4&0P|XRBiOs^f`5LgsX&ZI-}}x1yOFp0)%GJuE*a=Y3$M z*T-_grf?;i?7d=ZQ2))}c6Slu?YqyDXTld?Oj&GE98Ofe8S@#@qUclo&A=bh$pWnjxvnYs}CN1A6Pv^4V{qqa38_MWJldvI9y`0*cg zr+;Ssp3Az4QRUfgyw5P1hgwj;ObA2ITXW82@G^~pQO37lyZh@g{fx|p{z%@#&57%^ zr1^0u`1jA7xJ&mVI9FS^Luo<+R1z>Vj(ssJUjtlLQMl$~MVBiVX{q<_xAM0G1{a)d zSiJJ5e0ogo?c0KwXQYZtz5-Ri%<^Dsq}=)*Cr;WI0x%*+R!*+;lIYT+WvE!X(jA{jKQtZ~8A6r^S|U7X-qWF}a*dxW)B{@(eu3v!b9M zcQ^xNt|+Mc6ujDX^bfS zwZAbqzdryi&L1z!oLE8})ijQhI>bTpA{du1JbHR}8m42V1N|+xe?Gl!w=iGuQP3Ot zo49-UBN+!ubL8Y*c_XWD!&4`@xBYy#v+Oi&fPNPF!!2Y|?9QNcPR=1dhL#J>b`CeiN<4 z&L@78M`^{+H^HdEhQe&}J;;Yc6Z@r+{#6^6{hs3JO1ItG&~P&v{FE`vC9n0#L8*q8 zsS13eEH2NgmxuJf%-u}2bq`B;;K#eUZ%ksTv6vtr@xDJ8tQe>({Y-l@W_E5;9pCPV%kqEf1an-&q0c5GqXL^zhGxCi5lsEUf zy5>L5E;bqEBPebM`aP%;&QW`JT1kI#KB~a0Bek*#o~os4`M;Y4f3eXJ_jO0i4E}wi zK;YOKGF9=3V{^~vTbPgfFoQy}CYelu`?WGfp>)hf1(!ccZP!$?w;2a{8Ji@}lo+!@9+{J~lzcL@mRKMmR{e6VukhDuadB5X{K#Tn_|HxkjQPD6tR zJk^OB(hz_?Puvm7&Gi-?N6se>tv`0;!+Zq#3Z3?Eeo`6V)~0W9e($^0tWmVK`eD?G z@$ol?j${*~Q4n^}#ki_325u;l%xGx({n%q$5_ept5&GeCz>p95bnaTQk!qGt*0!RZ zh(M;#wn($ZKP7y9zX`LIOZV88jJvKKxUy@*|j|uzt}B2)jG#9kuq?N47tuOEnDe0f@PbnAS*=+VabZl~;a$ zP?Bbo=WAwJ9Cky9nGXCkmQqxRQ(^r?6 z$k}h$0%T8CdVuCKB{CJc5FcPEHb&@LRQSTgdQ10|5oq{%;p7Q{=HO z+kzsrwF?ifpYD`@DaKb5*{$TWIX+2WW;#*t$+NUPx5Y~*%L7=XT^27A{S{a-mA}tZOxaq5lQek1j5$NPl?fo!P$iP2N@>`TgGJwP9_S z;=A;hUXAKj>U&k;H@?Na@yJ6Xppbh;uPD9y*l(KIPQmWSh_2C@v?~Ev$`s)S2JYAXVb)R;GYp!7m4Ixu;$S~s@mz45uUW>O1r}T-oAC={*=-g^g zh3*Dc8PXQ`G|_I>GwTj_`pQ*!wTm^lSD5mj@7i_Q9>gJ1&&=rh(3)?NJ59LzhitnX z<)Sf3LWCpwqY=C1CW2`VyS4rO6$1kU5v3FAL`9rA7-(s&)YZB1UF`N2x*qQF_B+ld z+jKXe<8JgRE)oxp2tkbR-g1uf`qHVx`vaAeuj|oSkMBSo#N-MgRUK6kcC_-f?9J5d zD~1~8`Ek2`e^(MIN&Lfwtc|fZUeRpk)T{|*m<$oZH4dR!t4z_Bg!?!hTwR&4#Gq$m{}+dys^5GH86Ng_cbAQ|9-zEZn*DM6_iW6Xw4vD>$jOsIOnKNW!ZnH4ymFV?EjLg->kx$YyfV6eP~w4b{YA&5~v z>#7uY+u7t3Vd7~=xjm{Bbj~p-?9CrADYDy*g*><-Df^qVu}KP>MOa%@8kdd+ro4vU zvAw00Bi!h>JpxmZ@YYhVq^Z^xcIr_R56vu=@H&uP-xbw%X>Xh2$|^7C0qwWy%xf80 ze3!p{m`Ov^eN}ELoUE6GX-FS35B`*C&Xu*w8J$21f zRW8=@|Ln;0RkEX+XV_u$g=!ck)h>DD>+d6hGle$sX!7Aj`r$*nL$c2>6m!yh?eY8; zzgpJeuG6ZUYG0twpzJ!Cjf`9MWTeNAL3@sikGI39$ubW1pFe*R1eP+divQcy-ya2M zOJ?y-^8*Nii)heQ#Xxft9y%Y-w>8pa)TPuG*7ec^Z869{mS)Tq2UYsz^krEkPePW1 z!qdJF6G4*URuGUZ-5U4nZdeD$NP&CHt=i;tBF%oi{jvG@H<%RVEz zA}CF=XxpEV_#HV`%ilg7ve#@;&C7~okGa@ugd2*ZC1lQ-@_*u(HMf(|H(l}aK+K%i zZ%L1YS3)ae?{oe(nTP!b}MhWos`bI$MFb^mwWyO(uV>zvN^9p3kOpXc*@p3ldXnThb) z@{D7bdG)15y%6vPezu1}DGUzqS%{j){j7Q*FTOTAcJWR()TlnN;4L@juYI|7r|Zhp z2H(4ojh8_nnV#sakbtU4r1$`TZT-cOR}vGKn8-=N!f{_K#NYX7ZqGK0sW0paNl9}s zn9~h*NC_q_AB~7L5orB$Ufa5OE&BN9dV9k3yivtvwyUtmX8kL!@LKPVkJ>?$`n`Gf zH#t}x0DDK}N>d<|B|%?$53DBzHt#{gTEeF~KwI^^@U2rJU?<)M>z%xYvUaI<@`$q)N5>32yTVfNR8M>h>gbm$`@AI&_>?%zG)!YZq-oNRi>a zC&_W}&_>mV{J`=~OG7hNjfQZ5AS8#m%uAZtS+Bm#{W|k?kiBXko(~#*&nd}fMw`37 zvyM{K$p^>9LBa)OqMS;f%VG#%hb|eAHthUf=X~>d#ha$QvHP%^#ER+2FspT{x`}4w z59ShenLZtdNHXS*t5maL3EukZ3Ic*%JFJFb=N_^m4cz(C3qQrJL4|vuUO7(~9TQp8*j3 zW`S9)*b0*12$^^?8NiMF>@b|PbGlxaSrB6{1i+JyeJX3Dh`5dXY>4G2O1w3@wU#qy z2ITGXofD6PBmm6Vqrp>HJKGwqon}5s^DSo5H*2I_6tcA6Lh{xdwO$Xfa|9tP3h-y# z_-X9DGy967+~?Y{yp}I~Vg*R98sUsgwLEZ|9@+9~kE;!}g5$`aiUxZPE@6ITKURcn zIR555nNOz{W&z{*Ry#+EIXdyWG|irQ(P+Hr_Z|t_r2Bx4UU(BnQZ1}%0_4bVXVY=3 zG8+w|S2nO1HQ=KpR9?U-hzY*WWTJmgNzoi&sQBA@NF3Y^k;ds-{tzlaD!W-3#eMpnC`Agp+PF`M3VdmaI z1scUasBzWBS9~z1b7Fc{|E8@YxxsZ`D*+cp?IKIg?Acc=r;g`3WND8BA0<`tD*(UgYaXPClwoZCJX0Dt@c*xojZ|h_(SmZAJnm+n&o%~&wcU^<^QH8~E zg~dlp&&^q8tYGR?nL*6%IcDILv4fN&Q}ufz%i?Nz)8jnPg(b+cOX9;K&)tb-eoFgP z+-cEbZB<#4W1>!4Q86BP8$8OFSz&&m3p6&6n!tSHa(O2-cVWIhYZV&@soJSj;H9#q zW;nLjtpt0WfCb259YhLHUj3)){^}#-@xw4Qf>632AMX5e(TmcQ$?p0v^ni&z27Wd; z1r28HWx}1=R!-bhm05tNhJ7uSdXT&K4Bocnsh`XW-E}<+DT$sak3Dts9RV`EQD@ZK zt6w$LNR>yuwuH{BSzKiNIf?}lW^o+{U~`EbzG=XoX7G{Yh{n;VPxs5?^@Urhs!RcQ zva+%ol%<0Rv_l^gPY&z@vi@qUj0_-+(ZHs{Un9s(&QXyRO$&Hi33xPQo9WV@bEycm zlX0}ie6X=`7e8fd=l!n3=8bvf!qDb?Bi3V;e6Ixdq5(677<0jMySftfUSTN*gD_#T zRAE)-miN(T*=C0BeL6#PM;!90wQ-Z+Z~F|*B1whCymL->{h9iA3B`QuE}UFHL#Nmia)Y0LC2n`A#B25^lfjV<5wYM7FT0 zi5q4`H18yAzqqIpf%5Y0kteND;7)UV_bYNI1@c%uc+Oaq|ncR7%kxrN^&y{^Tx zB5iYAif7aB%Pt95GkolkQ`@RN;HGM9d}zD=o?Yg4)82ZyxAeQ(NL zPg@XS|4WAb@sU#$9Ca&Btq)RyL*#Gyt=ZMwPXACK=db0Y`N1$%O+7d+wP917$1u3D z#P;Ls-M3dduVj$CyNI%ktNge)d65eqE?-$$8P)xS144fZQHB*!4zf}$ ziXJ4X_%4_o&^)I1;mlFZqJ<&-HyzF|o&gz5*3(|%vypL9cgw5A<9gXHAM3lYizn>A zSf(zCV1*6BBy_JyI5KmD&+x{?;%9!cG?Px^XY{T~Q8Ug=ny^Y+)fVRE)@QlOr$2nJ zk1I}1(RGN$2vB98CR{mV#+sttAL4A#~1I))Qo!JZ^apXb5b6e zY$5+8WPY%CnvqEo(2bOZ4^M*^OA~-j0DPI-dKFD$%pCJzB+5#(N2vJqv4V(Hf#`P! z!1+YGA?RWN)^)8_Ls&dW>0^<R;s9k@m>Z`lNwZN*wC9jF~BMM`Q zkxx{7a+OM_l1OaGgnD1NaMWFoc=eP1_m957jM*xegYY=Ex3}@1k4%Tep>rN_h1ctz zw0K0}MKI>MPNG6*h8$$-P-#}c4nNBhebP?EPy)v7TG6R%L$S^S@Po)3J+hb(6#B222iIis|HBaC(+4Y z`ta7JzK*I#ZWcp#^60FNsO6pP2aBgTU}!}wK6Mpa{2V<8MsnK`5>0buJV|kC?uQ>W zZ3S*Ftaw?fcHS`OV#YHRcIr_A;*7%k!v)kB9b;3;Oj1Zs?ZL67$kyZc#&TJniV$#P z#L<-(lcnaj+z#YsOYvWoIs0}ZI24v9q>&Kuh;-S19$c$Zm?TquLF;5FOqwIEe*A$+)oABi z?&jiyQ~oNtFC4OYy|&3MDZOXLUE2Hw+V)x=_%@wTL1lA73z#|P+?JGK0%VM&YF|{? zarN2B6l&o#q~T)0qZ&$!au`b!Twfm7$O^_$5$cbkg$|#VF)M4$nB3b73$@SuWG=Om z93N5~%4w83e#fmb>doefRk_px+YLwgndmD!&-`0On5lmJSUk}a`fc(_@$OEDN;6o1 zK3lf_rf3O`Y0!?_13VRl8_}`O^yqd&;N%>sElCMa{^25N`7N)tJ!|ar+hutP%I6KY zQ+ATWK2!h)PQU8|j>31ZWPEt$djUi*qLEL>X6XnkWM^9sJ#J39J)i!QXK16%X==ph zo%>|Z8~>#Fze1!)D8CESS4xopRSGm^TMH({Yw zX?dZqt0hd0TN_U?8c5F>$d|e0U~KFYGgh&HZpJPt2@{St>>(+r^k-fGkx>wWL=e7r zC!KsjOA9aLVgP|el>Alkl7oq0Uj0^17v=#GV-gU^!SV4%E?^QU_7EAB_s$*k^Y>R9 zk_C&9#p68U%&2yQgd3PVFlhnP^<#Qb#uVS4);eu^Y86Uv@%3EhS>PG4J?ETt7q;AlX6u0pIfzP`ysG78-Q|@X;o#i|BX{ z9w0GVU|SG>LBu5iAVEP4gCpPxnPh+X{EHJ6=NQS2?=TUn?SP^qcJ}`jL7{p&eTNuy zp)3T>2+YUw?>s-L02ZdsQ7_zw{93b_G8|`tiqHdcM@WSZ@QDhoEL=?zVt}O`fcE0I z&y$RrdP)z5(FH;u_Ya>i>EZ;TWcHWITUp&sklRl>E!7Z7yw2yAdmeGP4!u{P2fe*G zl%;XYxg+98M#6uXg*)^S@w6yCGGHx)Igic)Oy|#vN?oHfQR;;uG3vM)&)#Y!H>WQ3 zbf&P(N-V8?`#lOKLe!iKVk7+dEWfinA|xf;D?r(y6RnBUjD)ZM`-AuQbQSn&sNUgk zb?@B6;8G#W(U;bGp=WS4tbnl~wlMmzk!l+FmIwhk^~}%!GuOs6`;I;Zh4cXa7GB+Q5hn zX5S@3?;CZa7ndpwngw^kk2O_z0o@ZqX=2$;_6x>iKv@tRqth<&WAHcr(1}4rL3ij2 z?_Re3D1{0ac%OIkWDOVb*9P~-X770fi3myaM@qgYP$>{?0{%RCJO=w%cW4I@ll$ZT z^FA=x(HE5Tm7@4z#M=A&W58tUo-2yMFLV`o;c&sJ+QKM-CnqBX7pfzu$eC%pt8SAc z+St@2EhiTZQZ8@aym^0ISe%S_?M@7pa=MqM93nj?kfVqXxQn3e2hukdW!O09+jfqK z?adi|9dTU!{TGh2ievuX!-Ip2&=X=x)Y{;sXQM(K0bE#-i@wp(-C*FIDBjNBs4HKd z17RQZ#nK82_2wupJnKW7c769JvIq!Kx$rMqN!$~HJoNB%Wr)}P3)E5HiwF%sHyTzh z+G4lA$>DGu@x&eQ=fyCR3r-j6GtI(1LVg5=I%qafol5=k?-f11#RLV#LqqXoM3c59 zt_>hE6uJDnchnet_a0y_+e^HGsZ&7MQfJjvNP>ADcxvtw`TnWT8>m7=H{zU+d4mq? zKac%pmYZi+h({JoN5HfH&-=KURcbU8qVb5-E2Vb1v6P96sqE5!_X`!Q$)UzUY{Icy zpcaIsQp5Gfzq}k5`$ZUVIFQZu|L0h1UFA&_QvH*2XQf!ZwKg(uJk<^YbexEj{$l1F|t=hu1$iHWueBoAW1} zfezxArAC!Q`)}&pcbe2=BnMx*IcT(l?#S2we%Il7LEH#?F=?lO)4uQCOGw5^*3n2~ev4`@a8=TS*CkVPnTgmz>}P zKo%$v8#x#gZ#OWA#Sgck4ai8IZ+o&d32phCCr7`U5jPQ(TYCS|M>iC98c5ISV1E~BHl&i4nt%4#S>>mZ*7PIpT@MTGS>Mvq$Lon4UIHG z3xeU3vk@YQfo(9zl0ldRQG@^d|5u-$xESjXbSGO*;@ctp_wBUv6I@Z4fvI(e?3luu zM&kO^&CO28@^b289rZU6lE9cR{>O`{IQGSGkxOeIr6?xWxnV6$_TNJXGqS zj6Z=MNHbYQai2eX0=kBj{UN#7p^u9v`SV<0!;ktytR`-FD6xPXjqW=+cH|&Za_(d4 z#10Y&*UQVx;Y`(xL=+51Gfplp^@|{fL~tfa<^W#g|8@|~ zZ|wLoe?9M!GjJ3zrt)$r7z}(A0IQZBt=fOKiUZm8w%`d_T_g4SavFHsM^!N9*8nsA z=cS6vTr$#nar6jSywzRA;2qnYT3}zx0R99NQu$8A-r7xj*P7hpa9`8H+$fjxBOYakXHbcf5Hn?cF;Wjfo z8ZjAxQ9DeIhm#C213Iy^V5Iw^QIdrjS7Z3!V?q#e&Lb#Z{6$+e^~8(6y!E>)WboRl zX~~Rn&b;U(`)4aqzT~mvh2}rd)9#$aFu{`viPXX^r(~f3@%P91>(0+#dBFPs34MGz zn&JBAAY;mb{+-B8?e~Uo;gSdHTrilvTXAtz$YcynLVCE9id^rIlEwSg%L z%nGOeGeL{Vkz}NNFDx{-9yEY{1Mx&O$cJ6`>(|wLLm&R#Ir9p!T6f_KR6$tpe>+D` zcc@@l5zgg#1?>kzSlT^F^Qx?4`cbhN9K;~QOdaJ7E)VJkY5#svkxTvi)YFy08&2dA z?f;%Y1ov-_ee0qY84Yo1 z+5;&(1KuN#@BHrGpCoH8)@K?0UWvbr0~2$x^$h*fBbV|wS}RuX8j8aR9ZZoU&cQZx z(h||}0R~qPQWLFZm{x3QVT*F%G8}=BD0_MT8;77Nf+wUfbL$H54DV*D>k`R$gs++y zCg+@J-v-*5FO17@-nz@($j;vXej|9hb$TY9nPA;>`OrW63@^$ShhwCUa{X-$nPqq% z6$W3{f&Je?IaOBcVt!sK)8L^YS3L$ZUcvdlJpSmz(|A$hAl}mVat^IWM)2D`M55u0r?Z=oV`pc#F*7FK`6BPi-uy*d ze}6W}-2l;c-}Eg$g_vrX#@1TW5x12r+D_H`=N{HNeF?qekrV5Dno=c@1%r?F=Gg}# zuyAJI29d9SuA;vDhFuk9Czdf$3m{Fd7Gc*vsjufJL=4$@b>f2Ct4$C9oquw5`HB8R z!<1KxOvyd4y2;cSxth;m#`{qv@*HK27ONy_<>CB^F(T#K~frIaIeEs%Q?cs**+=NqyG) z*Gq-*ElIYJ`A5KzZHJIvkZlNj%ZHSu~j-jF*&*s8bFk3gFA0k&e`Ou~AbH0UJ=-;c8+1d&}UhRz4c* zrt3t(&3YV+W~%X8@ICeec#a(Tp<83{mH&iKlcvkDUx(9~+{bXZ+-^DDn!~~QF^1w% zh~WSn=jRSGOE4S0S^dxJ3=lB}9zuY8NLVEenW^rv^lNAF*)R~ zj*rvPcD8MAD?s9+b@C*%B?gy73|MB+F<(R6EbyP-zU6HF^|eBXFL^XHId*9t-pX#$ zyh2uXHWG%S6Ik-u9&R!`aw3E_W+!yO)Ku%t&6){0Y~ zL#KQC`lzo0D?`rN@t>TiDYwYQzbuEHgF{+HCCOcm=G6vQy$oiYffMc{wSQr)gXXa1 zw<~Usg~ikR=quuv%v%}KXc>lFSZK^3#{8{=*jQvVgrvI=x1MM$KM}CUL<_e|y3cgg zw{=y6G1B6f^$~Ga>LB1`fEca!Z;HBvv>mrArc)*r-m3?Wg5Ar=0W~tYD9+S3x0po{KQkI47f|s(eCu| z49N_Z%k6&rN~IqgUUz%tdsaU*pDAWLU!+EL8*z(t()>DN#W}Jd?^`WA)3SdLlNHX8 zgDF{?Q-{30OFKDQ<2ILH`mB(LwaT3yL{)|C4|@0Yg#JQNN6x*^dU~LG#X@>|{rYvS z!*Mx(()!${M%^KElG$CAPD;$UtabZT6d>}*)E*Ix)$X5bpP3Q3`YrI zMZ;P2mfFdaJp&R+IqGAZKDLA|hrTwy@s3Zaaqa{Sg13Q;QkpJ9-IaNH&!lDh+D~@1 zJhXdRC}!Si?jfW^7E9qpB;Yl4!~M?Qi*ApME*^MI)#zX6VQ*_on&Ei#^1(M(H>`2kJvNU^GzkyH0N?FbReA8u`kd8WI1_?CH!P-T3l9R1?crCd@G!_P_akCa$(O7+Ha0epyDhSuTp9f6{B%7;z{D5U7B;;an=Rw*Gp04x%%fr`!SGq} zaSKjO)sTZQhH0-1eNpk|+tg-Afpd@;m-WgzzqQQT#~2J=kV;aJsn?jIQ&}-Om1}R4 zkzaSi{h^oLkV^oO9!?_^f{I+Ykm({cxdHV1-8DILqiFN^eX4vDBDsO%|5nIz5g|kF2c)`^&A#)gSJ< zUpBS$7ocp5sgC=dD<;I1$~dGcY|ch2VnlnuAO0z9!M64jW2Kw1pd0fVmn-uB%n)C? z{xE)D%(%rBn0?eCdoM;n|F~x{*be^n0xs6bKdjh8fv78meQ) z%oUhwLd{E4Nl2#m(N09zUU|+Me(WIsOYZHLX|cspg6zx$zFX31gV=X>Z50X&Gc~II zh`BoRj+Q3afSrv+lx-LNmr(xlW&F8^$h@K(#14@oOJiU3xrdQQE)KL|Y0-QV8dV`~ zng0HM5E*gY*G%?;*Es>{ug}tKr3w0~Bd+b0oa>$6uja*F?;1lG&)eI;y8Y8-h zOzJ$f1t6TPgXh9sODV6Vbx3J_e3%Y5uaUK`CwjSWd~|-Yp~O$o*=g9wrD9mh{Kb(& zq*L>udE(4v`Kucul&WVkv03`kX>YJ;gWkobHBXzC(BI2o93j`9ON`JsMQ$fZRh2?s zb8szWX3Ls4%5~yF$XNINgv8z`0fB72+~?`<8tqM!7)qBg7PPHWr^%+8^wngA1@TnQ z$-PUf=cHfXwHGU#(|OOK5vwjm(Rh# zkO;u!J|Eval%&CofFcf5he$SO`^mLkdE}0c1_$dlkI7+jU(Q_wctY~$3piWzuYPxl zX3~AW9s()`S!c4d%J(wTm~o2?F?8(f)ac%hDID=YMtDveGd`=?s>;giIAv96TMo&t$67_oco&p=&Ig+O7~v zjMyMk^$VHtHy!kqrQenf=L58ZJ~_#7qRYSh-kKc4cbO6~0<3lccTbLhRmDt>REMDr z9_=xqZ^VXZe!!R^wQRNj4Vus>?Y^k8v0ppYa5os3EJu%0On+NP(_(O#$cIRQauj$X z5i7;VCw7kj%@%9`A>KB&Pk3$t^4zkpiI4LfsUT`jGpr3G>NY|V@(M-PaKu9bO( zqH#|2?<#hVZ9Vj)FIt&D_w1QrUzXYd5dP_QfVVo>ej_-0WG}WFj_@+4S6fNErAQ3cD)ixSrd-|hk@))an@0vbV$>9sV zC_4<_h&$Q|F26DI3!19csCs23v*s#RJmXAtT4AurrvCdCdQn5au5FpB>34m>Cu^*f zUTHK~!czex!C&%VTpbND70ZR3Egla9<)Hk1)8Bwa2P$Hyju{F{cZq?-8e(M2`3J8>rKBuO zC9l-l4ml1*%$HC59()wX`Dw(pvxvd}U~J6&g2|gw82qV}``mnXo$=imL^FX31l+_v zW?ZvAPwpI_kYu{%HL>o4zi_g5Q~yzr=|ROTJ&RgzyMW&C(C*c%3;LgGr+;?dAe-XM zbiH(-ab706)Z=zEGgqnyPkhU$$5yk@ICX|2x@?HFNb(-e@c-1UfYU?5U0g!li6tRl zophflZ?erGru9{wBOS3YHnO?3H3vTE4@2R>%_5;|m;!G7v2b|Q<4fzR(5+r#^c#Kp z%O4t*(`(0IV(Y~VS~Nc$^6~r~bwIf5e(6EcW^Zqg*#2P<8b1Ybs=e(08uEy>#U@F; zuWJ(@*N_l}pDlC<63bTWzwiG{S(TZhMhizPQscT1krc54o2j;BAE~WXhvGb+oJZ+r zDFX*m4}<+4!*jwtUwwY)7he_IN{#AGyB-%MkY`GR39Bu9t3o@`?yJHXUv>~Pl~XQ& zkBg1M`E|WFk9w|suJd{TMRk{--QhVa-8asytCu)2N6G(W_6Ot7$+NtX)m2CuYGY#} zTy4kN#h7J8K_Z;i?})V6YxUbVlq4i2ZLePCL!~GrP^RB5b=xs{HLvdl6`-Rlx#h;< z>1!ZMEd-$lIGJ5_-!`F+gg6JC1O+$)e{CoK4zjqDoRhh-U7uD}a)kNJ3kfq*%i4&U zLM|1~j3=L^9Zsp9tz{$FsCV0_YXn+q8D_d3;ZpxN@In_-Mow<-iMsYxh*Oa0iAazZ z(|3O!GLXTDjnH+=N#B&gK6bV`!a7l-oK+W--mzfcDt}%Lm&rJ+S)+-g751Y&02#s2 zO@AM;Ezc*Di@XG_;*xkYoZ#)vh$>@9hTDlKw0$|f5MY}g6Liq*U*QNj(Ao*`45A7{ zb8Q~dpW?}E5lS+M!$@9s4%vAWm8DAbqbS94R_Qv(xp_=3LSm!<)>bff3+9<#E}_7N zzO82;5Wt?ULjnB-z&BvvYk43X`l+0Je9wTpv!}oMV>B;QC{OF^UAvw7%AkgqgWZla zWBBu>A!51KRuhHG1S8U)R$S4y#G_Lczc(4yXhsAx*y^g{G7I_=8#K;kI6~Xx^V^L$ zGPrA;KNA&sI^#+D%k{s#$u);G3O`}eFJYy7X$rWUdv)q6jdmaw>XS{*$syy#UtnP}j zQbW>ny~qVjTDGG{(c+oAad-}V*SlAqOeaCJAr>DC3ory|!ic~Ji;){2a@xJ=AO*Q94KS7|BBvOy~~OeANFGK%sGpO-NaBZ`0A5p0^j%h)10BlXFJ3 z-3@T_a63%q6k3t3K72eKRUI#Pwq6ZI91qc-MJuqA&#-Be(bN<7O`nS1~2)k}gsG{UTIqPD+j>nzGq&OR4 z(`fhVGWfY^*Y&j*xUBg0i_}F=af0^9Au>OTrQ*GN>q=*DMcA^6OX)<%oM~_OQ=~jl zbWZdy899juSH%K)p(uOzQTqDECCn5jgSZUTB60NzP=3wk3&`r!_=?F9fdGQ1k3T11 zrcgR9hB6U~q!Zpk{Yd52x+7|6)D4sm(2{Iicr_agmcJO-YcLdFT}T?*x@zz1%Zw=b zkuW1koJVzWAtjNJlA417zAnIhCHfm@rD1{}i7>=x-MKSeJsq=^9KT@ebTI2H7OM3o z2mAX=1rBI6lr|NID(7Gdo@lh|%VZf~vjz!#bWX~TUWPau_TT@hbCbMAOSncW+`D5v zByWkK(1v^#SH5I-S$g}ozYH5~ce&|TjjBT#G4Soj_{sVBPqkT`XT$k1Ri#7@uHGurUWZix^kKz4*qFVo*&TpXro}}sAr;Fi* zHw;-$5K!b%L>XzBfrB*!#&NnJ$4-RNl;6=Uq!env4S-SA>@!ZMuX2nxDZM(`zJ|@N zhP#9xpM&;77h0NHO&fyyMbt>}jgjp*ED-P@JI##GNHOKk=OJin&rP*BuQW>eHoR*z zGH6Paus+7h?XApza(C0Un3c9W->Q{I&r&=0xk)+gfe=&r%5#2|=N|E$C!1;!5X5sZ z4vW;B6xj?cRZ}3`oz>5zP81x<7`p*j^NIY$LQ5$yfsIrz^awtS^E>({SX}x_;-os+e}3!qpY%V>`Y4JC)SzWwmVNhkPWDz7xc#`4qksm^d<2 z2(k3_F(XTb-=+2O&v%v0Bc5VR^XdW)h+s3apW%w zawU2$t(TO{ZB2OfD1UnwVR9jq4G}!op~Z*?6a{%_Jv{$lt>INDeX8Gl;bXiQ1OiCx zJ1RpgE$gti>7}r*B(k5gzBBK?pX#%baXMaN#-=I0@Lqi3$L5%F_J<>$2k~)(!++J! zG~byTq#_Fs=FOq(itwJ3JHQ!lC8NyRCzbIVJAfXFxJw zCBsMvuhWyXrBe2giN4~OAbgb8uhcntec_Yw%7cxhEz#+3!GXO0q!cbW&!D2Nkqr9k z6a#$>C}sc(2mAqL=M$IW@K7WHFW@DAg3b0O9Fgl#!8{52EBhkx6acTsAb9EPkWS41 z{*EK%&WNhVB0{-JL*45C+WPp9$MgBpQU4BA$4EU(z3eJoc=E*s80S(JL8vD zjiI0oUlS}8kIkkxq@?waWUBs*GU_hvS0mn-hwqFzl^%VgcuRY|d$5q%MhV z(aClKxPPalL;?JVVGN9kI*JSR4~XDCEC3L&0CXX6?l^$+@amD{1P}}$L9C_On($e- zP8EjZE=1*NVeMEQou+{|U}&}=Gzk)tCKIu#h_2Ua9ox$Y)YKNsXo>t!Vg&;+{#a z%g0%}TxTO9D@E-XlCQjFhEwD5IvE-Dm@=VY*Y#?6W=jNf{`buXz z-}W|#@s1aGs-f194l6IQtzfF{mk#@xtV-y+Gq7pJb^baZ6$V8wi3J!vhSpV6EWUo0 zS`XT1|K?O+nT;2t6^0^(Q|lAStBsUi2RPdKVMuIt=*}-$z~te%K?KWats)3ApvDh~c84pa4+H{tInyyD@ZrkOjxt0JCpA@?ixb{)3KLD0n4 z?J-|pk;y1#@v^L@>a|RB8os?OT;uq2D;-{@EWw4DDsl)Af#WPzm^COr`EIBRU;Rss zsyWOBp9m6<_AUoSg=7=zuO1)VM=QAFCF9in#p)mw;@oi03iWE)^&l4fbNWRJgw%td z$h-n0IVt}6E8rp?g9I^bF<2~JXDyT;s%?M@0Y^w1=1;Ms2&4INp+}(Tcv_nc>^CEJm<$= zPsgdKyxLc-xeqd*TL<@?KghCS#vN5{ar^7cUAtiK(GLy6)MVxzn7xgMV;Dkji<@_x zI~v5uND$EuIjcT_W2J~ZN@}Z%3$&z}pg&)TgbjE#sG7 zjSm3kDsJ|GJcxVPDtg#RFBUjh^2vI<<@@1J%@31BftJr~)H}V;b*rj(UYEOX{FRaF z6y-rO3n`E5wTx#o9P8wpD8fmWKr;R&VT`#sfkLB7LoA0co{iyp6gu6NaR zJx#7+bsq{HE^C`4@63vjR$MdG!j&33)*R&2bLG@2;nZ1LnmV9S6%4(4Z%0i>F;=_Y z6DyQ|vV|w?+V!4;)T91Z_2m|$t#PqS#y$m!kE?iuie#YYyt>#!Srow7?5q6cmB#n`2385UKvltD{F!mOM4|v%3;O3e z_0>Be;-8dtu4SdoWiLD^apf&NRKduD3Q$g%s2*Ng_~ZhAU0L+5GW(ASpHQ9?_wE{& zG9JBr>dhY>qeq_bDSunoZqN;P9;%P{L<0EZ(-DzXoGitf(Ef zaJVBz!-{&&wjrQBT{1I(@3&K3z66zXqPBBcojIH-ZwqapYFJA-)KFjV4vXmgUMUHn zU}pXf8i}^MNKG#jHRIOT92Z!0sJ4Lxu#N~Sw$3;kY`}%ZDX#dJ8%bO*zlClur+;Mf zU?DCV`9S|tQPAmE7-*Dij*In-1}qUoW8-l6krJ2VVAOE)CKCd+wjr-ZkSes>mQ{>d zHKE?5>A%%yHvBn_#-fDyLj>9-AqCnjx^R#gWSeLtS)9(t5b}N4+`TCd5OKQ zG&Q{xG&f2ECZ#Q3ooxMtxe!p=BkS`SZ%``Z3ee`;@`9%p(3(qvzFd;&e2m=&Vji$+ z5}Q#GIkZF+D)E+MgH+oSkEW4o*!=T$oK{UW3Q#$J08U+6k<|GFpL zdS$GsSk?|BK~s#mpD)%^i!m%k9CI&z$(^b-U^^_jDLRz3^wI&D9an`a8ykq1(C)o5 ztpBONx3`S0Tjc}?&k^=iMw+;#q<+rN1nD%&U!J!-`dT^vuKafUhdpve_L_pb(caG3 z&_@t-9_ZcfKm)`m8X*wt_579mm>V32=a5p;`the5$LoLp+7*m%UjB8NhXVjH)cZ6< z5Mk5~8;wZk$%o?sy_F$B%bS+W6a_~y_5y{l`o8*?#72b&oQ7tvHk&}zA~PXlkd-Ni ztmb5d{7h2mY!WFHLpM@C*xsM9yG-cn3cvm^E$T+UvDMeq)jf_w8e^L&2Ng)d)h4`j zO`tsLQpYIT$wa4$N8eJ6zQsjfb0}rM0Fh*25Frh`nUyxI9siI&FYFW!l^<&wAs~&= z1JkZ`e$D|^rfABwP>dP|#($B|dI$9iymSF9JtsMjSt$Snrm|LCr1d zD}JS3wfsHC#Fz9fqvp(~N7td);Gzys*0|lS`l$e;Gr6hnj>us_`7yw1o2Y|I158T( z$4Pp2FrG})!1Z?kPYmK|aKS3nOBIF_V-{(59eJe`0c=saWR>q?k-G2nRu$+~zAp)( z<_Y4-pi|5=mUcaEb0yKW@_Xbo?t!hJmh!JXXX75?ez;yv6}CFRza15zX0$>%VG{iczV9g!fxiDs zQ3O!W08Nak2wialCe+yIO7_U**0YEAvN1rm`1mxtalfa(epyWXhvBbrPxEUtPPg!8 zu6nBs770Lmd4wG2A19faV|pYi_$7`ptWq5FD1Iq{;=*J4?fOe%3F;zmHL5ikSZMZ& zo^Kb}-ASNZEGc{|a-_Jr(N}ECjXxc#Xm1Rm#OB@s$^*o1z5Leefq#xRk#D$($ldAB zfE8L_SvmRxEJ1_-1c^p6aN960mzN#HzT6P%erbZDkM!opVq zPJVEp$;il%JT~PycUi?ao)0ao`?{9UJbq;^X4w3(c^?B?f5dXxZ?Z=R$-XNZ(TdcL zSAN)XW>g?gXJD3%;*ZR=`g5c?WLx+=)^{XzHB`6Q>}z0AjA!G}>^xbwG}D1ceTQBY zP(*2$ziU)wRoXAyzE5G(s+q)qNSn;y0le<~aUWM#DAr$BM?I{G zdYE=STZHCx@FGB$Le32}`L#`VVp6$K977O!xqAbv;fcxxW*`6{a9j?UqN=b9`7#(8 z_IZ7=I@?*LA;_9279SlmoEkB9-zGW75^BX>T$OLb+0xZLMJw$!$_~`@VFGJGi|YQL zBc$2r8c9X(hR3%XBL&Ef5W>reHFXd{@}RWcL0bIfH3AZF6V$qK7o>=(g|@5PG= z;7`Xcwey~8W#Bo+N!u-De5f7@ESBMHmRmHU>?X^dR6Sp-%mb>->7!r9k$FQx!5u%z zb(1jq&}K6%>87j2F{_1qEgY_?e>`m2Pcd<0@zp$7>28B!$8+L^0*Sv7+p(bpELrrR zou@4%jn{5vzOt`-yLUrWGLu9#@&@CV*!a@exMR3(B}~x`Z*!cjQCC+&q**q{$5`jU z%DjT=L#{!b0ZPJb`!y@rG@r6*o=A%4k4iqIg4-_MyT5%Ol|iNV=hUzv{*3SuJub#{ zo!C>ya4DK+EThPq44(1<>z4}jdjZUv-t=i*1;E~%<7mRg{ zQ=oL!IJp}s77sF9YM_p*a_8hjL)Xnz zXMSefe)DFIo1Z&VzOp~kYYrQz6T1)?cyRigSMcF_LP#7^bO2QxQKY`&Ipi7_yLIAJ z>c_ptAdJ)FGqMAG>Rfx^PFic<@^;521(T44h+&!7B931b>JV4=B`wd38FFe{@rrWe zCk-k3S@UzGgR;N6vc4Y3T7y?bVpD3xge4iwb{T!eD5Sxi??~kR)TC7Y7>jQKs$nz~ zg-I?47ynEjV40ANIV7#H9xD1oN5-&zKW#% z?2Qx~qf$N| zZJX+|iO>fj!d}ozTq4{>BGYq9792}XF35UV6S^iJN zb*#-I;gGSs5FN+Z$EPnv{oFEb?N@c=+k3G%%V*k0^8iCwa-W@`D_IQY193Z>2{~Xr z_*p&OVK6wq5h`%OM;h88W_0{gWpBmOG+D)|``p7g^hFvs%s7uVZ$Xhj zoa&W?2gg^WswKR(HRK7#4d0tt$We#gx!vk4ieJU^zk~o1;V5^Ibu0EwM zrNXjRsP7x;(3b5uy$r>^aDka-^5&yPYB&x8bH*TVCKh-^3Wc`CCp9qTsy0&Z-atnS zk$7dCIW8&lXNTYDrCd}-*Z+ThmuR>MrLgjLwhkfP(dkt_CD7M1zq92 z=zO_o7Tn7LpHK-0-ZMqCXC%n4^xI9TRm~MTkf&P|wfvgQY81CAIPT0L57aU&VDaos z!y-VNAut{`T|El93y9beW!pc#ImmN7fHn?C25M>gMzw@~AhhRi=AmrWgk9eCPu{5iD)p7%`xM4M6)9XHVP?1#f@E@YscWBt#F2oux zo2^To8SqWsDpv&`)gJA08fTlxZqAYuTAfT)q?{zqNM&W|?3?Y>A)qFytWp{sqMFk1 zg_A&OqR}f5!uf#!?PK5`2$t+?*Dz&i$o!<1w+G_)@mRd6N$_96d_)2caqNQ-O+|)U zsL)tA?H%*xW(3z~E~>kx>nVqufUW3#wLCnI0)dlbcA*NkO)9=3PuR_$!?}Eh!oW&h zLby;_6gb7U_fB^HL)thLkGqn-x?60jQZ%HdISj?&r*n*!8MKEf`Oh$XPTZ?Pl7b^$ zuQV+yJ_jg;Pk|L66d3%zVFp1XhxB2-A~9;9at8c(IsJofQI(Nth0Mf6D=5DQojK5# zL-Qj!qE1dupf3&5Jj4xa5jsT`PNK_Ha1f(t->!Lbfu8M$bgO~-X;+1;eyrW! zT_m1dMdbcQFg?9hDI_UUFYz}7+fh&jpb`ZXlT6b z#!U(bj=Yf(klq4q{QT0;w0{7p0qgQ!(<4x(mbJlnN3oiCIyLGfK-<`wwUGDm~a!d!_}AnoWLn0&0~Eq2@r{6`maaOF7Xt%xukW8morlg?<$*uFmvA$;rW$BOmeg5_ z@8_evGT&J=YJS+iOKKkjlhyd<^f7elYK)99V}#~tV1}ZjcF!YHm{ma}K{V*`Cy$2- zuS9F=qc^qk0s%=B61^+L-n^pl36&R?bO$UY7A6aP@#C$IKEvfr&L1wT0PhhpFd!=! zkWbw?$~b%@_9NKK%6xA!O4xMfTp{=rTSPtcwle`b4v>=SJcM}Y;&7X%4f;wr|RVz#R?MX9)xe10JKqDgYqTp$bg zo=dvQ3x!MJ9Ok_D8lm}mudBk%zH$GSzpP%JB&-?8h99p5pT|H#Tg3_3-Zx@T3UB(0 z!-JFdRqfGN*IZ)1@^WZ|S(B-;T>kQYKVBf{xPQ;m$<5L+%QD3RVY|aMcom*mB2h@e zQz$Y#;()DT^@v1@PJR`;&* zQ*oQ^i}!i84^V~F4}x^6tmGj8u=wx$VzygKA+hr{BisnKjz*0w?k46}&GD@JUcoy`~_!wcRhc#v; zpsWpC0ETJeokwx8T;R$3;>8QqA=%Au-(dN_5#E{)J`ks>Bq7L`0WU>~zlVV$okdMy z*6_;ozG0S2`%69Fmapz%>(}W1Qki$5G!N_TgikQl#z_bZj)~j9598ZxJ6jAHiAC{C zAbvwX3mO67_zNnZ9-FCKbe&(Mn|KVB&)ho$Yxp^PL`e(~aK_$ocNRVAyh?;~>xRCX z%T_6d$I3d~9rSXK3P9 z73;zJh7D9B%tJLi59)89xjR)_+BURp0h(L2VH$)e490bO-}?s4oA_x%E_7 zmc)tC-=nb&zrM6m)GCi*fj6$q(Z`|f8dGxS&tjck6PaR=_F>1+&Is4TI`Q{zUAm`K z-B>_~?dj?=P>8&hvT9 z9mSPmD43v;#K}9Jk>v3#xza_Mb{RS1fbRAW6D?wb(=CM}0v@TyGm0-AV^I-WQTn#^ zsX3i*!Q9bB)M17G3oDqse(9&sw<~Q60#6|N`F)-bxxdZV`F@{T)jP3a*{dTcL0NxB z_2V?s&1|$>+^c>4bZcI`tNk3Zk#2M9T28Abur6D5mQuECT(hIIV4d#Q8<#npUYSts zQ1fS@G7?PqWSC!Dzr_2fGP=6n(0`p`EF%6z!%B{Osk$)T=DmA9hg&q1eDRYnI|9va z&gfkju@tT2Sg@!OWeG19jzspYKIQCVt44Qw>Bnito0I)J8N|WvgNJC@zNUN4i}tH) zu5aG0F}vbm+r(|I+&6c1Df}j~#U2MYNlC&tr)^g7AMXQ5s%}c)A6nLBs*xs&@=jtR zQEz^d7v;Yvd|}yMnAiSQQB+7Z zmeX6h$2Q3=WZjhx4Ez@%;Ie3G1HG9U*Oh^zQj*(RV>X}?&!4H9C$PS{>CutfZp+R} zpgzRJo!p)n$}EWc-HI`m-EnKC?)l1F3Rb5KSNwexnx~VZ0Yu1GFPN-oovo`6Nzri6 zE%xc1&PmoRD`zKV?{Km$k3K3)jhlc#gz9UPrnaAzE%W#|-RCC!MylVNW zfPM6cjx2`48gn8H)^bvMn650gn+rUT@+zr~H7G*?$AbtLNoge&$ul$^Y_|Vev2%*P z>wQ0K_KGbni8H&m$K*Qq+b?CT{9@I~(R|y~+b%5ow8ZSH74t%tFk70o)bb@x)mK9O z#^=*rdu#0PPR*7{xK7@dW<2@qN#(ugZ+~96Az$osYU}=}Lp{pA+ z-OnO?@fq1$C*N&zwO~jXePfzlJ~G9%`T8y{u8IM>_iuO~8458(E{%Cg^+AtOa`gsaPPz05;7Ut&4 zW@hmmyXdK?6WJG0%r2TNrD(mf$>!qZEF0jtWz^@|9bhD56VH}i7ge519TJzIbwr!L zB*`#GK&YmkWl*PaSG45X^_kA4D>95iRd$A|?Q9Ku!$Z|yyeh0yusOymJF0z8{LD@TIe__*sL z;jg~OcT5z%R$cQT^yF9Na*k{A0i6Ec6v~5elLHB7coStfwkdcVwfkEOAbXr+gPGuB zib4S1f>JDair!b3+T6j$*5OFt?h_r_;#@i}l#Vcqt;%$IrLM|4T;N!=Kl!c}Ied9x`Z&#u$E*X#V{@~cj3j>$8NwdD8IM)^Lynf0ok(LX7F-*ojx zA;*Fh!FAOc7djbe(vRzgp6sdNFc=9up|3ge>;!Gtatejw<9ho2yzn9lgcidL5Ikq)A?$EhIo)=Z`Y*evz=&IC~EG!J!csbXl zl6%6!B~2&&n%?fWj{55+)-JF2IOE@E=P1Rg9kbfEQZ23Du3oK{NqpLnKCr4o$I4y9 z;PAKaN3tE#-Gg=BPAXY3;yEbqH3oL?0#pX zm!Ik8+@Ge)bJRnmma6dguH!B|0aBtvxis5agow4X5XHgp~t4n*h zwR+^h#X6fafmKnmg`Gvl_Nv$8J$~ME9*|dHvgk_=R%)YHmfRZGv#V(^#$L6?Q1`qc z3dww3SgFf<_Xl-nCT%T?I_Y`!>dEakcR%M#KbKS9v$+l>oX)>~*zeWO=z9{lex%W3 zWm4Au#Jn#u1_gex7e2)vVShYjn9Z>JU8bc*+OhN#Vxh`CYULck&pP<8$txNX?V$K% z%1Bdujy_O`M^mhxvFRt&%NQ0ag5$4v_G?WyPs!Y!czV) zd9NaaG%dN4Cr_5Vp6zs}nLWtbsWZaXtZ6kPH^IW>B6)gRp>oeKSF>J^%Hf-O;;EA2 z0T4n-8_sgSt2ak!@T^Z4BmjBNn(v=0PN&;1qUx6{x>)aFFTSrW<+)Y9+ScuXwJ*P4 z$}15XSUs_wlkuf+b9ER+u!d2+E2u{bJ6RwSH934K_WoCX$)7hT-}I(c^kya$_g0VZ zvZ>rPaYiHUMBQpVhso`nWIZY>)U~yD2Uj4sT+}IPZ7h|!wpU~1aA3QF2Ek^Wjooa>#94!a|GGwni;y(nCI z$QGtV@ zLdK};6#Nc_^5iId427~p(8?F?Z2Cj`le(AYEY6qj3{Z16u=o!u8B47g{2910d4K7K zC3iNK$JRG!#vB<)u6sJKB_*zCtLJMKpm#w2vazXcfuD?u*r!(vgJSf)LEUNQrfHn& za`~sOooI=Gox|?wXR~c-h=Wa|80xYyoL^=6+MmH4j=5**XEOCNiqD$R5}Ta@6)Ejc zI(wvQoh&=m0xozSjal*{hg#sMhnWIAa>jPZ*ln56C4n2+PiHfP_N2$JK3%ojC5fYI zS7cMfaVwMDkV)KtLg{8MUn!@Ro0~gR?I+H0Q3M`}UY%bOU%VQ7Volt{=2z6d8!Sd- z2dYL+Huj%6G46kmWv0biMOoiAtv}?bP30b!1d~9nyKdjkesvI;wjq1yvt}(WdPX6> zZeX2{5xUx-#aQ`}OHy?7%K^JvY<;fuYh1#jm{RdaKD0-zHt5UUvnu6R54j$3u2g2W zxYDO2DRoRynih51oRDzUHM*hdUu(ar1ip_uk#v zX1%klE$q_Mw)@jQHD&*b;D6wsrxz-3or~z~stx4j`=FE+l5|K%H{GGQ<>1emcXkOYqxKPr~UnTO$%H8=fe{R3-ssXv;S!2|JlgXSy(l3FXhF-~F>}BhSZfHbiZ`SUtkSf>u||V(w}fdZ&Ei#Px{tFhX1W$droDy-Mw?i*qQzf&$x*H3fMoEfCZHFXT|Jw*8P2HdQ}egzke^jzYTo| z|9oE4^08Bjx1mu;Yo=xJv-I>#r+yW3qlX`iL{V}n>^}Z@@p+#(h493#u2V^pN0$G2 zg3@AzPnH}@otI}h~rJr!m$S^4ksnVddtUV3fQclQDfzYA1H z{`&==KNsD!d9yY%^?{}T__y`J6_4J&Jj-@2|ECrs3Jb*-Fb-cbHHxcgYq&8z%M5)%>#boejX z=(gt*5J<|((g1;^;dhbh#UG^!A>RARlRe2=X-D)^n|?ZPGdOz}(O*!T9b7%%&#v3`F#0e+R)gT7!y#@k?%hY5xHR4j zPG~c)KCqH#_wO(QlMU3gw9b%S_!mv+atCA9@o9SBziSQCuxZn#gr`rHT=F~qx%z^+ zYqsLg?XXEIIpiA!x#ppgq+TH*d0YR_1t0&b5C1o-QF^KXdlnJFGSr%RqNSxpJI^VB zX!}1l;QXOOXlJHwZ=cq{## zJjjUt?^+vXx2dbC#X_fA;939Eil(>pxa22OFJXWe97U@OA*NqcN8R`THsaAR;(tEG zhVn#NcRoLfF;W_Se@!UE4U?riGDta4YoTZU%TG@mqW*m0(Ccjkkzf`tw4e?hdY;_j zRD_M=kwJ{hZ`1zRx-IMEA7MW%$kd4GN13N9HZu!3y!zkdxA;;+kyIVdAV+QFRDh`P z$n4pyDk*spJs|&@f~_HPP%240*g$`O+CPSoI%x^z^${L=CLVUu%~CtZF6x|kWa;fi zBj~G{hxxHRPQn06z~gxLAs5ThuF}whX4D@lWw!h=+<0j=Ykal1RxV7yRzqF=u4z?- zwUJu!A!zH}Aq{N~VNZ6m1n8{W^yh~r+=1)wDIe^O0Y7C05UH8|; z9ReuXaRrNvW2R4 z@0r(@D0yA~_m<4f&^=?~kzu(YzO zM~|;$Lmt5{;|nhyVydURM*1$Fn#Puvgd1A~EYOSluY#kKPbS*STemzrio-(x%0C`p zjXn>3J+yZu5d>DFhbugA%SL|dlhN>5KuFUi`6_s^s@N`U1;Bk-d!%73jc zdK>`9C>a~aAawl)t=%&UMc0#c#ag5{R;JgiJ62E$gQlhuXwKVn0!2Q0bQCrU`kwXI zDoSmO!n)fD?uo35M^CnYp_KI}7-hebD9nof>!O~v4M9QihrHs;|AyKWO6@QZe?GNe zeapsdSbO>s9^UlkN1qR--|c>Mi3R&{i+cg<-O@!}h z*fbNa;YZ>#lchGx@c)Oj3mo^vrYOAxaQf7lvL@kRP=+uSe!kWC79cNve$+T_gYFXF z(wAwmf#Z_oC)QeVt2XKjhSocZwBGgTiG|5qf+nmabm<;FQ@PzyE1%K42KxjtI|=#J z)Ia-(NI05TZQn5R-d{_IQ^)amyMxHuH8B_m$h5NmvuF5fX^;6eCiLS1_-R z7t4;3T<@BM8%XZF#W6c!Z% z{I>WESK$amvrDR1XwKZ#(K2-2Sxgz~SY_>zeR`~Py#mrzqI!3C^sfP6j&B*)2~U#5b-h% zH8lulDj^o+N9QtpVIhFugND-!%Mh4BKt<7qRLu51OyX4Bf{EJit4ltu@h{1lzxP-G zouBN+_14|gf>XOv@<~Zn_9}S_24A)kLye`i*GKel@nY@z|9F)@uSKuAr;b+v#Mn?v z`Z18f+PMyoU>sE1@G=8~gJ_;*oAB(J3YvF6Yw4`y0+uodF1;qTjr=0^a+Bg8w?d)F zzVoLK#xht~Sd3TA|Eik7F@R*!Ou2aS(AI}IZld+!$7_LcjKn)0rF5n`4JYy*vYh*N z7$LEvR4=c*Dk4A(Md)SrhVh5TlB+|e=FekN=)?opcPsHSsyjPp!YC!q%($N|=&a|j z<85eee#{wpP6Y?oRCyVhdAQKWbAZ?z00SKFV+$yAd_9I9yyOLGM8El*d;lf=WKTaW(7R}td;p$_6O@M*W1E;TX=YKtr+cA8&jL|nrJxRm7zxGkQn5HO8 z6SAG-=)q;#^6WH_w8+Sh0{v7H=gp(55(dhL1neC)NTiB7=Xynl7GLjNBb^5B@~BMhHcN76`ch;HT53^?gcbaaC^MTV7Z zY-}uaTwSv70q0Tv-SLTkyTA!zw>Dt z2#lf50-XS{$@^Hd48s=}ls!{?jUGRIcnE%eV0gIk-d-K)OwT{^UwrwZi4-G%G;VVg z%82K35DpI&u#IqVaNwADe-4Eb4Jms0ypCVwl24{fE5sjkJ_l_vIZ{G=__$;sL694TwWhezZYSBX=y15x6pg` zB;x6S8KJ+r*v(pgg%^8+@H#O$`EFHjT_~TWO8OSSaOgfQ)$&aD35!bnTX7mx8e?yi zjvl?7k~fgJD1FdEU1nM08`Xy5l0cP#_7Z3(iTm^=CgwF7OJ(gvT|oZCx_@$KIPrg-$eiqTrfW1d~7q%ZKBRH(D7E1HydqPuJD_F&z>#6iQ*I4~Xe_MD6k@ce4*Ajq`jCiW1tJqbt<_g*{P zhMyCA)^WBs{Nhb9bxqA+jID_ga{ThZWqGL*RvkXCp|&;}+p=u&B6P5=W4QwcVS20= z2Tuqs?!R$FZ-6lRaGp=X=Mwp(^&tFf_C0?nduNCF=eKtg%6?uK^X_41t%;Srvz)ni z)NLFSs1-3`S=Gg5(#INNhw)7_ea9pcF`zke@>k6nHFWjRK+!GY&Z_%4eZg`&h{cE7 z?Z@~(C;^NUsI9k^l?~`Ko8dOv#TGE(UZDNd@Vs1|8Ui-Cx}I(H4?C-Tt9n%(X0U%q^KxU3Dd2@+8f5(cPm0(?(kU^}#f;F|w3NoI1oON?)XZ7^I` z=t?{+2xOTUI4!~-W07#;QQX?W=m{8QW>GgKmVjeILPG4qXo++T2)z!Y(LKa)A~_Fs z6md2hv8%!C?$yacRu;-m9pZn>ea%U_&6@#cNVfO)$Ams`y?H$Vq{OdJG=Sb00g|~kn6Z6WYyvDDoDnkyI1q%L_W-t`IT_%^B1{(lEGT}4D(B^e! zcEme%mulRZPcJX$;VKXo=hr7$X3MX*iE`KR9_vn^&^-sR`)v;(EU*XAr-iuTB2}sF zBCYcy9iw|0Z&(16%;1cD3|wwPV&ZX4J?Fb$-iKQ{pTUFDZ|7jI1w}Q8f^FcbP=4!B z009eGCQw8DPRALiFH^8QM3TT0yQ4{$6J82BIfzNj^@FKJDT?R1Hj+Ww$If|C3Sd_O zY&gym9w0V9Uq>g~2E$mI_?mQ$LEB;Op0VjNn9FL5BOpfZCC*9iY>n>!(K7JVv9f zD>veT-qI6S? z_frf-56G*6w8TQy;cFQPiwkh%(H$M*GtW&s=waYW9-7F1o(NQf4CPec@|U@Y7XY3d z7_j*K(NK_7e!|qftTtZv>O9^5JLaloOl^$c>2o4C_}e?QzJ>p)4OCbuYlIH;ds@A|)^|ur5LXRB=!F9hk-K42#D5=SA)J zQ}_4S3G$x(ZbHy(cQ)lo@zn6;y|-m{u3L#eeK_+-vJw1N&4)Z!krdfVc=^74jLbKr z`Ou0SOfFEs;8f9kflXe2T*hm{9pljl1&XF`2n!4QcI>+?gK^^W1ObbC=D~dnor$y) zd;<0v3S^E+X7OUSaJMA64QYOBnjStiMxTJ)1aCP|&Kao&Sk?M|jla~^E_KU6E0RuM zvPkUbSA|V(zKXPqi>02X<{r8IhIV3}))R*u>%ATxwee_gE#`?DEf6V060ZQw?Acod zfWbg+A(E&MCML&+$jqGZT4WGIdCdd=fRunT$k+GZZ*lbc=3PMVNEo2kfo;g8^ROw$ zj~{oMXwV#FXPv&Xd7u7+*2c)kZquKG8>*`xk}hHyd_33^L`a)fU&fmDuvH0YAoc<0 zIDvl6ubv4r7u$Ums#CM;5AJyz$u0|ER6Fl6Ilrq>-_qWM!jt6?{OiUuGd-?+kz;}5 zXx2B7P@-e<`oiX8zE}NWJt}!C>)yAs4Bw9$IAPWN^f2k->WsI(shokA5~PFeDE?%3 z28H?B**4)8mX?`DCCiZj>W8hgYh9BHR|Ov00*P7Sb3dM<{lwGqDsac-^&vl8G! zcY=^E;X%CNjKeJmF*?xNA@4`mbw!W&&qT!+MHX9q7{$d z7@78H;gvl%a+9QW;MN=Aa9>~imYQP5)Cicafw#F$yV|U+b?-OR z&%e$_-om;)M>(}{X5dNytR!*?O=uS4HCt-%>oNhEU0q!nRj*MdRQv`~x)Cwl$#m0% z=g)P^O;ix{KRbPq0O4fqN6aEFXE3!f54O>-y=nm&V#+6WZTp?_`fh4JW2w=wIARv_ z@`NkHMKoc~nHqWzYyi9ihq=3arN4;YRgI%DWr!7S0W|I2ySHInCFQlzSIlK2SBCTY zn_HQl>W$PC7=58x4tYDj14IHL|=1&zF4d4y_42? zyyPL~mE$4~Jy(FdVR1~-!#fUmA>VlyL8iU^=t)*ENw2BPuTY&%Z{f9U+~fKEPGmj& zX$Hm?>v>Kz#JJca2{8Z!F*9A|or1O=T3i}W=*Kl1}@00t;X{q57LXqHXYPOT-}(W zmvrsg>RFtWR&{lqI-A{s+!t!Ec5k?PW_D%*>SQKFYV0T_2dE_VQ-h^mEp0SV{N_E^ z>pc!bhw9C>t(;(kT#J5&;{oB4&b~jfDqoko05dF9fnN!egeCxEYf;|izt~jTL@=x} z4uo)r`(QFA9@F3D4_Aoa%&q&F_~rkgMtt+hj>mHCz5Vj2 zCAoDT*#OJEdU#WHuZ8YTk|OpK53WW14xL^a&rlC13P>_HGc$j%`0e3XK!Nes?ARq#-e z(zNHT(;%%p7<{8D!vq3UOyaYFpYdNs;Ib4erg=uKK(OJ9WVC^5z@vOt<1S>LX!AR~ zIwgK|wrxIfa8dD(Qu?)9Rgv~QV($yW2k`OoKF0GyFk&1E5skwOB&MV& zz-_RM+Mhms8ZSrh+Fc6HY#e=YPcpy0l;J(^MWP<#T9?Cz&!db``tz46)f=bV%?8nF z_?8j9*)IXxPSGSuG0u>==`9srq7US}D>--HGha-(?pB}=i^?};=gL#diQFoz1CsZv zD1%6G!`{g*7zl}CZD4)kQBh~hhw78V0xt_NYxr4<6&BX!gX^p5gH)0PO9M|v;{Z1y zjo5{UvGz=N#{#m@tX&35iBS%I4N-D}ilU>J$TWjKJRbc-R?$SVZNJWkna0Q2TsN%S zdo5mEScbgd`=@Q_dK3EkjI?5$_uT7etTdc;24h#R8FVcqFlt;6U%GBD!wMh>cS>px z+THT&XhY7A(maI%<(z*lP6DSzoVCJo6p@TwMXk3B}hr|2Q!LqknUURiWN2Z@E#x^l6L5_@QD}`Q_aC%?{ z{22}g1qTZlwgI6NWMy6#mynb5BV!1IZ3oLF<_P8Jgux$u6$W$9P#Oww`Vf5-JgVm) z7KF6}n#1X3Y1%<0KK4$x?zJ5b6?-8Vx5~PeL29NH&AF3sg5APVFpS^27Wfv322%na zp|)ohod7ctV%}@*jhC2B0JDw&O2wH^A-U)q`n2~W2rPn^2N2)9N9&=j_s_PA1N!5s zKMO6JxINJ@4Ln|iP5w|;{Uj<&(f!1r4kixxBq%&Q8JWBR!Uen^JWFjBYwtbm7nQZ%7u;%2prPt{OF&w4zN<_Dk<s=B7{dkaw`Eqzh%Wb0Pj^f)PmxXoM zp&0Q5Yz4EhlMKei)q{ZE-$xIy4WJCtz)n!~vE8H$X}?DTLxhtyxt}-VffGOkDvD3X z>Yp1uiiWk0+Ng#)nf(*Ctsl)g)nL(V3a3rwLwRLWi{|oJJja!ZXcJEhDNV`gTJ1SI zXwc+ZIK~WftO#Bp6_TVfbZ*4sL!D;Pj5-#8Tqp>v0EAh`6Z5aCPwXp*MVKCYuW+EK z8$+;In_>dQ6T@r^PononFbClfLoHKkU_~-aD;Ya5bRCJ=>QwJp%MOg1#|F=!jgEI? zm7}29#_YDCd-WdcCllf$YB4S2BoIR%araeTlLv{1N1h^KHqv8Qr~|w>xTHMvY2-Wo zmKG6SI^NYfamQ7FFVKSHF|4yPAJCZ+jo6Y|e|=n$V0~3;gvteK>pa*a`1nD6IE}&UD+C^RkK+tnz67#Br)Iww*H;>l&^pigjB^z}Q z(@`yVMpQ@QZ-{t4p)Cj?0wH^2a;S}zPCG&qQ17U$s2DJZ?k&p5faP`H6yZfkEURK{ z977@y6pu(*Hl;McV%bBCj}*-`qypRQ0QlcOkvr(!i7W=WBrzlqww)8L=K$n_K+WPC zqxHE4nA)I+W?(qFFw@?(jAUjboQ*V&hFTe+LVMA>Es{lNb-p^eQnLLkI~17 zL_MdPqX}8_pIGM(OU%>+@OsWTp%sVcTcl00tlP$+)Jjzn^UsN4MFD86zJYmPRla#B zaT623bOV7WxN9bw3{nwyObj*!xQU9id5JO_>mLZImlx=W#iaPd1b-4~xO{|d;fc_) zK8i3L`#3MBn=IZ~j}}_S7z`8&cyy44MHCfh#asQtwteB8n|OM5S~Ib-qDaNMb2>&M zjF0oBhTk%Z@$iQTTYic0Vo`aNMs>QhS+m=uW3cr^Gg{@ym+-s; z`LpP!7lfE^dx*qzxuQw{7~1L}6DW~OaUmR^z>rJ6kaa6>dQ=qKgxj{;Jhu5m{HnD+ zO%v$S9k{C;lOgy5n1l{IOhyuQo_Bi)aRbXm=g`SI3{`e}_Uz%kQ{H19S%;btZ8_O5 z*EVsz7aArV3*$KIMyA3hCMK4&7Qw#A%YK0ns|LXIHV2uA!*?WlH2!|^;cH}vm@-oU>dmymE#er8HTYGInN zL^Co9r;Z=cOw|{A*a1^_P(Yw*+`Yhb&t?(hHp$WgxN)_1GV#sFIuhU=&w(cX_uao* zeYpPV9ITYU_7KvFyDG=F2+7fqz;|GkW=%OZFgzVfof}A9UTT5+A({)tQ|{TfPoR4= z$2@eTP&4oy#EhnS{;sAz!?-@8-*gmgXS7&-fwV6FI!}m~Ad^n?>_{l{{rPKcFJXys zbBvG@`8Y~?V8wBaAqaBYJq(`}hDzu5bh9cSPw%m?5BCG#p;kttNK}|C=otz@#?Gmq7uaif<~KZY4OdX>98VMF>%HPhhp%niw@s_ zIoVQehALhm#BFsp*)$fc-D@g%7x^5;Ij{knEnD?K7a@yXW2-Vm}U=KIY=stBxdU**1DYoKt)nj4M|(*^!u)p zH}%_RhYNq&pkRZ_?JLZ~Z4Q{+;{$q=mdMzW{3|lH!L3!F?E0eoSX4w=B$Bj@)9!mA zja||26vr}HSq7ybOg( zdfdTW6K+UUksJ%|+6NV?^)cqo>)X}=)kGn6-^18vvoMG9N^t$s@lCQot7=3$(a zNqT|D*_@1w@h4_K{bN}J8t*qr)OCRqn)4CAg9>D##l#Dc{?!_z>;(&Fcz$#HPf#ow z_nX;ofRK_R#67oVZuuW=CE*i~yecSvb<~9;*XXC)`HIJX5nYL|D(I`CpZP^~YX#Z~ zH?)x607#D}{cKwcJf@zOO{B(qr_Aj8NNnQ_k%{LAHZJfR&OB8ywCS^h=)Yk1yY=YKu*Ym znIyh1JJUcT*px%JM~mmo{M_|tvx9Y0sp&;vVh{i1*2((n?<}i;Y}x~DmH5b}!Mhco zg^jKK4l>+W{<*leo9f zK>Xu2*CK!$H5J?Fu>vqFz_GE50#MG6qKx$tW{C1(cy=*S)137CB8OBEDUCpW9!20Z z*FF<}wcGw14AAjFAm^#IEse0T9I}Y_gu3StdLpz`L2?ig_zJ5n13;HTC!d*=KeUz{ z@)lL#GQu&(>-^|tR0B~=9*#}Z2vKz3(9ipfTUc4C;UWNOq`(|Z zejV?MbDL3NPgNpl9W9KLr$`{7Oaxh(d*Ihe7)MMCIcJk`re+&hK7mZ>84rYR-~b)< z$L26&sRr``7u4bwzDeX2C})bW`%C_ zRLfVi%Zix%dqJ(#kpx-A;%$fwpm8<{_q<(V>4Y6ofLGk)!Fls#3o+AUS}r?IyjAjL29 zqHIM^)?+j7sM$avU$Q}w*Q=obw33QPGlWF`^8Rt}Va$B>YZnK%zUb!-lli!~9iX?@ z-rvPv-&;`BJfUPy-PG%Mu(oOTT-o!vCVs{n5&Y*pxkt9t`XQmI_3D2XrU-W*SXr!v zgblK+BxU38?ZZdSD*gnGZ3sO{%p{VI2qy`T8Ck`dFm>vF(;)L?mn*OzhTIyF=!?Kj zXT)(yv9VGhWt30}T?n9o{I_NE>H9MyS)MX|lD5Q2Xok zMkIwMUUn#@mV(gITL?K(&N6|%juvyjrV}0|kPKYx@OzfEy^K>b;|9N&hPO@TW(eKB zG3jAX%ovx!^xKoAb{5`W1I$r#oCoH@Pt4|V$XfQA4|4>_A?&Bl|Ii<}+suK#;^o?4 zw*lMk`ldOnDOO1Nhu2EhH%h6#)XhP)8RcoTQV%5`)pJ9lA>3Oinmew#f)57 zN!NW#oZ64w*>A1kreQh1O@tET<>T80>I$J8f=p5gim)2l&d}EQoE$B9+SQkjz-3+J zj&*i%89-F00WhYN{bI-kMMReHGTP9uTj|?o0;Z_@6~|j*L12dQvJ^IlqfrDfS{^ZYjn0`-*saorDP|0`UYf1-n%*j>2!q zh8k*|kT*Q=cx_}=aH3hYH=QHSj1p{*F}`O=B!l1dv-|Axk3G6Rsr%q>^AY<=HX3q-X5+j2Hhd^-oHE* zTu$W2KYF7SeU!k&x z#$k5GS+Brd9btS`@Rc05(P(I=ZqNN|(HULbGGODkZ+gx!j5f(ulfQgCi>?PI8Wa`k z>gk~l==|apiMH)Iqe`|T5`7VSPk7$Fbmz{U=;&ytu`iY9JX+{|qY#X|$g@2HZCrB$ zO(RJ}3Q`LxM;g(2Xc724RVk@UqN1WK^zo-R_Fpg+1r0KEK5}15ZQs~C({x6DtH*8G zwu7iFoWA)X*OBvs7lYfcg<@T7m`hEDx#~oJ-Lc-P$R-2=>dD%CM~@wAdtQU&`4ddz z>qClT=93@m_l8gX{Rt4ZouZ<;tmnR+&vWXJ_L`kB2kstdPK!BZY`jKK|I3@(>;M+` z7B60WJi|;1#6-lo@3MpynC{Fdav2I$h!ju8Sy?*sZzKBfy7xE`j=S=ICP64%)sqPw ztv~_I6x}qTBA_Oeh^d@A_k3cn#dWN0(vi!nadgPTP}IxI>-+e)nuSH8*W9$3PPO-dlyp5RYcP!Dusz3iCXFX4&9mMzp2y zar0N!RU^@{qGDp3wrokN2;RpfF5dY?3r~)hk44#@9!kliCbDfhwBdO{fF%V51(`U0 zMT?%srSV6NB)l*8cjRYtn15|fj>r#71hkB+(!-mq4;o+41#;?!(`1UDLHU1_M zi{j!#D2D1st%ruTb|{>!#@EkB@?1w!;N{8j^W%z&n#gx$qSOFE)qE`^X8hg3sy^^H zHJ4UxtWP&ngdD14n_IJOBi*Nl_tMbN5ON6oL1T`6H!U4q{F^s26MZ!}(O)R+)JImC zmXI#%w2rd@<(Q~( zs1%Uwu~$=SFFid1AtLp#v9TOCSj4npZ^_s2z~p3BxVWb_Ikd8P$&wRl+0gJWRgtNf z6On)v$v{nvA8M2SL(~mLD`-C+FTyK1Pm#g97;U$??Eh=X3 zA1I$X6}?;I$zwdr@jQ_d3%uz-V{({wmQ@030(T1vYJn}UMKyhbj}N8t{{9keTLdP2 zcxO_D3De<@99a+c4N<91WX)5fl568sWPgCGEK$*7QUCZhDChW$3|^3Ia-?Dy^+*1G zol>*GO z)(@}PUWS99cDINz2{Ku`eFrnA3`O8^&UiQ zb6ria^vQ1^~6|gm__gV@Wwpp0G4EA%a5al5vdF&*|VM=leL(S zneRHn{e8#t(a}*xVW-F3dU>%>0`ee`9#Z(nYw~6t-fHK0E`8mOK_@NdfjLJHpX+F`@$5g$yp%o5Y4dA~epn0msct7p&QZix)G^ zs#w-C3#*a5E)2&6GC4arIHUlL=i^b+D5f^MfB$}x=_3mJ>XnrIeV)TWcFIUMWS}_H zdAPmBeR$SuZZ%T<(V#DPadRs$FffoqN?EoaQZPCTdt7N6;QKyY#1dtY?&N5T-KQhq zEIddB`*JG!hhiR+TEWce_mS@)3?j?|gi#VjD232SKAUzyPn5h)4Q(9x3}1t(HqxkL zsJXm`juZn!4HbcG>u<41awMpgaUD;pIv7@YTtxHRPZfn4 zPCd0))*H!B6?6|CXxIMz%CK>oP#z{`>bH*>R?%fzj5wb*{lL7`ZFZXCY}LbMOVfGh z{A~67q5y%4ha{t2pQz47%Bem3gk8TjN8zYZB1$1h{B!l5`O8$r0{00g%xZZQAFmS} zxtJo#_^WgUg}UqOSKXfM%|5kcbs>&AP0Y)fUYH!%lvBRbP;uP5xVzGdKgquP^={3S z2Z&2myD~rSP0=q%#7>=ccTY4b@#Wa|_I`I+fF-H*bL_n-f7aAA4plYm5)ws6rf{&a znZ|qBVxNmSxw#3txei3t{PXkk2^xTEix5>aO%E|y$|5u)@o}{G)2ArHYz4+5E74|^ zsEuO2GuYMD)YOeA0pG{U8d*!Vaei5+$B5Vj9w*X!E?0gU^>?ud-V-3orJcP?DBr$m zNv)wUy(%xi`a)3DK|w*`JBrPn=y!Ji=w`inXnw^n*T>2+zBrlS3aZ1spR^HK|W~)bTC(;Vk0BFPWV_#>Bjw@^Sy?fq_I==DR<} zzAmHm+Z;Jn6MYm5OR=MoeoiSqOx2-R)z~$Vth@bd;c$-6g4d-`MA)zy)Teqn8^cAi znQI$aaFF2PJ zrv~L;k77J*v%B|o>Z7Nr$Vv@$_{@<5R9t+|6rdrk3k)8kSc`m=>3N zC`S&)Qg^{Ye2@|dYO%T(A0Ho6a+u+ESXh!j)xK6{CR8vex(@%?&B=KzB_+kd<$#bd zN6@0-;bDvBZ^QGXAeq7#>D>q3u z5~f$BrAOiXH4Yu}`TLDxEB=b6CQV2gQOSk7L!M`zBc*U4M2_%HF_LF@nwy*Bzbx8w z(qbfc-NQbGpz1qGbL6&x2izkllR!T|KMU+Zv@m+E!HfmnyQlHCMvRfBZEo)nx3F+t z5IdJHY=+5!5E23$bE)k5VQagw*n0^{_OGyab=55KU3;4U4&Cb*NxVogo)m6Q-OlbQ zA_``ht(7wp#iQWt}N`?f{r^V}H8MQ>^UuN$5(B1{#upLlc=Gqb@Tqur!nQ$o51 z##H!=ApJx0Mao2- zLP(~bgc;a*=Y9-12}z-R?E*L_mBnyQ@tDu6S5s4ifCW`7GyUJdPRdxo-yRd%t|KfCB(*zPelO@m8d;FZ=m%!5N2y zge-e)htT2%laLCaGAW6$?m`C6|7A(ZXXq|=cw*#(0mS_1wbRqzKhF%=dUF{V7+~8U z1A8(`c%3UeUk^`GZgRkUer}eSMiiQEQ&d!3wqgYrKfeZ`O@-zZ@JfBIquKP#%v&e` z3i|3%2|Ixod24c@KfOx)4u|?#BRyq?-bFE{; z{MVNBP3zaQAsA?QtSrec?f-O#*zny451xQ=;@Z0P5KPhPRjX5}x9N|9#&+)&a} zF?K`;^|7)Wq0tJ^Uq(T@heSVE#N06_vL6(7cI<^Ie=WQ|Zr9b_O^WcHzcwqAFmr57 z_4?+$2>F6W^iy2pK}wVjp$GVQb7(HXL!Z05 z+4t?+SNiJJnW_k}?Kj!6riv1?865o}S#Fn`)RK_&{Vs(tijpX47(+gfxM5l`xKBw% zCGbIbxO(BavpBj@ZpE*&;x5hFr+wy z#iCV4%Cbo;2yd$a3%Fet2(Jcc&>3Y)$-23>=-U%fs#wC@h;w*h!qwNz8M-m#8GZ`2$m=4MMlUUX;wfY zi>X#SN5?x(uD3jh^pOfm7!PtrF;vVWEAY-8=dM?)2B#rp3ridkkpgu5`0&N$p!c(J zLM#QbOl!T6eU}so{qRI}2vp!G36j_D#%Kd|*iqnAA?T$%;`3V6#q*x2-kO`22ZF_m z=G+&6dtWlw2nJIA;tHC3s3s$9CfOmFIC7ik1qFOS+I&{cN7jL&oUe68}(4cqw6^cq zL1KcV+RGCkPwnm~^4w$s)?lV%#ETQkOQ@DbixvULD&dVLUTsvAnW>u6URRMuimp&t z!pLLjGcz@kiq;_J;P4Q^)yzh8jw4h)(JidFhcFNNBI~#DMx* zR`Flwt74xDqDFuh6$&K&ko2V@7vO_|$pnYtF*V$P;W{V33gRaF0G&vA3(Sp*oSZ)+ zpM{CzY;@Kt%63CakqVb)3NIA%26Tn-gZF$vOv$3}3lN65>7QEt5NBPDEq z{Ti#HQJ+V$+f?R2#5hhwL}@Wh|a zG`Ob9iBqRe;W|*v%&+7mB3ro|B;NWxGi3e~7D48~+}u==PKC$Bz-gHSE?=9C#^g8{ zxVgEdA*eS{zo->}6SwWROt6b_56i5KVHA8h*hNL#;p==W)1oB(7z6!5Ls*7<7Qx1! zHSD-tYD4c!C_21!yaIEW*@Mtfi=6!YEr43mD8VtJclCB%g*lKQ`qI!1B+PvdGx2a0 z5FmGF3OZ9gXP?b(@imf?mc~B-;ax27ANJMV!bL`t^-}jIA{e1TS^+%tNj2ZL&o!>dnd7kH- zX^Qc*Jia@c!@5&#vcjxojJNzBD%;OqhH{jb4+(&h%X~aT8qMlA5Z6R0f(T| zF658HjFKx`&EulPj|{g)w__QWAs_K4<7+&Hoc}{gzKz`$F9m1Za@Hb8@+w!Obp218oBWPm$d@7S7%Q}vz%u9-id5>rrbmK$UHw$_P!=87? z<8G27gXn|zM1{T@w|x2X?xLA1xf?hBx_@Q3G%bxOHcN?kWRJ>3JG;>P)I4nf!%1vz z{1RRbn2ckgjl2xE{2zhMzT8xU1_`AG6v;1s0yT-99CO~E08}8b2X%*%)ZWSAd|lDg zw~Qq&>mM9+#OG>#z`!`dyEl>u5BzNK@{R0DQ$*G5u3Z>btsi}z!aA&%0UF z%xA{ypx&^Wb8u1c8owiThI&{yRMx|DkhSHvJkL#_VJC_0s-k|C1zyRW5j}T+yl&pS zX%;?F;MZ{NBedfV(aB6-`BnFb$p5P?Fk#P#Rz*&pisK^+6~E&TzrfpsTyDIx7JS76 zDUS!9$HCwKGQ}$Jm?%gp3d16k7SsC=y^}v+}#oP+SV{BrgU%cnK)h}G@ zqZncLhh9L}c3FDc={mWU9$#HuZmx>~OU`=cJ*6=p z3w*XO$x<0k(q9kIrb#*THSlp(p)$2Sf1Z8xs1oqMOEjRTJN%&)Gz<5v?vwn2=i2k< zXLok)v^%%Vo?8NW);2X)#D+*S7A_;o-aBe^!nU zY>ImFQ^7mUnNCZ9X0z4>sQn^3eI4e&gT>{T2g;}w#(=~|PP3)Q%GwiC@~_M;_1Y8l z<(b%N2nx~-fTn}fLY@UkXO6g+LlJ*w*1HHO8W8FfK1iHqCD6t`)LLRK-@e+wgdL`5 zVc}NQC~LF7J>|jx%W__!3u3gE;3Lc)Na}YgAJYk}I+KG|Ex|F2&J;eMbw2oyN+ zxm<26PSm>nEQXhfL%cIS;fRTO#|IF?gZ3HNHHD^{T+>e&RbrewX|N$hU6T-c=XSRE`Qs z;Ls5P%9C%wNDRgR`quJ_E;|)pCq5buVm&a!P=}&*ROKY(LZC0EBdQ*{W10xq_R`-O zV`mq6g%<&r$SI1hz|q6QBONBYtKJkiNFL(e(>q#Qcz$(bHvb{*K{&|i`G8X=?kKEA zQDIjB5&FjQX}1{qvYydj_Q4+22AAgWa8P%E;by6OwzB$SrjgM_D}kDhuI>gfkwD?5 z?cgZ%Se0AZOgC(Bxm{~ui;e~i%B1=8nxN=u9e4!>8-JLgU|cdwh?9pvg(R2@UV&{| z3~n@;)~z5VBi+6#sO{_99eMch+wsv{a}Y@jEl(J*^oChuV`FU)EkHDk1EJRR15@A> z%kz5I*@wF;`(y49&r+INdik{w)x%oL(mS^UMXC$k@WRJa)TWYMj%X)6z#8a{$}?t6 zreFd)c&D8xA9=wqQ^7;_=4+U8TnH;?VjT$n(3A1;@i0kw%?~Pviwu>B+FNSFkiPu) z86|ulMT-_t#eV~6P6b?YU7EcTV;!^S%uz>c1T6Mi762XBlDK@}OX_YAYSizPl$KVb zgMNTE4_MD8u&1H&=&Xf3uC>%9;+6OaJD-XR2T4W(lfncWjunfvc;wyjU07pCggqdb zp0TlmMaV#mR4OHZ|KY<5C}Q4Fgcun?3& zTr9j$hqUC9WrkacM3I25YBt7|?W46V)HF0wV`J55h>4(4V_p5NrXfv8g=i_$5f)vw z((|~mSN+?q9W%IWa5D7;!F!^*CtySRTY_PZv=V1Hj?wT6kUQCkBQi2Wri(j&{ye$S zW*2XLnCt~r4xMV;nzd`Q2i1#V2qXcCk0pn=sSI9q9K3uKdp%n|1bIYWcwF?SZxPj9 z%vb;-;dosq8d!ePzwkk+BqjqpaPdEQYf_2}lzYiOyYTRES`h>| z=!9n>OiV%vf+7TR3-M{)u2qr0Lw3ZE7z-9GppnS)VI%39OZ~Et2s4ooy6ST?jlQ^c z0c^#BwXhv2%27D_}gMqD^Ojo6^X^;+3oxBgFa;wa5$A|VvK#ayE;MjH{ z9SuIIvTqdce4A{ayg~Cb|CE63BUF7#Udr`(U|3nja{3gx9f+EruHyJXcc$ZUCse2J zP@w*q)KJ`*rM_X*>_iNiWMKE|blr9>UyO #include #include +#include #include namespace behavior_path_planner::lane_change_utils @@ -53,18 +56,18 @@ double getExpectedVelocityWhenDecelerate( const double & current_velocity, const double & expected_acceleration, const double & lane_change_prepare_duration); -double getDistanceWhenDecelerate( - const double & velocity, const double & expected_acceleration, const double & duration, - const double & minimum_distance); +std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( + const double velocity, const double shift_length, const double deceleration, + const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param, + const LaneChangeParameters & lc_param); std::optional constructCandidatePath( const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, - const double & acceleration, const double & prepare_distance, const double & prepare_duration, - const double & prepare_speed, const double & minimum_prepare_distance, - const double & lane_change_distance, const double & lane_changing_duration, - const double & minimum_lane_change_velocity); + const double acceleration, const double prepare_distance, const double prepare_duration, + const double prepare_speed, const double lane_change_distance, const double lane_changing_speed, + const BehaviorPathPlannerParameters & params, const LaneChangeParameters & lane_change_param); LaneChangePaths getLaneChangePaths( const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets, @@ -125,10 +128,8 @@ PathWithLaneId getLaneChangePathPrepareSegment( PathWithLaneId getLaneChangePathLaneChangingSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets, - const Pose & current_pose, const double & forward_path_length, const double & prepare_distance, - const double & lane_change_distance, const double & minimum_lane_change_length, - const double & lane_change_distance_buffer, const double & lane_changing_duration, - const double & minimum_lane_change_velocity); + const Pose & current_pose, const double prepare_distance, const double lane_change_distance, + const double lane_changing_speed, const BehaviorPathPlannerParameters & common_param); bool isEgoWithinOriginalLane( const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, const BehaviorPathPlannerParameters & common_param); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp index 87ea4430266b2..09922a98d0b0b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/utils/path_shifter.hpp @@ -26,8 +26,8 @@ #include #include +#include #include - namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathPointWithLaneId; @@ -72,6 +72,16 @@ class PathShifter */ void setPath(const PathWithLaneId & path); + /** + * @brief Set velocity used to apply a lateral acceleration limit. + */ + void setVelocity(const double velocity); + + /** + * @brief Set acceleration limit + */ + void setLateralAccelerationLimit(const double acc); + /** * @brief Add shift point. You don't have to care about the start/end_idx. */ @@ -122,65 +132,23 @@ class PathShifter //////////////////////////////////////// static double calcLongitudinalDistFromJerk( - const double lateral, const double jerk, const double velocity) - { - const double j = std::abs(jerk); - const double l = std::abs(lateral); - const double v = std::abs(velocity); - if (j < 1.0e-8) { - return 1.0e10; // TODO(Horibe) maybe invalid arg? - } - return 4.0 * std::pow(0.5 * l / j, 1.0 / 3.0) * v; - } - - static double calcJerkFromLatLonDistance( - const double lateral, const double longitudinal, const double velocity) - { - constexpr double ep = 1.0e-3; - const double lat = std::abs(lateral); - const double lon = std::max(std::abs(longitudinal), ep); - const double v = std::abs(velocity); - return 0.5 * lat * std::pow(4.0 * v / lon, 3); - } + const double lateral, const double jerk, const double velocity); - double getTotalShiftLength() const - { - double sum = base_offset_; - for (const auto & l : shift_lines_) { - sum += l.end_shift_length; - } - return sum; - } - - double getLastShiftLength() const - { - if (shift_lines_.empty()) { - return base_offset_; - } + static double calcShiftTimeFromJerkAndJerk( + const double lateral, const double jerk, const double acc); - const auto furthest = std::max_element( - shift_lines_.begin(), shift_lines_.end(), - [](auto & a, auto & b) { return a.end_idx < b.end_idx; }); + static double calcJerkFromLatLonDistance( + const double lateral, const double longitudinal, const double velocity); - return furthest->end_shift_length; - } + double getTotalShiftLength() const; - boost::optional getLastShiftLine() const - { - if (shift_lines_.empty()) { - return {}; - } + double getLastShiftLength() const; - const auto furthest = std::max_element( - shift_lines_.begin(), shift_lines_.end(), - [](auto & a, auto & b) { return a.end_idx > b.end_idx; }); - - return *furthest; - } + boost::optional getLastShiftLine() const; /** * @brief Calculate the theoretical lateral jerk by spline shifting for current shift_lines_. - * @return Jerk array. THe size is same as the shift points. + * @return Jerk array. The size is same as the shift points. */ std::vector calcLateralJerk() const; @@ -194,6 +162,12 @@ class PathShifter // The amount of shift length to the entire path. double base_offset_{0.0}; + // Used to apply a lateral acceleration limit + double velocity_{0.0}; + + // lateral acceleration limit considered in the path planning + double acc_limit_{-1.0}; + // Logger mutable rclcpp::Logger logger_{ rclcpp::get_logger("behavior_path_planner").get_child("path_shifter")}; @@ -201,6 +175,12 @@ class PathShifter // Clock mutable rclcpp::Clock clock_{RCL_ROS_TIME}; + std::pair, std::vector> calcBaseLengths( + const double arclength, const double shift_length, const bool offset_back) const; + + std::pair, std::vector> getBaseLengthsWithoutAccelLimit( + const double arclength, const double shift_length, const bool offset_back) const; + /** * @brief Calculate path index for shift_lines and set is_index_aligned_ to true. */ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp index 0595ab5e1e36e..eeb5d1712efd6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp @@ -495,11 +495,12 @@ bool isSafeInFreeSpaceCollisionCheck( bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold); -double calcTotalLaneChangeDistanceWithBuffer(const BehaviorPathPlannerParameters & common_param); +double calcTotalLaneChangeDistance( + const BehaviorPathPlannerParameters & common_param, const bool include_buffer = true); double calcLaneChangeBuffer( const BehaviorPathPlannerParameters & common_param, const int num_lane_change, - const double length_to_intersection); + const double length_to_intersection = 0.0); } // namespace behavior_path_planner::util #endif // BEHAVIOR_PATH_PLANNER__UTILITIES_HPP_ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 0d0ba208fdbe4..acf9734827777 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -209,14 +209,14 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.backward_path_length = declare_parameter("backward_path_length", 5.0) + backward_offset; p.forward_path_length = declare_parameter("forward_path_length", 100.0); p.backward_length_buffer_for_end_of_lane = - declare_parameter("backward_length_buffer_for_end_of_lane", 5.0); + declare_parameter("lane_change.backward_length_buffer_for_end_of_lane", 5.0); p.backward_length_buffer_for_end_of_pull_over = declare_parameter("backward_length_buffer_for_end_of_pull_over", 5.0); p.backward_length_buffer_for_end_of_pull_out = declare_parameter("backward_length_buffer_for_end_of_pull_out", 5.0); - p.minimum_lane_change_length = declare_parameter("minimum_lane_change_length", 8.0); + p.minimum_lane_change_length = declare_parameter("lane_change.minimum_lane_change_length", 8.0); p.minimum_lane_change_prepare_distance = - declare_parameter("minimum_lane_change_prepare_distance", 2.0); + declare_parameter("lane_change.minimum_lane_change_prepare_distance", 2.0); p.minimum_pull_over_length = declare_parameter("minimum_pull_over_length", 15.0); p.refine_goal_search_radius_range = declare_parameter("refine_goal_search_radius_range", 7.5); @@ -368,7 +368,9 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam() LaneChangeParameters p{}; p.lane_change_prepare_duration = dp("lane_change_prepare_duration", 2.0); - p.lane_changing_duration = dp("lane_changing_duration", 4.0); + p.lane_changing_safety_check_duration = dp("lane_changing_safety_check_duration", 4.0); + p.lane_changing_lateral_jerk = dp("lane_changing_lateral_jerk", 0.5); + p.lane_changing_lateral_acc = dp("lane_changing_lateral_acc", 0.5); p.lane_change_finish_judge_buffer = dp("lane_change_finish_judge_buffer", 3.0); p.minimum_lane_change_velocity = dp("minimum_lane_change_velocity", 5.6); p.prediction_time_resolution = dp("prediction_time_resolution", 0.5); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index d6add69549067..3077eca12cd96 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -418,7 +418,7 @@ bool LaneChangeModule::isValidPath(const PathWithLaneId & path) const bool LaneChangeModule::isNearEndOfLane() const { const auto & current_pose = getEgoPose(); - const double threshold = util::calcTotalLaneChangeDistanceWithBuffer(planner_data_->parameters); + const double threshold = util::calcTotalLaneChangeDistance(planner_data_->parameters); return std::max(0.0, util::getDistanceToEndOfLane(current_pose, status_.current_lanes)) < threshold; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/util.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/util.cpp index 23d5c920ce8dc..1d3475466db6b 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/util.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/util.cpp @@ -14,7 +14,9 @@ #include "behavior_path_planner/scene_module/lane_change/util.hpp" +#include "behavior_path_planner/parameters.hpp" #include "behavior_path_planner/path_utilities.hpp" +#include "behavior_path_planner/scene_module/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner/scene_module/utils/path_shifter.hpp" #include "behavior_path_planner/utilities.hpp" @@ -84,14 +86,29 @@ double getDistanceWhenDecelerate( return std::max(distance, minimum_distance); } +std::pair calcLaneChangingSpeedAndDistanceWhenDecelerate( + const double velocity, const double shift_length, const double deceleration, + const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param, + const LaneChangeParameters & lc_param) +{ + const auto required_time = PathShifter::calcShiftTimeFromJerkAndJerk( + shift_length, lc_param.lane_changing_lateral_jerk, lc_param.lane_changing_lateral_acc); + + const auto lane_changing_average_speed = + std::max(velocity + deceleration * 0.5 * required_time, lc_param.minimum_lane_change_velocity); + const auto expected_dist = lane_changing_average_speed * required_time; + const auto lane_changing_distance = + (expected_dist < min_total_lc_len) ? expected_dist : com_param.minimum_lane_change_length; + return {lane_changing_average_speed, lane_changing_distance}; +} + std::optional constructCandidatePath( const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line, const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets, - const double & acceleration, const double & prepare_distance, const double & prepare_duration, - const double & prepare_speed, const double & minimum_prepare_distance, - const double & lane_change_distance, const double & lane_changing_duration, - const double & minimum_lane_change_velocity) + const double acceleration, const double prepare_distance, const double prepare_duration, + const double prepare_speed, const double lane_change_distance, const double lane_changing_speed, + const BehaviorPathPlannerParameters & params, const LaneChangeParameters & lane_change_param) { PathShifter path_shifter; path_shifter.setPath(target_lane_reference_path); @@ -100,6 +117,10 @@ std::optional constructCandidatePath( // offset front side bool offset_back = false; + + path_shifter.setVelocity(lane_changing_speed); + path_shifter.setLateralAccelerationLimit(std::abs(lane_change_param.lane_changing_lateral_acc)); + if (!path_shifter.generate(&shifted_path, offset_back)) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"), @@ -117,25 +138,22 @@ std::optional constructCandidatePath( const Pose & lane_changing_end_pose = lane_changing_end_point.point.pose; const auto lanechange_end_idx = motion_utils::findNearestIndex(shifted_path.path.points, lane_changing_end_pose); + const auto insertLaneIDs = [](auto & target, const auto src) { + target.lane_ids.insert(target.lane_ids.end(), src.lane_ids.begin(), src.lane_ids.end()); + }; if (lanechange_end_idx) { for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { auto & point = shifted_path.path.points.at(i); if (i < *lanechange_end_idx) { - point.lane_ids.insert( - point.lane_ids.end(), lane_changing_start_point.lane_ids.begin(), - lane_changing_start_point.lane_ids.end()); - point.lane_ids.insert( - point.lane_ids.end(), lane_changing_end_point.lane_ids.begin(), - lane_changing_end_point.lane_ids.end()); + insertLaneIDs(point, lane_changing_start_point); + insertLaneIDs(point, lane_changing_end_point); point.point.longitudinal_velocity_mps = std::min( point.point.longitudinal_velocity_mps, lane_changing_start_point.point.longitudinal_velocity_mps); continue; } - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, - static_cast( - std::max(lane_change_distance / lane_changing_duration, minimum_lane_change_velocity))); + point.point.longitudinal_velocity_mps = + std::min(point.point.longitudinal_velocity_mps, static_cast(lane_changing_speed)); const auto nearest_idx = motion_utils::findNearestIndex(lane_changing_segment.points, point.point.pose); point.lane_ids = lane_changing_segment.points.at(*nearest_idx).lane_ids; @@ -151,8 +169,8 @@ std::optional constructCandidatePath( } candidate_path.turn_signal_info = lane_change_utils::calc_turn_signal_info( - prepare_segment, prepare_speed, minimum_prepare_distance, prepare_duration, shift_line, - shifted_path); + prepare_segment, prepare_speed, params.minimum_lane_change_prepare_distance, prepare_duration, + shift_line, shifted_path); // check candidate path is in lanelet if (!isPathInLanelets(candidate_path.path, original_lanelets, target_lanelets)) { return std::nullopt; @@ -176,32 +194,39 @@ LaneChangePaths getLaneChangePaths( const auto & backward_path_length = common_parameter.backward_path_length; const auto & forward_path_length = common_parameter.forward_path_length; const auto & lane_change_prepare_duration = parameter.lane_change_prepare_duration; - const auto & lane_changing_duration = parameter.lane_changing_duration; const auto & minimum_lane_change_prepare_distance = common_parameter.minimum_lane_change_prepare_distance; - const auto & minimum_lane_change_length = common_parameter.minimum_lane_change_length; const auto & minimum_lane_change_velocity = parameter.minimum_lane_change_velocity; const auto & maximum_deceleration = parameter.maximum_deceleration; const auto & lane_change_sampling_num = parameter.lane_change_sampling_num; // get velocity const double current_velocity = util::l2Norm(twist.linear); - - constexpr double buffer = 1.0; // buffer for min_lane_change_length const double acceleration_resolution = std::abs(maximum_deceleration) / lane_change_sampling_num; - const double target_distance = util::getArcLengthToTargetLanelet(original_lanelets, target_lanelets.front(), pose); + const auto num_lane_change = + std::abs(route_handler.getNumLaneToPreferredLane(original_lanelets.back())); + const auto min_total_lane_changing_dist = + util::calcLaneChangeBuffer(common_parameter, num_lane_change); + + const auto end_of_lane_dist = std::invoke([&]() { + if (route_handler.isInGoalRouteSection(target_lanelets.back())) { + return util::getSignedDistance(pose, route_handler.getGoalPose(), original_lanelets) - + min_total_lane_changing_dist; + } + + return util::getDistanceToEndOfLane(pose, original_lanelets) - min_total_lane_changing_dist; + }); + for (double acceleration = 0.0; acceleration >= -maximum_deceleration; acceleration -= acceleration_resolution) { const double prepare_speed = getExpectedVelocityWhenDecelerate( current_velocity, acceleration, lane_change_prepare_duration); - const double lane_changing_speed = - getExpectedVelocityWhenDecelerate(prepare_speed, acceleration, lane_changing_duration); - // skip if velocity becomes less than zero before finishing lane change - if (lane_changing_speed < 0.0) { + // skip if velocity becomes less than zero before starting lane change + if (prepare_speed < 0.0) { continue; } @@ -210,9 +235,6 @@ LaneChangePaths getLaneChangePaths( current_velocity, acceleration, lane_change_prepare_duration, minimum_lane_change_prepare_distance); - const double lane_changing_distance = getDistanceWhenDecelerate( - prepare_speed, acceleration, lane_changing_duration, minimum_lane_change_length); - if (prepare_distance < target_distance) { continue; } @@ -221,10 +243,17 @@ LaneChangePaths getLaneChangePaths( route_handler, original_lanelets, pose, backward_path_length, prepare_distance, lane_change_prepare_duration, minimum_lane_change_velocity); + const auto estimated_shift_length = lanelet::utils::getArcCoordinates( + target_lanelets, prepare_segment_reference.points.front().point.pose); + + const auto [lane_changing_speed, lane_changing_distance] = + calcLaneChangingSpeedAndDistanceWhenDecelerate( + prepare_speed, estimated_shift_length.distance, acceleration, end_of_lane_dist, + common_parameter, parameter); + const PathWithLaneId lane_changing_segment_reference = getLaneChangePathLaneChangingSegment( - route_handler, target_lanelets, pose, forward_path_length, prepare_distance, - lane_changing_distance, minimum_lane_change_length, buffer, lane_changing_duration, - minimum_lane_change_velocity); + route_handler, target_lanelets, pose, prepare_distance, lane_changing_distance, + lane_changing_speed, common_parameter); if ( prepare_segment_reference.points.empty() || lane_changing_segment_reference.points.empty()) { @@ -247,8 +276,8 @@ LaneChangePaths getLaneChangePaths( const auto candidate_path = constructCandidatePath( prepare_segment_reference, lane_changing_segment_reference, target_lane_reference_path, shift_line, original_lanelets, target_lanelets, acceleration, prepare_distance, - lane_change_prepare_duration, prepare_speed, minimum_lane_change_prepare_distance, - lane_changing_distance, lane_changing_duration, minimum_lane_change_velocity); + lane_change_prepare_duration, prepare_speed, lane_changing_distance, lane_changing_speed, + common_parameter, parameter); if (!candidate_path) { continue; @@ -370,8 +399,9 @@ bool isLaneChangePathSafe( const auto & lane_change_prepare_duration = lane_change_parameters.lane_change_prepare_duration; const auto & enable_collision_check_at_prepare_phase = lane_change_parameters.enable_collision_check_at_prepare_phase; - const auto & lane_changing_duration = lane_change_parameters.lane_changing_duration; - const double check_end_time = lane_change_prepare_duration + lane_changing_duration; + const auto & lane_changing_safety_check_duration = + lane_change_parameters.lane_changing_safety_check_duration; + const double check_end_time = lane_change_prepare_duration + lane_changing_safety_check_duration; const double min_lc_speed{lane_change_parameters.minimum_lane_change_velocity}; const auto vehicle_predicted_path = util::convertToPredictedPath( path, current_twist, current_pose, static_cast(current_seg_idx), check_end_time, @@ -583,15 +613,14 @@ PathWithLaneId getLaneChangePathPrepareSegment( PathWithLaneId getLaneChangePathLaneChangingSegment( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets, - const Pose & current_pose, const double & forward_path_length, const double & prepare_distance, - const double & lane_change_distance, const double & minimum_lane_change_length, - const double & lane_change_distance_buffer, const double & lane_changing_duration, - const double & minimum_lane_change_velocity) + const Pose & current_pose, const double prepare_distance, const double lane_change_distance, + const double lane_changing_speed, const BehaviorPathPlannerParameters & params) { if (target_lanelets.empty()) { return PathWithLaneId(); } + const auto minimum_lane_change_length = params.minimum_lane_change_length; const ArcCoordinates arc_position = lanelet::utils::getArcCoordinates(target_lanelets, current_pose); const double lane_length = lanelet::utils::getLaneletLength2d(target_lanelets); @@ -603,21 +632,17 @@ PathWithLaneId getLaneChangePathLaneChangingSegment( return std::min(s_start, lane_length - num * minimum_lane_change_length); }); - const double s_end = std::invoke([&s_start, &forward_path_length, &lane_length, &num, - &minimum_lane_change_length, &lane_change_distance_buffer]() { + const double s_end = std::invoke([&s_start, ¶ms, &lane_length, &num]() { const double s_end = std::min( - s_start + forward_path_length, - lane_length - num * (minimum_lane_change_length + lane_change_distance_buffer)); + s_start + params.forward_path_length, lane_length - util::calcLaneChangeBuffer(params, num)); return std::max(s_end, s_start + std::numeric_limits::epsilon()); }); PathWithLaneId lane_changing_segment = route_handler.getCenterLinePath(target_lanelets, s_start, s_end); for (auto & point : lane_changing_segment.points) { - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, - static_cast( - std::max(lane_change_distance / lane_changing_duration, minimum_lane_change_velocity))); + point.point.longitudinal_velocity_mps = + std::min(point.point.longitudinal_velocity_mps, static_cast(lane_changing_speed)); } return lane_changing_segment; diff --git a/planning/behavior_path_planner/src/scene_module/utils/path_shifter.cpp b/planning/behavior_path_planner/src/scene_module/utils/path_shifter.cpp index 2fab91e03365d..8783413b7fb7d 100644 --- a/planning/behavior_path_planner/src/scene_module/utils/path_shifter.cpp +++ b/planning/behavior_path_planner/src/scene_module/utils/path_shifter.cpp @@ -40,6 +40,14 @@ std::string toStr(const behavior_path_planner::ShiftLine & p) ", end idx = " + std::to_string(p.end_idx) + ", length = " + std::to_string(p.end_shift_length); } +std::string toStr(const std::vector & v) +{ + std::stringstream ss; + for (const auto & p : v) { + ss << p << ", "; + } + return ss.str(); +} } // namespace namespace behavior_path_planner @@ -55,6 +63,10 @@ void PathShifter::setPath(const PathWithLaneId & path) updateShiftLinesIndices(shift_lines_); sortShiftLinesAlongPath(shift_lines_); } +void PathShifter::setVelocity(const double velocity) { velocity_ = velocity; } + +void PathShifter::setLateralAccelerationLimit(const double acc) { acc_limit_ = acc; } + void PathShifter::addShiftLine(const ShiftLine & line) { shift_lines_.push_back(line); @@ -195,12 +207,12 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs // TODO(Watanabe) write docs. // These points are defined to achieve the constant-jerk shifting (see the header description). - const std::vector base_distance = { - 0.0, shifting_arclength / 4.0, shifting_arclength * 3.0 / 4.0, shifting_arclength}; - const auto base_length = - offset_back - ? std::vector{0.0, delta_shift / 12.0, delta_shift * 11.0 / 12.0, delta_shift} - : std::vector{delta_shift, delta_shift * 11.0 / 12.0, delta_shift / 12.0, 0.0}; + const auto [base_distance, base_length] = + calcBaseLengths(shifting_arclength, delta_shift, offset_back); + + RCLCPP_DEBUG( + logger_, "base_distance = %s, base_length = %s", toStr(base_distance).c_str(), + toStr(base_length).c_str()); std::vector query_distance, query_length; @@ -238,6 +250,79 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs } } +std::pair, std::vector> PathShifter::getBaseLengthsWithoutAccelLimit( + const double arclength, const double shift_length, const bool offset_back) const +{ + const auto s = arclength; + const auto l = shift_length; + std::vector base_lon = {0.0, 1.0 / 4.0 * s, 3.0 / 4.0 * s, s}; + std::vector base_lat = {0.0, 1.0 / 12.0 * l, 11.0 / 12.0 * l, l}; + + if (!offset_back) std::reverse(base_lat.begin(), base_lat.end()); + + return std::pair{base_lon, base_lat}; +} + +std::pair, std::vector> PathShifter::calcBaseLengths( + const double arclength, const double shift_length, const bool offset_back) const +{ + const auto speed = std::abs(velocity_); + + if (speed < 1.0e-5) { + // no need to consider acceleration limit + RCLCPP_INFO(logger_, "set velocity is zero. acc limit is ignored"); + return getBaseLengthsWithoutAccelLimit(arclength, shift_length, offset_back); + } + + const auto T = arclength / speed; + const auto L = std::abs(shift_length); + const auto a_max = 8.0 * L / (T * T); + + if (a_max < acc_limit_) { + // no need to consider acceleration limit + RCLCPP_DEBUG(logger_, "No need to consider acc limit. max: %f, limit: %f", a_max, acc_limit_); + return getBaseLengthsWithoutAccelLimit(arclength, shift_length, offset_back); + } + + const auto tj = T / 2.0 - 2.0 * L / (acc_limit_ * T); + const auto ta = 4.0 * L / (acc_limit_ * T) - T / 2.0; + const auto jerk = (2.0 * acc_limit_ * acc_limit_ * T) / (acc_limit_ * T * T - 4.0 * L); + + if (tj < 0.0 || ta < 0.0 || jerk < 0.0 || tj / T < 0.1) { + // no need to consider acceleration limit + RCLCPP_WARN( + logger_, + "Acc limit is too small to be applied. Tj: %f, Ta: %f, j: %f, a_max: %f, acc_limit: %f", tj, + ta, jerk, a_max, acc_limit_); + return getBaseLengthsWithoutAccelLimit(arclength, shift_length, offset_back); + } + + const auto tj3 = tj * tj * tj; + const auto ta2_tj = ta * ta * tj; + const auto ta_tj2 = ta * tj * tj; + + const auto s1 = tj * speed; + const auto s2 = s1 + ta * speed; + const auto s3 = s2 + tj * speed; // = s4 + const auto s5 = s3 + tj * speed; + const auto s6 = s5 + ta * speed; + const auto s7 = s6 + tj * speed; + + const auto sign = shift_length > 0.0 ? 1.0 : -1.0; + const auto l1 = sign * (1.0 / 6.0 * jerk * tj3); + const auto l2 = sign * (1.0 / 6.0 * jerk * tj3 + 0.5 * jerk * ta_tj2 + 0.5 * jerk * ta2_tj); + const auto l3 = sign * (jerk * tj3 + 1.5 * jerk * ta_tj2 + 0.5 * jerk * ta2_tj); // = l4 + const auto l5 = sign * (11.0 / 6.0 * jerk * tj3 + 2.5 * jerk * ta_tj2 + 0.5 * jerk * ta2_tj); + const auto l6 = sign * (11.0 / 6.0 * jerk * tj3 + 3.0 * jerk * ta_tj2 + jerk * ta2_tj); + const auto l7 = sign * (2.0 * jerk * tj3 + 3.0 * jerk * ta_tj2 + jerk * ta2_tj); + + std::vector base_lon = {0.0, s1, s2, s3, s5, s6, s7}; + std::vector base_lat = {0.0, l1, l2, l3, l5, l6, l7}; + if (!offset_back) std::reverse(base_lat.begin(), base_lat.end()); + + return {base_lon, base_lat}; +} + std::vector PathShifter::calcLateralJerk() const { const auto arclength_arr = util::calcPathArcLengthArray(reference_path_); @@ -386,4 +471,87 @@ void PathShifter::shiftBaseLength(ShiftedPath * path, double offset) const } } +double PathShifter::calcShiftTimeFromJerkAndJerk( + const double lateral, const double jerk, const double acc) +{ + const double j = std::abs(jerk); + const double a = std::abs(acc); + const double l = std::abs(lateral); + if (j < 1.0e-8 || a < 1.0e-8) { + return 1.0e10; // TODO(Horibe) maybe invalid arg? + } + + // time with constant jerk + double tj = a / j; + + // time with constant acceleration (zero jerk) + double ta = (std::sqrt(a * a + 4.0 * j * j * l / a) - 3.0 * a) / (2.0 * j); + + if (ta < 0.0) { + // it will not hit the acceleration limit this time + tj = std::pow(l / (2.0 * j), 1.0 / 3.0); + ta = 0.0; + } + + const double t_total = 4.0 * tj + 2.0 * ta; + return t_total; +} + +double PathShifter::calcLongitudinalDistFromJerk( + const double lateral, const double jerk, const double velocity) +{ + const double j = std::abs(jerk); + const double l = std::abs(lateral); + const double v = std::abs(velocity); + if (j < 1.0e-8) { + return 1.0e10; // TODO(Horibe) maybe invalid arg? + } + return 4.0 * std::pow(0.5 * l / j, 1.0 / 3.0) * v; +} + +double PathShifter::calcJerkFromLatLonDistance( + const double lateral, const double longitudinal, const double velocity) +{ + constexpr double ep = 1.0e-3; + const double lat = std::abs(lateral); + const double lon = std::max(std::abs(longitudinal), ep); + const double v = std::abs(velocity); + return 0.5 * lat * std::pow(4.0 * v / lon, 3); +} + +double PathShifter::getTotalShiftLength() const +{ + double sum = base_offset_; + for (const auto & l : shift_lines_) { + sum += l.end_shift_length; + } + return sum; +} + +double PathShifter::getLastShiftLength() const +{ + if (shift_lines_.empty()) { + return base_offset_; + } + + const auto furthest = std::max_element( + shift_lines_.begin(), shift_lines_.end(), + [](auto & a, auto & b) { return a.end_idx < b.end_idx; }); + + return furthest->end_shift_length; +} + +boost::optional PathShifter::getLastShiftLine() const +{ + if (shift_lines_.empty()) { + return {}; + } + + const auto furthest = std::max_element( + shift_lines_.begin(), shift_lines_.end(), + [](auto & a, auto & b) { return a.end_idx > b.end_idx; }); + + return *furthest; +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 11872b0efa849..2d8f3eeba12f8 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -2645,19 +2645,19 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre return true; } -double calcTotalLaneChangeDistanceWithBuffer(const BehaviorPathPlannerParameters & common_param) +double calcTotalLaneChangeDistance( + const BehaviorPathPlannerParameters & common_param, const bool include_buffer) { const double minimum_lane_change_distance = common_param.minimum_lane_change_prepare_distance + common_param.minimum_lane_change_length; const double end_of_lane_buffer = common_param.backward_length_buffer_for_end_of_lane; - return minimum_lane_change_distance + end_of_lane_buffer; + return minimum_lane_change_distance + end_of_lane_buffer * static_cast(include_buffer); } double calcLaneChangeBuffer( const BehaviorPathPlannerParameters & common_param, const int num_lane_change, const double length_to_intersection) { - return num_lane_change * calcTotalLaneChangeDistanceWithBuffer(common_param) + - length_to_intersection; + return num_lane_change * calcTotalLaneChangeDistance(common_param) + length_to_intersection; } } // namespace behavior_path_planner::util