From a4be97337db89bcfe3ba48477d2a91441d0d1044 Mon Sep 17 00:00:00 2001 From: Thomas Dehaeze Date: Mon, 7 Apr 2025 14:31:16 +0200 Subject: [PATCH] Change transpose symbol --- simscape-nano-hexapod.org | 52 ++++++++++++++++----------------- simscape-nano-hexapod.pdf | Bin 4624703 -> 4635437 bytes simscape-nano-hexapod.tex | 59 +++++++++++++++++++++----------------- 3 files changed, 59 insertions(+), 52 deletions(-) diff --git a/simscape-nano-hexapod.org b/simscape-nano-hexapod.org index 434640a..2debf29 100644 --- a/simscape-nano-hexapod.org +++ b/simscape-nano-hexapod.org @@ -696,12 +696,12 @@ This equation links the pose[fn:nhexa_2] variables ${}^A\bm{P}$ and ${}^A\bm{R}_ **** Inverse Kinematics -The inverse kinematic problem involves determining the required strut lengths $\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^T$ for a desired platform pose $\bm{\mathcal{X}}$ (i.e. position ${}^A\bm{P}$ and orientation ${}^A\bm{R}_B$). +The inverse kinematic problem involves determining the required strut lengths $\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^{\intercal}$ for a desired platform pose $\bm{\mathcal{X}}$ (i.e. position ${}^A\bm{P}$ and orientation ${}^A\bm{R}_B$). This problem can be solved analytically using the loop closure equations eqref:eq:nhexa_loop_closure. The obtained strut lengths are given by eqref:eq:nhexa_inverse_kinematics. \begin{equation}\label{eq:nhexa_inverse_kinematics} - l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i} + l_i = \sqrt{{}^A\bm{P}^{\intercal} {}^A\bm{P} + {}^B\bm{b}_i^{\intercal} {}^B\bm{b}_i + {}^A\bm{a}_i^{\intercal} {}^A\bm{a}_i - 2 {}^A\bm{P}^{\intercal} {}^A\bm{a}_i + 2 {}^A\bm{P}^{\intercal} \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^{\intercal} {}^A\bm{a}_i} \end{equation} If the position and orientation of the platform lie in the feasible workspace, the solution is unique. @@ -745,7 +745,7 @@ By multiplying both sides by ${}^A\hat{\bm{s}}_i$, eqref:eq:nhexa_loop_closure_v {}^A\hat{\bm{s}}_i {}^A\bm{v}_p + \underbrace{{}^A\hat{\bm{s}}_i ({}^A\bm{\omega} \times {}^A\bm{b}_i)}_{=({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) {}^A\bm{\omega}} = \dot{l}_i + \underbrace{{}^A\hat{s}_i l_i \left( {}^A\bm{\omega}_i \times {}^A\hat{\bm{s}}_i \right)}_{=0} \end{equation} -Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in matrix form to obtain eqref:eq:nhexa_jacobian_velocities, with $\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^T$ the vector of strut velocities, and $\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^T$ the vector of platform velocity and angular velocity. +Equation eqref:eq:nhexa_loop_closure_velocity_bis can be rearranged in matrix form to obtain eqref:eq:nhexa_jacobian_velocities, with $\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^{\intercal}$ the vector of strut velocities, and $\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^{\intercal}$ the vector of platform velocity and angular velocity. \begin{equation}\label{eq:nhexa_jacobian_velocities} \boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}} @@ -755,12 +755,12 @@ The matrix $\bm{J}$ is called the Jacobian matrix and is defined by eqref:eq:nhe \begin{equation}\label{eq:nhexa_jacobian} \bm{J} = \begin{bmatrix} - {{}^A\hat{\bm{s}}_1}^T & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^T \\ - {{}^A\hat{\bm{s}}_2}^T & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^T \\ - {{}^A\hat{\bm{s}}_3}^T & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^T \\ - {{}^A\hat{\bm{s}}_4}^T & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^T \\ - {{}^A\hat{\bm{s}}_5}^T & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^T \\ - {{}^A\hat{\bm{s}}_6}^T & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^T + {{}^A\hat{\bm{s}}_1}^{\intercal} & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^{\intercal} \\ + {{}^A\hat{\bm{s}}_2}^{\intercal} & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^{\intercal} \\ + {{}^A\hat{\bm{s}}_3}^{\intercal} & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^{\intercal} \\ + {{}^A\hat{\bm{s}}_4}^{\intercal} & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^{\intercal} \\ + {{}^A\hat{\bm{s}}_5}^{\intercal} & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^{\intercal} \\ + {{}^A\hat{\bm{s}}_6}^{\intercal} & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^{\intercal} \end{bmatrix} \end{equation} @@ -769,7 +769,7 @@ However, $\bm{J}$ needs to be recomputed for every Stewart platform pose because **** Approximate solution to the Forward and Inverse Kinematic problems -For small displacements $\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T$ around an operating point $\bm{\mathcal{X}}_0$ (for which the Jacobian was computed), the associated joint displacement $\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^T$ can be computed using the Jacobian eqref:eq:nhexa_inverse_kinematics_approximate. +For small displacements $\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^{\intercal}$ around an operating point $\bm{\mathcal{X}}_0$ (for which the Jacobian was computed), the associated joint displacement $\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^{\intercal}$ can be computed using the Jacobian eqref:eq:nhexa_inverse_kinematics_approximate. \begin{equation}\label{eq:nhexa_inverse_kinematics_approximate} \boxed{\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}} @@ -871,25 +871,25 @@ exportFig('figs/nhexa_forward_kinematics_approximate_errors.pdf', 'width', 'wide The static force analysis of the Stewart platform can be performed using the principle of virtual work. This principle states that for a system in static equilibrium, the total virtual work of all forces acting on the system must be zero for any virtual displacement compatible with the system's constraints. -Let $\bm{f} = [f_1, f_2, \cdots, f_6]^T$ represent the vector of actuator forces applied in each strut, and $\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^T$ denote the external wrench (combined force $\bm{F}$ and torque $\bm{n}$) acting on the mobile platform at point $\bm{O}_B$. +Let $\bm{f} = [f_1, f_2, \cdots, f_6]^{\intercal}$ represent the vector of actuator forces applied in each strut, and $\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^{\intercal}$ denote the external wrench (combined force $\bm{F}$ and torque $\bm{n}$) acting on the mobile platform at point $\bm{O}_B$. The virtual work $\delta W$ consists of two contributions: -- The work performed by the actuator forces through virtual strut displacements $\delta \bm{\mathcal{L}}$: $\bm{f}^T \delta \bm{\mathcal{L}}$ -- The work performed by the external wrench through virtual platform displacements $\delta \bm{\mathcal{X}}$: $-\bm{\mathcal{F}}^T \delta \bm{\mathcal{X}}$ +- The work performed by the actuator forces through virtual strut displacements $\delta \bm{\mathcal{L}}$: $\bm{f}^{\intercal} \delta \bm{\mathcal{L}}$ +- The work performed by the external wrench through virtual platform displacements $\delta \bm{\mathcal{X}}$: $-\bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}}$ Thus, the principle of virtual work can be expressed as: \begin{equation} -\delta W = \bm{f}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0 +\delta W = \bm{f}^{\intercal} \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}} = 0 \end{equation} Using the Jacobian relationship that links virtual displacements eqref:eq:nhexa_inverse_kinematics_approximate, this equation becomes: \begin{equation} -\left( \bm{f}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0 +\left( \bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} \right) \delta \bm{\mathcal{X}} = 0 \end{equation} Because this equation must hold for any virtual displacement $\delta \bm{\mathcal{X}}$, the force mapping relationships eqref:eq:nhexa_jacobian_forces can be derived. \begin{equation}\label{eq:nhexa_jacobian_forces} -\bm{f}^T \bm{J} - \bm{\mathcal{F}}^T = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-T} \bm{\mathcal{F}}} +\bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^{\intercal} \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-\intercal} \bm{\mathcal{F}}} \end{equation} These equations establish that the transpose of the Jacobian matrix maps actuator forces to platform forces and torques, while its inverse transpose maps platform forces and torques to required actuator forces. @@ -913,14 +913,14 @@ These individual relationships can be combined into a matrix form using the diag By applying the force mapping relationships eqref:eq:nhexa_jacobian_forces derived in the previous section and the Jacobian relationship for small displacements eqref:eq:nhexa_forward_kinematics_approximate, the relationship between applied wrench $\bm{\mathcal{F}}$ and resulting platform displacement $\delta \bm{\mathcal{X}}$ is obtained eqref:eq:nhexa_stiffness_matrix. \begin{equation}\label{eq:nhexa_stiffness_matrix} -\bm{\mathcal{F}} = \underbrace{\bm{J}^T \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}} +\bm{\mathcal{F}} = \underbrace{\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}} \end{equation} -where $\bm{K} = \bm{J}^T \bm{\mathcal{K}} \bm{J}$ is identified as the platform stiffness matrix. +where $\bm{K} = \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}$ is identified as the platform stiffness matrix. The inverse relationship is given by the compliance matrix $\bm{C}$: \begin{equation} -\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^T \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}} +\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}} \end{equation} These relationships reveal that the overall platform stiffness and compliance characteristics are determined by two factors: @@ -949,25 +949,25 @@ where $\bm{M}$ represents the platform mass matrix, $\bm{\mathcal{X}}$ the platf The primary forces acting on the system are actuator forces $\bm{f}$, elastic forces due to strut stiffness $-\bm{\mathcal{K}} \bm{\mathcal{L}}$ and damping forces in the struts $\bm{\mathcal{C}} \dot{\bm{\mathcal{L}}}$. \begin{equation} -\Sigma \bm{\mathcal{F}} = \bm{J}^T (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6) +\Sigma \bm{\mathcal{F}} = \bm{J}^{\intercal} (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6) \end{equation} Combining these forces and using eqref:eq:nhexa_forward_kinematics_approximate yields the complete dynamic equation eqref:eq:nhexa_dynamical_equations. \begin{equation}\label{eq:nhexa_dynamical_equations} - \bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^T \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^T \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}} + \bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}} \end{equation} The transfer function matrix in the Cartesian frame becomes eqref:eq:nhexa_transfer_function_cart. \begin{equation}\label{eq:nhexa_transfer_function_cart} - \frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{T} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{T} \bm{\mathcal{K}} \bm{J} )^{-1} + \frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} )^{-1} \end{equation} Through coordinate transformation using the Jacobian matrix, the dynamics in the actuator space is obtained eqref:eq:nhexa_transfer_function_struts. \begin{equation}\label{eq:nhexa_transfer_function_struts} - \frac{\bm{\mathcal{L}}}{\bm{f}}(s) = ( \bm{J}^{-T} \bm{M} \bm{J}^{-1} s^2 + \bm{\mathcal{C}} + \bm{\mathcal{K}} )^{-1} + \frac{\bm{\mathcal{L}}}{\bm{f}}(s) = ( \bm{J}^{-\intercal} \bm{M} \bm{J}^{-1} s^2 + \bm{\mathcal{C}} + \bm{\mathcal{K}} )^{-1} \end{equation} Although this simplified model provides useful insights, real Stewart platforms exhibit more complex behaviors. @@ -1292,7 +1292,7 @@ This reduction from six to four observable modes is attributed to the system's s The system's behavior can be characterized in three frequency regions. At low frequencies, well below the first resonance, the plant demonstrates good decoupling between actuators, with the response dominated by the strut stiffness: $\bm{G}(j\omega) \xrightarrow[\omega \to 0]{} \bm{\mathcal{K}}^{-1}$. In the mid-frequency range, the system exhibits coupled dynamics through its resonant modes, reflecting the complex interactions between the platform's degrees of freedom. -At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: $\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-T} \bm{J}^T \frac{-1}{\omega^2}$ +At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: $\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-\intercal} \bm{J}^{\intercal} \frac{-1}{\omega^2}$ The force sensor transfer functions, shown in Figure ref:fig:nhexa_multi_body_plant_fm, display characteristics typical of collocated actuator-sensor pairs. Each actuator's transfer function to its associated force sensor exhibits alternating complex conjugate poles and zeros. @@ -1572,7 +1572,7 @@ Furthermore, at low frequencies, the plant exhibits good decoupling between the \coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$); \coordinate[] (outputX) at ($(P.south east)!0.5!(P.north east)$); - \node[block, left=0.8 of inputF] (J) {$\bm{J}^{-T}$}; + \node[block, left=0.8 of inputF] (J) {$\bm{J}^{-\intercal}$}; \node[block={2.0cm}{2.0cm}, left=0.8 of J] (K) {\begin{matrix}K_{D_x} & & 0 \\ & \ddots & \\ 0 & & K_{R_z}\end{matrix}}; \node[addb={+}{}{}{}{-}, left=0.8 of K] (subr) {}; @@ -1599,7 +1599,7 @@ Furthermore, at low frequencies, the plant exhibits good decoupling between the #+end_subfigure \bigskip -#+attr_latex: :caption \subcaption{\label{fig:nhexa_control_cartesian}Control in the Cartesian frame. $\bm{J}^{-T}$ is used to project force and torques on each strut} +#+attr_latex: :caption \subcaption{\label{fig:nhexa_control_cartesian}Control in the Cartesian frame. $\bm{J}^{-\intercal}$ is used to project force and torques on each strut} #+attr_latex: :options {0.98\textwidth} #+begin_subfigure #+attr_latex: :scale 1 diff --git a/simscape-nano-hexapod.pdf b/simscape-nano-hexapod.pdf index 97f8d9415a8104ac217c8f593924d89defb9eb4d..d103735b16424091d30b2b42590bbe68b4c453d8 100644 GIT binary patch delta 162027 zcmY(q1yEf}(5{WUySw|w-QC^YgS*4V-EHIUPH>k5w*WzcLxOv7|2gOU_kQ24ns@E0 zsi~fxURATIpYAM0dI*Xb(<~WsUFakh>kWrO{DmeV1zE32 z7YcoS*9w)qsvF>Nx(2%o2X_Pa@n==)TecWk`m#F01(?tOC@i@JnC`aeED0}UQe~rCC~kCdkgK;e zCOA(TIu<54A4rWwnh|)Ot>C`SjW%}qjwKih`_%_ya6XAwNxv;$H%%cGQgIQ(noeC} z$n&QPX)qXeZW$&m*OKG~JXRs%t2c1fXvh|Q=x87PEP?i>)MS=Eo=vd@sl_&k*fmF; zu2k`FItA8DV~O`pYlEU%w$iKFyWbUx?PVH%;@LQ~XQ`=paurZd64l7>W&x;Oac_6f zk5C%EkdD4561^wM4wvX&`oXdnZb{U;1OkW^sY$P7h}`K^PkU|_7$vOZ^eMnuazft9 zDUIzV9!FQCF3^e5WyC|jXb3<;0bp?L+E_NR;Gl7(nPU?KXm+%7%SG&H@h!lIjl7yS zSr>oq3zeQ5;sL*rC1Aqrh9LDlk+bNU)Lf>HKP?6dx%?;{SX-|5VzC;zVp*zt&Qzm$ zkJBnqf0x~}3|5H>E<>bph>#dYj1q!7m=X;^)Y#|_)&YbR0WK_ImO~)#r|pO!(}y+P z%z&-V8H@8|#k>mS$Jbz&K5UGC@!Xr@H;FKy82pRewSa!kf=+ISxeAW48ylP>XkcfR zNw1f;#{lPam6+JNv>J&K=WYh=Ol03573%w5r96QO(PSbf4wvYJtL(%>@I{Fl80mj~ znh5%|eFLktf}a$#rGZ36dC3wL_XFq*kZ>v#Sm$5K7vpFZ1`@vQu+{O7&9Qiph|H*+ zuTrfw7XdeawX4?(7%V~ZrbE1w8l%dmpYs7Jgn>Dm>C&{cZ5b#bwe>2w*1I-p!pWTI znd)5%Imua^_M!9^eRVMbvpIFu+^lXD?Uo{pTN09tn=}`JE~>B7-aGSO61z*Yg7GXt zqJ0UDc4hK`o|S_&jc>Ny%>MfrTgyVM1_}8K8^D*Uo@c$spf&2_-5ZE+a!@CKD?~K4 zUOeC19;=qmC!?TIT@SKFf_sZzpU&D$7GTe_4}aclaQ!g^R@KL>Cw~=uXajh(0T9}* zDg7;VWxs=Oxu?ZnTm|WCHqdc5pI&A>7Y>()4?$}!J(;KA7IQ3bx!)~$=}GVJVr%>o ztpw82`yVH+RZi(2g3k)+r}@{O`{&qapsr(~iENKbGR|XF^KQEKY=0NjsBLS&d7J&3 zfQKvlt%`hS>FG(7)Bd5jmB9e{k&3{h{OoM$Y_7@sB*OlX+NnOt`7A|mIe|OTc748z z{KEL*&t;oHU@p{KNk($4YkUa^@Rb=8oDF1F$c)vZh%y2VQWHeSYN5vBK?LXd zZ`PGG1{$0jq{fD>o2Eg{3C^1qP0a?)PR2&24iW>PbAv9k2~i;dJbWPV970@3055wB zDa{BZC}n^Y6C3~%Q{pB9HAtf4gIw|nG15dBu)#Ugv=}1Oh?ua!d0Va-7{NhmB+{4= z0A7$9E)C&7YiYvVn4;X6z&{1?DacPjeG2+hFrR|`6x^raKZWoq#7`l0xG^EWE`K@= zE{v`R8izz-f#72UJwl>1AoBtKaTbBqhnEb%mzhI|hXLT@{AY@c)tZ@&8SpvF)v*bM zLJA4a_s?Ypx`RV;1_9wvEI{O_(wL9{KHjuz27>>43UrVlJPOX|m8SuZ5(_d$L=ovA zLO_uO2RVkJ5rNth7r92>Yq!N4Lus19kj-V-T=3^fU-i zaUmflBs=@Rw*S|$#KqBZKCL^!p-_PQ#nCnXJpm|~Oqi|%K?2>k9w#d!RxSi+g=baor3h0IJ_NFygqcz;FIQLet;nCr#+j}P79UYewk|?$S=(6y z5cZl$v)e!c)g!PXM%iuJtVYT2LhxtuAl+HBZuo6*zL0QQni z*19-mSH9O^`2^IM7W&Z%OjgSjIq+Rx=#4*3YV#6r`$9dL&Epp7=6kwvvI z;Vy{cWh!6{w-`dh;p;kK!4J719vHW5z#}op*iDlGWln}Td6?#)xkBHe_@|2n$YZ7{ zOQ8c50+2XUU?)X$)zd~Dm9f)r5`Q*c!*>xDA*Xf5J0?>)sfRZHv?PJgT)=yV5&1%1 z|5I|;j7SA)OCs*4utm@a2*#~@zZZAAfY&LB}3^g4NaHu9tsd~hbAdjdjOYFWQ^30g7$2s8eXBB4pQcRXLIo)YVqs(C5~D?l!@ z1ucM1yT=+Me3D3)u5F2^k{3=K@UR(tNs3!qL(+2DZ!ylAs(X84sm(s}_|1Bu^`*sJ zm;Jr!RTX&(BqAuOp5E$ms-cq<%Z}A%7{#UMZ7M3?(Z~z6GQS zXkILTv)07Ow=6Sz?xmFPe`#htMfdmDRP0V2xzxRWdw_f|ag2PiLM?b5DIGi81d9L$ zzL-=T=3cFpvF0D%=`@Q79D=Vueq6=^KR%#doPU2r-mk2D9VnlNw^^PZVA5Y|zKblh z?*A?zEa6Uks0;cV>HdwnuK(xEY;*VhbP+ovlvr0poZ%G5vsb@o{6MG0IMPnRkN0Ij zdt&niUJ6p~Nxg-`8o&vHgT?I5rXawBCPV8hFA_(H#Z z?sPEl>@-^cv}E(-^w6=+XYM~{At3WwIgQRH@>_(nksx|@ivZe~6;M+{+kFIZwS1KV zu)wl;C7?Vf;!7aIzFPg_y7AKWx^)3$3Np)RT^BuNVcELp(qHPbu_HbS$f~uP4l0ru zuy*U7KFzQWus3p0y5WS+99^3Mg$fn7jDG(7Ua>VbEg^TRH0SeGnTj>GpLIQlnOD?E zwEwqJ6?eP(w1T#y zi6Yh_ZG$^utU^sc4I>u=l*);d8)-%<;%7>j_I-q!g~io1CQiZ7aBmL-hzsh>BXq|? z;h27HN?K8=d42;c*hrl8LRWf~=^rEQ&$tf#2?!^c*ibK}jpzGuBbWhSHO80nWLWwO zMc}aVA#!X4DRTNx;MZ~KGC1-@)zn4dDahm=_iQY1J2<@`yDjP-R!DD(TaiQvZi9~L z!);B;Qz>2z$r6sriRD`1z==I~mvL-}hVltF8`ieiwN7paC-#)ZiD8fB3n{Xz*5onr}SW0X^NsYAqoal@u8 zhX9%xt!K7e(6=nbT%R2BQcR>}{i8#Mz|{nqI4!*V5==Cj7I|}N;Bwa7e)+r`qV^Dy z-4T+Ei!SyqvAnf@w?bR7Gr2xeN%$-uy^qu_N{Y?e1mmC8fL6StA$|S_@YbT{%)^3P z_Xr}t-&JRY-{W;AI@-h9^Y1sMr=t(out073?xm-}7ec`UA`W9lJy@Qv#b5 zi=w_5(nEhy_YKL%fXuwGIJ%d}w;}YJLk#>;K@AII2Vu*yOjqnS1Whtv!FXU`hYbr+ zzdFYw+{Z(xM{{4Lu53!4$yx^Y(`Z)|e5;PZ6Ai8rBUEiAlA<_>qI zeS}s1{(*Nq{2W1PYzE&@2!7vZ1;XjsDS{F3U+b3c_;^PETacL(f|-mV_`!8^$N-27 z#VS?f**y@M1aOn4zklaV5+#S->tb@caL0gNdi0w!FxaF?%sh+qvQ0(qU6sv_?=PP1 zAtC7J8nNAZkjiplla>#|q7tXJsQivZS>+_hd^PNFzQoe54VL|6T}W^;ZG$4v3Fr4b zU|tNyANt`6{4$-VGZ>%XM9h3|x3;+JVro#Pz0fcyZgLeVu)$B@Xf6x+WPa&D`3DSV z1OxHS5Nz@=N@mGtE3+&mL76AV6dGcRtSLQ)jdCz5V?>$UP$CogM5;Tv*yL<&ht*?? z2u$@${)Nx#YePlp7aFJE$(T_;Z17ZtF050ePfAluw0 zruUNFjdUhljjx7^6K(+Nsgd+L9F4E~iW3Y>3$3wo`KHC3f88}ad!db&ELJP{`5DMD z5_apgfxVP7H-CS-s4G4>-&C;5L}41wRYqB@YyHki%9$v$eX9H3bXtI`@u$0lqwcv{!<^2vey^06sf88Ik;U4X@YPn(N!ODXmu>qD&_+4&^( zVSuMs#Azy(RBYRI(~!}EC0Ur5`@@z#bPE|9 z@nm9!o$+lzl*kV16J`Gt=?$s5>08(bDR8*(ugxnTaOh*gS1?JK{$M zY5T}k;IAQPhE}K63U^5a3gy6X44l1Syj=CP}0BTq^|K1Nl$>r$AKq* zVc@QY@lE91qjT>*@#Rwvs72hFU&A%VM|MGc}(>&U-l|1eVml*%X#tMWLw;O-J2sht5$Q^ zGsOZ_T8gXnsz4vLo2-mPpFkwkO%lG<1dV6VB`S^G5p$#p1cjeL0nr-lx0z6g$(DozL`aCnIy! zdgMbjT9(H>!AdjJNq~bHeznlJ?q;Z_vmdPzM-I=;F!tvM7Q{{nZ*ZFT&C!RW8}NQf z3y}9fT{uf0iQqGT=7Ubl89MGB-32o*JM^_A)JNlSEWk~=KjMfBT1w$M_{etGSz ze(mgj>{ajN!q@IykPFzq{Q6Wf1dO%gFT7oHa2qbHjZxHd;0tnSt=WmfMPiIqZMQZ*IVuPIjiZbiYe5Ib*~0bJGJLt3zRWzg$ZXc zZj;&^p%3z5-|>&1H8IQIF!8_bqZ(ls$gzNcq+zUSHv@|z$2>E6NPG!eeoMH~CEDyI z@X}jM{P6q`_L+a(47O_wN?Mh9NOf{+nAeJnZJ~16lL<$^5PHtVn1rhZ!&G89;}L&L zLVK7?j7IxT@LnPgZ>ZL01pK(_v<0t&d6jGKZ1NifHb}n#n1Aj~iZBX4fx-6L8Lwys zpfHCi#fiXQSDi&Va+RV_HG$!yvRTMPOXLRYel_gJf1`7|CgYv^?V~)8Zj>N^z6h&= z4_qEBr^VY}Eb&(Xab?>@nH7D5*ba|~{rT!Zuhr`t^ynO#r}+YShi9K>6&M|0_e%!Z zxf4jye0$Uzt(kfXAzb9jD_cM*T zn?`c=!?{eGX#xM9Ck2xw$I!fW(>~wEWy0kHXOShCrQrWw>|phgh&K+=clq=U=X)r3 zu*~Qm;;!xNZc#EkL1+Yek2 z;b5ZoC{>h9nd`#NCy!OWb&s#>xaBP9y*0{{Y`r>^c9qZ36=JN|w+hwB9UE!Q5&c06 zRMD%m!Ds;o3et}fb5u`+`Q#=A+P9i+Gx)_t$FTCN-M-p4veGQML=`c>40(@#JnMGd zjtXOlDUF$C58g5x}T#FQ9Bu$tRA!(8cH^2RZ=bw!|PKxI>(0IJuh>_jZ^1mo74e1-7@p|TxA zH&^oXwQ@lo#=D%IrUHn5EU^xK)VV(bh z6?=t*9eagDy@mg=2Q|=@2(jd+16-oSjo@5S`=Z1h`=TV}AOHFf!2tk)E0FSZEQ^wA zfPb!P{?4oi3KJ*g{oJ@$oV4-N$ft{V=gRGRH%bqfi&trY6Qu_@ejnH2VE+XUi^bKut2YEq;UTW zrjRI;PTKqfGB6=HI6x_u+=QS{m_pSd*iM=U^%=8&ePr(;<@zKPpFWa;qIyV^KY7obv9U%SkiM2l25d;V4KmOBp%nXpqf&a^oU^zJd zrA?rJ!W#9-fI8%d$gIG@xj)xqb$lNtTSI{0U<0KDGt;7Q01#Let(A++BAcDTeZV1C`jp(ym`Y-SG1Q~0)62E5#0$vb zU?ChDOC#S>nI;qrUYg5vaoACO$Sg775`eL=>@g`gA=={x=y;53PGPc=ougt{@aZxk z`{^nW_Q@-PO>&&*%P@eoSUQwFUW79CkR9O9Vli>}SDPR51`**>Tz(Zpj;E(&X|@b7 z2;_9+5cC!t=qX5LiB*!&?5Vd<#Im_y`j%kXY*K1PwqOu<>3c_zRT+uQ7!0b?#T?}+ zU_S6rllojKk+2LyY1EO$zT)usw$&C?nnhe=?(rzC^FAoj#idYaYzV}dbn(M3C-^{0 z?pw<*N~TyK%;;e{rKD6@DymgFwn#J=&E{K0!C44Yc}-I;s5&xDdp4>OW~v%GbPbBp zRY^4WG{y8}Sy423TPmhXGgvt+HDXLE09B=|pCOg3oNTxPiz*Dh!~*;z8A~()G8Gja zd_`&&CepfM`cGjgZ-5^A-cJa3N(}V*Kba6ce_O2>K#I9QGBvUz=mXv(a zmzoTUrC~!AEP7C}oTe>x@1Jy<`s7=~disc88ES>Y4w7Yp{3V)_c2H2MoWr^~bJ5QV zP%*ij!DDU|%=FOJMT%95?zbS-?D=$x&F18^@8RNR$mLg@Qvf?>C~dcsIdx#{Pbh{6 z&Cqvqc5t#nx(f}!4CZqSfm>>`irBZRhTuR`N%Xe1J#q1( z*24u|dW5fu#|Q}#6bhJrxv@Y;TiI_~MDpZnmsF3}W5GhGt6?Wn*iHUJ^?F;~$sf)f z2Fpu+%)Z@DJXY=9#INVhn6E+*Ro^3rM-5be+eoWk!JE~2i;mD} zHXQ{P&qa3XhNbdKE2aFM`OXjfFBAwi!j zCewk}XF@?`I2oCKDyl`6o)VwC=I*B3WJClAhWK5^d+o^UC~od3EgbpCKVNpxB~k(q zA_rTOhYW~Q#V(@E$jN+i!x)m-cFrUoBN#Ivy*e0bo}c)0yF~9C3#=VaPuP}5f9iW}T(UI__Py(it2M*R*3YM47y29SU&ih`#{dZZ`cb2p=0&u)Ym%&k=x73+T&0-jj)147G59ixosMD(FyK8*N0ml_( zU$^*+y|zV9Ux#@jBbfWxO5cVsY2XcJfmkhR;f>QyhowTQZ7s*=Jm(^-T@hV<{)7ev zQ=%W13f2`_QAiQRBVN6t+&|6u&)o=rzV!w3yZwfsqqUwM32BXTbX%6UY8NtQ&&n{X zp_&7j`$a5}`&)oYEjM$GTS~j<{TjA$>)6Agu41Hap5q(evNU z0iBJWk@Y60<6r*EoL0KHgRD`gZP{FKFuJW@snSFk(&yj!ycMQf!nE%%;6^!S;%<9u zU}1MyR_t{!&-jFK%fhhu7HU5*5L^aJ+6!+D`Dw=iBou%* zTIq`?4|J6og%W(#XAFmBTKr-qeR=N;QMCjOew{hH1js7|3JWx|IfzYd_Sv55xeMVbIq!lPcLlS-b^A=ReJ}YAz z_u>Vvl3jF(xCC)@#I*}}iyt3&l-#XixDn0K{Q~>_?T?X+%C-acU{PFlvi{01Kh9?h zcn{9tV}6w)kFSOcR@7_OHSt*knsra!`O+$ZP_T{_=ekJP`VD204$*zqF>ffit{DcM zD>No$r)x8RY4WwOs06=z7;(uM2~rCoCL<)`^lrNl%lk-Fr@4GgHt2P$Qyu5g0dq3+ zn&svYy?-r1E1K(VcV# zsz*sM)GDKp^gkK zx@phcxP?qi&dm|CEffXmq;hd$PaDkwV;x4`k7|}@Dxn#BmarHX0@S|xO7);2#XCo) z0N6hB(#)HFw=iYIv1QJ);rx!knps>0P3V=Hn}g8$xCS#9%-VQn9(!GyyG$MTWh}iG zOJ^ga<{FQ>K#gWEJ%O=Vaxbrf0k66VRy{~=9ri;3W_Qgzu^4%*#=pW^ofT%lizF7t z)e^5C`2=v+qMB&0}Y@_u)cTA7cg0hiB0K6Ymp2 z)&or@znmRnM}9}xzhza(-m69}xCXQc7Vh8G88kP9TXDD4c!>sE!A`BF&#dN|F*yun zGTD4se)R{8F#@_h2o@Tw8PXK*m6?=G2H8Hp4+KEJivzO@2w-|j0fg4VeQ?s-g@ zY6+hAPq1%;^f{Rbkva$R&s%4n$E?>`*jXcyP`+S=of7u+H?My=Yp?&?ue`M~;eGOF zogc-V?qy6X@UEuO_*}Cw5@B8Y=G9Xfx(}_p-)x2F%!|Nl9VhqQ`ZS^mKdw;6Qugn7(?f zq%C~SBQDE()Xloim_)dFl%ZNN*v$B8MPJXf-PJCyTgkUZsuudqWQc3oaA@9nBE z@Im-c1eWRCiz*lt+a{tBy$hz`T9c z`k2sF4^6EDb{MIu{Ts5Eo^oiQJ-)IIgca?5$&Q9C;b2Glh=s}!-ILpkcu$;HbDDPn z_TBKBifA=;10gi7dF@%~3{tuCp|TS6B0pjVtOD<9%XNUxxlIZo#qh$yctAjS%udSQ zUL?%sk0L?>4~Z}*+aJit&*B8Phwk_(E}lp%lqi4Lqu!fgK70h(aTgz|C;;hH!^XRu zubAtmG{h35mE(~YLfRF$(H8^S zg#f;Z4dETl!=Uy_M6keH-m3>l@KUP>V4TA|RClA>*asc{YZ3S%EYLxEQI2BQ zBuU7=g`zMYt@JzDDtxu*sdFO2{IfKgMtjiF(~ipnAJzRF*+Jk*v5K#x@9t02%b@l$ zO-%eR^)%v=eeP_y7}l*Nsbhi{)}AwXo|$mHv%}Q2w=TwBKL0Mx>=7YB0K~*|9pJGV$YU+tIUOhy;g?PK( zcf(YgoVF$9;lpzs<@08yje0I}G@??i1k5r;?}oO+B0gP*y{-B22YoxUyrZf4l~X)C z2EjwzndqCK7T%aYYK7%uqJk{Ut)OF#J3q_*mZfJm%h&r}5m8sc^jnn15>&=px`b$P zYShrK>B$Y|t~HWlvSb-xxe={gmM-RZSJ}q&d$xxm{gnoTA?_}vW>Y-Hv?KFId!PyH zfW0t6 z9>ek?2uI@z(*_TUB1&))v&hC+<;4`A)4AzE-eX0qzL`4MN7(3#tkD{+53?xrI6!gA zgfP>#!gd3A!jV71rHlUQ_K7f2B`|t%g%2nF9BoMYw7y4A-u|2$T8J9L>+S7^ivRWP zX0tmq6c$dN%0bqI?U#WbKFOLaskZOSeptBiDX6fD>1Z7lJ}`jll?p-hzR;Gh=;FQy zmK(ml^}}pih-@Z$tdTI;W;N&p%nP>`fJs?8a6tU_PJ6(3dBm6&uu0Cz1tb#I__oWz z_5b`>B|eiw`rN6OPRY_1%OAO5r<3U8NRc7%uK{1P1+56P$*l(_*2^DI-f%?I3Vwe) z0g`lw>_oG%eX@(^#71a--pY|ZPY#UUB8YOPyF!VZ1YU0|^TUm!t8AG@ zV4YBHK>#RkCvfReph}X)Wwo$Qbp1dW^I{w&*8z;hDqsN0FD zc9=bqnSuY?Is^sa>TeWjcCRt!j{F>N^CJ9nTtBX znCmT7Wve&b@61341wn*mtPAe&4bO@TGzbN|* zmxjBEXT%ih3mwfMz5>Sg>#2CVH$>R*p_l(mkyw)(U~`D+!}zE>`KH) zwKL+O^y#vEe<7Bm8TB# z#H3K-*ME2@A}zqU^B{zRO`r%Etx$q-Uqm7XMR?5DZ~viW;2cPB+4~#2C9Dq@JWU-fluCeYg0L9Q zqBM9zfzGKjPPUp${*8FhLOw>htB0*}F($%I3BBNNrNxa~`n5fS}{TQ2Kp0_z~Q@!^tRi{p6#CF>1vp+PJlQ6vsw(K*cgro=99 z;f3M0;XsZbYTH(n^s5qH3HF#!FJq&_rj=I7Zxg?znZUNRVT5$J>gUPrK*zn_GxjD# z;eoP{itpwfCzg}uy7)me*CQ1TMGFmT%`ck2E44xxIqBM)>g!j0V|VK z#-iGQ3iMF}uDUH5KX$4guM(0y+pnsCUD!u8$J!LP9&1?t^a@{w61Ug1(A%+>vrI*? zKVuyHmQA3mfhjkpl`CR40=h`uk$M2>JhGJ~^t6&Vlfmz}7hNDll;Jl>d6<*=(%+Ts zD40^)%Jb)-glFnjlvHD>Vuq;1cZ+d{7#|N8xuT~7S5~!kdj}6Y;-P`aF(VU{ha?L@AImJ!~wr4%-!|=XM|xHrqZL zRo~;Oz<10^7|ViY|0cL6sn|dG7i9Rjqqx`|@;;OvYXpP@;r?9m?>c;7XLKsUu#(#S zHQ3$-JU{Q(o^*A^>KJK$nZHq00p5);T;-Nwc zH})?smY0r!$Uy3`r@gP{@ZRX_3Srg#-WA*jlw0YuvEkGooGLWyq2QYLr0tG`K{mVW zXDmVe@vBE!cy=R*nI>lEnLKtTq$o%2BvGEkLw$8i^hg1$@t0;x5yEJ@D4u`4_B^O#WG)m^fka|%{HW-9H?TJl;kS)~GG&Bjn=r+TYvbjy#UrjQvS&Vw9 zK*>x9#K;hA@lm-ra<&J}@eoZMFdA~z;sWR_nFu{wCNWHiPPncpL_&z06m^1l+Sw=O zT0H8gaCA{&;&x{_#_U>t83c^54E%L1l^!?Oe*^#5SI+HID0l5LuTfX0+uth}Z5TcS>_NaN>g6 z?kbuJuYIFNyv~_KE=|KGHnN?(PKVUXf3GTUObucz57auEUE5;GU<9nqIr#fCeD&Ms zJEw34+wU^+_r8@O#myEe)3@ew1De11I-Q$e+ICM*+WDD@*lhjU+#c}`%CP(W0O51T zA(o%PD9IlHQDzn%;WTY2kM;dg2rKoA1X;BV7KUslqEdp5k?KkaA3MBcR)UR(l39=n z7t+<{k7=yauTe3ZdUCX|dTnWtL6sZTo$5WmJX_JG8w8}VB zhDqozeOQ1wvC;2%7Ge#5(Z5$Wh6`w1cqA2Yz7#TCo3qQos4te5m5#q%w`A&sdi-s& z75rJ3Sz^b8A90#Af|2v54TpWj9jIDc-Om@aLN_rrt{GY zX-25~4bxHQGG`{g2Uxw~_cj*Pv|e4mhQaQnkLISKL#&L!hX$<|?9_8Sv0oQV{N%>P zw7$8CLF{P8{!!98&SVVOa&Wa&KeB4i4_--4j zoy}_u^!Q!H;J>StiebIg(9r`9Wy@0}6`%$;U@y^kJm1>72~@;u;70UrZgBajveg>a z)48sdzn!<%Pafje`Qd$MeL<>w8SI@WFgVhC-t8ycSxI(?!k42MkEqVh{oIYtXD6wC zzBLx7)b_<@>RDo6XhObs&}OH5{TzYEHu1noDuVDw<{t*&K%Ib!`TXrp`i)-#OjSMj zo(q>SscLMJ0dRv;6AR_ezVkj^^_SN>&OKyhknQ03TTiKEHFIb6GXd{DH7w?^Nv6Py zoiLyEd1;NkcW#8gLwWm6N05zJ)5QWp)Ims6FG0a_3NL89MoBY z^CJW{d&ut_7hzfogNuyzE}0-%Nz-d7`G$w7(JtCyHsDNs+wf(H*FlpVaU5L_ojfQ1 zOYipP?T*IXp95Z)3h*f(gl`xgAypCPtefkz$ve9pOTB$x>h`~}HLY-wZlobFy;^MR z{!p{qvoY`_dv?wsy(EcDXqp)u`uhLnsYTNB8lB*lLLB zD3v6^NFZ<{B{lu00S_$%TUn7XnAjr%6hy;-J48O5B?Lt&0z`JYU{RQNsri*3Vz(h5 z=weegLS%&{_t=@l^{{^%oO0-sI1Rky;QgwUL^70?nnTbswnd4Duro-2`%+lfyN;v^qcgg)+q__3BljTIex4HS{;UWABf zH(`K9Qx^DsV}GQ168FuHonD3xwZt#NX7+wp==Z4QH5=&OZM#>mf^z~Q9;$u-J>Efq zy#lm^>4~GDXzV<*=&VaW#1$WV^0>vF6&8 zWa+#93q)WU9X@(UHE z;-=$lGq|Jn4AzC?MN5I(^@wfREHs6>7vVFnm}@U^|E8qa&%ZDXUgF$8{lF$2s%UOgVObMrhK_mV}-zAB7 zD@s#T1s(nmm6>9v+$F{zgpwkHd;l=(6nB#*PZ|B&BvaOHB@}%g%U9DrR?Kv~Bji>n zM4ZW$r4QvR6n(mollU}oKkql;<}z{wL5e@`jHgV4&c$lncA>le&msA7SRQGbXdG6p zl4)qQWD!0!K_pwP7Ur~NEHT9tiHPXL{n=1m*$g{BR z4R3E)3*UcNN()QKvwYQ)TgAgRnNP>29~a`X?u_&o>ifz77Qk9I3(?-^L17)O`iC~F zU0!zV`lR1uu*@{YvmD6?)2Xw~;@sq&zT8IMgZ?TCUZqauBpbBHL}^LSXsP!4Cy#c- zimZ{YfQ2;_y_ZQksx4;>UD^{^c1js*%63J_NP&TyY*6@}QNl+}dOgbnH`v?*6#T-_ zTt*R!W78E^al*G5VW;kb|AZK+1sBhawicM$3)T%69Z$FaaMjaZyI$0@M|t}~2D*yK zAb#2->(7oxtP&mKE)kwW&6^MNzA&R{LD$U3)Hte6E}281cZ&OCCJ6vWd!OwFml%QR z*qBuaIt|BGF=hQ_uo^@exnQJ4R}GZ|UX@uQAw-7CsTPEaHQDJ4`{iR^>sRdET`Kjw zB2~|DRDpzo@=YiM;K|wZ{t)6cfGTdRLR-T{p`C@ah@+^9BG@}VFLuY&TJy6EQ>maR zBX%CYGNs@f2WZUxPA?!^#8PquN3`2A#Wx%=RUm>xkOlD}BinH+npfPl#9-9*aeY19 z%DumgTa@Dzd2yX*?G1ec9JZR!jPk|G^N z$|6xdp&W#3MwCu6)AR<|5(+HRdO)!H;uHM21 z9Z%0EdxwZH1ri*Yu4d866uq^Kzb!mPUad-@)G1kkYRhp;IjxE%w2 zvHYE?{LYYr0p7N^s7=31UG-L~rJnIoN9Ry!KZ=GaM9{xR2v=s3{1tBllG7z|bKHBz*BAr68eUrT6ftu@Ttx)8)Z`qByi+KPlrpvnzHa>Lw{%ld zT?QhX)}JZAiLd4m3idvV>fMq)CN9M7*pep37`e4D#rPW>4boaZq(n3d<|i`;FaQ|} zr=fZx<*E7N3slnb!;2fS--tMB_DN}d_(wpr8Ueud=&XLKf0UjN}9+J_;hxx$4>S^KwuB3uVN zGh#rc#Bcr*=ziy8e{yKb( zCY~O?_w`VrANt|6jtJYz!6t(KXW}T+lh;j~Q!B~SXUE3tHkYbFMG$+X4Wd51po?*| zjop-DqbQCOS^B5}*q4bfa;+@qQL<3hQEq~A5VtQT81-A{AXhzd%+I#9fBqc@#m>XY z333$_rU&Y8I&W}eeC9R9GR(-d&Kf3P>B^a(>C)Rt7rfc8p&vdX7ke z97J|^W(_jYl2;gble$i)z&_*Y5rpqLg;C*Y zshNXEUUK7k%l&@2_x4olY+U0Y+4(0XHB>lf{2eG~i5cV!+E{%Qm=oPT^~J`c)HN@U zmCg%;h?ZpMK;IFO^}1iVX)&3@I|4~F?MYJ`1`G2mrKil>x!>Oh64V!eR{m)yTILfd zHzn0+xHDAiN_cEOa;}rbrC{jT@vgv7$#mF~`o|=ikkZYQ_FRALb0%f8Jgn%IvkemL zSOGC%Ol$_ctL2CCuFPyFZ0Wn?*)4{~$@B2o~NBRKzk@CAtQE2>ZQou;3@$9_SjECq%V{7=)M6GYR*_u@ZNAQe&u(I160-iY&_@<=1kMoZsv)vtKpg0;wYRSwF>M5JY^DDl;HjtVdhI}COT1P2i-vk zdcy?KDApx|sNm3eWHXAKE-XCy+8DqidR$Ir@d7Y&Y62YhYVupaCDJY!W#n6AQu$6N zc$F+(l*w4IfMVsiu-b5K-HS9rAnA&=uzQ_y_;qJmNCc#$m>~p6Vzq1b3&_jMbRpQYaAN}ql8S>tBu_Rk!l^=tOG z_zyW#ngX8b?;KItk7O}HYglVQNz>1n@X4A1t+NC+0S%Y)hZ#`&lGGLChMEBP2Tm18{|?aT2B0`{#Zt zk1W#S|Hsr>hDEh@VVDl-Mx;?d0jXhzMp8PZyF&ydBm{;Ik?!v94(SHzPU&utl=!yi z9Ob*tb$&dvhnaikefMGYkJx_p>aUY|~Jplw?dGL~GbrYOk{ei)T8hFv2}3t%8> zIn>UnkRg;ZAG@;V*mYmSr>;&Q@;py`y4)*d0_FZe*hNBw`(FzZK{{76g2BFT?*PBwWR+_xyRc3TCoSWXUQGS16CUgV>^-i zQ?ZHJ9R}~4Zo4_hmskg8jCf_*<$V<1^B%-y46Qk=)Ct2bUt2sD-P`Y8w`#YWM7q&l zf)dLfnCkdmVH=42GnMDLOlvPX`n- z+mjdb$}MT{0eT)1blLAucisvzVJwc1CjT`oDXO)c8>DmVJp&?B<=rq7nG>V@}?4>kgDq4&5Y?*)E17)Mxex}ye| zyc9TScq^Ny<>s^ZTK0VrebUhL9K)Gl^MHLO_WdBYZ6l{2!(=B}c>LOCy zgq;1EU9541+7LTb)`#IFaSsEgr%~4hz+L0iI zW6SzSt%17B(kLRUMdQy9ftica^|Kc!0O1B#1hN9O=Nt{ zHnVn1%2mnZ9ijWWTHF#)v)!77{Q@0Mt&$qc$Po)NT;>RNQbw-O`HYu1`f8u#u&z00 zw=LX59hrAV5VL-on(Uv;e=MShei7|Yb*XU{4kat+C2cR?#9C3~Wg&$f>XSewPn~)1 zJ;YH%>o4V$nv*pb%ZYw`tPg{L?>5q%e}m43k44xjX$>3l5|&;E`YSheL~q1*T13oT zn=u?&SU-wt+P=p2iHr0=0M;I1*(m+@mx>qmbkEVlUs5*bLqOx4G;qqNc=Y%(YZ+Gk zH>B1r8?c)}2T3mLi1|wsq=J=~`2P0qr5wKW!(TR6w_`u~nv^!xv)^#G8hzI(D$F(L zoDwsXb#|HElj0|YF9}NTDW=A8Ic?ctUa3vDxarwB23H~FlC_Xx4l{=iS}%86^+EK{;s#<@Sj!xPlt6u74V4@Lj?0hi-ApAT)klK)hojoUT8IQWzC!p5^|Cu+ah$+96r*nHm)-}judsg< z*^$?{G~p=v<<^wW`*mxV&dcqI_(2OYeM1}gMgxi;7Vd8^{3=oRu%5;A9fM^n@D7Gv z-|G#XGo=gztv32$zH~=B$Ad1BY&aLlqPXR`qwBI%P#` z7b`oAmfeZ}%BrsS@;9y&Mulm`FjNT7LBLx?hx<_)NqW5NlAvO23K0v}lZH|oo6nGG z_#8K^!ll8guEJ0eBx|)7jQT5S#*dAtR;3Wlj|rjF78wKZ^e7qj<@04GZ%b2EX0c zj(m#j9!);h60;(3_CVbJncXG<6D#c5ZUF4^%(I4R@nFYWEtLapZ7>L$I6okQs5sxn zd@k!Cl1Ki^fj5Ka4a$6_GRJm>OXoTc7XmIh!B?28CaYI#24kX_KI*7MRC_BTJQ{A~ zl+=z@AI>m*SPw`B*teL z{+5pvru^Ma>9RxiS}U6eD(Iq!{ds|fty^%4*pZXckXWlq!l+I>r7t+HRGIX{ZPF_9 zRit#W0PId@>eqy(5(+b|`Ys+r1}R;^Q`lNITF0~IEYKRv$U&Jvl`xbKwP)eQirnH; zTmqv;MuHVNzJvI}k1RSLROZK>)5c&bV;b?qviUeF{3Z-yixM5Gp~b|k1jy{f+&y1T zbDA&*CMmklKcmMfK5JjMtpR%)$;`df)wp{Hd16>mf#al0qZui@d$%Hq5~93(_vzfZ zOOF_tQBMNLm={ZgHp9nM&_Sc=Zl^P1+5gjd%SmsMvH10Pj9>uhmBD*t&1NuZi68FI zp(E3Jl%-H(lJ$dzDJZ4JWQiD0myMCsH_sTPcPVr{M2;Qtb`asQG3YdTOC3Hn>q&9^ zvq(PM_gHCUtY9SZ7waYV;av`&9pBL%GgCQTk+qW#v$d$lZQjhNzw)#dLPPc?tR%;@ zn|Sh|n>rTQQvZ#HeBGB*2<9tGH)?b<$^?alls0(dq`dH3uO0M=dc?|*mPwh^NP()& z(?e3E9Q)1FKq2fEEOJ55aQtN_q5`R|A?+^N;!#CYUE()eu(Pcqw4Ll-k-IVvMqdjO zx;%BTK7oQK=OPqZWp=c^QM4uMzL7?~?se<6R3qu*bz|a>Ife-Evr@9BpRO2w+n6AD zqeh>2XT!)*98wH*;ijD>S74Lq5!(2|%vLV%S<+CG-PmYTrnV6qCXssw5<`J&do%nL zJ4W3qe(-Fh`k@v=okDGCfMv5Lil96T#%@BDQNp*HN)jaVq0knTV{0;iWvXKhrFmVn z^g(-VoXaW+7mUX66Sgw(tEb>E{IuIK4kl`HH$UG>q*7Zb(`5D>tY!sW7j@T5+S-QM z;VbxLKa+fZipkr1=ITTLQ*lstf&4MGZuN{}fOl6;(bz&>@jju$4JR8xQ06Gpq~UZS zUNGyY1qpcK23ULZo*UWe4%BBJ0~}GkRR_U7=KMI2!JZpw_DltfC4CjI{yyb)Z*duzDlnB_k4=Ix?`MblHz9jLMV(R>IW6fLK@6Le$0-TbDIBDHOY==fJC(@_5!B`!Zq_Z4QT|N=})NrQ0OzHl3n|R~_y4`yT z5$e>_FGexQy!~rvav9%B zv)=AsP?KX%^oy^!;f)CFRa$yXR5G&?2ek#s78*rAv`h#Mi1Yk)cDg&+2M(((7JA^4 z)_$R6JXJkRTbUm%fL)*nJ|(ewnNVDg-fExfzek#2N*+>Y9YOvsoKHq3Cvn%_i~rKB zC-NRw?&4E)0%D>KuNPy)PHD;~M6LMT%1;}>ACMQ+qjGKMisRhX>Q-NEUfU1c-m4ML za2w|dT|F?QqP~n5VyG+XF{GIZ;hLr|-TMZc7<#yv!O?4qN#H#%kr@6#vRP(ZYQ6ds zTnlbz?CW*{{b@vArXxrCk+lp(X~SeWgXC}1CCFlUtM^YP`LK#1PuEwNbwXXY&h@Ge z-|9lQH;<79*zp=>8SPEmvlP&=x(9uBMcYb9f{8x9^H`HX+hHh*>9rpVTDCOj(6UpJ zTByY!jeF}Q!GxV_7Go5y9WY0NO_vEf$Y(gQy1!=`5H&1#?hi4D3mXav(qJGywL2Q% z5{O+lK_X=I%#}czjQGAT3NM$Z!*DKUQ)dpfnmX{*Xn+JAJJ<6Oj=P^p^1M!yP2y}6;a0c$@G%jt~N-B+qg7m4b^ zxUiya>;yhJKw*B-&HUpL!h=Bn47yT?ZE&HI19XKapQ#|vz%0MpU75u|EF6>|@IR)) z?*IluEUX-@Fcbu4|9ua@W>8`SZv3a^@^@ed0>_^tARvJMgx?PY`4fIW&_90S@1KDH z;h*-}-+_}71o`L5e+Mog{5MYQtr9B>kp5|zeZmX{A}bL8LIAzAAjn?|RsaL?7lRex zfc)iP1wbHwL0AD2$X^mx00r_Fg%x1o{L8`$z;OP7fhw^9G@Sp@0Pg_+!}%A64S?bN z3&RG$aQ=m117JA+!mt4_oPS~102t1{Fl+z}=U*5$0EX)?43rI^`7>z^c-H|KuD>ws z01Ve(7a5* zjXw!Y3FQDb$DarR4*rGV0APT<@#h!-^Kbw4@23aODh^<8{C5mEtvGskXSXd>kyp&Qm2aZ~1)eMgH@{(j_}s$!M*4MFSZV z#~imfN}G=#Z9b-^MU^v}_H)uk>Gw<0CL0a0zhJb3Gmn_K^$K$4j2%7FHUz@v5T=R22nxOgaGP7o4FUW4^a9zLjz2I!7?Dj_)I2S{b1{K>+!5)}ajOVSo_WRn}>sOwZY64aw5u zPEwA|Ozcogyb#34e8S368L3Ds6F8;Xil`dXDhU@!7ML^!3_CYWvR=$^l9^eXVQZm+ zb#RzwoUq5JW+=@+TD-X;>5vsl)7Tg=_oaFf2QLJAo}5W)o^A89Q{9}jnJ&S@!5kVv zG8Il5A3KvcYl3p#FqE9tec-BcGfUq! zm5;MWR`sa5$^ z8XRwJxsR^u;s>9&e{^tGnCdLHplwVfTts}xw0!ns;>D2w6x7&a_B|q1Q0unHMfcyq zP<)$F;pW<&Ht5xPqkM&m?=^nUg-Rt-a{m!C;zzjMUsB4V^3yd`U{mgjUtn48y3)+> zVf|rs>E!4d>o%Ze`C*g!npI$>^eXh0?w%bw2wlnj!0N7g@lh_g zCM)RovoA5P=v-C4qRwRT(gA&sFjzCNQH_aj@2n#$n3uksG%{aX%7Wj$0h%;7fB>kRBe35H_u?ilEPH%Bug2+VkU!$$qxd ztfr)C=?nEkvST_lab)vT!35Vbwrf4EJ(f`@DQ!XrK|;q1;IH*+^dA# zLD-C@gPY^c4M{pDnMS##V-u?8yM@vDr7?Coxowd_Ilk`E2k0(P?gJ-QVjGgzDw~An zvj%+`0S5HTVT1->_flLAP zlEC3P)xdbCa{{MsJg4qZous!Le*0v`FO8o8ZKfiq-4dD;+V&@Fg*XC6Zaldj{^570 zZXB<5`9C+teR1N7@9-=~Udym}CYJw(cD5Aj_04_7FTb-HvdKmgNA>ZPhnr(6r|<_W zmc24}T!n3g7nXBaPOQ_BRr6QL6>^960|mD%?zvWxQTQ(t~<`}Zv|xR1Ptr#NN0`!^Q_r(qs=q9^Rjd z2qU(w=G*cNM6qi2u8qS(&Y4Ws%PExvdo*y}#&TPF`D7DRIpFpXxKw+Ungwy^q0HYt zYHE+Ipa}dF5VHwHjXf65sOSY5oJ;bB@fHk|t+z!LWlX?V4rJJz@Mn@B`C7*C*g1k< zJH`fQCiSCR@V$ITo5vzp62vVp85xK{KY{rkj%Kw$yiB3^NzfBS=L?S=G5qzjKIxKa z+NcnoN;ioz$spljgjdfC?PwIqih2S9XL<74+yUYHxG65u%y$?OZ%PUorc|R-+;VV>B>~m&G zSH=UZyzCYPsdxC36sK#$Xve2Yr|J0bW=Y+f@eZ~f%3YXERX)$qVyvWOHWf&uM9`ic zNwYH_&~f$t`ayL)KuOK)v7N^DvQ~_`^xN)ot>a{2m0}&^kAhX7qInU<6-PuajO0c8 z$x0-Hl_?pM#>Eg7kExq)<}3M7hp&ZI5^j)#)h7}i-!#ue8*k>SM-Q4m4|bJu+cqQ( z5e-!J1l9L-m39TqTjgRK1|+t0U8Bi2cq0E08MrybL8}@l?SX4Rd`MC&v%j}5lndKd z6yTdYp6D1ym*e4GlxbV3yo>R6Xw@|r{=yti*NQr#&2g(zH!JRs=DkP@jg|bu=q@ct zZ7SUFU?<6@udVWndAk;$OFC~AE^tVhP=L?UU*v#or6ztrHB9Y!7}!0kFRS*MK|iLa zII1cpUlfwyV7Qb&gKCNdT5V1zZTL2s$;0t5zO>JIuQOkL+`tvNuVO5lP;AD;#$NhUr3%TZPsUofaD`H#^@j|D z-j|)VS3d_oWMIU<^`s#f>axV{w3xBiUG4a;F*48QRpQ?tDy<^Z=gAsY7EHa|Sz)RN)8Q3`f{kwrk~cK0g;qZ~qegaIhZ9m;bcA3dyS`KP zk*q!;>^{N{5TzIKWKJ4nWK3#gwh3Qjk%cM-e-xmMs$w8|pmm{B2~f6?8o$hhsLV?rTv+T+VVCK=D)#f3KkA#ZZdEbtP2kbR5PUD2 z>TZ&8bgr!1BlXL{+N#s7sb2kZ3aW#7Ah=8P;jG;}u@6Sq1Ed@iL^{F0SU$>Fpot^IspQN4?5nT5N z3kW2^2u|wWtzGZFMac9E61wqtL-BbpMQyZ3=E+xU0r+;qH=Kw*>eXa^HVl4IFI_SH z=)8$*I@7uih}VHH=wraXkqd@gTD%#9OV6Q^w=$=?e!gn|^hm&Q0K=Vrk0Iv({T>oU zS8JO@rSxwn;_sXOnXL_*LIn%^@0cfe4$$wJ;B>WbQmF`mQB-wQc(LYbR5-DwbyRe< z>1kB5*s+DcjqsEl9KUB`(Zw>BQ$3IEX#?(OSPtBetq_0(3bsK{g6o(SW|w$@Q$0)wbn$64rWFYBmAQU00q4bK5)jV%Yx|5)U9D(e4SrQhw7 zK&xcz?hi^dXt)xA{s}eA;S~95u~Xr`Rz&iQR+x2pqXDxs_|XHRIakFH5zUJ7}c zSe9N=d&10^{XE;FWhQ^3bL-l*_E4Buc%&nxI#C23!-rh@PD-COl!>vt4@y-2sCjR= zU4u1^mi?|CYH6PK9WrR^IL$H7vRJ!kvUE_>VR#9$f?8haR~^>0V6J3iX}1V~_E=hW z{c;^DEg=UN8V$A-m$yNxw>OJ}i3~$kFiME`#p6GZUTwV_6~K>;xxYUnn28=hf;$O` zgHt%k4KKGs$-KC0V<$^FEFoIX&^`no9P>5lqG(or*)yO*Ec8XIAfEko=wNK3_>JkP zqv(^bKD1gn#01e)EMJJ7>YdYFOS~gPH`Q^M_JSZ}Ywg6Lfr;Jc_@Z<$yX+^tFg>7z<%gyHUM-$*rm1?SYV#_B{%!rt0aQZ(dcnPE-Uc zKRKeHwfZf3^R?I|T{F#gnCyISG|`Zlk9FoLDUG3{9SiZR#x1@|DB)+o z#Cjb@1k1((ug+MRUA#6{)i7hJu>;m^{xIx$g6}hx%VjhJjPJUVSUpXK_|Pl6dHnAg zx1b}?uXf@`q`MV%Y6wDjNi>HEj9fi|Y1x^-lFF#RmeDZNfip;vH>533{G0lYk3d<5 zEm}T0PgSAy^)ApCX|6f}LK@$b-ubeIv~dM(Z0=r=F{`NgxUndITg_Z*cv)o_v0tc0 z)S`9Al)ge7Tfq`-K>G3MDaniuE7Kl3i6j&$^O_Ho^Q}>OZTMKs!;CKy zX|p92F1V6sqhrHSdpatwo%mkWdVS8bC|SsKqf@b&xLKH39#M=JIVc^TEct4rg_hUk z7d^ivq6|wM$DR2pgDSAwG#|Zo?B=UqcOz~~Xt#ZAta;MHhSouYpZUkg0zO*CkJ4&T z4O^9I!gN^{)|{clo|v)dg3hQcl#lNkE&bi>Y7hN-%1Bso3E_$|@|$NdSOL$gN<$JeKUqn*A`?v%ZuAu@_~ zDAvg*w`aA|wM|Y$G0)#P;S?b$B)5~j3sJ2y;UHQe==*t|;q}#hR@hf633mBx>qF%| z2*xYR2X}mhyji}VxY+Y*ZG&a(WDS#8=)=5c34(lCmi^7l&pMHLM>U;p#8M|74QRlN zPjjKq7jl;T1LJ>|QOM!^7*WEjVf@umaaQ*X>uzWdy>JmcAhPHg1!=6IvmN|28A z;6%qv=u#ZYbBF~D@P&Q0pP`PdqXn(EIBCzBcUfz_=fR!LUB^`rfL+_a2$k^6+#G^G zKASiaTiO2xj(OF_y~R9e?|JS|*wxwmV1HoW*Ik({#EKK*XY85a@8+QV^MyaJG(!O<~}_O3>%RE-D_b9SIR?URo0%Q zz97xc9v($&vnR8YitTgp>ysp^l+n@ioLwp7*GWz@?)+f{YMUXHoR;pLSWofYOm{^9 z(UCR}vA!b<|XQvtG`6?`eQ~#6nv<5o|0Kz*1R;*z2-L(PsgA7 z8I=^>YaxPbW9QJp1r6K%ipe18v`TO5C-;LR_8vwp#O!zG3Q6p^!B2+V{POChq}O{I zUr-aRmmtBI)%PbyV5cRW!6K_D)Uybm`(UI%KeX zFzwEzsCaJ9V?|YE@6t(Yt0HaJlZPq&WrwxKB36XZh5sdw`73-cVp23g;94u!7QbGL zsq$^QrpBC1__Ux#>X8~!i}}w;jh*9fnlxT9x=@ zK*vyWs}B+IPX?11>q=2d`t zIMC(?QLZp>=VN;CW%w_WQExXt)jzCN@EzgOF4GEX;~K#>&pi76Sra@z?=@_~qj_GL zTwFW*!!?T;kJ9@%M}8kVI&bCPEulN0V2JQgt+!xd@oEI_4K^a5C;dci*WHA0Tq@=J zsK}eE0)bV57UKjK(sHcu3x*;2)=vu!KfgYRQVn$M3DKK)bQ5uSGtsq6D#o@tyeAD> z?2#kC=DpzfV54;6@^!+6FrT9+tc>5m$oY2v=Slg&e9>Uo*18=z)YF%FFI}aMB`NOk zy-rotY{?eWU@~IdNug5hmlx=QqtW^(+bMnUQ0sCRyXxFd*w5 zBZ28)oDC|Iq#bw<=ES?PPLg8^1BP?tb|JW-A%b%ymFF?0-_cgu=_;RRxejjSSorW0 z3CwJK6@+C|-PH6?hT>76j0hTOG~4j!$~12zdSs&pW>XDb7UVZ?3^d%t$CkM+w)rwb)9)d+r5VvDC} zIs&ojBF6g&)P?G18T^gIc(}9oSzYgknx}m8j~xbL*-dT;t+d20yY(RNBV1fXBhO@i zygO79HsW!2dA5q0er6==8lDpA-ahg6UAexA{q|QT+vKu*?U)OSkh@InIOo6Dg<%6eGs3REc?oUO(6nBt zBXGYg9nmxfWgh3u6S|2nnxK8tObaGbqx?p{jlRB|FM7M2%Z6pp>+y*Qt5)JgIihtNG?vZU<$a#ED@6SC8yAe@_{P@3Gn zmyYb)Wg^fofz=eLKvv-BSnmZz{$-u%y*c+?+DbTF=li)$ZZ^f?^ZmP7=ra{w*8RCb zMtm)W@X3s06|PLHT9O62FD@m_&0q^t0!6pXoAbuC;HRV2{;*3tGdq`F6vX-|_+m<-cY zfo>&x4K%@9Pw~Wp?)G)2p><0t7tazISdP-RU8Rgfar2f^-hps0a z`dJnn_tdP{>E@zhHD6}ry7|HN3=`jZ%W>vFqp2oHr)$7@rT}NU91iSZeDA!11@X~e zW0aGjo1elc_P3&Yn<&7-igE9_r-}f-Xp_k^`D~=4vE37Q<7+JXM`(r1jos8#HOo$g z^0h+Tba1;c&D2ke@!jC&_XJLPz2-NUuo&f2d2$y^II={b=Q#Rd7t1z9&aUxW&$B#A zsgA#wf0ZBDmI=+Lm6rfzyV>L6p2-z|&}iFR!7lVuZEYAntPocvR$J52ro^3f(+`4rOZBkq!5zrFGuB9iqgAMO z>=+;Qkep}(u&6$oS(M`{W}nsb%8nTqM}ENPeoa`1Jr%YnDlrb3VnD8HzrjK17YV^N z$P!!ov5}XQ)UCGh83t=WJn2-;GS!VfrVPIHZ5#rPYjP37ZX;CL#h$IhYApFaRmvma zqCvpN(M&*Hm*ibSJNlIBF>Hu*rsagin_8Er$d*^@s|L68R7WSq7$!fCGzZvu=rnis z?X78f4g4Bp?%JQi)OjknE$k^c=rANor?Jv1byoTAz$odhH2q3u45P8(I{h} z$rs8|_3Udrcszx!z#!;^%=*5B7E-Y z-YeSXT1qrR7HA#B_#JlKF5>>YJeCXror9_WrwsG_+sr|z9WPAHDydp1@)twZG^y){If*XIc`k^^! zL|UV=sObF&1*r&wX)Bg&*f=6ZHulT4YqNNKb?wuBD+QCPSGeJx9?aiR6o{U(2;~iB zPRQX{{UVoVmwWi?rvmdPD?q_LuWLq9;~mHAe$?+~uq_kaNQ~ZWdx0%t(gk6(D)QMD8Qv zR$%$a+r58>N|?AzG^E8~jl@FNd93Eh({zg9VAy4_Ls;0Bo_V-_wXM@Gc(sq^Wx7i8 zk&J|u7a^?5E0eqE*l}Q1r(A7*$B9kBtHj6wV;TA?oPuAuX!h4x8H1)Vc0&7F_*%UI zuAHpjNSK+K)jiJWPF3bbxnShRNsv)KZeYcT$EUeBnV>TY4c6A+Pl8{T$7 zyW`gfk*QLfly4Nwgq2%vyJPywqeTOPDO>8wSBT658ag;I!Dc?+*|ai5IpCRejFgjy z1^1xSy+h7oy|`7_ItIwTAZ}E4ms71cRrCUSpBoUL)pM1{>5G$o>PK|0 zCO6ME3Qn#e(B)bAtPp5{uWEr*+qUAwU#)UkSxgG4J}GeS7br&sRXdQDJ^hF>UXbRO z(lXYj%|3z{TR+h+A{+)So&?mU5x%S7?N`v0pdO@)BF8D5#WS`-D!k@yF5RCpmQW2- zbeMI9Bqjb646Tqrl!I#C8daT&uc$`Y4l2scO*$Bdk;K>=G{acM<4$6>+qAv1q)DiC zdG!QgJ#7v|&++i>rIu@p5bjl+l~0Too^R#c-`)9cJWP76QdqXpP*htyv-A2AGn)^U zU~T)vkPPrD*XQY$uysGlxHE_@&BzT9hUdWmrJK&Z z;WdgHP4a~+F}bZ<$0XQ9biKOg3$B1dF8iUSElZb`zrr4z$hL@r5>b9+8RfS3xPBh= zQM8+U2>z1qo)br?pDkpRB!sov%4^0ibr#gJsN>q0Rt76!)@~M!${F}EhQMa5;hWO~ zngmH40%77wgCu#88FHc$?Q*`%5AECUcVxymksT_nu3Q6Ga!+u+ApTqt5}J;QX1DN7O#<^4jQ(cAAOI%4?IUH=X=yd%(@XA6_bf(PyC=gJ1B&3u1{#4jv< z9elD=Ws918hS$8m9ZkR4L$P9k(+VG{mh%k${JU{4uh7I>AMDor-3A}8HX&ekNPBH8 zu0X(*+<5R|_CZSa@d)f?^9WcF%2IX7rp2yrc>$py#+){!Jck9wb#t@2TknMl)G^a! z_at4*Rtmh1=?SHve|m=vT98q^T*2$Fg`pBl+1oyc^C|dxHs=|pSNVAi6@?Y)jG%W~ z9W(jiDfTPDr=Q@2&VC9V>)Y(4d%+mm(REw3D97O4eA63oc%FG;f`o7M5xVu{X;WUK zVK!47?jZ3nkz);UnmHfQ+<(Pih~-|NC^>#i|A>VdWHmZ)r7XjrPe0n z-#>LW861p#?Q2(yVqC zF%@IsxqQYf(G8I~VG5X^wDPP!0@a>ZJU9NjLAGs)g6qR7VxC_8Li&9OUoYcGzpDxSslf1y$ed87w2q_aU%M1;< zN8eZ2t{BNV*Ct^^;HGF~t|sr*_Pof_n{$d6_%X5)?(R?u=(}*YTDrpCA0%1iscb+s%N^&B-^c2WGF%RwBnh2Mof* z_M!e8E5sCP{v?c+hZ{9-Rv&5mZw){2h8>t7Ww1&mloYwIaMbQ zCHTz628|UCbV(t_2)tV=Un-d{?>8FrhdN;-MIi@`%m7pRwwjfk|o;-5u!&*_4_v9mt&$VJ=ur5PGrpg9r8ST)&Cj~bX zj(5&WcO-z)yoi|I=T}csTuo=H+|LA7x`<@^&#^&k=*Zl5-`P(s$e(HGU3yU-27`1cR!*F3xZe_BC?jtzO=gZeVz?r&ce{#Xv?8WCytT1Y zH~@Q}nANdzkxh5DVC~&@b_I>PVzM`qCxec*{TIJEimfF$G#%RK2<{(2DPfy${@MOsC^a2vpTFYl_@K&0&fyts9BkE4(vv4ln%- zx5P@s1K#X`Fo#0dR`BKz;{{D(_xwLs?u7ktM8T+aeCHtFVm%RD)dJx(CV;tHKC$~W zn!MIrur(euTb5Fb;q-Y=)Qyd#DqWNVI;tHzP>EV2YhTjT_EnH(Ov-H0DI``ZwskID z(9z*e`R0A@4u(-G3DVG(VqB(@`RERuf|U`UFlS9zzSCR-F6C zpruU|4i4V(FjC^7(P3ncT>gYUVkyCPXMSQVn-4)FZFC6U+E+OlEl*Z6 zNr~>xIX)qB5=_%GqpJiRyo^t0f|Iq=II!Qlyw!S}x3=v0GK)D54nZg83QaszMC(;Y z1LpuA+()muLGeUy`B0uH+kt8D>8>hu-=#l7DbuxZxZru7upeZt&^M#q=%sRXw6c6r zb38%ms%3IfUFZBpNt(=#)l1A+C-oZ*kV(YyYK7NqK$L>oQ_6=RO{&?ngn(li?_m|4 zE;Rhx2DV7*x+kEH)XJ|@ zNg~Id46qT@mhMrtpv3a6Q=!K;b~4Gv_Wq<|gJWm=J$CF_EYUd?0W5nh(>ay2_&*n@ zsr|}F?Ts4CtVgXFtN)f70>{A`oA8#J8Sx*z@b@$_QFt&1do7_j^*6$QFKGkji1no8 zr>n)#rKX0BE$d{`hz-=E<^vSK9zAL#df@vR;9@y6zb~eXS^E$`ZCdp26FGCxXrlbN zkPR(AjW8TA7wtVi4TSVxrT1T-82qo%`#V4=!4US?mT&YzQ1GM5%Ld%~*F9th!e0*( z1cbj9BnJ>4B}gFrbs&L-~|Ly@Lz-XAG;X*sPF;?Dfm(0 z1q@Q~qrwXqq~J$|7cfY{j|wkfkb)l-Ucev)KPtR{Kni&@cmaVF@@Vk>wu>Q;3NK)g zLLL=fz#xS@D!hO}3VBp`0fQ9ssPF;?DdbV%1q@QiqrwZ=#gIpX7qE*Vj|T5=yBPAQ z@B(%*|)5H!VB2NkVl0Vu!|v&3NK(6Lmm}gz%GV7D!hPQ40$wo0lOITXz>2F ziy@B+FJKo#9u-~?0Q0Eu0(LRvQQ-ybV#uSy%K^YVD!d#3%%j4~0l+*Oyc__`qruAo z*u{`Xg_i?(YaSI|z%GV7D!d#3%%j2!*u{`Xg%_}kA&&|#7=U?Hcma1G0xZCPLN6fi zLx2VNlK>bf`{StuyfwfA{5c4~01NOZ0WiP<{7C=|umJxhz%GUW3-BiaF#leb>9+bH^e+u?>O+79_;V0|0T$p-0$_jz_>%w_U;+Ll00vlq{}OQi zLx2VNlK>cC0sbTa23UYU34q}ML;psA23UYU2LTvh0sbTa23UYU34r;xY2x=Q1S$aJ z->!*&5%z<>7yDgflMc><^akjL%`paMXE_6g{py8<+i4HQ5HfIN0k02Ki8*g^qR z0LWtx1yBJXzykbv6aeP2ivp+skUw1%zk4bGn*Zyf0BQgPc>n+WC@W9|Adlsj6{rG` z#{$d>lmWrXlU z-Rl8x{a-l-$^qp6>M>9cApcj8fr0?}zlsc01jzrDWS}HK{;wtjH39N}MHwgx5H9H7 zeZ&fs1<2pJti%eG1;}GvW(Dd3Fx2z!O9To7h^40|6IB36;%C$ z(t;T7eRGRJ^NW&qpoB|>{%CIW8LC)>)HVsy9#PbTvck0JfUN4amiv^Ls`n=bGsLf> z8`$v8K)_`?bCz;6+4xOZ*#q?zCAAE5ih7h;49#@d=vZa(&#u@54XJA|;fE32Sw@J7 zJBkA0!+ywG7R8Nln}EA%))9Wb`IrL8aG@!Q!;KUPOL!@;pJ;3IkH zA*S?-2wSyhDW<4DW#>(YH7n|#d!k4hQ`yeCgRySF&US)og057a5zUAcQpZB`d{j?N z4N^YFiijU~LOfz( zQ>QKe**gZaKT}B1YCymQk6F0w_q@=@$15(%l>beG-K7afmyqz z7E}5$I=3H6vYuWm!U30H;)s#x96}hUHk(_?&h?UIrJwGRP1eS20U3P##3X3S)w7Dr+RoP696qLV{O(whX0xmGji!Gv}$e zN{9)iIxytjEyFV&9A+lR9%kureX@qSHm|HOiEL_47$-#Btas}?SCjrae&5=0c-|EG z!yFQALm(+ZQM!jNSN0gPebmp)=VKqqR)<#n_-`n|1(a)+Z+nRL^yuVG8(H1 z$(S*{KvhQab`_&z{(R_X{UvvvmEpZtJSa?`F&22_o(iCEF@0ulquCFk&`Cm^8)1|# z8?C@Fo|nhQ{^iqxB2!&dIb#1ZEAfU^`s}BK!;lUZ*UO0Yj~XKU&fb$_B-C+886mEP zj11zgi^fb|BI<=L{VQ_}=T9<1tlP0-dOkQl2x3T2&|w;1&uG-F2{X)&*Gk5@S?j5B7gWaLfH zaHG^7>m1od0_M(Zbg0|;vjHM= zqo+o@0hryk>iE|Dl7&1Pq;}yx{5@5d(t>M6b}z}?#6hWXP&ykiok6^+;m;eW1=1)H zWD%KUrzB*&caw|Ex&enKWX`Vwao53yG9tNtU~XH^>tMU^YKV(Ce0Sq38lQbPt#dX^ zTY`6V^a|8(don^1NGFL2xa^RhT-(sg%TmeXn%IbXwnj~bzcWDG!=&6@@mS^z;q@?k z`Zmuxu10*19!gmq5pK6DMoD*VsqXL35hN)N`%c=xZAP?*KSKynf@@4;DIilOH0V7G z_Tf8M>jaY5;}`jDT*R>4Gd@!&c+T(g6Gtrk_szf^9=NO-y{@f4L9ZRV^LG_J?eZ~& zK1jEHEVjRyV5BWIWj%?lh*S3VG3CHqDcPuxnCJ|aD1_3ahMkd4nFl7oja3ApE*a8u zpirmm`_wuU>hON9FzCX}{mwYSSuoaE5*OeT`ux}3cjx&OjwPEPGQ+z+EmKTo-c436 zQSf;cac6x%ENMEe>QiK7rsiAi_uu)BjwwgFW4AIOQyeMW zTe_+{Hg_UJhU*ZjsB8VjYNt#r-Z!GJ^j8lw%o`V))P&f?8*tae7Cbf0794Zg2b$CQ z4&oEy+3&-gFZb5iPh;SrUwg8=$X1x+%;lYY78&{G8ii7U=(uEUWrdev4DrEEy;|Qz z>)5uQ6O%)7Ekf>pOr3W;mGA$@vt{oULiP&BIL97YA)CmaDG}N0kX4AxV~;382vL!l zEqjwaBdcWdyH5SS=Y0M+k9wWsotL|}>%On+^}MgUNfGcycT=^WL*M`HHP*#fv|=kR72e?{1p* zrgmNP#6QD+u*`Kl-IQ^bDX}2nqsUc#3lGmk+0e!>{xF|Sl$aDQIQ+Dq`%5^(x}uU( zY@xv1qV|#a+(O+M4}8qNc;~ng+ytU}K{>b9e+)k&3~C}h*0_LNhF^AD?#&&!!Lu9+ z^M3yEh_NR1Of~;`v*#CodDY6(n;Oe4oFzZ5VDmgKJWF*9=zdQtyYwXcm)sH0&7-G? z`bEbxZSaur+JLUPeebhO%iY7Q-$JE#554n~r|MI2gJR@~1m?^Y9b1n=S!0KBH(AAh zxj*W05u{QM8e1mLc~eDSJ#5)IBohRG5ZuZAv);tys0^Jf#Z9Z zJ|C|wt>f3}k_O@|wMx63sAApYE-aX;SQk7OoR-XrP&UokUnO{%{lS!PG4S$iR5a3f zn52V5=G|;^{gZp{ZJ1}$_r|_E_1>J<>+tksxUKg`=jZ;1)KbYhy0PLyuHEXsJvhD! zIgQ~Ct+H58Rki%Hva`=5RhcOS`VDFjOmSj}`+Wk8PI<GrkeRqjR^x zT@U>E3pdF{tyBBq56`Ogm7>C`^_14rl=>M}dab`DABy^FC&u017t;!6=nnb>FXk%u z+kbG&f*AW@nbU=M;d6_tJ=t!P5JA+_Uq(QgK&P#v%c+vX9{<+cid3?Fppt5oBGk;q*rt_ z)~MAmVO#6n^GEDonRYapcfY^5LUPiV{~_O-9Y2O$gnRbGUd4xxOp!rN-fASL61Z@t zkXVY5QxLe~Nn(riFx{-OvtuTCHgexq;6v?|Wt>2g7Y1x~f5dg+2><&lY|ytlvhMgA zFWNtx62w?cw{5FXd0fo>E>855em2{Rc?fsLPUGK z?nnJhesk1n{Q)Qc8U*(0aT<7V&E$T^`c=R(DmFtHqBcn4zU zctX9PfL4)HWJCMa&FwPj#Xf^v$~cGGdX&?8L1 z+X!DMCojT7gp(8TRSwAPhvKA&aXC(&TC!XLM&v`Q-y5q?VM0X^tj$vL$bXjgw=5On z5tNhkA7q~oeLTj;=Za5!hh5G=N;Ps?U2BWi@^R*#n-0Ut!`g+;%!|_o1Cm# z>y5?E2fGw?&9dJ*Ykh_ID)rffZ*+sn$yhuBO9#STG<+37QD3V)a$%S#j{LXY_P9X znvmoBcG;0YhW&m>3!N}s!86gFuEE^N!~%tCE{)I!99ktp35b|Pi-!>lZFrT@@+5D? zVYn#-UF4k(nz)trVE0u&@WSL*Wl^1F4$0JMi{U*AJCAu7P^@-GUL^#co*A4;$s4@# zq-_s-xh0*Q1@RUCWr;0zrzyDiN2mbD$rTJYNM7&;;fCGt^Pm4qTc z6_J=uwGdr81xoDt$13(>@(P0TB+29~*I=~Zg{AQ#GtcM-_`9mRp!}U>v*655`t|fq z`q6RCKI+bZ60?xZE;#+`LB+n0+Jvxtx9XQqaNJk)7sIPx{rH6WX_32xhVgS*ZpKrr z_lpyiy99LD8dFpVcJ`!#k59MT-eTek4Ln@u`8C_RE6PShO?ZFpsrQHA27!+gY<`9F zu)!^8tTs-}gtY%ywd-NVovG`xzi)D#SMQ|%ac1B4e^HjQdi={4-YvY6>aKZQtG}DI z{ad5p*4o4Uj?Bw@eS4wany@!#kqt$SUy@u`N)FomMkRi3c#IFWq>*1X+`AAyKk)l> zK%&~Q<~n|}W3BwnHKz`V@5MQXr*E>(f<{U4C)RXZHeSk1?wq*5EY53aW`DiO_~w1? zbyHhKVzXr1X}Do_)&o9${D4zCNH#;7W5l6qJw={I)eGzGFBk7GS*|AsUa8MA>z$^4 z5wcg)?vrdw#c1iWIlPUG{^j1B6vK)?e2>AXsaiFsM<^EJl_9ltqtUO|CA9^YQR~oc zX+bbsi>?(*<<{!1wC#+>%FB*4s*9DC8@z#0w=MIA>duYz9>k=>bGXIqZJ_X^f~v-J zN7$t)dw9PmDcpeG;zLrX=#ztx`Z#&K`J6XB+xj^a+gaIVa#xPA&mX@!8*ISTNSyvi-q2rebw|T6P4qe5b^l+S4-r|*6_anf ztrxLW!q_LMctVpLm#41h1O-!Y4A+%88{WYle4&y*7*`&zJk1?FJ7d3aI(!ax2!0jy zqgwD5`FGb>darp)@+&)sD`U1Z)>;2}K}#ug+X5vfJd&wi$L@H$+~wfy51C?wkLPbn zoqbz;v2!TRFavoK6UcI)+Mj>nR&nv`_U43iP0HFInV*9bA(vdo4vb&?rDJOrj@73= zR`m*HMhtGl@p~eMgIrbNriLOx@BQGHBzZI`2*8Y&IhydJvjG~tIDePi=R3}>tk>1huWvLRj1!&F%79xvJOl3 zn$|%b`4wX06GTi~6EpQxtLLheKA~lcvU-wo!G|vWTdoo>e^(4cutDLKQ-Z8~E(fGZgyy z#=~f(X<-~9A5q(#$lQU%Yu@}zrBjBC{7fG<4$C0RZ!7t&A@eeOsbQU!&msq}t7czQ z!4r?qVv4w~JJU1%IaPU4>6JZmBiy>%Fh(|5z_T4Y&5~R;_>cV=;SFb;7Qf# zeZi^rd?vii_^fZ}Wv(Wf7!-K&@R=nUvl$vPb10{4)1)3P$Ha+ei}J38K{FM`A?Dy- zx`9E>^*P!wBPU&D-sIO-%tIbd(E-g=z9}@GAOX6d$@!*DIuby$nI(6ebsvV|z{9sOt;u>f65^Ssf@oy}S zpZe1otC2ctGbTi)Rvr8lCzi$X&q zWf1}QzzjhH&t$=%dlQ6$ch#7{(cPh;LA)($3rL)!G2qdQ-{97;Hww~T{Cs+Ru{~@~ z;*z55TOjhX%(`E(kU@UR4-P-vm5pX#X;4b@q?RGyWY#w$X*3y8X`DT8f$sbuFnBY> z=xn?$Ihy?OGZwVw_9ic)vq)ceg#5@yAWfYgJe{3;S@dNlKJn2W!F&?g;1|nbov)!k zai5BEjJXdJU%Pf8-Vr-Y#$otui77NHmX@Lbqh{R2|2I{Dw@I=4z!i8b37yJ9?T{hI zjm8%Z$|vI)Qong$V!a8lu zb>K8^ky@}7tFh*@8)=$scJ267RklVQa@S^QpKRmgT3IOcMen_oq`x`fm%Z`|gVKTS zsd((()prZ`6i&>-b!sCj;ExDZBVs~d+bxi-`LR9e)%_m1L?hm0$z&VEx73g&&rq3K zw$Mzw=`UGS`ZQ-5|K9jdw_IBmQhLe;yo!M7sgyK_isxNT%aWSJ#5DV+{_B^-s z1T}3VzddQhjV9`VyrP^de`36pZwDwpqEXR8O zWN9EfmE!ZOx13g_BYVtdltmk#k_N*zorhe>@~jN)9p>UJEsf=`ITj7PF>ZjLhF3#4 zvIfX7d7sYcTJ;@!AdCzxD9=UMTB^A<>jUcgOV(Xw>~bv|rfe6rT1dK_3A>G7dhvD& zg}-7a@+Bb88xcu{j)uWsIS5h{2z|H5xaIq9ky!rRrdTbXRJ5vtL zDld5+iazcaXBIK$x?kTF z#rPB_sH5KTP%0=!4GqVq z(Rl|#qTg!7N6k=$0#>B|GyGMZgJvKW?O$a`4G`pQE`U$dr^L?U_ ze^0sig>CB7sShuI64{*%(~cQyB5*@BGB}irM4s%oWTki%HuVxSj|n7)ZYYLEl<3^U znh%b}xjYLFzM*I9NBi_L&owSF?kcaP#`+a+fyHKpw=I5!MGutV(FD{4a8@cJg65R+ z7FB{W!jG%&hGEoJ?eqT0&A2p|UJh2edBgdCNLJ;_D@GrfhmwUXryN~iM#avCSyX09 z>L#76n@ZrOhEZZm=_o&;!&12yK&*IJ_=A`?QnhO18^0OxCI6SOZ`rGTl|f9C*JDV( z4UObj$kn~aEuY_xf{R?J$;>{7Yqo-`ezA$^B~h0!OD{7+gIZnrhopEU7`%s_Ba(it z{6)=g=tb!7=vZECtwyvu{kF83VeEP=s%~EYV@q}de^Bpr_tBh`s_Pr&gLi^dg45F* z)LJ7VDqNC1!WdjF_2I|N{Q(S^wzka}>-6Msx!)M~a6~qqW5I*277cFZHAhUhpSHrE zS=SN|k>HXmYZF?yzHizM+cwRSj|?X!_W2Mbo6@`9Ki zvRC9DIkXXbV9Q42f4p+b&*8_3Agh!Rj;n%VgH45LSisdVQZlzWDs6ePgewuR36I?t z-gK5H#mafDS>VCp8!xWqxLJ#Rf!n;oxt?#V{b2uCS5LSzf^Khp`)H!MYWY*s*o3EA zdvLBU1J+c;TUX0Q2d|H9SMu&<=RT{Qro5Cnd+WkSGx;dz-~vZhim)^O(Zudq(F?yl zrJJ%rqOqQ%9{L)dA{4&K1UNbhn;JLxzOq5&Yc4S@7#~Iv*i)ie$N#@T6Z!ug+W70Z z$q`TQaPnb_iXa9?MZ}q)|1#EpECuvm#QKk=fQpL!V=18Ma8-l_DvC-oAwZzQOi>_E zQJokI6rHPz1A&UeKqmE{R22wRs0srD9fS!1_5YdbKb8UtQtkhbBSCftMQ5rYx`U!K zRgm04(U~d;?x5&Q736kMbfyYoJ19C+1*shrovDJ%4vNZD|FRTN^qzDevV)>CRgl<0 z(U~d;?4amO736hLbfya8Iw(3*1!)}=ov9+TI&`KAqI@ViQbn>9P&Cd0qI@ViPz6yw z6rHDnC?ATBQ$dsuMW?AC%7>!ER1oDu(OD{p@}cM`6-4<^RFbNXWGSHNAQeRUP;`z8 zqI@ViMg>tm6rG}iC?ARrQ9+wQ(HSb}Gmt?3?>`ho`C$7mlmceZSPPP+fTHtL&~Q+6 zdk0c{6EV=bWVU}&rbbRA3>j{1KB zZ3jbREuigSXsiXa9Sn`NfVP97u@=yFFf`Tz+75=sT0q;u&{zv-I~W>k0bK_ZfudLf z&~`91)&klNhQ?Yz+riLS3urqS8fyV<2SZ~mpzUC2tOc|k42`vbwu7Ou7SMGt@VoFI zmI8*xT0q;u&{zv-I~W>k0c{5ZzYG7PCx96=)&klNhQ?Yz+riLS3zDS(Px$;_p)lw> zm?)YhL9!Gu^ze&hDPZUU7|Bw=&_ghirGTLaVI)fdLl48kp#5Ozff&hBz|cc6lBIy5 z2IGG$1?+#r@jsRV_MhPx^dRg%<1uJL*nb9O(1o!7jL4u3VgDJDK_9~YGbV#Zg#Bkw z2Av2KhoeprNR|SI8khgF6fpF-jASWb=z&=nbR!HsG9y_E7|V<}+h@mUxQ&@l7>Eex6xh901WL07^g#3G%IIKhjn*4c>LUKDZt4p?vv z&J&_01!FP_y#PNE!p-p-FFfUu_KXTy$K0uYZ(Z=K(nDWwHmZ$zpJyW}`msh%AUs^FJijt&TCCa3PP#I`y4=Qe6~qReSA9YPN( zCl{PL?;Y9ZUXf~7)5Vjvj}o-$r7~&P>=ItN#p6$;ETQj3QkD?T(q`4t72C)_wF5LXMn{;b~&v&B!cjhnnR~AxKiz z-&g*XOj?Ir=*?atd+=Ie0e`+_8Pg%bw`=;e{uK*u&%-~abH`L#=guAQQkT~0vvMF_ z*=obGpJX4?aS($17#B{ppNB?wB#f&_lceV)rXZrxR{3`Cxiwu& z49Tuhs&KPZhL!we-ZQ$aWu}@JgPInm;e*<cZ}E0g)STh&y14l9!Zqf>AzSVaa_?ou9=Y%Yt7}J8?DN|qx&i(+qxbs%pS=*GiquTJYq4)%>ot2c%zL9VxIFr5p^?o_qKH1)HZe5RB z_w~5@Pu<0(pY8W7+Ki5Nzui56Vm9m)!H+Q*(_hQHSD2FReE(H*lDx2Y9BVIz zSpGP5IjQ|qEw1n+&+oNXmXcp}GS3gK+dZN(7YTQY0xp-dq2|e|uN|2TzE+u-TV%`7 zY=Uz#MJy@xK-ne5R&r(*^l|(E7k54>#Te(i)5*J(Uv94pI_BGGo;W|=Z{6qTT3HIj z=Y=0m_0(hpl{$z8ri;8iY1n2kvuu5Q`B^UWkD+BEJ)^SkfcSaEcRc94OkX1F_7!hE z)9HB$!BV`B#*gP`NS-o^JILTfs#`?n9Spi{3YkHj&fAxssf7~%*gxMpF4v=0-2Kzt zY2W32lgnHxV~m@=)HXnVMLqEQ@Z>pfrU5P7GbCIh@cVBKvjVISBU6>;o>iu1f5r|T z$ygfH{S+e}rGLpPWtOI5uQIAtOhUoF!O#+UVzId7u0W{Q5crE0<7ln6JaSuV99az?yIHey(=_2vZ69T!%BEqDpPJ(*xr7{qG2B3|zf3aJ`}A9B z*3ERnt$jx9=!?}+@{y^X3>=G*uROD5er7ivJt5`k76o?4nGqgYffy}N6V)bPkVe$SDhhI{7EmX2_)=D0oeY!a`|5L6cY6KmVQPq0(C&5Y=JT$QMN!CkSJTA3`mqMPzEk~P_{ss zun-)5)d%Xp$Ec$P>VQPq0(C&5Y=JT$QMN!CkSJTA3`mqMPzEH*7AOPqpDj3mbwM4t z`a<~vbwHvH7pMagWed~+iLwRCfJE5>Wk8~AfifUbwm=z>C|jUR7%qgq1O#>9W7OdS zb>J!xWed~+iLwRCfJE5>Wk8~AfifUbwm=z>C|jTm$iKGWNIn_V0gdtn>VQNYE>H&~ z$`+^tSEDFfpbSWqEl>s|$`&XC5@idN0g18&%E0UheF+HafJ7ZGPzNN+7N`RfWeb!6 ziLwRCz*RBI7AOM}Web!6iLwRCfJEAY|J}hJ)B%n11?qrA9WGD@B+3@30}^EmlmUsd z1KtVYlmUsdB>`qfK%;ztIv`Pp3)BILvIXjZMA-smK%#7cG9Xd5KpBuI zTc8X`lr2yOW(mL+{NEP-pblu1FHi?0$`+^t5@ie20g18&%78@K0%bs=Y=JT$QMN!C zkSJR)F#ZCK@&)Pu`HebUpbkisEl>v}$`&XC5@icn2Q?6m0#CIP{S}L3!Po2v> z8B<#7OdTWp%k8HWPp=R@UeAXM>ZyGt@K1Wh>0l?W99kOPdSAJTH`k6-!1@WxGcA@Y zw>-GXgm5%f2&0#kudK4yg$HV@|6%se(4)X0qe@|TF`_WUMjxNrWGGTdM4wo#mJ+j6 zk9iSzr%>@qjx)wpa?Ca1F#H5LoD|N2>KS~>7cov>pUK9tMl^+o(do&*gp=KHRI`Sc zLW7rCO`eBHR`V{uf5tmJDX35>(yr&L+fMhPLozP!WMV}ai)U3>W9%`r5>cYBkWFeY z)<&)PFZs`)aJWTb;yqHZR`L#gzA-ZejeY zG?;O#VV?5{6qCxloP7E9SjT+Cd~SB2{qa<$aYoyGQI^pona11~adk^@Ew>MM%?u$v zoE+;SMY^L}Q+|UIk6gm30=aSX_34Q2Y(Pf(hhDx^;`_BkIWVUjkotOKdH$E}0MB#5 zIOWD0wzW02mD0>wg}-G zx*i9)8D6~*uKcAQ=IuGoN?dqQ-AIMoGvR+=7|zEuHPdTCVS2EBU^oU>c<~}o^26wU zeFw438O@pov;O=pKI9;aHuAK-+Mn|#W1FExKu1q_;V;v7gQxxxHRsdW3z8=f4~e{Y z4PE}EWJC*7l@gdKeNw|&iZEdbS3Laq=*@Uyaoh3Tq{N=6Ke4eJ`lDW+5U$yp=?4$b zf_$W9p_0DJ9r<5$A)ivJ;FWVJ(LH`cd-$sNYu|M<6RI4E545jSm*tWebEilpLT)Ap z<&8vti|o7j4oguu_(j?=eO!>%-TdX0X+ko%c6F(~{Z@FoNG+Eb*Ar7VvE9)XKgg$7 z{n;2cAD&$@ha1M_SDbv}HqzL>%6-Je-HXLN# zJ!zN<7kw?0r6nyXnGw|`%qz%MqN+hDnI_ljQa5e-X7Bx#f{# z1^wyR2Ynmzo}Q(7LQ^P$?j3CA?w)>O*NR!$sx6o~_ zA9Uq1y4PYDu9Y;y*GKh32A9R@WOQj;CQQW*bKUXsDXAl#7wZVSO3<`6>0pbdX5ZF* zLEMJnAh~3Am*pCKg1~^%)9ahrBVM6^wQvHWn-8p=6IVTBIcGT+w}pJGR&Ed8 zxFT^le;s4!Ur+pddO8-ksQ9~QGQxz4leAVRR3HfhG5B1B5(k|8M4`2ACJ^0CuuLbxJ**OAS2-^xE z|4!q*Dg=0I0d9I72g$BdVF`onk-;2Z9!pqE9Ko6*LWRhBEr8rd84#^pwZpFkUK0G> z=owfPN9-*K2_gzB1Q`FWJ=Bg>2t59KKRFS?oLL30)}&G(`B(Tz5?NTt5h3}I3)4AP*6 z`SJi)LF@ou7R)?~6mF&hX?u}T1-FkM&ko3<=WYG>P80oi#%U48>NIpI9M1{HrsW^E z`jkHXs+Phjau<$h_B;xInB5w8_x#fZHf`@#izhpTI_Q3ep>s>#!%ahWLq;RwAbaSR z0C|mhP{pl>wU${2N)jY8`Quf~Tb{3ncZXk@;bcU<%~JLpO3jl&Tb|W&#uo8U##t5v!$@f8;)^$r~Q5+ zz>!~e`McFAud72%)!*plkcUUx7Poxk#biwpZ=Lv<5Nto1H2TOe*4JE)3@1~Sa4mBL zhUaBJ8Uin=v7X;zCm#2wr3z?)$GwCZ3Xl0p$avNbN%q1wh37^r_P@{ig~t}?;4PB) z>L2~;n~h=NR=n3-riP!QH5piuRL62>kBI7|CA^wxyVq_mn6WR11_vfvw^{o0Iq@cK z<2{z-pCM2-?T6?042MaJhNLE*VyQXW%^266v%mc9dP)$eCnoi3Raw}}cW?gsesO}~ z%THDuZ+4!#!E5h0dax)fs+X$AFqi##WPJWpV?0agPM%k=^&KaxJyRQkW{B^Kgt^pm zk+sF}#WJzFRrFk<#O?{Z$Nh)VpH!vrH~aid`iQDKLRO!O6~NxO5;hHy2i(x-H{rw< zJ|8-?n7kN0YH%Zm7LnWTcoUnaDm-VrCCU z43VvO@UIBt+wkhMuaU;_ndIJe2)oq~=C-`ZkJagAc1ZXt*b+y${uaNSAC1^JXT7Q3 z4F|=nhkF&laF+;$0!QhWZ!bq@!`cRfR-eiWrk8|ELJqA5&2IGl992K^RWG(-Jnh%~ zasJdd-7UWNXKTC0bLOk9X%X9Zj<-)SXx_CNB!5WdR9j?XVfY< zdOUypswF&iHmr!A{d`l)#QF>_eto?FH|Bxv5z}Dpv#&Kg^SssXsWA6Hg)@J#Q}GYO zjeM-h?DJZz4t{QKIBu|TZ75#+&&AzPs>|CjFKlafhR?yTGySlv3E{&meRlBI5Q5GW`^~k-#-C#Op*CC>eXFJ|02#?G}Gr z@f2N=Lux{A#-;d~QBKq4M(zpx&PpQ8ji&YT+OMA^`sHv*XNtYbjshyp^`o~P;I66n zT=_Cr^e7~`f_gfyJybTIKTb22mHX9j=wlyfG5&LYEnL9x>lH&G!^q9tdta%RCt|hs zCN$skl6DM^a}$*_#R^wVCG=n6$YL5Wx0Nv%bO<_{*XH8bl<-}5qlycUxSUicO^N)Q!vcj| z0~7f-Lq#eun-lpr9R&)xS|svsvI!J&i9+PxR1zrUl9kB6c_L8ADJYPCC(_6dk^ktw z^*$C^S%RB7?yk1A7X*U2*niK8wXz>XUSc7ZsRgNPW3&b1FcFvZf?c&`G=h3qe@`m4 z0|tUP*obSa;0pwp1$QwK5*&h*wL+|dc-V+kZt$)qhoB}F;)G9-sa;V|5k~RUx_?UPzh4xj2p;*2MXLpzDFR) z56;=b@$qc%He;xfg3Q{e9{`EGmF z{mf4LZpSupzD|0$={{QGXD`7MZK=1_7B-*cW83w%F7o@%1IN+Ym0dm(75Dug+J+H_ z!|$afV0d>tQwbi!9^O$gQ!6$~!06KIuEl8MjVM`HA9hh3TMjCfF8U}oljlm6nDrUlvByOD!t{M+bl+Ib z+PRfo+2Q+Ni#*>7GdOpwV-|zURO9e2gv9JyEB9NN!O@9QMH2gv^$#Ds+QTOnT*@yd zSFIs!sgVqhgikJ?_fiyTO}bk|i>c^j4kvy{|LSv8I{8r(p?hr)+8S1|$N$1)4suUe zuthr!c3MWE!DQX_QK$YX#6>00T(>l{>v=)$(>=J($85SZUHCU{)$d6p@z0GpD(DR$ zqW6n-?RCACt3!&PX=1Pu@_bg*yyGjiy|y>(Du87DT zSrU)4#|b14eRG#~9*r8Fj1wI!mU9g7&g+-NUNs8s4=Rp}wElX{)r3H6;PYB=56|-5 z+b=>E;n?K-O5Q8x?NW;3f8@;^6fcaPJi1@pweiLNmUmHGimY%6^P5K(o&z*0j_&w0 zt_>Nh7S2Yvu{iCFL=aBpp1NvpH_^U51HHEo&3RsB&~aA3sbuKQjY{jDFUeQ7YKpP1 zfKHvwcyHR#-VuNQo3Pic57CBob!8H_?xQ%-1}(gnUY}Jdk%^7LYWkUjrLl3pfw-T% zyI?K9q=)`l@7thqFS$NO=S7dZb@j;;IQ}KGn%=I$m#)f)27dP{!{4+SuacfnY+4x; z;l8Z*OU(Rr~=ZXg}_d`U0slwghK>5b|4k;nU zTVCbYY~JU^ISic}M9cA&`qi8MU`x;F6pud)oqtoPKG{!UT8Q!e8uaygCHp+g?$(B) znC-7-0|FwE1kdu@jQ%pl1~^(zFE-S^-MF7rRR%BnvARhQ%ekA%4f%l(kP~#8&s1+d zxl|sW9($1W{Ju?*Y(kITLPA$q`;XlZt$V+jYi)Q7#Eqi3ygub(o=!U*F7&fIi`F|73-RPz!*QC%XuXM<&tqD9iI8RFL^kJ&N}TsZbA;oD=>$J@FRh0_sm{V) zwixS4?7`lxy8Q^HfO_)-FY#~15pJ(c7Is=aaL;IWa#COaJ97YNaZpTO;o=ybDNGd8@V z;B;$ZSa{93pe!1Hi)?U}+)N#zwxHyP)omS15|V^TJ$i-e$eHbWT2^&#J-f0jschlL z?D2wqb0yyAMZ%*_FS43fgc+X;GLSJO+Tw>2@y2)9d|Sq#od1xN>LQAd823`Vr+y?0 z$N&D*Q2}OyZ*f0o@042gRu4 zuuI|NS*T<+P|HoAuE+@;m}w4<@-^nmgbUALT*n47lUZ&rL+k=u z(p7>d`Te#Nd_1uju^NLU@-QfYxne7g#b7K$wBI{vZfbdDNjw)HEE=810(_sYQ7u+o ze28jM)w<2Mpx;|UN1o(4(;96h!kcxgBAc(Zy?K~k)a*uBYR4=5u2o^5kXJ$XYwp80 zhNevQZfP5Pan9l7^!PWKC%kfOk&w6ly*nSKts|tb7lEH!a%(t}| zjV#o6d#r|SD;nzB$drVaQ<%)%*qAB@heNLSl_(rLt9D`rVfLSH*D?3Z+DTte(vH+p zCeZgf+S#nSB$QS4DNX7SujXCRUP%Q=$9kymRP&K>Wee8W*}GyIn3z) zRxdey9iEB5{p+)2S;p~Jl~45((PJGM<|Mhk*kThIS(>;Yzdx&B%d|V%C6H2nIQyWz zPMskneRTNPZfupA$AYx`yJeH^1sjQ*Z)cG$75_O7E*s`#b5#1?3ps|c@v|y5XT}@X zj}hBTlEX)TV$;YjNamIpgPxE$wI0-+OK$~$)SGjq&ih)?5s$$c2Cs|krISbI*hZ>I z@#X?r>S@ zcdAlLOT$s_^&#m&oO_in4C_mXllwu6JX2o|e+);hF;b|}WEa0%Wfbzg(gJ5KbQPSb zEcsKQPjK{-fU^5(ZYyzR7hjjhy2hKCFC10l98VAlzKx&kdPt^gujvIkN)%+vO}Sir z_ONDUx-B9%0G;w23dOd*5nI;KB(=0>H%nMadvGN2bt5eP3HSS$0OJdtZA3qbVS`ob zi`B(}P93#O?%C9*s&5AKgrFPnFCW5Vt_Dcq-_~s)U-{M5d@HGLQTNHkf^A@cYzcw> zk)j;Um5)j6;&@ofhfQ~1M^m|fyGsXsH(JvfnL8dH?mbwk+YmGXNR4E(<9^oB_NAR=XzrSnM z7hNX|r=0Y;N0-@bX(z5uyF2~DN7so;J#;diEg(&7B4%98u*m*nXGP+0*VZ==Xz?wH zrP0T-*;W^2^dZrgFWXzbl2)I``D9`KT0cKjrx37EKr&@F(l=kR7B?yh3S(Z6AOD65U3Q33k@jATat7G2V_F;IJ z+Kh0I;5+M|YvSbQ_>E=hUB}J_VvnZdJ1mS;4}=QoT^1Ag?uO?2^0;Syfiv`_%Gc{g z=kD}oXQXMJc|440tUY2ajhZuEEL*IF6?8=s_ueu1r2OzX3vHMwnV&-S)5bbi71KL$ zBjQsuv^LEuob69zw`~-MMm7^~td1tSSrZ<-{Q8mT20gbr;aa@QqpUg%mtAsdSm&!z&+NIlDGsU5FZJ}6Pufwg$I>S~b$)tz_Q|stB z9W&=8Wa-O=YdiGti}BY-By4JQX}Bk9Q@hI&F7|!fxx`py_&Yd0r7zjk!!=@C8O*Z- zWHU0gryZ5X6D=ZPa`Zo*DMv-SC>-ICk8ymdKM59>OC|33mQ)uv@cd`=@m8kdLZ8dQ zTV})Z9658%@H?@6s-r~7qZQd&*xiK7vU{8PiN^s`0s1MvM?T`2*(3RHQhQ_JfiWpt zlcfxm2Y%IZ7w_na-+$qCc7+>#C%&m2eEM_fX`EN%AVqSO5d(3e_`<`t4GH^uDNkEJ zE1GoRsXco9(co79zN`xw<2_B9Dc1E5D(aoTlz`4E4%CQUerxHGlW zAU$oE@QoLtC4`gBee|7GuXyuBn8$O`vSh_W>mz8@OQ>UYM6bo8+%y4ZxH}EW^`l)X z$J^Cv+5^vCaNoYF_xXcW@nxo?>zfxfX=4kYc;pCFNmLSqxUZx-zhok?l@Ly_Q2#0X zo%O?ETCxId1n+kapF5(pkG(&AhpjddrwJ^!a(`ik#7)^r*s8ReLEnnoc`-9(%&mru zNcog`-re+1-Xu0^JTQHbpCSdXE*X3HVbbaPkz8rxphy{Gkm-p(Q;^2BKsjcu*nzTE z?t_jvYEs_PK<=I@zku0i^F6fO4L!9x7XwaPO4IMZ(Nw(2%(lU})-zW!S&$jSm(*^r zZ|N*<`KdBp{9wbbbe?r(?r6U8tW&jmWh)jx0QSz|VEH~VO_=}j?E)PV_@r7=;a$rV z+ZyAQv$%N3$Nima+aBhzFPbbzg@*Iv@J6S(ij?j00vqo%@6r~NG0Iw`)esyL1l;6O zt$m-{o_?p~M%cn`wZcffd@< z9t^h(R^G!F-+OgoaCOV6CksBgj*VFQ6>WJvdhSi@vARBSTcHbeoCo}i)r0F}mf4bw z2A#JLO4H<|==VgUI?1Mxmt9J(7b*^g$F^mgowRt<3ulS!k`ERw~oFniE z-?X^%2_lstAN;m~ypbg8Tl!F{Z?>eAl`% z%-dv0{J@tq_&wfBTH`CN48eOCxML^VyGi%ln>cXF+~mDOu^v1!ruyiEHKMw{ohLtR zoV$TxR&Q^DdEW(-&In`5FnDkKialx0R_l|8^T*fb=|2(NEN!|MB=U*Ae!{zH!dsqp z{EDUohA7{aFJ?GCIgCrLnCtNIWjeTitZ)gey?mAKNt!Lm;CVP(S$+G(kfl`qIT2ru zcrKx7%*QNIJ zUS>%5?9DOnpM*Xme2D3#em=oKj{B+~D6_UoSmNFncxzN!I}R<~cl5}IpWJ2|Ol|Ry zHl7iPR3~_qnlv8$US8O*^LiLnMA)yl6_yvh&U*Vj?e*G50&{Hn*ttIjt9*X<>$tp3 zvc%;c#>sizQ?F|)_9L{|qrRkTL(8aSsEKC4yZB7!X(PNVeK20SX-9Yeqf5hR#FK%> z&27B9J=aypeNQ)zG=G!8&*7iQ86Fycd?ih`Ai2r;ioT7Dkz=p+W)pMr*TTYB^4lJ{ z*q1M z>`lua+B?m7ulW3H@!4^9&x8IuUwq*=dcK@iD@Qw#I!7~4bV=6-?vcNf^Cu(sJWgkF z_H7=nJv+a&m5s`;RMC*V1}E0OWTAA)gM4@3q7~m-F1_`!GxvO4Z*HLLo%N(U7j2oR zdxLbb?4yBiPWz9_^Y7Kyt|K7oGP(1IE+sf{Q+;i&U%5}`A|pqKHCC)lhX*+hbKNTf za{^U~A50tPS?J|iVhPV&5iX*B##1H_a*FSlSCXu%)cgp;tkaQar~BU~RvqF)Ula}o)YHdidmN7Uccfka z)9+>!NWD_-Gm}#&+c(uH5xKZsHhs8e&Zs?S%eeUXi~pI?MdqJ#Tj}J(pGt>9F4~p} zzgj06vm$*CPG)%EU&nu@n(GwS!=on)Me_Pp;q1Fi2 zKAm`V8J7;_=rx$o5MJdU7wTk5P~e%5B9d(yxZ+Rn)YNRkx7lRePx@$y*>3b zRr%xV)g)yTJe$~OhLzzMFtb)%9dEjqOO?cmn2Jw(DIbR1^US!Le&SiLH?#Wva#jwjr<%2hqg6Itcv7H3>k-!$-90NEBNuZFxI|1>WCYi}Y7R_WP33Ac z+BFs*nuhi+LRs69gs)l@5?${+p%1$J2Ur_NG81ixZHd%OnQ_`AYZBq#yhf6Vr<+Yg zw6#-x{q|ia@npJVg`wQ5lb%hz!<1t)v?qpNxri|*L{x%Sd|F@XkJg*bmlu_Zq<&gF zrt2PdjHLe>sCi@zRkoR4QWX_Ers!7 z?McQk%As6G1_53qURsWJnAWp7G+*wo(&%VFYJ=$?WMBPe1d$-T_`E6|cCCGR3C886 ziW$o69wxV1c%#+sI+8mn)5OW>6It%P9-cZMV3l7$0{)cga)o2JBA_FVV5Hvytmf|63fDHMa z(D)egJE7sRzuyT3-~IhgC~yo=V37Y{V_<0<4*3r?1{TL5|Aoeo5)HK>4gCihLpu5o zF^07CA7BjW2~7?o(P;>p97ghUkbmUxUvL(QPD9Y-Fp{2wpvhq*It@XS!$@`xf+mNN z=o|!14uc~GBnkyYf^!fwIgI4yAZT(J95gu4sDp*1<{)Tt7zxcm(Bv?ZnS-FoVI(pK zL6gHsVh(~PhmpV>1WgVj(P;>p90tb?NMxAt51d7!(-1T{j6|m)XmS{dPD9Y-FcO`H zfB@wG;Xfog4MCH`$P@#DCWn#eGz3i!BhhIHnj97dTNDG0I$TI}8iFQ=k?1r8O%5Z` zX$YDeMxxUYG&zh!ry*!^7@503(Bv>Oc!8kFVPx_GL1r}n56&X<6$qLfMkY@XG&zh! zry*!^7>Q0p(Bv=@ora*vVI(>YL6gHsbQ*#thmpY%1WgW$gDr}IM*RvR(P;>p97dwk z5HvZAM5iHWau|tDL(t?f5}k&i$zfy+1woU;NOT&4CWn#eGz1X9|GTXciB5y(VgK(x z6^Twm(Bv=@ora*vVI(>YL6gHsbQ*#thmq(s1WgVj(P;>p97dwk5HvXq2L}#l)Chq@ zr~i+tD}jfy>*980-^rSNNtQ7)4592&gvh=nWRDUpMk)KgG?pw$T1d7cYegYTyi!@S zYf)JeTKMjrG|zm$_cw3O^UTaW#+`G|`Jewe2aPa?A$1y!Foz*^8jUcAA$1y!Foz*^ z8jTQ#A$1xW#qE6xsngIZ{u6;(z$_wVtw1km82{Y{YM~L%Fr-eS5y~*6PNNaVFr-eS z5yCK}PNNaNFr-d{o=pGV8B(XwB(gBx5`1t#Cg}yK(`bY%45`!TzeXKW{2_H3jWC5F zbs9}Z6o%AkG#ODCQm4^~fhSU@(TIr$)M@bjLnBt6NS#I_cAiL`MkAJg4{Kfky8oUe>7tM zA?q5*q+Lg(PNR_%0J5&ZeG=7LjhMT$HgYgr$bPfMa;fF~DAx=^~u7YR~m>)%c*k`EI|okS7&% zCbgPe&nKi_Ohv0*`r`Jv<^AMi)gI;rcjKQ`^z;>nEHgq`^eqm?*j+y>>V4(_)fIk+ zxc)0ML3^dRq;a{0<>$O}eB5%PZi(jHb2VP_wg~Ar5jeoXEBQnrj8#@DU96bvu$%(k zd&c)_Mx_Zu#eiEiWr%kK2R7#3xWvM-Nr5!=g>1u=dnTfHKk`SE-j5l-<-6aKCOgfS zRz}iXmx9lDlEWe@1%z0rma+4 zFYhN*v4P{MT{l#WckevIa5p>osAE!WJssY-Tj4w*UDc5#h2zX(Y6ta`U@2BX)83g& zyXOuG@6uujb6=O4Nu9izVi?6LnoK34BTTDxWnUnLZ6`ISZRgD=(P@U4k`IE5a$#KS zcV;N3M>}plF%)NADi2+La*4-Gm_sy`9xHQcUy6lfN;H?zjOf%s308BXnM;RFBv?=4 z%O#fgU(V1IHoBD7p*ty_PA`~wNSHw+dtb`>t(53zhN7%jlXZjxS-8(Eiq4o%>UL7= zTV(8$yC4%rapW$za5Ihm;O(Q!cNY6QsI89jhfzpeH-CFQba}sitaLKZ?o@hj6RI$Z zI-2GEnZ~=5qm~n9E}cs^5YaNoIAZ!~^m{Y%iCR5Wk=s#nnO)vg@v!@CU9TQ`Cp zhM&hes_(to`D);4vi98V&(&7P8pi*`T?9R+y3G_!Jxdt#dPBwv?wej)=~{ix@jRJh zwk`Lgw@3OBQMRK(@)e=Y>s>jAOFpfBrl-hIr?8o3a~Y*l8lyU*N+DICO8KdkG78Lr z!|OIuR{CC&sXgGE%XWs^ZIv}TD_Xfm7-hA26QdGY@Phb<}4%}&|yz;ZG@tPIbuqc z^39%zf`xG5W1pASHc#)VH&-JA;# zLAnN<5f}XW?|*o>q%Me&O!?wleqV#pfuZp7T)?kEb^ikPKMs#0lsW7pWR9NqQDc87 zb5~Ui@5G*2q?1*1|I~HkZZ`{GY|br-7t(ra{YMT6m{G*zcR#o3q1)ev8ND%f&Y}8| z)E+Uu%U8e6MZDd0;mq;M+%?LA$zg_1V=QmeDA>ap=k!+%RC?07Tdg^>pF6B(!Z`qJbK6)f1<ScC+)uPF2j7Z z{oV5MhbRV^+CO)=KkS$^{;j!rttD`34?O;wHTh#Y5_y1>EnLbaMAyX9p!yKXc8d6u+#pC;P2}2vyBE= z@!B=P`eRG$^yfUQREDyD#~63?v~R_BeoY9G(n!zi>~%jo^n2oPQ1VAS<=Ex7KmMU= zaLS{iH;JpOBG{0E0w9i!M0rt46eiBR0J0z>@VVFI4X+@T!qETgzLuG z4dT@s1p=Jl2P^@U6z?Gn9mM{CeCU1?EEkP3T2;BWGFJmdNq9G@#QnFbSs7gm3Zqqd z!E03iPQe0CPjSZ{f=>tYut2pk8%i06CD9ZB&-!m2wA=|SH68I~e>DN!HD7>szkWVg zLHJr#0%e)ZZg8JiPAv_&)IzjWU=gSxc!C!ELB1L(gF`ZhKI-hA@4 zhAtkgLUPQ3+k-*;a^Un}5Vst-JQ&0)2Ob#)ams5>C4!uJR;*dk<5QF&R&^N>&?l=SoFo-t}JwpuQi=#kn z0%VdW3Bdsj;)+AJ5QBK)5FEfDjyMDdFo+)x!2t~7hC^@wgLvT(9KawxI0OeU&;{R) zjUhOIL0oVM4qy-u9D)NF!~uuk00!~DAvl0R+;0dDU=Z&cf&&=D_lDpA264U7pr{_m zB-a~)0~o~fhTs4Oal9cofI<9j2o7Knw;O^37{u#_-~a~kxgj`!L0oPK4q(7j{>8=+ z9KayJ3j_x+2=D^I0Sp4XKyUzq051?6z#za21P3rg;DuPQ48Z{mg1bO)0E6Hzcz~(^ znY8C2IDkQb7YGhu5a0!Z0~iE&f#3iJ0bU?DfI)y42o7Kn+y#OI7zB5L-~a}T#KsUD zz#za21P3q(@B+aB3l4~O9&2N z5a0!Z0~iE&f#3iJ0bU?DfI)y42o7Kn;01yM7zB8M-~a}}T_8AsL2wsXSB+6anmRx- zE(QT!U|lr^0bU?DfI)y42o7Kn;01yM7zB8M-~a|ZWgBOJ-~a}}T_8As`G>oJrVbDs zz#za21P3q(@B+aB3*6nMeIGXt{O{b@gX>XCA0XTs2W}%?SD{$ z3}iB+53N3y%<4n4k0mqv(C%Z&>^?O7STe&8EkBmb@)C7OQXxAPdR$p#mYGYJ}h zEMokL-~bk}{zPy9i^~74z@i8@d=)sO$37|5j(t)N2%rL2K=3ZZghsp& z6k)MpuN?l1&4{UhG26w02OnzL^e38~i)1)l{6P_O@2sfKo_0{g{N&NX0fEi%SF*t> zRBnJu7{c2&@#)j2d%^d7UXJk{tNQO{okfPq%h3B)HNVmK)WY3dG-(rb3M0&uxGq;o zna8~Rc}P??_aLokYioCJt_!qJwABRG@(Z{k2FLNF~DjF+w z_YU>G+_ECx!{*BUFT67)u3_ZD`fW0+ysp1AKs(Lu&M6GyIeheaoYY;84?`YSab9t# z;r}{Z?}(r2PE;tO-Z`yD&tnjg9>qPQ=SN$w8&~FXwj-5uk;ORZ^0;Ue=Xx;ew|E!_ zRemf7UA`@zmtkCG>*q^}9Xpfx%xyy3VnoI0RK+SE4e(510kY;ImKAJC(*4QI5$a-J9QEb24vwV}QE*~0a&_yg9 zd)lRWE|)l>UUHih%P<)^Q1Z!8C-V(ix;Y%t*Ec#ShL?QNvomesP;W*Ij`!eoeWRmH z$GCK3tBrQXMekua?!GJ& zQ&h4a$DLrxEy4A0sYurP!B@PD!t26EqHCq<}LBtA7gSXG*D44&L{SJgIWB-BMC|?|m(+ysxS@rb-SI3v zux}bCxoAWv+Q&jKk+iX>W<2)r%foJII^p)f?kBi~;cKWbG8#W`3H2VCVy)T}8`Nui71<=Rw!4;)BA0e?ea}B?e%v1CW>*E zz2N1cGBaVX;%nCFB7D9US2`OvKX)a&xBiyf_|Sfqwb|Luy^m5G76Jzx73*sG9iEtf z3ELGS``$JB`JQUVwV~(sA>m;m@yxR<8lzip?(e)eA(icW?n-X+36FuXiz==sJU(hw zH*!=ze-uQpy{>}qs{19y8QzoNu*u^wD_mU`kVV_Dulo61P_0;AOZfZ1)~)FGwZ31g ztKTl@^xmziM?I~7Y4e-MeyJsdRy}f;kCOCGwVb4A-pF%t)~X*_O?@7o4=rwfGhnMC zEZZ=t`u*Iu={fU&t;H4lGq1Kwo<9$2+G=)n`|^$jp2yp**~@>J+F$afK7f7q z?kLP~(bJ~>xy&~YoU~uR2(UwC{`@#F-0P(zTt)xB=KJc!PyzfdOxB%^90wAr_c zWcR0U4|(?;R8@DPY;)7KqtXwh(s$r~?lx^hrGJh}---MAlu0v9+_DpGkK zS5?dkD_9FdAM0#=qd&Y!6ReupOE_=>#Rbx%{c$qVgo4K^Ow_=+->#q5@E171rWc%F zWVYKBf193-hVSwu^*i3c!cj`6s)SN=ou`GhsqZ4ce;CI9J>x&)-&J`{ndn# za+eVG*bvhfy%}TPArr)f!s6uSOwA)tq~A>GpOJA#;}~`wPSSZHif@0dHuJ6nJnEX_ z1xJ)qkGBh6UUllp5NuFNJszMe-tK>B<{dpJ?#SEgf{C0nGhXg$IR0G+l9F)FuT$88 zC;`OL1z-1Ws;m_AU^h-1>*}Gf6m!ko(3HwVepHCCyP*4mF7qzG@1i&3`B6WQ=)O4R z-Jw?PN_)Y1j|bl3kZF&SpZAKqygQeC`2kQn?f>)OXvXjhuGjpQmKsx9tfQm;Ym+ki zQK}gCE9SZe5z`wRAzMrHZ*xamHp4Ic+FaiVZ5VTI={Q&Aa63Rzkuck`Hx4iTOXAvR zVaID-LADBACmzec)o2}PZ|=QHxbUZLUY(9GTlKqiR?#PbN}>7h-T<`)Al(kim_Y|J z2qV-U*~eNN;f4YQ)V_yQmGH;HJ1$UP-Sf|EOH4X}C4g<&)e?ts8tg-~z; zwM5L$(FaU^MoU<}gc5~l0E8R}GM7=T;3YsC>00N@C~kTXzC+*uX7!az zm1GE2v8de;IN%}_`e2#CvY5Zf0TE^ZRchvSqEH#|Y&e5ROHFDQeCZRG{oI7R$tYGT zP|git1DV?Er?3;W#Fzht4Ztg4MK=Lr4d8dgsK8=xG4O`OU&`kiN`V3BwdA0{Nx+YZ z(h}0$vC@R0LhuxTV}OsUmh}dzkAVuSN|-D~U4yfU!pcyIC;p}=L17w<2DfKw0|~}6 z+f%fG1YPd!x!FL1j_>xQY#_l1Y|iDrktesImQx zinjq4Fqs*)rqjif4P^%Yt11!=gI|(tCNuaY$!0PG&y{>8Gn7byFz{N*W-^0MoNOjD za9GJ^GDD9VPd1eqI@GF27!3Vsva!t2ohF;h483Wx!OYN^CY#I*eQ8xB3WlyU*=%O$ zNpBBlCNV6?#xp}d8q8<@7X(2Ng={`E1X0KaG(#tvY(g^xQOHI#LlA{*Ml%Fa$c8i% z85XKY7z{xavN_EVM1g~vw}UYVqL2-0h9C;rq-F@Bkd11Fdz5TeGXzn{hBZSFNg*9OdMCg}myB89=05JVvx*9<`vvT@B2L?Ij33_%pKam_@A1=+l2 z2%?b9Yla{SGOyVZf+%F;njwfnHm(_hC}iWBA&5dYt{HxX$;LH95QR9dnT%mUHm@0e zr^)6uLl8w334IIQ ziW(C9LJ$Rvnftde1X0wG$QObrYDnMG4?u8%<$Rm?p3)MoRULwOn4T*Xoh@yrB zy%0oELtp!63e8dAOj*?dp}C!3us|*QCZI0{q)HD8 zjXR^V51r_$!aO{lc&p8yJ2ASXmqQ@dJ^85H+S|3TK*LWm798T|?Ovg?vz#axCx)JX zb>sD%&E&R_d2n4R34fkFNMna&up!sWxqOMEF3Hz)_WbaYtm)CT`;c|MOzGw7{?N%4 zb@e#D%4@1#of&welQ$A9ij{_Jbzi2xys*A=JT0zRO!kloyL`TpMcTWkZozvyJu$M& zuCjiVbQzM*clGYKD5wG*z zd^#Vq2T|nqQKD|L2J7xGh`OV0ao)~t_JfdY86o47YX%oPs2IGOnl`+nu+Z>`?2hA> zC87J1I3&dr2zr@ZGKSsCmtI~t@@S{+G`mXC4Z#SHwBCycZH(o$>|7~RGI-zQjPhPR zvyqU-g$>O&|L<8z*?{}i^o;+c6|X__J!nKu%4@26Md!kaOuoPNn4M1^e)j(ipvu`f8;%HihuvS%j?(;|wCT>{?asucbx zyyGcSw1du&@-S^Wdo+!lIZDv6LP^z#&-b;BhzY%+CM|Qh(XV!Sb`HPYPwZ|cWYE3g zfB5p|0X^MZhKe^{Vz;8?ZuX2*`6RxnWGyljuw>2PiOBuMBtzK1%iqcPRYA|SpW*y^ znSPyq@wo%8tW;E2H7~ysj@1-f2CAjPinQ1s`_XO$e4F;0LmQEe@QvcKn*Gl|Z`|=9tHPyZUGPyJ4JA%LC!nm&aC5TCo~> zx_!Pa9i3eF+C9kJ(d~q2tU~1Q{gTLYYT1dOrF;)A)gSxXOli1bAb2yZJBz|Ba}U1i zJ|DHV{vo}DNfGJ-&s@CxwDixp#xTM1w2>W@VM4WykD>>0dE!R+&D<3ufv>Gg@4A&c z^RN3BPPN~UyIs)CFVsGATJR{#NRar`{QVVc&Y3PTram;&lu@AU@nmi0$DsAWj^cpy z&X+w*izj^|oKp||z)~mFl{$C{_AkGDagp7@ccx7fulwe+Rjy2%g_mygd5f1J`$Kdwsf$5osz)*XM0?~#{$DtnowwnOTH z_aw3zJ_r-;5p&dc>Bilmns}+M z6JeU(;D=i*pOzw`!k7{lzQ!)!`KiXK`t^I{=C0~nu)1RbmQ<&`S@iIpEtS>|(Cmz&x@dljoDZDB%# zlja}tcL`VLPcWOjR*^9o&B~3H>^?5gWvr>!y`%YpXvOh?3r}WxN@OIv`lCv7gMvbAyY|L69?&$+XPkiouA%_js?zgki zTbkEiIS9PDcn)*NyAp%@6L_>~%z8)e)gK+~1+T3N9#8Pp&-YA*)^xE|Jp7e+ZO6}? zP5Hdo_Xk%KGu}shn_d5|b?s)ocJ|TRfg_vGxsrkdzkdf6WP#tCwfWh*`ZogQ7V(iE z6{qI!0n6-q1igoVR!H>2JFeqwmKc@ecw67g*_1t+HPuuz3_iWOL@=CsYm5)ky8m;k zHiX;xosO0rAyX0M8zQGy=c<{fiTn1p?&rDL`0$YkhE$Ff^_$MOu}fE)LPY|qpBCn>!gVO#d|<-TE?tn@OM0)Nx_`TV9@^F;l6 z@z<$ppT)ot#5DZOhAA}1+#H1IQ(F!nv5w*KRdkvv)xY5 z*O)IU&ujOM^?SH7?l>2V?U--nFjFc0vc}PJ*erqT*5t=!)qU2si#GVo1m+@MCu$_M&xpZ~A)Re-=G@(i-B23m!fS1jS~O1Cw4JHBDg; zN}{7Z?DBoSMzu=N-aYj4vpyGdhBR&Fsr19L8SI_r)J7vu1x{mWM8b;u_9khb{C+;6 z$S`eS{^F@D_rq8hjEL`>RDAE^(7+$7IEJZY{cJiPl^W68l2#O$6>8I|1Gpr0-|`*k ztQ52EzSr`%Y8Y&m*^*=!Bae(-w}=SMR#NBwQ9K=iEBG3^d-;mW;N1WA=k_T6E_aWj(khJ)hL3e@@gj*Afs(q+JFF1#4?{X}wPK z4dKcx8wMKI7pWGP{!=X#B8YxL>C;xb-`Mpn%C$w1iP1TZ?fv<6u6t-7i^;HMrGyV} zpWWF!lWEzZSjy_>@H86F>7p&uh?XBxb^+fKdq($jtKl~|GMoz{^{WJ(TrO?xmek)H zXE#!x^*KyeiKqX_{o2&0_&{s!3b-NF&;dCNtzb6=PKSKEz)+vU?)CsN&SxnMRRNr}V=J*EX>!+2G z^&|H#^3uQ8ys((tLbF$8q+9UAh{5~TGPc^lTN6_|XhmkfPQDnHT8dl7({g-B4D=eU z`Q7o0_Pw|K&96DpJngT7ytOD)Q76YZyZ_TooYcN}q|{8whJxVNxHUvq?y3>6S2f>n zS#@pER#EwBM<#)9(=zteh1jM0!xh(ZIM12Z;U)?19m{>b2wfiwllK74dx;gsB4gEi?Ho%KZl# zUl7cvRJaJ~b}F0%l|Yp}wQr88L{bv2fB^#p$`F-3#6beo%4(oVA%iX#;f|dOD7z^!pJQ0lNK2G93mZNG=`v z{75Dpy8K8Y9eVso9v#LZNE#g?DB9#R$zULY0&Lj23iJ!}S&d!S#_2mAf(bqzl?V2ffc7TBVg?Z%+X+B2hxN)I}}-``g5 zF-Ztinpa6%`$!c2JacC7{NSK?W^8_jwbZ%NviU7jecR(VXm`9+J0P|-`M$VgM;bTI z;IefF-%bPD={rJqJc9; zyJcdm%w-IZ@btP6t^_m5?VRVc;^r{?0jLO$QM*B&llv*!GsH9W5S_0 z4;mTgoRK*0Qkmo)le=Guu`8}1lACrV&WIzMqH8CQtNzoz{cm(BSKeT1@COHI>fAq=@`$5h7ViiWlFI8zAk zmLGcf@?-`lk8u1c*Nf)861YqAItCRxx)`sy+&a<}?wHtX-Bn}|(83fwa6|YYW>{oT zlZn&(QG8Qa^{EX%-pB`>nw*3lAwLJKf&gKwwbp+HH(KZGfPJ+Y_E@kc{s#Y-!Hcep zhA)1vEdO}$GkM6*6KyJN);ruf-Pv&Nu0i`s6 z=LPqt_KCa%9T3M3`X$bPIWbgjAU)Q2x@YR3-^EdUfq(Fw+2xW^v8w;NO^ps8)c%|^ z+ZXaVRj-tF&?|@~x&QIcgjvr+5>8=EIM$YZVzG%IFH1W-QfBS6`w^!8G;2z!C)945 z75i%`u+!(!-no+Yx|2c!ZbePWXHG3Ko*32LrD*;leAV}pSHV5;&q>NQlddKH7&LlxeK3eH(tDO-N!`H2)MvDxj_9$&bSq2XB`5St}+V3_hb-SY?y+YnNpd zZ%pRuW!7Uir*AZ$^q77=c-XbsGGm%k;9E{}^w$*+Er%7qvS1Oks=kzMEl;PUJT*dk= z0gE+0^JlC7yWx6mb)o)FWV+?*-P0Eb6u7?BJ2t6Y)Yi%q&b!`ZaXUTISfgQj4!7`W z_KeEslb7>{za7+^ctYdM{ty$U&#$T*l^~VyMe$+Sjn()sw}o4eA6L19-%Jc^$a)z3 zb*4SKGWd$umv()T$V94JqGM;vGfp|(l!+N!@heUV`!=P$F0{!I{6wUmXp8|e|Cdk* zrWB?x$w}85Hmj&mLM)n?M@Vi_VFj2qG4=4GMdc(D5FmID&FYgEAdleJts+5%+McU2 z)2*UG1(=JXJt|3m$H@V39YT-WQwMaoe?&3c?Cs zsHlJh0e%vS?@0|W5mElXb(1)V^8c%w1h?QjkwE=v%Iz9UP)G>^6)@-v)>yL0D;R^f z`J4Z#wO&z~VW2{(z$3_+;P_f&2O;??mX2_DQw0SJF(H{!V|$bxMEAkbvOUUf8|&X5 zWd|j2v}}*EgA({~!6-X|*_H~Zv?TFJz@b4l!w!6qWHao*XGJ!{4z7eS;=mzBHp33C zgwWyON(dVc9Af`B!VZXdgbfGN0J#581CWofg9;&RICzMWkFbL(A!In11|T0{2bDs| za4-$|h#z zY=j*^4#5D$|4##ujj)4h0J0HwFbzO9!VabZ$VS+~GyvHMJD3I_8(|020AwTVU>ab1 zgdH&t0=blABkW)rfNX>v{4SD>u!CGmFv9L1G6~ZFID`xb(*QVx3} z03t~(kOlxEDVGD%06+wP#O*u?NCN0nrd_6d)rSf}H|nL_x4qP-J7P;CLG#BMO4O0%Sx%uvvhNC{L4iVtl$-O>xIGH8oXkpRYgf z!Jn>cZkH|iFz8Z?f#ga16E#ZLQBG=3*%H?a%h*kizG0M>&An=wq2k&)<9^hLFD0Ee z)tDxe;i~0PTg$powxlaoI7tpW?tuL>We4XL1$RbH521%$zcP7Qn<$o4;%z9?b=o9N zU&LOhK27P;KJJ?{yB~Mr3>$-;4W}_>Q~GMKIkqkV6K9U)d3uGthUHG-^+zbHD>+wE zO{{x^m#8uwBu0zwFTY`Ywdb4H^CEGXY2y<|c+PRX>(iLpLnkiColNnSx-k37)eBYE zxXzsrNMn}s+I#fq)6lOmk+=48;}1!dPV`YSG${-*e^=*jG@ju;(j%Y3n6s{Cf-P1v znat;a4~^Y7ZV2b<4ddnJs17EUVocE)*C>fW%%eZ!Tfzo!k(1cspqyZT<; zxZWH0{b~D9WAi(KCXqemD~y5nSK_W7gB=@Kk{3>W(Bt`t7q z_2Q-MZR+Hok1i+?v)s{pgSm+yXQ$-xWTcp>us-?K#c5zv60Ut^DQxyo$5AzAM*9H&tf` zu{`>4*y(j-^$MNY?D_ZpqYUB$ue_Ow1sd>8OS7LkWvBb?!7W*V~dVlrIIAV5<K|07@?R|)*0sC$!^+qy+3850H6}b5Q>Ji_oh8Wr@M7ZN?|hFPR+`z& zQPb?pMGwNuHvder43et7CjT| zDw~J%f4u4!bPQkr6Z`Y{f4K#(KIQ+c&XWweV5n_Nh~c%(JQNu!a>#QfZ)KcI*8L{_ z+>noelIVZC2cDHZE;bfZ6Wmhgcd7PXwrFk0J9ymR@}t;nt9ps6%TEtPA3DV_Z+i+ocPKPFHp!_%H#XxcZH^t zLDnd0e*;}%19hS79*RHwoIj(fzx(ejY@x(MQ2uL`i`~OQXIefHmcSv}Ra9dg-MEmb zTb|QZg7u`Pm|nu;UE->{=P+#FV%Wz${12QyH+XrL-8_x3!X&^L;c+-6tKo9nV{QS1 zCWb}!15@AV>ZFXi9S=-R$?dOY2xONqym0#T`Ujoyc4`)BN=1TD*uq%`h3hl)B2PN; z*wc$0@e9wZ>6#J`J?i-Vg=uddvmy7`WVKwXcv{cf4{rWSMT%@Sg-dZ~=5kml2hgal zrk=J?$FmE}!?y2@Ro!#U_iB4z5HRgMdMnlTT7Y}wQp!?E$J;Xt$_rf8Qdt@5bsP<$ z%&&qzwn>+bX5HUW(IW%n-AtA2sz0zOR!^CuNV<;KiR^so_8!r)7B>+w{fg%)Rsv%0mOk zE!Z;?+^-nzQGUkQrOaWI#KUR4ZlR*&%GowAaqdcAWvtw=gZuSa1HNgmr7Mn|U*38R zNHA}>Rwd?-zq=riO`%;p$$YkQgU7C9LuzTnEsZA6W+zYe6Fc?qZ8E>|I$zla*_Z58 z(%y%|tJDX(QAq9-pWe4tsphYtK%Jn;H^xB!HQhF1w(x@_XV#qkoyb!+92w{8v;-a* z-dtLqj1c%CVl;W2hb!q$rPiEy@h}ecpUdhE?PG@5l#>~6D;iaXO4<9DU=A1Bz2gnY zzHMf8rtseUbZh0aT#w+W)Vi|id;SG7f)uJOciZt)$`vZC+yawIbS>RfSMTopk?gOT z(v`jzS>1J#S!VINBK-@o(@QDlJndHU2PUTmTycDxyCNUcUsLqrYu8Pc)UL~@EyJ`P zk#B2V4IJ6nx?CBv{^Y0Em78|H7B2*nF(IK|3_g{ww;nIt4<;!5*k}9r#obS1+MBT- z+SA!7+ws9WTg3ONCx7F5!CX0gs-MY7P<|9|H!LcCqH9IKSUud}okvzT&ErbR9Qc;j1bZ zkFk( z-{Nhv8C#s4o!N2rf!XF^!tU2ijMwUpd+YZf@*UPspSbUoFjkQCOTJs^sqmQNsQYKu z;4`IlRqr*9pW=CQ$1r%@^+CQtz^9@0pqB?3L%(Qzvbw1L!FVz?o@VsbI!lKzFO9o# zH|B(Ke^x2Jwxw>1=`;1Uick?Jw&l?yKA)6E-gU0neQ6$d&d`)+!jnp z@8sI3lnM7fJ2Nixa!e-8DRSzE^O1>ONj&F<)bimO#n=mn@!WqN89K*zY*BRo9(^oQl2@?$(EVc5mq?ypKqre5;f;jG3mJk5y znW@wOyV+--C?!DED#3VXVVI%$y9!LvfcHoRQ=bXiYEpc}tD@hvxFF4#nFhR#8i{B; zO-n@Hi0@5I00EM*5S#x6`%Gh ze#^m{rUFL6Ubl#}<(+tt| z%iFoddw+-xHWy2lQIF+gkJG*KsnIibVlw?w^x^+Zg(z7)z{3=!!_QTg5V*L*EwD!g!Kd~~E?oH~{8(1#tN?gebd8o?YrtvC4wC(LVjzMWvd z^FnjC*d>oa_x~0qL@jMg`CnEXSYarV&q2RGdCQlbb};Z`oVU&X@w;@a4;<6aPsMvL zx+n^}b(&*BX=Yu(BV~?ecE@7OOVJa0#DCc*QZsb@oh*_ll8XiL7IxMwCq1o!P$p=T zAY+S`t&%ZxUmiCK?sF3Adm>S;I=Jb}^TCzyYT;gk~ z;bXzdI<^y23+M+%5@9xF2kbp7Bz5uHr{`Vl8$-(EQP&4G;+9h{J-j_tIJhkPJ`dxyzQxXJoIr$5$`!Yj~evG_{?QxCmg-4 z&z##cSnqhI3-fWQt?$=8;e7F%TDOzyej91gT}O4l*V;K>o?z+LH*oZIa=WZ^`D|;D z-ldS-^8#JcQ^j+q7TU9CP0HKSq$>$wl4iZ?H`dmc6`o|p$5Y##KQ}Pk^P}@ScHirf ztd#?YJYDK9*d6+a_c;{AY8gkb%p8z4_a)s`j#asGGBV3)tgPvFYsME{pI6miW!)C+ zA3d61dHzj#yywlU%@z0Y3tvQ~-sj~jXdnNL6);y%2g)wsJx8A2Q-@2=e4dV%nGS9g`XbeZTw73FR4DZS z1NRtUK!_a>uo@@`v;e&DFKQ1YB0};PwFeRrefW#o1Br+|{6+171Y02Jfw{sY!~x(D zWK)9y8lj9}Zvcyc)v5oGNhpz^5CD{rO$!Dv3E8M%0Fsam3I+&?G6K3m2nUqFA_xco zNXVxILwykPEyQnNJ?gd!5Wa!ssQ*NO-oR?qeW0~=NSy9>4Y3%dOy?*o~H z%s}7as?7OI7SZeUFyk}xB%Bp%2ly}+74 zBq2rs=>sB3Er8ksk)##?`hZCK0+IAr z1Zx73q!w5ch$OYZnm{C}1=a*2NiDD@5J_r*HGxP{3oMBOmDeQD8mtLql3rjEB(5+Jh_)NrY-4$rXs&gRBPWE>H_(6G$RZ3!wPhBC$OpkV$$$)E?l}q-O)Q04hup zfm#3*CW$~T6p~yaqV~Xf{&$;*+5;CBk)dWtnFX;uBDg@(jfmOdV2f+5gKjH#lZ6G6`AUpz4$Ps{t=MK1lXb2Ah6mkf_lLyF%g76sF9vVno0GdVM*)g-6v$e_^9Ni&Gz4n{8Tkm|X@EjwqBE1Q;Gqg0YT$tb z5B1v2B#mFxz#G|a@PM?LQU#Hlr2(iS$uu+LI>7e)+luU`sJ15|XIGuwjQVI-#q|2( zl|5{w>ghu|zp~Aa{Q7iBRdPq{l9GFN`Tg>bYvGP#LlZf1=@WKb4@He1ipH;Dd6tG= z$mMTHQJxr|%=Ep1h` zWoGYA)N#6XD=zb5#+xkTDMuIfL-pN)zBz_^N}n)cGyy#0}f#)PwX+KTQ>%8|l$Ix?qmi>~P)7I8(tw8zk`^ zlOld2`5;T~kst{#85{>%40#C03hv~O6&zw=#eu&V@!@+(Cy6QX-{Tzs3dCHeEn3)}SkJBpXr~|bmeQ%>2 z?w;e$pot2fnv!*fM4K-hN4+G*;~5g&?H61v0?bUW8nFB@h%|V_yu!@?cu0VmU;hg; z-`lhslj^69HAEIq-tZB!i@V-_Xff-vQ{x9I>Cc1DR~wzXsv}E>e%mV=;@hQ{E1d&) zN^e~mtNR>c`d;Yz^=6#bNP7Cm{?nM2<^@9Q=hcNzBW}$*2fp|(dyl=MYgEc(ZrYdo z^}udigRMf_hkT8e+0i#4wJm0y)w!ikQii3oeTPjSyrK_(So~Q^(KC14!#ya}1^-I1 z%F&2cu`HI5kbBSZdPO#@vSk=Kd_ZJreZ2 zpLn6_v0HF~i0jmBUTjYfwd3pa4mIudp|rg7_(>|lk7R|wM3Ikf=jNw^miF^b3iJN7 z;f+2k6jl)*njHUKfHzt@>g{c6Q%c&b=S}O>+}}J)FRvt-(#0O4H_`0pBlTtuzs5$)Vh?m8OPQ0nV_8 zAd{u>hgcC!15B54EvVYwO-Z~f3R|UtYsBhi2*;6ZdW)H?+~d|0Bd2UBq;T1 za6znvjbPBHA^Q(&0k0-9uz(Q+P)8w3W*com5h%wF@DLhnG+6(ZW-r%h9H9dU1}qW= zh2;>$Aw)E2>;{)WLpN^11C$gKP*4ptsq?|=(o%s!GN>OFm?Y5$FeG9TH@N?g+6D0y zcn`F%lYtH6rT`)XUP5GdfyW=N1_K@ASg26j?d#M#G}h?B(x7=A z{0RPbulv_64!}5Izy(~rwzyBj7P6xLF`qQR&#wU8i32=?c#dwzN+_HvjH)1~IDj(4j;+&%yDC2Qp&p zfo)eIJI{eWDrCnwREX>}hZ>QcsIS!QpvG-jW}xg~V+r(31h^%Iuzj&*`%BC_86Fd`!B%?~4@zrFd1O{ic*MAn)g_Jjj6=_?2$BC_86Fd`!B%?~3YvflhK zA|mU}488MC{G~w;&htn2^@|#GY_KCOL#KA|mU}4JSMW< z{4gRS>&*{&Ot3fq_Ck=yL~6~iPwWW?WKs|UBOkZ~ofx zVGVnKDh!qY8;`Ldektq@K{#c+PZn?M7cgSLv{~-_G{8q$uYQf-%6F~puz-tSq`G}A z?SUKbyzliqqB0)J!M8+9YdowjUa4~Jh~Ns;Uka5F5l)_R%t(l$k=?cTWV@N6)6zgX z*QMC~|M5wQ83!24Qie@tr4-kAQmHt&=%mLfQ@a}ZJQaMCdqwDD))mcN_p^7n}#ulOz?>nH;dO)1A?6JGtDa^cb$;4j$RjZJt(i zP*A^LDyf9ewi*>t#?f^-$oS=@xY+23ju}R9Z7CB{jg_9L~NQVM%^`F!Zeyr~^7nfEkHae_e#ih&4p13|btV2r0 zrNK1eOVqRir)gBI$9i#UEq z$vgiPcM0iihB(vAOpU2&P zjF+4HmDZ0}?H7lR*;clgh!LnX>^$CISlRFXdMjkzd4FvtLwwMR%rg8hS+6)&M>B5J zaAr&8LZAH4vUhtL;$&mKEw?Dnw-CNbtynX3s|yOLzG5|0>|&H-xjk6);8$rGpEEvx z)tLH4m|Ur)@wp3wtAoD-mzqT%t(2%gXlQOKl5QB7D?69N{b1ze;G6j1bIX4=*JVrV z>$0qZy`-LwOWroHQa$-OzWHSIrg2|x8DG;?y`^iWi|3yCvDZ5--7YY!cm7nLe^}^lE3!mp31WP+P)m zQfH5Co=pG2owVZ;t0c8nV&t6E3$tOmFArXZov|04u54WGGbUZulo0b? z79Zs~8y5YC`TFeh_?y6%cWcTzE7Y8d zpUZWb#@`HVQj7EXioC9t6Z-O-BCFMQwVUsrz>~>4^_q1(7F9_shE;hn=_PHK_=kia z9hh(BS3lIOS|3WC$6L^s{iWZJCj)cZf@(JlK8t2_RrnG&+K4$XkZ3kah%jHAw^*qW`Z69h@^-NXerw*6>$X(i64PW^orCzJ! zsk@lXkzL~zb*r;DPA-1e+0g6^K68%aK9uhq<#WRC?+-tw7_Oh_SNAC|uqb|DO8=D2 zLO}=q`!mU){{~`f6y_Nv_qg{83^a_oJidSQaet%sS#z_ye3na%IR86*{pnwq7cO25 zAF_VjsjE=H@q6sfw~=3$>mF}mhK@3FC?VrR7!??3Didhg&TxtDt1QlFoj z@cm83k6yt&ns--lYqbTuKcrk=UoHsI1uMTPz1ktqQKcy<4L;-%Pf`R{@u}EqIfS{)nX2$S2#wUzit{5I@#rPQIodktW8s) z$A{h4iXEh$aHL$lIp5(?LBPH8$G*~5 zQ+w^d5C&`hN7Xwr>4tdgG!S_Yg8{!f@~dcsASM3-kj$jS zgP!c8%!87QV8uhz{9_ju4Ve*p&+|Wvj{j*ZDeC_iVg00pU7GwdlXL zTg~IjJPepW+30^froeup|LtT`CUaZykbtlV-L z{LhZcf8#{G+=Bo4_J14SoXi~mV{50e9`;Ke$@9neQ#`#U>uf?F_tyP(`=AQzRbu5Hz_wY!+S!hi5#&01zln=nMO*7&k;;yMBW5$OaZlAmU^0s7N#+JonUj6)9L@-8wk*M5=f=p`0 zV(Yi`26~WT?t73k4K2Bb9t^ZA26|#~nd}Qh;BZ6v8jw@@8dQp+;{cCKWDrq81mL)V zd<~q5d<~w3(J()6UJPe{Py{7@>*?LsBrci;@mk1}2WRAU&1m9d8-i{tP=hZs=3UfR zDCGJbsSUK~1W6B8PJt(YR*_}d6CW~Sb?}>da=uvh{mt{F@bmWb#*yit@OHzrnPFCo zxur!GZ@N-Z0tLo)GvLa%K*o%ux$HU1Mc7up;EXKz|52uNxbDZ;NIKbb;*kA@DTf6Su%4G9%yft?&{*PJ=H;|wu*EI@zv&0}ew#_h4~I^c3>)+#yq{kg=|7eSZf^R_=F@6pb|ZN5_OgsQ_S zIQ#AKY}2R8kdvEEmAQ_vf&jCv)#6yVS(Cx6eX&Tr6SiTW9bUImp5moTa~tvcfmQ4Z z^IZ0N!5Bx@682rtR|e=P1998-Dtq`jl^gB~b4skVmrT<6Rj(see(KNHMr!2uy5{Sg z=I05mnl_FZ&Uu-Yu7^M2|5UChn+*~8^nm~4Z-|<_fXIjZV|w&oH$ZqK zJ{_c=i~p&jvHsZK8M9F(ml5)j{sjMP2DnGa2MzfjH^To6BmFGX{dcW-QcLphItNDA zbG5>xL0VZH+Lg3zlQo5$2hAwUCa)xcK1`BAkp#RXnS*0WH=kWTTYRa?McU{fP}eh1 z?7%ZykF(uYy@#E5E#lh#x}I+4tMhcDxWNfT=lZ+uL9{3LX`m$Q9bT~u_jzY?)TEAS zm|Lk@`0$rr^L19m{n-Q{(qohodJ}2+MqKjZDJYBkhvu8?di~MJUjOWUveIOe8TBU2 z4p&L@D4N(-g+Br0JMtzAhG|(j4*a|g^JK>VM4Jd(_AWeJ)>>T`n?ry*-L0t(8$XR* zf||r%iY{I|y7j0D{YXEN~9}S+^y*v>p z3)B12(`<&P4b>iS?T@!oS}Gcz1zP-w2WvXV2kNnN?D3*#NU+WkVpOd@<)M=YT??`d zjZk9fSvN~aZ;1;T|VpDtr*5!9SI7hzpOQ+1bsN5G$)RT4( zF!~}ilq_0$Z`iYw>NA;!$)#QwRfTOBM&gIoEviP+!FUfCw0}w|FOzdb!2eO*kaI-%%t@(Qxi-|XTw>4CQ0X8z~x$w0GXJX4bq0iz-JV{e5%L6#Lk%@pc87LSYUGz?&cw!^tzfV$nm z`g7hml^7A9Lc|>``cAVHJRQop0)K}0R16b3y5$A%kOB=TyaPFf8mNMM<95CwH0kOC zdwQ6eRdt(YX89{LsE+^(_iI=-#MPp4LZ(VP(=olU!NW)&!PUs+JQBKXF1yT@{I%U1 zyQ%MQfc{0YLqE8FH(cgH`TqDH`>|Vg$!8R~*J6^)ZMim*gE%|wd9?16JX$rHgQ#o9 zaREobUA8w+*kInDvJ53C6@uD12gPM6#yo-sA^sCZDMjTMarXB#MG?buCQ;8`Nfb|q ze|;^)wX%YgfC||#V7y|VaQbj+x|K?A{=+6sVEeE-KOp9mMQRotXbz*^7Edq+1T7%J zBVfSsz%;qXxuaP-X~5;vljMo!7az124Rju$T5=%5O_WH~+q!rnvW~EM@C)8>#)M=ky3n8t0n384yA=F5pV^-h+oo=VazlZ6O9@4R zh^l%tft1hhgo*%|XUE9Q(Fb_z9##6mawO2g8t$tOb7hH>zncEqNt0F(6hP`>{Cfsa zEbdM?-L4~n>ozF8;s2OJG2F#FcsB#lwVxG&%9IXh!sslQy(6n1V&k|f^gKaAaE z0+%`jX)iqN$6OGQaREx&&Q%#6_ZO?3JJ^A-k`T7Pj?jTNLJ`G4m&I`_0n=&FXUuG) zb>T6uCxi)g^!3#(IdM;3_R(^H*Zu>5%)h#{gT&xyn{8v?@-U9G(aZkrFb=y;hX_9m z3i;kN!d%BvqEq1lB9{;+!QdAPv+z57b&SX1V|mfQVwTWTaw?w4x!ogs(|lG?WA0l((B$Km1VX)j3a0 z$W!UgyA1gDda)4Z-)?_AdDIvV3wePLcsy%>aIn2}@JqVn$af-w12>-SEzxC9njcGv z>X!h*VZP*TrgiolG+Or2eS3ulj63;B;MlRI0kv-^HV`aJPVj^|^mqkeDm9dtJzh$WC?naPkjOTm7g(2?5rcs93I91Bu6HlJ^_7juq zS=g+=48%Se2JJA~bt88{E688&Zp0{dM%S+C7%q>F#vXExY5ypS`HUg^$Z_pQgcYWe zggmq@lLNtImjsGte61P*QzuC1z0wmYb%tLff4`^9wHVI@1~^C+NP(X0@g)wwWE$%8 z=IRZ|W39=`6vj>p2TIhcoQzGp;Vc-F4__z-o8>tCUZIC*2;Jo(hDfn;9b)~RkWTLs zaE2V%YkBjW*Z}{A#>&L%@xWd8SjLNE{~FWuDZx?KK!jfz~n?2 z6P^ET2u9NOZG(Rp(E$}Z?~*s}gPcLN$0o8bd=2D5D)a5^h7!9#7kFZAQGJ4cskjeO zqhk;$P5w(zyo(D4Y&jffz?`K%;!RFs2NzU~EM3?*bnJ^tYA?y3ce+FVb`USWV~O?u zM;5=6PZyMcTYjjj1|NAU^Nqq|>$9AU3Mqa?lu`3|P###j?Lu=)dett!=RGsl1XQCqAw0`AzvTG>nDeY%f=wikw5r~Fq^-aq-2(|S>NSg0@(Y{X!-gFU{$&W zWc08pAO6WvEn<6aVf^E7t4TwWVviuAc$|tb(Z<6INX`0&sjVx|0>>*DfTu5!8tXy+ zanBA=>b2YJg4Q^79O#su9CoBmzGv?t!~}hY%ND4LLzHmJqhXnLk+L5y(gNP7!KGa? zA-Wr#8U%%t|L$ZfzpP{v>ZqNPTayt=W7SV&@9~fR1S*39F3Ohq6ivR-G^@s5J;1a< z^sMg!jKk@4hWqo)p2|Jl4rD@ZsZ)e_w-p#0sp~fDw8nNDsoSE(=!rkHjQsV|W8Bmj zIA)Gzpct5$qe6Oni}()DJyP{#u7+2&_mI^ZCH|MIj1k73y~tVYgK&&ClWM`2G8UHk zDGs~}+YpvaBEN0oKwSwx9Jrh1g~-VuPICtWXdVyavEQ;5t=h!?HsG>-bp<|RWPoz0 z0LVlSxGGEy371>AS?~y$ybA{Eyc6-(rZla=ZR>s|3sr@zxc=$r-Nr#Y!^J`r>hRay zFyJZiOG1t{nX#Y7K=Sd~yTRceZhFzfze8fM7mpbK;8^FbTH2Cg_LBbgWYJ4enuNFn zyd!9_|M_NJR!C8IH86B&a~*Ca!G95NdQ20QZtIsCWeN+>K_5|?VrCyy`jvWc8wDFi zQM$Jac2-}6%hB#SnaZd8Hf-+sP=F*$JqvVwAgSZy;ZGj=%_X=s5}lT^ZAi(mo87ff zpv)#j;UKPv`$&lHTN(aB#M7+$`tXzt@eN{P!r%F`q=5Qg-q?SnIUD2uE6rWjN07VT z)o%{Ly2NKzl3PcOICTd?vr9wcSN{6+V5~Ah-Q)tV*CD)~EB}HLAV(XPHl;tisxGhn z=k-$7MrqcR$ywjcXMfcYO;5n%xkpz2FI7yJwY?*2u$S3>P7}9voFhxe*3_6|0#(VY{}?6qBwuYTy1gwhtlq7WAB~IVSl943)aw#a`EgYudLT7e%DS$#su+8X%wmVV^7(U%#AsmE zk^Wzjzcy++<&z!u*dkXG&YLDUK_6R?KST<9Q4Ot8FkZ3?^1l1iiI2lz6d zXB?M5yeBBz%~u(#J}_)YLNnnF-nlh?n_6?)@s#&oX>$87PpPx;L5NonLrOfp?uZ-|5L zTiRjGp7by_O^sL5qfeD-U3r9Qx}HA2=pfbGA8^`Iql(ZO`>zAHX*{THkbKREMRFdX zB6stLVr;ul_DFSQrQBK=@(IcH&hsTd1sb;YRrWB&BT^*oKM6q#J5WH@jfDHS*U?wM z_&KRE3QPcmNo><}Diboj7J`N$IU-6k~A#@m<(EXu{YqX)kVfVlYdWaDIJ?Cz3xDO9{R`r zf}QAt#FGcY;5&IS_;)T|+9RNP{Y~S!-BW$Q+C2rhnFN{UYPW2?PZ-HX_jctzp~KP* z-JCBw0&1Ey$r>dUC+P^&=nM#Kw0s_^T(KO0vuLqpl}L;BS+8bUbRy{#^Ae~wZUhP@ zwyN57RE-o07;#b^xA6tV4W<~hi@!vqRBFl|h-23;)`K#NVN>qa;b8Ew7{kf&s;;*5 zW1@~etC#s5f~Ac^o{3W&hsZFpRzJ|scTV)YFRdFGlqz8{dz-!3*rMqefqt_ z3kpOw4YJ~qbo8-UZ7n88?qnn8zCboH7sB6l<_P6oaW_K zAapH0B)~r4F3C&SCbhPHqZqDjR$L+F4w1jk+-SYoMlQ@yNLO6^E&EZb$HN%8|A zIkZ?k4AYm*mTX{*75xcipvFPgX6920!erdsQO18Y`1 zfcenuBiQ=&?2UGbv0bH|_00d5^RfkSk#%$zPDb+??}nmbv&lyI2R2BJxzU!t@tP~f zi16f-Ce>@!wk%VISP$TvVNs340eoOHACr*#$~PXH$vrU$Z5}x>%LIbVW%7_w&)p_V zAYZQ))#W<2QjV*BwF5qZCOR8cUp3KyJMdH{;_i{#IORkzhooO86s*K4xikhSE2(Mj zOf{t2Dlnsq+ECCZrgP>2j9-xDzPX%uuRLdnY7xp@u`(<4a`cXWFe8C>Zk zNuX#1tr&{ae=iLl4LTSC2PLJNk>bkTropdHZwtKe)3L;=Z*}vV0@duxfEYgh#aqZ3 zQ*`TGT`rV=Z3KDJH*m-kAFu(qftv@#|Ijod=X7`GK;t^znS7W0(jvHF90SK8n4=xz z=3MMMP$Xro(QQ%>WV>0ke!n-pJC=@)61kB_1x7_e+^D(YzXm7K3Gu&TavI_t3NW31 zfsCx`#|IOIh#50Uo)(gkfOCFl35iJ=B|2=4y-wQrEJm8T8Jl!&W>l8Z|y z3ycv>7h|uian!H9p0Ycvv2}`ruv7?S{4Ru;4dkw1C!J~m+m(hU=Aedr@(pPAMhT^I zW&fB(lkCnS?)`VzgQ$ECM|Bf=R|wJ#{;M4=vo4M9rM>?H7FJvOO7A4n;_Q1uxJ5-2 zn_Ppq^-HY|xIG?5I0giu3<8hg!QnwtYVWrJvm)m;QSfJw3RnKGtB`I}q=7VVm$T(( z`&@-%6Q}X3F*Z%YnZWPS;zQI^lEAbp9~^fS~3pFEe>{CPXmwQ-2N6vJCM#GTiX&Zm9@DC+Q19TkXd; zl1|i0H(`lNfi1DWz`!pGM<>7R;X-8FDcJf2JMj8C2$$@Ec>x@#sdjmAM^IY6=qfI! zJ$hMryX6t?(I0pKF!LgnnNq2etOtakf5rpk%x+oN<85~l6gBxmhZ`q$^Bjm+Vi_SW zV=H-Z6)}97Oa!xvyaNS|iej!IPQIb24&bR+$@mkY)@iEB=C>ir<5iUSVQyA&)&JtZ}m!Qf6lqr0sZE5v<*M(XWR%YrR3Q@P)+X4UZDJrQczDmvI~b0FB9>WYu- zo%i>!I7*Iu=wEkblqmPnjsv!v zPTh&Pc7ANb*C$Bxv}gDQ&{u;Cw+%m^EzKqY&3D!W6Jb~mu zNp{OTBp_)uIw>ODt9mUnb@0MoqOAS=-O$K9rKIltRl%=&R1&ldsgFmkUt*-TflIdl z`W!pqzx8UvKkJINY!gP_t-HyvxCbsbBh#h2`z*Zc8?0b<+pw|e#h+;VND%@OfX zTddB>4$oy>fVsDiyWVTX<~Z&D=t@vl=Kl_kP$2yN|98b|&xw9;^IHFz96|ZI(yQH0 z%NeoUHZ^UggyB%kz%s`nkxOq1a!@c{n$4ucMv0XE`sA%=#iMY-9V*^0W+Aj{!9_4T z{v<+=lOIZr;lYkZgc|Cu2uO*^M_CooQx6L*py^FbaUye#7t(94}=)6@6Bp^n>3iTQ|T2KVg=AaY={t-Z* ztKZ2#Nb~~&fjy|bB~Bb0I>t?)rf#S*SQh;kc{`2X7yuIzR~s1c`_2jetv*Wv+A`$C z8O2sJ<1AxE1e1o05xpGTpbzV8E5~>tGf0H-SFIG09Wf>#+C#yIsvO#2RYRgsfq7K* z(gEt1dKkQQ{+$Hem2#;yiuz|s3Tf#T=(6dF`T`<;dk>$o;(PgP=C~yu(%JBdU`Z4c z)?Mivl*prXz_Z~ddB~M*kfCaVV9lC1Tm_z0i^8#&1bHy}9|4udLFZ5@6F+O{GiPTU zs6^s^zLP9~0V_g5k`WVby#SwCzY0loxIxw305--fC5oNCP$M}mWmQ>pWH@Fb#i+zT zYQ*3?1E8=-q-CqYkd_>e5i!R{yZ|YKMyH<^8cr!^YQ+*XN2-5NY*u*46O_jR)PD{K zPND)aRmSnqb0inBl13m|(<%$6`lgimp)s6BumFT&QvK&C{~6g{lokuj>z&DX(Yy zV?c5C8J!-W#eBlpuF=|sJUH2I-Mu8-*6hx;$>Jd*m1lFY`+EAD_kH-o^U~q!)Uk_8 zlU9Dx_!|s|b`3E)OL*;U`4EHx2cB1u$i0yzl`Y+^o+p(~JF$^TT<5f>bzeTw^{vax zc}2+T!eE&roEj+qJNs~5Jp?0IUc?}jQjgMgM5k)|4cWL2pTz*tn_mpf;11C#|LpQE0r%^5TpPZR%)FKCM=*Zp!={kuBNo zTPs7i>eoWG^`|gsBp>v|J9T{C3LN0gP;m&KX;h;)TusWB1HN@2rc^bhb}rly zJ~VKZ=C8TVX2lwDb<@U{B4>)pw#e#Xo~2twzb@?Y6jz17C~v-hiJ(wbEoVOU^>ug2 zzX(ii@Qv$m3`;&b7TTXv4@hY@6_ZZ4;=vcJKE>CPzVG^-jsE4oTDrt$zG&_*aH887 zr9Nru)SAVfZrf09#gG<1SaFoT6#%0tYx~bS9oEyEQQL~#V9LSks2>s|HY-hwmW&Zt>I$L=?twJ^#L8(gZL5b5diia@E~#(>L?m> z9;(ay7+0Ds(`kH0rp%D)KDr=XBzJe~ObuIPu8n)Nq*Bp@dS_ja;BrBC)UPc)4(@4S z;jvh0T>h7TETA$6(l>3sQA$ruut`HdlrA=prxrgEeb>Ynn{gHcj>rIw1&B`rf&HHV z{h7$8DxPaNmn)nOC1B|$q>qtdiAa%(+m$rhC~&7TIhq=bb&gda&<4jBNT9=+C?Z*a zTcWjU(-3dPzCd4Kaq2c7VXp$izxu33lsg7-2~u=zDv#pyVK>Y>Uy>WAp0yxD5$2?g z^&d{8VSo=V(AeNap)V9IKBN3DHxu*VtKz>9WD?AC(R|aluQOIa7 z8v0N_-zfv*zD^PxNa_Z)DTfOmsge_@(~{_nnX(51Nz%oFhEM7|XhO4Qn>${`FNbz{-1a=IX z{yl^eTLmmYTBt|qBh#dcDH7#Ohb}bhGGs^i&=MKuZ6#2z>s zHwO0?)%yjCZ?eRGiM;JX8klTD?Mn%Thhq$aCQz!+x)I>!=Y=Z{9XR}`3V(#+Stcq1 zcqO7l?TRP>`xBi}0*W_BWHKRja*KmaKO?cFpaP?SCRO)VkE~x%V)s1TsnC60g1Elm z>kD8;Bi%bH=+>AmPE~n;#9%w*?qg2q?#=(8yP*WY^0Y;A=JlB2j9h@sZ6g|)rig6Q zz!@P>5|JSosqG|=3s@l$Q9xcrccgjje4)9#YCA03OboES`@YW?_Z&c8G35OU@YNEb zJ}Kad!F~+57x)HO5&Cpk!RVds1eyf^rGkQ*9VG8!@S`P1a|&TJ>xl3z5+#qT{G3Xd z@|8d(yE_Y^H-p>pMbRgN4E;n)Gx@YQlci37PO+EyAn}q!{ejF!+rzPr9eX5UckCT%44s+IusoB69XbAfCDR_rGC^O$tB8?k#eUt zodjqE5eOy}IB?L_4cN1zBM-pcw_^z87Q;P&lQRVG3g_>qD)GM4(_HM%a79%mJ+zboJTM z@5$^%HUtl9+fv-fS<>g&q30G57e&w6g$w#RtawWXrPz7i1@hVG`3`)a{KAF;`4olF z)a=d35L94*TENf;bpQipMN@4>&VrHyg0lRaM?N?Kz_joCZwMlZ#~fz%S6BK2g)wUZ z&FBPnpZ{(26V5=c+NeSr&i;M(0r%Hs0!G1#GbJ7sE6jfIwUyru3fJ1nQJN+Ce z&`rSWOLtWuXNiq}yvF(O(X7AFpN$^syKb*58IJE2>s}}y!fMLwniwRY3lJa=t<~EP znVj=O0NfWi2q5j+^5)SYh!fQMY7FRI$hyacpM$T8(1j5Q*ah_c?c>+W-#}0>kP0F- zC?B#F43NQBinmN`>-*)ms&D%cik^UHId1`=>*?w5tcfc$Q+R(a_s{*W@mCohq;55G}q|5X7jM9o+JKV@A(-ST#Zo$vZBfa2G;@fXY3x9aKlW^7)1 z{ysy-BSY{vB7&nIhx_MKOMKO@JzKa1eV2Zq&+2mEm+DnjP;KFjjIZ!ALIIb3LeNGh zz{j?r&>wW7EPX3ksJ^i)hQSY$<#$f2C?rY^)FYTzw|1ZwpN@|2-YbZSvE3^OhtBvz z1}INrv z#<$nO`w4Ai7;>jJz`vr$87idyaZ`o^;Aexx@8#Y9@$LJ4cEaD%({0aw{2c@S4fI_A z^CfoyB=%vf`2~yo0@_Nm1Aw|Ffa-fC2>1q!RI`2~P`pq)T)X!0=K{bx#t%GQ_`kRi zq(d(GMMFQJKVVj!&w+p3=^k`qTBy8~^aNGt1B5Z(8@JViR5eqF;$GJue(A+MP?>a(BMG zli{BMZiH^#XZjlzo(|Pzia**45RZ;C)3H1KD6T1$t*oTZrFgEA8g4OsG?W3=lV?2E zGL=(eHY98@uU!d^=7A=clN%1L54Jlcps?S0xf;I1e8Z}~8Pt(+XGl7~YwgN+7ch~L z40jj$uz1LgzHlBh3bV-G>nr?#4&wNAtW8E0ue>P`;I9o4PS^@jMGo`=aGD8dS9Fiv>zkDF z9&c^I75pIY49u+#FnaM|86CuLD?Lsdwbkc`K;5LlYIEqmFeK9r7eMxoDDbN;>Gi+T zpCAubIzW2qYri0Cx6jQ5q_+>3<9DPi*Bcx+Ar|M2KUQ_cIF6`eji5bM(aJB(;?3AT z$XlAahaIz|_p*c*z^cVC+3nYbIwms4)2M?Wuzgy4^I$-&qNcXqILIrhyl1&w0lJn( zQm)j$uz4Mp_Y*x{wZ27O;IV5Au8Yj%!J(m-Piu4gy{sV{IOawHnYx06sh(=q11Kih zqvD_`_4{wiOa8(RbxhGYs?h#c@crOI7lw|6xEND*$1(HmcK(R_?1wv>PgSp~i9IOg0AZ6Dbrk36sY%6Y2@pWofF3o(ITwbb9I6%4vl{ zkDL_V8L=~9&8z7EnHZ{NxrNiz1l20VKrDA<`yl`Uoxz< zi7+c%pi>07sr$G?RjyXiO?I_#Gwb6Ld+F4MGG5;$dtODjT1uCXgukzWaq*h7+>_Fa zhvvN%0{AnL?v203%ZzK94?Zi|KxSDUXW?9`TC1;KX{^-&ZEdf27Y%gOWnHUwf6U94 z!;a~Ai^-@OIvYm6bnj@aQ<<7P0rSr@hwt0MZ(sKC2G*0 zd)%Rf7Gafu{2CcG6!%chgOHVfXJ)tt)?M*wUIhJ;ulPv|8uNuM9GW_GES2Ru>x*5h zS6eDP;N^cDMNbxTXH6&ff@Xx-`2g-m%I2a32K$HjG(FmGtBqzyRmk*C9auIpJh+@W zQw4X0ap0>e|9bcPOG1itwiFb3$A3bry!6xP@ZOGuhnR`O)KnL(vB_`oSJ-ysKzsH{5A$w{7t^>58mQ zHjn#J-g3t===qlmX@e=qjR)$tad8`nH)k<0#6~+$YOI%!V@$1P&8LN3p#}oWEbXBq z4zv_V<*CGoDx*u4?HDuV4w_c}mbT$LIW9i{%!+u^*!GS;py0`viLdA5Va~Hj9J--o zoygxZln3eeh}9q3^LoXYa5LV<)u7(z7uG^Y;X4$<3f?Gm&WD0O9H!`WHg9e`ODAxm z#q_x^?`M~vFbJr=uB&zz60DAshF~=fMx5!CzCk7*m!xxF(z377Bz~mhMvH<%mMU!lqIXZi4 zB=95F52!sXbAzfk(B40=dZ z-QbuDyCa;}OY=VN0xL^-EH1EeO&u2il?^Ebnrp3A0&h~pGpWtF-ZLDv5n7xT@abZ{ zC^p-m=#}I&T{jvm7CoS4{4qn7FD1G8w&Z1GNH7W`eu0#+o!O)}p4v3_FxE_?*th#` zInD!#A6NZjS#iL4`4E2>v$pot2?yK;_^mw=IXC7Zbl9MbCSjjH1vS3Zle`mvF|U9Y zTT+EJXishCLk`Qn8Jr46?m9!YtYE)XhMoLD?lQLA07o+*e2><;1*v(SN^N?_V&P>{ zNb5E&j1q((f0)?k#OU6D9|6umqMR%j^iLl~a>JXi`l+ACFk$<&CUXKLt}3RVe8!bS zq)Qc|N{SxKqzOECgMDJB1Q#E$T3N+`2Wt~;eT`P1OUXj2bpB^$cpBc2%=|AQA{OFQhXNSXXb>xbjhkFliet+$gnBzoh@ zxKb5@?X=qXBrJxUUP=W>nvsbQFCnb_`#j|0E0*D4JfgUnkFV;tEL?4TEaKcR3Ls`9 zElCAy1FNAmlNGv@iszotF>!A!lGug|DF)wpaXT_^?{1m`p1%Ny{AW7kTL>Pbq-Zrm7tBB3 zoh0tn3%QK1K?@`ZK#fT8az@3be_0C;8Rj8vwgT4$5g0Dv*;!%r$XaR&&O@q#s$P|u zw>^iIgv0~5WkT6N_DVZkW1KO%F3;L!df_@EE0;dNys(?}&f?hF7fadoji^YIhGe(q zUA(co*$*BrxtAfH&W1A%ZZyu|VFGX7LQ`O7UnK8v=(Zj?xD55=vUr9HaQp+2#mCh) z{HzUs*-*z$03%a>Vo@>c{8o10y`Pd@RQcZe^mqc8)~qUMuXW&a3?=U}J^7g(<5fPb zR9nZ}gAUdc;a2Ff(U9t0L>$K2$3|6vrYohnMPng0Y1wbyu~c%R{`q|zX0u}5EfEZv zOKHJ#%O^Pmy|UuI98ekm{6KkXOdA`o>oG^}{XH2elx*RCXhRRynl{@h!tj{ivT~Fg zx>O5zdMP@Aiv*2x@>mHRZa)C7pGHEAqbmDtfRkgo?gSt2l-Bn6r+?T*>99}mb+K+* zsoGf?fr1artzoRCwKMr)_A-$j)wXN%-QKvf?fQN%55y|MauZ1K>9@vYDk&`_GvVD`mNaJvOn{FL6_F(^X8n!kr0tcId1Y5Q-`-| zD$feSNOV=os<1BCkN?S&fJ^hx_dsi-urxjf%0HRTgW7G^gD(JOYmP;ro|P1Ky-5V9 z8kSp<9=aoO+IlTO5)rQHR1_J~x!T#TzRPnQlks{)!2$*=IlB^cDP)8f1Ey$gPj-iNh>kF11rCe+eH!?NQ71lL`%NanM zEf8kg#D2SqP3pyvK&2g{O%oQmrP~B>iHMH?{Kgp7#@K0tjCiFV{S|NbcZ+rBdcu8e zJl%Wn%QK^OFF(tX?dcMgSAmO(qaVd^Y!<-i^6PHAO6ff|;JmhT=F#{v=)`d&-NmKV zL`h-=$?^!se?x*SZgjfp<9X5+Xw@5rrmcx6Nn2#g6Tlds#I`yS-|($S4D|rEGRuyh z4`B-LXuYo_&aTL26{^6-D=-4`9{~i0#Ax;3b)m`(p4B&*3ZTG|vqSB%#cNj$H*a`U z5AHCJ_f(%uiL;t^`ogit^D?rjnYp9uCf#?H_Z1YW4=1)EBAM%8u=_jcWHzu|o5tE- zUWanNixU<}iZ`e>JmGVJ0>J>8sG&NtvPCi>;&-!h**@5sL<|!rSvbtS5!bxoCK4kfHseTS$F zgV*oCsNv5|@7BcPGC651qlGiHb7@c{T~Pe-?Z&(As%e_D1KOD~iAladoIE}7X0WzB z3CcP{HzaZ=`H4=FCewKkT4R9gTrTo(>? zBa9}2SVrS7RPsG1+;~9puKz7Fn`EC|tzVp66u|g|E%VrmgM$?j@v;tpGuili%n*dm z$34~p>p0xPdP7FybdW6Ztvkx@_!&bzz+X)odRF&+=ssn?@NZ?rh*^D)CAK*$TZ2X( zq@_x*T;aUEv}p_W1CMyu8?sO1CBZ2#4t0XdYMGl-L&gi^xGdn`F^bI$nU{pFkTv#< z0=jHNndR!xLYETnfKrg8wY=7XqD<+5BplOnwGWSdz`jRno@w<(MZBBj03 zw2>?J>IqC)(E-5Z!;f6KNquVu020*w$1DB>E10@m4k;0I8eJYsf$fA66N& z3zkXj;UFL;x`DoYhgGw$g}S-|PJLp2bCL=wqUO`w9Gz8ZewJKK037uaQJ(Gb6-CM6 z-@4`S1wFvM&yR5U&q97Y8C?a#!kMf$)`#%zQmadzy|gN5(iZ+) z5yY*ijROO)nOtyYFS0@1BvYW+(%E25Z`G1r-l`KBaqRwu_%dej3N0M;h~~?{>{2jH z4tPL8mObjTwyToYVG0qnd+)I!ZIEfVu5yDvqe8xQxwjJa7KPHHI%&M`dE58Q;TYPH z(gtp^U33+=evrx?HyAlFuTPdIcdjwfr8ioB&%josQBHOAdQyH}UMX3fIQEU#CyuJ4 z;UIw@H!kH-!ol=iBzUwlVNOAa_$`E??rB}u-kp7n!P&zr=4;3c;WO6^lDmMwbcB1l?_@!b%ps~m#y~f zQdVVT|2hPj2K-cv9=jA{8)*oAMp!~$|ht0_!|72$aUGh$>OZU(_F^- zbCbeh3VlpKq_u22mmbH){G8(DX1yPKToy#;0DHm25$YOIU{XMrZX^wG_N-f2&^JmYn3)00fQ2GvG|H-Q0tUI3 ze%p6Zd4e&`=NFiiobm&S%QsO~H7)mDSU^)!G;ZmZp5=_Sfd`yxIDfLMqk{1Zn%Mv% z;Bxmb$suf(H%=RKP!*Lf#!0#m7?H1n zAAiQX02UI_XuzqJ+AqJuIC%gZV{mr2VRnZC0qGF2{tJRL(5BY6w5?`&@!DfWWsXD@BjH`iP_u^?)%aw=b2k>#3n!2zxw?$|;FCOswYj$*zBaP|p0iq@vHP?b%bj7FF z*;tUeNNH!v-1D7N+Jpe$#>vKr3F?+ea0=wCxE?FVZ*0DE`@HYBZkD!&%fs*vXPfZq zOJN%1va74kK6o;qy||ArZqn?|?1k%;b5vg_%`1zy&j}%~JNg~#!8?z#>Rijzfqq@G z-ZRCPu{m|%8xr(xetR% z3is6W{_))Pmz?o7uwt6#6O$o%D;MnyCE_5HAFNKwMHyaV%>obLK zl6QK~-0(R@4XAM3fc`{x`fZ;5$xEn1i~JFd$~Th__v1L@RF-ppxqrPzr>Y-=mI=R) z;%-mrX@}gu&vX?W<-UoP#e3^wJ&Iw`BV#~tHIH>3vA*7wRfgP6S)*#91``Vhk52Pg z;;?N#1iyG|FL8{^3$m?*Zrq79Mq($d|5RH4nZtjn3Cr-zom~1fzRpg@XT)VnblCT= zw!Bc3NZuF_FVr?sa^=y&b};(Hk*;YmT0<>bPE|ru9L&jc+LyBGl6wloxfP_!UFCJa zW+7zr9}#Ap@ToTKx&)!Dr&iZt@Bw%O5KMM4=XtVW)gRe4Y{P* zUDu9Esn-6?%PkcDR{OKgIg5YQ>#vPPS=NuXlps;SV;kwn{*89`v4Euf3+k3a&K@c3 znvywDu3|EK4}Tt~d7b+vp{-dRSf8fpFrsK_%G~XQA8L7ynw^9hr&%S_BdkUw^*O8^W_FdTtb$61nMGJMaRw zgs-cXG1S9kg^vuUjeEZ#W835!$yz5ajLa@L_-%l*ombJEUs6!EAvP$S@#u#e`XM0- zyN-C%yIHW|&0CITTy>q6O$8Rm%CA)ihRr<&OQz*-G91kcTmhgTmz>#z<^x6V$5R+u{T_@E}QW$8YWTj?^V|1Y_z$}h*hj|U*$%| z!qSuIX7?J;^@rz#kL0z2=~9n~XxLGKSk7j2*?Q_4%cySk9=XZ}pOp=>$xMQ%BuwMv zSK^h+EJb~5hrZ?&AM(-o`f>4(-@<)?6XM58w|@xvmONz2qg1%Tb?smyXl$;Djy4NCxmAXoTHjnRJr}2?KmMllP zaMls$PW)(jI2OokZoTa(R#H#^W!bTnD%d|u_t?m737KJ43U<90nA*bxe3&fDW;Z+? zmVZO?O_j#^&>Ia>f{R1i3$^p^rYbir6qZ>_seAu=RZj9#|Eez;VKcdNAKo07RB}y| zx1fqzNzd2s_}+=&H`N4BxgH=dvwms<|z}T2`a88bj3{j@aUUb;W4$ zC^2nXVv(1BU3Zb$7}zJQZpgzkWy#PgeSiNjd_YrautsWd`ymhTy2FRr!sVRt?(czt zgSZ;@A!f6gyWZre@;g0H$9oGMCjK>b=bYkTT7;u&Tq};cy_8Q4?nu|p<`mgmyZ$*7 zMz+x*s>l~i5v0hoz45pob=oS^3&@Gbkrk9{`G%2RXWTaKy&PwKpM0w}yR|>hY<~n$ z6(G1QHnDK?P;!W+e#Qc-xQNE#cjwU`98@#!JAgZico$7f=76+*^S zauWRR8`rVu!u3I-0USjXAt>JGf{mh0<_Y(>+ zP36oCT$UrY&53a+YPX`4Ne(TI*t5!}PA7OH=4U#`P2$Q$!`d6kV~erVT8ybR;44|o zpGq0p$18j#s1Zv2(}hvkFN?C6^#thJPp+O$fBRr-es>e3HjkceQ9~pn@Dl*GYcpZ zRFbAKV$!9g8VQ;lP7`u&TIum@9VV?T_yVw_58sc88xj>~^BO2Op*|1LN_5%de>rcb z%gxEyNeDj8+T6_D_oM2}AYK87Pl2nKkp`&4aP+l5i~F`3NK7$ZfA68G9WfGIWd<3 zxZmfF;wr7@zY zS!&f*wTq&(My*n-W^4S@@jTD}_q^{p?|X92H}|!#>%Kmpo0sd3v9JmZWe*3VkQiYx z5s*AkOFP91{5`{|>Q zKpihvpqKxDZv+geF9Os-A>p0?UNw}v9~$B4gu$2j z*Ad7M6#$CK$;k-)4hO2Z!O;jP1PRoKV4UD?_=-@7E6^APMZhtB|46~F=!C(z%ZrNo z`1puG+&o24Xn#i~0U@9d0^$^qj8 zLBoM~g)0IIM|$ETypS+B8i+3rG}hJw8oI-gf1LIHI0ym%-VIPpMC{+`{zm^wgh2id zhCrbxH+Klq4}o+9Iv`x(Ktr&e2*wv91cV@AzZ@a1o_{EOJj5G#q?-f2G0SvIY{ShH`U*BQc(UU;U{g&~PaJ+WkcTY}N&d z@<9gt6&w&qn8U9jU|#N`rbvW`7hGHYuM1uU_>ayJjsZ%6WMw2|#ei@RAlw(~B>F48 ziJv?Cw}0`s8b3i`fIG?^=zt#r9*A&&3X-fMS65 za7P3Z@Sp5>HQeEkj9)$);S00^;jt$M1pWH``*a@h~Y_-}@CcH8j3wswVhn z;(yyzRZ+gc0DMhhaVZc`Ok7e7D1$!){xi!R2!G;l7oh)yY9k#`KrzstZt>Ujua3R{ z0)YQ7IRt?JOlE+>qZSV2{}0HmK~f+n{v-DP4fWq4|2KsH%JTmL`F}SA_HuRoZRY=N z|3AzSH-xL-Uk5yBy)bwJ=%es7K>oL@Is6Z4_2Dptm)n0^wJ{Jp5mbW;sKnD~W@N3OtAaS7RZ`~ge4*^l+Z-4P0WuRVYG`^4D=)m{zFZnmu;c#C#6fixB zf+~bLSBEtpzf@uM5ndirytJKuY#}Z@^xTFF)2%UPyO3m@lRcx015bB}fo+`I3{*Xi zb3c9f9`L1xv(``YP?!_E=E!NEFnMuEIG!AE#CCm>x`E)Cd8#Uhd@;J4;0}BA)qgkS zw_%Rm#=O)I_^Lanl6`K_mw;t-!kZ0R-@Giz*1N_gXSTU`7t?6pXR<7{&%~Fv=oTNk z6k{EgW{`PZSF!a3kmOT&b-uU1ZoE$(6KBpC#I#(X8rYp;RBg@ag`QK7tO&-S}SD&^%L z3?9RI6jmc^L_Suu9S=XFH(JyMLQCWNZxXE=?F~15B%9^Y*k#(n&S6VpAH5m^9kof7 zD+6#@AJdUKlu-LmSsgZIV}E4HD5KR(()8L;zJ4n)9o74_*QXOWu7;{0qV#bDH|h9g z9=T8!M0l@Hd@%A>(cm<06zgT4QVY0|`g!NY%)7oY>zU{qq5u`Gx8izqRS{2)t3i=BG)$(Pt|Uh42=f>3DR_xsj`oQFYd@$D8&0B@?u_8VcJmEG1Z}_Rx{38Vz1YbWTjwjO|s-@)4yku^qEdDlyRg+Me zWrlD@V$a@n&!aIyW2VMD*>r1XA+Y>g3qR69X(2I&AGZl828D^oN+Y#(%aw)o;zDCY2k*5BY3w zrQ#cHh_h4(zqb8WfJc~4JkU=;j176QI&Oo(?z839Ur}C{%bK2?dM%Q=|hHJPZx-kZ9;^n=qfi! zJjBhakM|iypw2#FgIfh5gm)}0ZcA;)kX-*7b=GX$BY%3<=9{$YgEq=KBqd*pQ)UG?tA4*8FJ`vlc=haH0 zFd^_lF`)aypG$b;HOcRdVi9heEYTz;8>u>L};Yg!))^u>(H&W z1~*;)7B`F2>`%pUCq>ED#m`0`v0i)=F-a_17P{j}BDBuJb)|FvzM=* z{+_*J&m&NmUAkq)1>;k>{uPoVXH_^76s=_N;zxFp>*nAAho9@^OJmN~i~}#Uju!MP z4}TN(pqU#zO~l(12}DZ-pxYy;m>=n3ygApRBb9K)m&Q0V^n%Y=zBRIXJ*T5hNMXW|8zs*y)rxzEStf*_m(7S61`OPi+;ukeHZ44J(&4%~V)w^=k6 zc>|XJK7ISf4?2t7d(vrNR{*E&b)VzdZ*&jM92NA9o(BMa||JpiB!tJw_hr!$xMQIS%Mb10%GNm8~POA{2 zU16)KtTv;~7$28;_cTwrSI;KY^uWdk;a#tnk39N}JBz5>xf3eTMOPe2XacyiIUMrs z8&*Ctj~547#Heeh@V=0@V|SbHK!59tPHE3O5A_mXLA{CVX^wu{U+VWmZ_jO1d!&ve zLDXVhYhYEp<$d$~jWe#wojPWLt}`omv2c*tSk3G8VxHR{7I;wY+ze*l)Es{pGshdI zYwkN4Jz!?}nMiWC>Y0oe{nn~i3}r=uy2eatMT3s6Stk^JA2Z{+J9S7g@XH2 zU6b+Gil0T%YRwyWjND-QKB{6b5Q%3QDiN)BkC*X zKi%xAB2IUjY4IBnN@%|Oo$gEBmjx_au_Nq#5`7$t$w!5WCY6qW`#6yd?frwHFQw)+ z*Ow|M?7QV17|SeZ^xJzF_J1{$PLrn%Y=h-Q)1rE~7zirq(+ua!1+Hi4Z;?Mj*6F0B zj(%5QEs&KHvRufedh%kXnVNx0r6@i`J>hwbI)+a>v$azRs(m^k^x|l&uRnBti>2-9 zGQ;!C#gedq5PHMcY(Xi+&E}lPYG=vqD%`5LFWD89ZY0*XEY05;q-%6&GqJzsU1A=KUuA2oMB;k zKmHB-it~}^?OfP_@Tp{djK5cIbsx{F-hk$|&?Uu$ZNVthl9KmiQ@rU?#%_;x`vVm_ z9y1tHpdXz+etN>0D}T^M#n;kmUR68)4PIU3aqVm>9Y%ZN+u31oP${iD&g{Uvtx3+U zzX=aYDQ&v1@cUW8uTi(vfv7NETb*8Du3Ov#VeZ>lFpAKIY>>( zT&M%ExpnT-hZ+#RMum1zDPuj=L2{Uk$CGbQ;G;D4GcG#%jz0<+Qujq?I%USD)!p=P}4u5-d*-x`1VHN!*Bri^W*nMS)B=i zi5~AyUbMAtcz>t+H*n2HWpXFx4h^<4@?1YT&+k-O8>K7CG9M7Ui~&2!xp?MHiy9QA zx~bZ|h!ZgR`T!mwmoyC}N{YN;-xh~uF)zprNW_}5@)jJKx<6bgRm-BZKhyLNQCtxv z6JP?vECk;dlCLl%G1|fR;)T`*%N~dL)~lhJIq6}mY-9$I{%`Frj+e96b}L_>ZjZ`-BFdW{m{$uC+FWgSSoi*Q0UW6en+&xY8uw z_u67w?SBEz-4&?%NMw_>aX#Q8O8bW%d*(!m^g^085C?cd6?yF*htcBf(FtKpO)V$8 zRf6FrI4)I1g`GzvM)OlcqF)C$WJa`%s5a^jnCwmh4K2d56E@sv-0>m)W$;U|3$_L{ zN*7Fj*KU|bBvgA+W3S)n#j&FZDYCOkP1%vF^nc;^e(%8x9SwTVj^yfSjs>u0F2*8c zXjD-4eL)^|M8pOz3{m`pH~zDj z`ABOchuxYlp1Wc9lN*g#ENu!w72z&*j?6nj#S$?Uum?hm*n3Bzlq}!rR?1T{ckM=g zh_`FlrDiUDCg34FZZ>aR)#r7KUnSGN#fE%7^x^wplrbY=uHl zw#9HKHh0y%Rs0BN#oGA3#U8x# zxA$J|Scb$Zl?xTY{8Xrq$J-yQ12{3}6w!?^wa*0kfDuYd0OL%FaW zC4rvP@Wl6IrrDmcHKzo*{NF~C%*7B->P1F6$zD6)ON0ZpMKK3Q4M=9^m>T%KmJI-rg zUGAC~NnC?7`T+{m3#S*vVSmEqMqlQ>l57%e^C_{XKdh4D5Lxr)x;8i@vrrW|dGmitJJTyl`^ z(j8_j#>rQgyA_6^1P{EiN)O{16mwFHxOewN2GFk~u&%DacJ?0)=YIx(f$Yn|5vNbt z8&!4ckLbz*TBWE~qven%HJ@u07@J{v1T!~&S|aufjKuV4-Q*eapP!0vD1Q;8@C(u^ z$o!d6t?PBAKHl8>ngR3BDza{(p)@YOGt_Yu^}o+oC9)4W5M$J2jx=5~Za-7i*Rcu-jfEW#W*I z{SZRZ=Q(%I&E+9mb3?PPj4=J|=h&s@?%sC2ChV$w$YO>|G_d8SnG@TRaklQ(RClsO zUdYJ_@)fuf9A~$=DCxeT)YP(Z?f#wsn@wD^(VR+DVabEi{D0k_MsONAidpUT)VqYxx9)$BuiX zE+x|JIrFiZI5HI!E$cfq^oGMIBbNYWMiX~)M!D}6oNDI?9iM|OdinAS!3q>__W&Kz zUw4xo;;I)NU4Q))>f<}-W3+GgMP1X6@{GmIh(Pyg1!W|Pr3g~A{oM#CgR7k|GDD0Xz<@S;9!=!!ilvMNP7 z2SQs%=U$$TNZ-AE*gVQ^>0(OOG*7$`l`%MJd-gOhz-n)*|Hbh^>@#6GKz(18g^!NT!N1cZ<^F$If?AY3RJ_*G_$(<9KTOt2JVIR^Lg6E z3R6U`t61u(UuwHgw<&2QU5WkXPez~FeRuESoqq>SvQ7eCc3D4*C`k~~%OJ;9(KU4rcfFpxl>ZqrEiv8&ii4fP{l*@5x~6-l*W>O%T2 z({pLu1r0fuzaNGV*P%k5@k>jlKeQomWwVavSR3wmPt2dqkx$aT&wVHs4;Tb@j9I5?%%9NjN`E^a>+4!> zTo2~f&5wV3OGAbFyQ*O@P6BP%vq@CYI$)^;_Rg1_T^M@j;M1jO5#C~f@I#9{Mw5I) zs}8hfMsHvr%-?2x8$xy9|2kmoWtbfylV}DSL2sw1|Ifo!o$V}o`>UpA~-87eWVQ1F6fz7MPe#W1r zyCOyJK9s7PaDXecV(&81w$ln(E3N47)Ch0`0S zEM%yfu{LxJc6$?B*$crErcu$|_qCAv=Alo(q%zl-W;_X`ln~t@sDCJ%f-G8_D<_Nr zo?`(*S;T>)k|tXb$4U+P$)8SGy{iqd@u}I2pm#BECsJdHB6U2jU&F#=-yO9D(^{P_ z$QRLki$Y0nmBo?lJZ>trx;4+we+ze^cQJSAXa4T-z#;QbtOos8L(tX|);B4|xr>N~ zf*k!K%%bsgSb0qqlz&%nW4Gn@O>TlZ;szes&hJ?hqcUR}xH-njBmVhp9)ZrIeRSIw z=Q0nXc$4lgV_AH6ze-0E=l9=M7Y7j8OKOl~E4TE8 z(d{j*>e8HiOY9};Lvb0TT_EaKP%G$^BlKPUnZHqVtGzdWri@C$q^FB~+7{8Fp_AcS?7iL#cJY zkp_dAq%DFr`hOT&-z-H>?*pprO<2jZCdCN@O06 z>Tzmw*&WQ)7B;?QB3|c{C3~q=dR5%GqEz>?M(%Z+TEIsAE#60>2{XYk-M zz1|j6@&TM5A~G3Py~)a_ds<%@j~B)moweh54P0hLUeL)PfCPsbeDErNyGx zpK;#o2!CdY$YVCoT{}VN>`30}&f45LtvYfw{a|GOqxx#pt!0v;I%fh9*5;_;3rVYc zFz8-SA01Wr__^~Nf1^>$EOTyHumbmBvY#Xajrb?pdQOzr8@dhZg&keX?P+)Z8o)>< z#l$d%M2e46#rs&p|7mxrTfP$o_@%{TiN^l{umeFCmzUudKNOd1-9;4>F*i0h3NK7$ zZfA68G9WQAGdMDr0lGjH12Q!+mqFb@DSx*GP@L%!E{q0u_X+Oq?hxGFVSvHi-6cqX z;1b+}I|O$N65QQAIOLMuJ-d6(|5x2xQ#JEF-B0)1{dPZJ)lj@wQe_Y^vo`@s+S|D> zurM<70>tFyKX3trJcXFOgQpY7 z!qVmKnEyNis7+}AEId41^nZi{L~MahAX8&IfV{DbCD8WmL{noMfU3PI2QpmVDA7he`^Bh3o-}3{lI%W8@mAk zE>5mMU+;fA{u{xwumH?JrY-;zpasYd{-5k`W}x|>_-*)3AP;~p^V{yR0GNM&{(jPb zTQ4(vI~&h`=zq+YNlE#GhLjB5pB?}06BV`h0C+R702o*~m;o#-Tz@P8uD1u@|IVUh z4En1I=6^yz*qPe{SeXB;_U)SfQ?c7$3qbvsIA{R>olL?0ZEJx5>VKA8kC}tn^zDn~ z|9RE_2>Jip@ZVYfZ%h8a1xdQv*!Jhxc6FC z1F{1u**k-Nzgym-n3?~__ogpX>$mrZ^V?qj=`wbH6PwE)WBiSQZ*uzYIwb5&?ahAc zj+KKGVC>{%>nA|GBZZgw8g`&X)fWSl^EH_!oR* zc>W8%9pLo`{I98+x;i<%jr|WXzK#4p_>WgB5a6e%`+)Pl-%3P8ylU(d$kuTLUDGODvgyqFltK+igOp(=)dLm8~hfE{ov4P#Qx|-|26`327Un97X zf$!SmzOr2iXA_?kTuHYx6IR*ul_LYxw+IDPAAjvwcyH3-=1IKNS!3T<%#T#T?~b() z4T2Y*pmDC8Q=V$QH%rnj^Na4aNL;O+ekhDeu{hRwRWrj8s`sVEjTC*ho+%lk5Db_S z8#N6bV~7yRlb2s;E#Q7<7=ziu#KWTmou$%5f?#uLo?pXoW2PU33|H~8UMZp8Pw>)b zIDduXXTD03bxiwcb%$B`@CoTlq@PhMwe=@w;R9;e^muLQ#)Hy^h;QD9rGj0~vkN5! zIXrc1catf~R7n&)1qL4xCQBP4sVdQTAsw^Tu;6Cpeu{pg2(5;R09|U@V4ZjH(GL{J z@%Jei0phVP0?D1ok|vkP zn-%Oiuo()2-XEU8OaU6Y*du2udWh^e+8@7uSc#^q!Sq2|2T-$!Mk}jO+E+A(_?uOf z>7@lXtb2<$J9`1Z^Yf6_O!MFne=3-FDCAwWQx^o~kMh9oK|a%%XnK)4KkHocRDTU| z#Z%rX!!%;yQ$oD%O}Y`@KQkF7vO;)25wa}>l%9^RHbsV^F;ev!CD?O^k0S-2cK*_% z;lJEOkMb#FyAp@uW#7_xs_u0sUv|t=%5gSr>Nz~j3NOx~kSHm)AXM}@^I~;cB~qT- znGx+ZeY8lO7RXNcg(tkNhaPKT0Dt&3K`6m~4JO5dyT_Wo1it=WWM=8M9{3>{j7uHd zox_rFluq49VIBXe^fI2G*wK4oXW${=syH_Alqora5FHCDJ_Pf#?9(fRz>^c&(3EoGS{%P&n-RMNku7kDic5El7Axl$sW{kjoKx@={7&5E`L9M4a==CoZ{)&lx4E=s#&N=kMx)};( zMxrK0b93n!qPUf1!hhrB#_qu`?GjRJFyAT?O{m&bbh%>lOX|Af90Zrb= zl%T@E$E%3(dCoL9-y6&#c2>~{L1c*jlIgK)#|nx|zis}?N`H@WcB2sy``(FMo2t&w zDhmql=Cg3{4jOu;U+A#ADHw_p!&2IAHL|9ikfTd;HEGSD>`GlSe^hSn;p2*1g|ciA zL1uIuJH6sAmk8J))l{b0eP=`~m2Yhahy7ed9xJ1oRvNEhnYZ~|g*0HcIG7HRayz6Y zMjy#UjuA&fa(`is+krUABgrw*M?oO6+qDt27T)R4RoptfG22w*fV?Z5yICIY@(Y1( zHnuo6vfQup8hP7*9jT2TCv}1}ge=wWeM863!cjHH58uSdX=}KVxn7*^Nk&`no3J@? zLp2J7n|D4RW2*1(abiQ_Li4rGs2 z2v2qFMQ1?~%ymUZ2$ROsncva<7#x$o;$<{tF&P#JD{j(lrM4%ZW0XuK2@BodVu2@#J#ws#|BlFB6H~wIT!pg79=*g)+pFW{J3y6yNHi z%8ADIc?E_JEF|Qkcfe{~e<>$8Xar(AP;%+=I4+|p+kZHFd2Y~1hKiGC)i>^odjND( zgOOA|Zw9>h)R-?aZAr#Cl|8^Fp?|1oxIKR|xVeV9_zDMpJLc0@%8=x+;30MTat>LJ z5|ahvFGK~iA8pa;wSa9?Tap-le{n?rWtU*0j;y&Ty+x!^OtLa9S=%-{)Bxc`_#-1m z(Sq|_Yy7z&f%$uV!i9Mmv@g>$VyIFt)vma$hd-3DW2ZgE;@ZDzIxk{xBY*W)Z&60p z27XW@K$9E~kU9MZ9KA+4h@oVt1(IugnY5MlgBend@J`9|_)rI~wd7C0qqQ*7ks*?fFsF zW%)uHU9-JHbst{MQt$1slz-1Hllb)iMZdpel_MMb5R(ncFaA8ovUm3>x@4`eQ z>|QAAODx}#w#C`VA*}J}1DP+1u(~rEJ{Zq&L*UrLW+%E`WdW1}+Y)LdEHK11Nc7peAC1l?=%Lr0#kVc9IUBcn2nx@Z3-QW?A z`1*5*2kzR6t0%Wx&VL@t`m@N>SPxt*z|tt)!cs6W*`WEj978v!zM6JC;rJ(Rsv#O$ zcCB01fM3Q~U!{b1wy%65Y78G1YpAgS+-w+wpeU`Wm^;o>8&XaXE~ z*lz1EzjClHXbo~ZJ&*ez>T~Y1&`RJyBtzzhYgvaNep((hdw*xd;H^e+>O1x6kP|#MvOVYG5zQ&|RDoeA5ISnqz!~LyNU^j%BMX<--^6T6r;>TC-aoN`jyA5ch{jD-_6R?Xt;0#z8UOeAKf9<>eF*rpm7#kmd=}9VSF&;mS8fogjzd#h9aQ?0hWJ@vB*a7OjM&SX@CF4s7K$y89oXr@-s#I&G4?* zvN+N=PVn%8nTp}mlZ_-Dh%P2 z&75H;FMmb^vXns$4fK{O8anq-`-l!%X}yRgP0bNM{#U&@oM^l~y?n}qrDRpN*4tMK z0@)Phqo^$^z+S$84a^HZJ5LOG$B!5+X;|@LW^GSP8tRdKzDr%cZ#{hw0%!{ ziH*yLjUO6M{ojXV{3DUa@A|J{9(NQOR_H*KHh=G2h(RuKIZLH<(KOTv&>oJ=vOjkM5BpwLrsg|bDkHzRWF*EHwUeSUxr8vu z2PRg|p^v(^E&Y6e2M!Z)(V0OJYLfWn{WPKGoE(f0S~NABu*!Rc*I(|?_+cr)kQYS# zY=1atQ1+38*T{QZsOXnyr}`7jJPc)SEBL$Jm7CkySGYwU={`qw)~g4GLok*U)1rWO zvkUP?gaSOV-7b}T4ma67iARve+WW`m{fCzN8a~I*C<(+UuzN1?&x#aWnqG<5DW_I` zH9hC*7TS*OA-kvhaj~l1gvs^m7n;(_yz{AI57-(;5v&hbu21)jmVx#<|$ za9-M44HnQCkJ-Q9;TUD&?InqMCHPH6ZoR{gn!T@BX6u3UCLhL7Z}odBNdxWvV1HyM z8xK1loM@yJz_*Qun^dd4Tc(HJzxX&MFy2#Ao{lb-g>8_xWrg&#w;{P@QG40!tv&K! z(*T@vV{%`2=nwP$c`Jqtx|dYwq{fpnr=C?{XQ_(FIk ztln&3M1s&aBStAwnO23Ce16un;(xh&X%Pvn=R^1cB13#%M!@N{($p9!v1 z#PPU@X(df4gA`bD(Q7`B#Ev%Zg*jor_^_{B8R#j-zvn<>+Ypc{+tUQn*MHx3y|1V! zJj(~mT!uqKe34F%9c{T*=FK0@Cc;EKV4gc`5?^E4+LGn%hoKXAroLH-I116aLq#gD zuVLF>V9*0`klGYg_ZiO@egsi@$@gRkox(m?_vtTX(82S6=9|%?cuWo(SNVY^jwujC_bvxS6s(56}DF}7omOUy&^=$z2Zgw_61;6 zaQMy&T!U>pw^7^nlFXH?B}&d{rAZOISfotw2FMFfG%jNOOJRf^=d`g@VI2Dcx7FHI z(eeHxX;ct5K`|xGhoz$g;e?7W9}D4asRc@O+1VYN{2g_OT}O7Am46JGJ}nj>3oVhl zCbpc0Hg**734g2yR89O?*vpAZjwChVq*jRi|`e1Em>Gr9fK{^BL%dW>0bSZ8FCeu!eLI56t&z0&eToJLlP!*k~T zAV$1TM)q~y3PDgbw|Kw{R||~B1MIj&QK~JRN0av@R?Y@1hnKnA41YDa5-YGrfV4+sHys4AO~)9|JwEM(e-5VsZyXT+owc=v_&D9a~`GfDhkY5g=ng-v1iZOT)S-)dzjp zjHGABA|9N7H_mUk?1dj;+T^?y7ydc@m4-BHs;GvK4{P@pBhiQLwM;35(JG*R?~cX$ z?D<1B0PQx`fq#rJ5yeyxq_nIEr7f3?X5df@{8~`)ZeP@6x?b3mo_zw0jFz@tNt+d} zY%446>rlYNt>>1-f|_9Y%{}?OZe=pMR-(5!%b^R_g^=u5w--RosP}8$eCxE;T4vho zAyzo)Fgt~}*s(XnwMBoK5^f7^(-uo z?sQpF@M#WlwbyHSP)e#RzSH|K8%cVr3;rs9EnH=D53%j`&sw|)*O?SEHUXc9+Z;!m z7hk7N?0<4m6X6MtzBP9mU-6rD_8Cl`IFiHQp|mzz;_3FsrlxXz_JMr_!)}hH(9Szp z4A?9@_C&l^d>#zYz<`*z3No24XE|Mj)aUWde+q}b^hXF|y~Um_k5?1HsLU^HpBQ;S zB+h}d^AeIvhEWy_L(~b5=u(wG-0CzwyMN&BCx7fGwNA4Tlbel$pILY!EtyRG5=T5~ zgGrWoln29uohTY0Z`Gj{*yVr3HeI3)CxO@MZ=`nYT%z01h%vsD^PLd3R-tPB zM+(qti&6Yw6y3EL34v8nIb^~ZFXzU}R5jI%tfchbBj*HUqP`nSmT?Tr)z3EoqATP;;C!a*=Fb;_@V7`p+*8IUKO z4VF9iJ?6pjkq;gC!nXZ&u0Y-DUgSs?e@3k;i`@v}i!b{JCDzK)(+U_G?I+5Qogas@I!I5W#^Uj*=LSIx6L27E zioIVwots~0MdBzDjm2_Tc`kp&>85^G$8aFoAf&v1XTs3 z7G-7EoazTXUcdBvVoF<*74dA~rV90g_s= zXCGm+`H1X8UcC>wTBD@+?;3fWqJP=hVx(tmS#_srDo(kzh^nt+4apxIk*0A)*I7Rg zo>4maQSmGS?si=iBgfZnbcL-4EK>WinIs$Al3;nGz;u_ag7)3 z$;_-$Cn*0i9Mu5NpE(ko^hcDNU>dZcGMjkn?=6ItN6K5pj_4h?6J z@Tg3I&rQ7j{rA!_XbN;|W6I{vKpqpLs(mexX8P!%*mZvVp}SRo!hfX{Tx8#yuAcFj zv?JKsy?3Euw7TS?^ift3nsRDtAix9Bv`Es%g8rR_FTSS1@fm30r$o(5Ycx~!4r|GV zTNFqcnyAR8L{h)C3eDyPu--~01jI?6qTO-H+oq#v2nLjdfB#{DsaxCC(nk%x68nnh zt!!^q_tZ`M&Y{iS4u9%JlA9C~3}TRNc`d?m2b;JjomL#40(>Btklca&WJ@Z!xeEP` z+U%3Aie`FZ*o(lrz^94Tv+ULd{Z~0NYsig$p5FISYrgke#89Y^?WAHzv~HANv}BVZbN*RF-ix_G5bbDknngcsP=`33l&D~ZnM zj5vNMLDf2DvPcW6(x`vkS-6E3nRIfi6Wro|y-^^wubJQI+9@fV?w@nf(wI}x5+8ik zNYMZUrM0GYmD%%*XNHN%j(~6&G?8N&W6hA$xPexE`($i!H%yobqZhNELb<;5x*i6s z6ES{vJ#psEi9oFhYRj3(jJ_>gt+p5JS3{}(7&NHJPizI(h=zaNlR6Kh#i1)5xJ0bA zXoAESBQT8UDvELj^kz4GV$^e@j9Y$Z${t)%KZIID%X!-(f?LL?X9YXA# z3oW~h_Y`xIj#2Pad02`1A>#^MHdid0Eg54%B1rgt$#bBusMT#W(ULhSFD$M3V4q*X zAQnWOEVXY9HF1Amut`4}OiO?stx`$%Srnqlu~Ozlurxrgcyplr6NX~id|%$h<3xaH zg_o5np%UqF^r$}s%ciFXV{$C1tT>Eh#6i4uGlV{c8+qNCjylL=^XwL>`JMT}+n;m@ z+*>t=3Xh!XeK9rZt!4d5-m;;5a?b`m|DSvWPA-~zq&a_hTL#%h{A8nrA6`lZM8MnV z(so|)3pc+t>?A4h`J+0sQIw1>r+)77R1AAzPjlZ0PqGQIY`+xb@EofT9;g%wcF5!Q z&1UHc<-1c_T%UfALhz9W!lh^cZ;-q$(F-`RxDAcZ=1My{(W;$AJfEB%OD06MUp5Ou z{J!8e00i(O_dV4VJ>sQY!=?jya0 zql{Y2)}~ic9-LfnjiNtgJ+IL_waA@Rtu8{R0y4}mPmxL#{`1E4I;YjrP^^xe2_5<- zot{1R&oHZjnaoLtPuGD>e#s7>*wN!3Up?Izr5b->HN;R969Rd(9G=QcuLtA0wtK&Z z#3yrT21FHOU)wW?6^_&e;oA_XZaRm1>U@z7M=$zTQy1@c@{_mGAcgc4u*{-PAei@1 zr#7Ppdmf7J0H<8u0OkDbr+)tRXRh@cw8~VCCm16^bl9T6HVh>vg36!0sCTNWJV zDYLeIf}mE2KMj=hB;Mk~s8+X{ERL~efrZ5D?X6I-6mFO+F-c+{`wwec|GN?#Bo&MM z!wk0IB$f<%WUv&^gBm=Qu2YF^{keY&os}@+^1}Q*mC#LnrJwNzU)%sw{aaT*h~NMx<@{W=wcy6{_I50$ZW~ zOL;H+3lui{wpO0a(0-lMQwge4aVZ9WQR*bD1oBx_ZjX?G6}u0XQJ4S;Kv%ne`{ugv` zzwy0tWbK*br_iC+t|lu=e6&V!0EBZww0-?ldnVaC)gFin7;cjC*c zn1jrP8__*I$bwIJ{m~4KCoz1sihpQ^bNnd;H$^arS;6qMxFz>)!m)oYY*~0$OpiD# zWL!9Zin?F|(d4>pvP<~j{HIfN@%}fF`Fkh5rpau@R}BgQq|7@k^f3-A7-4Yvj+`{ds8kWj;+B_|7vqGLPVeH7 z-$BMf8y8{T&e2w87k7U=37Xi5zsIkZLy$nlGp4eHczncGw>OQf7#VTN6sczgzVWpa zwy>jWrqh4hW&Vc7FSSc^Okf0z=Znj&L4x;JrzW*%dnna(M0Hzjc3ZJEI`PYiFxIo1 zkYH%2jF!(k4p$GR9klEcE9n|Bv{rgrE)j|4#b_ddE3|3-s}6rH@uxrUw@AzFx{SI& z?TbRgqjc22rhL1gC_qLQ$M2}!k49UVin^H-bgNG@9`)?wq6(2|fPZJoy~8MV_u)gI`Hn;@_dA!=)Xc%j z#NZ9wbUE7U%^4x4h91KXGjOUsR%(Z~^bL90t=0DYiwA0Db$G1E6+-I?SSiZjt1>e+ z6gFyjQ5BCHqk~6(yjrsnhaZ@md-KSg2z&wLg9sFTqLY6oCC)lwE+e%BSygZAcWji#`JjkUT((BHx~p~F zEin;X7;k^oa{-XgM6@O%<42pbf}~l_=t4e+Myq6#{OYOA;DF=8Vay!LLirM3;ySnr z&3dz4Dqg{g>W?&8a{qAB>15cOPA2emODIWaUa0=`MN1qMEO;?9mVS65!hf&IYIyVl89|1Tuc7Cs|fQ zxzQkKiin>~Y7DAd(y%SFHOMEIW)jetrq_kT(2Q(E_2xyUFQDR(LvLlz^I~O8O$D6C zL)Fihd0-zHX(6!pVlRKH_gHpA0;NW!<6<~8*5SYU@4|1UW$vm2cDMXh z0A9%KL@g{Ya0^T-@O48++G>@Xddi~)Y)0nF_el|{-^2X<93QH$5SK7iEjxxJ6yrZ( z2rM68os4<>wDiysqSf6VEpxyN;0T8>)K9_%HNY$8@ zMn$HC5oA5Jvy_?>wA;}=U0p>_pABY-q{P*&2YhTOdkoSS62`=_KSaf&7m4LAhV^m6^wz(xY_|{WW;knO9rr3`1OKr4cAy% z6;xrlQ5(l)8K3?OtdZ$eGPx38GAsoffh;B7t+tA|LU|XYiC;N!Mhdv1>`mi0#}RFp z(vVCzTNFK zR%^OD;6_CR|LLwnM74iQeiq-^n$;d#8j=v@92`i+O%pb7cope8?b-lC@yrqk?bibN z7>J+NppNL)ZecgB|62&YgdTQ}~-bbm>Jj&l8^r zwmFabETQHo=K~iBTWwI$&9wsDU93oBl-Wz2;N|?HZLKHN2_8BWKjJnv&$AsZg;1}0 zD4+>eGqG0fE2gx@x<@UKrDT!#TvA@GeDbXf5Lz}ns;)Sl*yA_RYrxl^a6IP>3}|@wUNUfzYbq|WPI`}e~{Irh^D3oR_@bK~OvPNA-R`XCsFkcua z3Ey5Q5V&(p!1XeEK**5T1n+6p^P#KF(d0dG1=wDxdop(Qz2YUHC11%Y7h2q5a*}+B zv1vz-s{(%ktusE@S%-<~Ho1$mpji`_S?F_xMx7yQCZF)<=nINC-w^&70hlMvT9`)4G*K!d2e@VD&x`$mUpj< zVrGA3JjHjNnPUudOsHpEmwe{PY4M~DINJzmj4UQa`%EwC>5K}gd`jTC^_>Wml>{G^ zoFa#EF`qdQ2TpSG`h&(RBK=Za3S5XMujPnD2r^l8f7EUJkehx*$%-zZ7286F+m_?psfPVuk3V7mDCS-2XTKz_!FsYVW5xek>qAn1w^C*Oau z*`Ws9vwqx-%|t|kPswo^TAeC-$Kept5S=IeP%C^Q8SNS_l~Sivqfv=>)s&motElM* z1X6y}SvwmkMw}rNOUUlYe1V0_15Qgk0=>wPxaPgtTBJi{j?UPPqsfQhda6Ykfk3rv>s7cipMfB6 z#nxPskPynEXFi=n3G_ZHzE)apaq36X!b*dua1 z^n20Ext15o8^eUkfatZpO-ws(MOx~uk<7MXg)cvQn4n6Xf(&BLr&NT-Da1L{858YcxKC{l7 z>Le&zLN(|l2%(!k}x!p8$m%zh$xrVUh8YM z9MBu{M`L~3l`SAC+%++G)u=!$VLiB_v|iXCF^^LlU|%_IZofJA4HEUf_c^}4V3pGO zKWkA_mqGnS7MFDLMH06{#Xm|Nmmm5?6PF;yMFh8_;y)cMmsb5n6Svb2KtC#%!~;eX zweO7d;__TJ}w`!LdK>2k_|94)|#j!;)l9xk9LKu%qUhZg_@@^Jxy zyy%RKdJtE8@Ly(hMgy?33&asB`mX>vXRx{JlYdR#-1R9=-4O~r;i;mfxjjJF(Gmi7_4+Rg7I7O_SC}X_w}*!Zm$`!rm!q?_ zB!4RhzysoH1JD7xfSujJAi(c|0UG8G;6EqhLT3c%*+5+WwCg%rxq6s8g8@$ldx#|% z>hhG~1_gng0Z+vNx+-b_O&A#ZXRz9z0UUt8&IZ84#q&4aU)jHjAkaUO%`Gh*9bo2A zF9_5cUmp=YItQ z|Ka5MZGM`-&j;oR16Vx`0rrDffuDZReO%1l!2nlhH?W`2za9UL(0OzufXhhWbj%?0-)D zw@+5q(G%dq$;S`i7NOW1s-g^687`|5@pOr2PL0{5Q-0P2>ODkfNKt{U2_Y zKm7k6x48qv-s`V`C(XLKKIvcG@o5X7{~P)O{O8W9gFz5ChyV4exSBuhfqx9t+Wzlj zgt#a|Ji#C>h^wW|pJMsbuK#<<>>*IFmZJ;g_p1Wn{ZmUd4shs%>9|8Rky z7U#c9DnKnALBBVQS3nS8?(A&tg${fY60d*&z=!8)6+vLnKQs*B=7Ku9KBWMj#`6PM zIXa{NzEME|0JqF<)1OHANq^;Ke$aqC4YE2q!AbBEgvHfj=URc6qN^My>(&}ZE5 z8wxDv(hD^AK0jLOQNvpkwcBoe?_S62jBmA}&wV5AA1nAFQ`bj@M#-rsz3qGNQRKiW93c#83ZMb@=K`2!i7UK0rIG6FH|R>gCVljeUnq?y^G31RBOlzA#9=MAkSvDT9TpC^?Y-kq2HdCN#=?GZ2&aCwa+*{J49s2G$ zs4{h;>OB$RzJIsDW>0v0W|`sG-?csJ0&*ZTg->E^Xb6(nt!_=qk;h=CcuQQDMdfxO z(n5hu9z&m$nV#Fi*Pw+l@YjwsFM%8Xxp9lI?MBn}fVX1!UqfAvru5cz^0h%)E zyV&a{gz&XdH)5r4YohYY_~C1+5wQ;}VR@%7Dn6f%c7L88ndEZ<#koqYb!BldHSFIL z7-eh5sU1yzh!vnP6{+tbd=M>u-pYpT`%@7;DCE(nClas_9#A@?z_CJ>ee2YYKqA>; z3p7pf{E=L%-S@z3*t2)&zZV+W4k5!F5+n068qzv-hr|}Ewu|hpC}CHRi3uN$Z?SS5w8~gLnQu1UG4Tren8B=OY;Yn; zF30Y0QDY!T_tqy=>SbfbZ5pWMr`RXdHBtuYB@-l`6B&l!pOzFbNYU_f%gwRe@!h5f7OeI(pFBGPNg5&BXN)H zbreG?a83k!f84B-qkq}_i-2hW*xp(~5EsOp%((xjQV`}IIlH<=I$aFVW?iOP$KC~qsLgHKdV#= zVxio#mE2?l3qm2&b-Rr0kLRjl<(63J8lT>?onp<$C{cbYDp;NO%}AK)p^nfmc(fd? zT*=$T9xAb)@?T37oUln3M1Fe7-M(GRmyy+Apc&iYxOKKH ziwYlKf~nmceW#rGOf|O0B{k$VRsKkALK?DHtp7Z@ua8bpUW{OGefDsQY|1+!Ta`<4 z)IgH(fWcJW6!QBzbHd2GVn)ozRB0i84CzNWqJ4gr1j=?U3HYCYQ5v)C34a@ASoy>T zyJwR7sG(n2t<>8QJf#^vJb5b7lpxc_cMTsVbK=;TTKG?3bI$9YF?VYMU_|QNccwNt z8Ftbqy01rKw`k<-O-)fo{1zHHokXNt$5+6Q%V^RyZ4X7LxlO)N9_mrfiI#*SD_TS> zo7v)a!fmKkVo9Y!1IpZq`F~CPDLMdZrl&zdUWL987EREX02-G0~+ZIrx)_Z~A*f9>?#?SGTtdaB&aTSoG} zmwM;SI%m-X~P14qM8p4+#_a}(!o2EIg_zlL~uky{LQiT zWvb}dA+nfnM+O(Uv;x6R2;~t((<{8B7@mv^7g;y zk6u&G5IS~QoAdhsegqcdBC%B>&HloH#8Ny zD_L}(tWU?Q=}s*TPlp5>%!XB-YD0Z+QyaQ-B&3-QQkt=`IC7sCJMzg zS`YCHCz>Pd!|FCgF7-)lAJUI&V(BtK=#51}rIdRw!Ap&=?5ZjK8&w2-f=sy#2N}0< z;uv1|`}8oJ%YU(IL@0UinQb+f-ewX8+<7?ZE>js^xbW6gj(1I8mXc$H$fuDhI#ZI0 z>i`|x0s_x)Un5%6KAcVu1@l>}nu(u7O%R92%ou)t3T}%^jmHCK^0W)Y=Zl~DwmR@m ze(lu+mTB6IsmctbrPsAfnik`WxaUm9d9hKTGOIYaHh)i6ih?xgk5Yp2->XehY@6$N z=JwEr-hpU4bTHuGXZS~?H?W=Lq6BtrifreS=vMa0g9z;AddL$j7^-g!P6onCO)409yO*FPmJl}4 z>?_9@kXb}to{aj9mPJT(7$>wKK76mr6)C}lzJH-GvftjCX=oB$l2U=Qn`|KfA{b}W zR6rAm!>ZBOv$-K#vUl$iX`^_}3V%ICHo^dt%SiA4L50gc!qTiBi#FZ9pml5THbE2i zVR*pRQqHV(I(HqI5!+iEP$?`>{!)gek9jX4f=4wSgB6p!is1dE#4uD!0Tvs(X6}TS z7k_13b-mBb`sFqMJXNRP^Oqm0*c(7IlBSl+25$xX@qr3P{jMB?_k;vwtmTjkM6f?V zlcug>GDiT4S4063mKAtl+wKoZ@mz&=NYivH+#<+pJxaFbf*A-^&KD0%o1ycc%rRb; zN)lat$g`tgt@M!UhV`t~KaM8$+^@MdWPcG;Eq!tk>;*a3`V`)QFcUU75+|g8 znXu0_#&<-?E#i2$oI~+^koJH&2l|y=&rhN$Ihdvc7xpM3o>tc7nl{&f1#bJ9!&BOw72jRFYaz8Z$A;^W0X7cx?lr!&t_I@ZSkh6e_0yo?s7&U-I7M_YF9?brs_M`I!;40HId(JlSi$p}de^r}E z*OqsWN+&H+QGcT|9#~1E%TNO*6Pe79qVHm2A!Z#9PaVUlCb|=S$xT$gP&oo4FrQ0) zh9kQ1jmPtP;Qg<`O|y6ugHK5(On(Xr2swdLjh48i*fUpzm~x9L18G7+wVY-H^9)E; z73%IQsQXm=#J+W*OfJ3AUok5M4QYF=>7k&p@K=c*c$*=CP?iwTd~Ay2lq1b$@$1lo z_l~^S8{$iCrDzBdHIxHb-8cx;;hySoDqW`N9cLA<7(nuR`$jXk*O(JMwtu}%t3inn zUrnwZ1rZMmU4&MbK3P=nxV4$|!Ft+;bYAOYgo2qnLctQ;)x}W@R7>YnnwDRS@h`}E zu>ED|R-lG?BPTo!@NN8|(D=aTRNb0#oWvS3AJ-&ANUQ}U4quphj*hS(dj{6`J}zV{ z_)}MRFSrVm;QDFgoXx1j%6|`syiZ7t>?%tyr0Jp!j3XUFSVj(@Gx39OR3z-``xHN~ zphv(v=%51;M=Sd5%x6vv9Qe^kOKr8DFtCf<7NwiX^n%F8fMN!&5@qrABUUN)YHx7^ zcS_m|OY}gjEuO?VfgG=R;W`R#%+?tcgVv3z;QZi%2w-36@Q2Ai=Dvt#5xO=ZbJ1=SO;xawhs2_VNvOPIkex8$wZtJLVl3P zK+yJZ&D?s0X=?=-$m=YTO0M&l<333yNNdusS4^SrCbcxe}5kdcXwFctRrDOzwT+v zshc1)DVNZa^9#BA{+jpuz?9wnIUxblkA4JXwFV@uH5T9A)c@ zx~bodNf<~?)_<*;#UpjFj|niXq{@bKG}Wma1N0@_mGkU(>?(w4Lrz%y!ml)q5u?V<3Oro)hcn()Cq0lPQTq7NNe z@*Xg{GBMkeY8j-P3be0gx;n;R^&c&3Ac)TRA`AY!MYyGP?(>54e${4=Es@W`KGy5L2y7x zrVO8y!bL2X4sMPtHv9_mR$vOU<(R&&=C2a=7JVv)dgpP8`S8fNN(yM)ef^Gr*+^18 z$LbpQ)PJ$5vzUMsxybO`F^;5mrpBz25d<~3eC0AT-Z~`=CgBq{`5I?14LGGdD#`Mt z-t9%lWTCfjhTcg1hJlLuMwJ!YN`8poXCl-Q%bm&vQ}L8c9f47IPLE2qEp?o^cM;d8 z$vi;@c}19zaH-9_AXQnb&|I>tA5=O;2&fRBO@C$jdVU)WmQeUy3hTZ%?dZatoHMbr z`=K49gwj_meg_$(caht~dYLGC80smRAzBqRL1ss=sfZ6|-qAh}%o&*xo|utGMC|Da z=wC?0e~P=#CWvUH&v%ck*sCa0AUhqgiVsS_=L^9#K544pUE`3{eQV!^Q$Xzp6;tOQC`cN<$;q>MPVRwj(^G=E(K z{ol20ZIIeqwaeI{u7ALn9Gb}qU2CB6Ym|<7J=Rpa@reBK^aUZ)P6;bA{q@(`fa>(< znOpV`Bn(4wyxWl1X&+^?yxozG%qUId_6AHW*>?j1$D>XF%khp!tdx6~Z>9^u+XSPYaHU1Z&uvvy&3`%_;D$eM}lJOwfNQzTHPIMT#(?V`q9=f@i z=7_J;MkFW|`NQ(sSH3-R#L1pkhP8d}Q{M@7otq|3vuKLdD$I{!g4^mhzJGl=J=Sl2 z1zf%axRt)DvH!*5*gpS=G8Je|o@TFrbKsHK)Z9H2!X6Oq4?6=b)EU|nzLPg}qan=8 zR>EkZw%}Dq09RmbMY4fsXRlTuI*W#$!YwkpDGE?s{3K%?q7Nv!UMUKbYdC=!pApkO z2UFON-RX(&kRE9z7CTop&VQeo==t`Jy8+X@S6`?{>F!8W$0Z`3LMh;v$b%>BGOjZo zdSjk}r(!sEV|u5rXk_wd6tm{+>bWh9&o_2!-Bp$@w}%j#Fc3dz<1gc%X2HwXOzofE z+FiLM=h;X$rkjPv=a|QQ)T(BAW6P*j8P+^FB#DFGp!C8%NiA?(3V$IjD}1xz_`2u< zX(|3AQ+Je&+c_Ll2ek}*7z1u}P|OtLO{|Eeu@)ws5)0ijX5V`0_5FE6*xCW|(5G&~ zqzPO&?@%Pl=$sUGy2Q-@ie|!v=HOC;b>*nEg!2Wmh8P~Dg`7)ej6IPH6SwWAYd zL+~zfoINnzXq2*UxqrIaTqjZVAVd)nPp~D5iO!^tw_FWkc&n6`W~=TD*EajA9=+L} z8QmNp5Ut-XKGTj@CPQ+Ii89!+~<@wqT(WE3h zYFIEkf1B5|bP3Tia#rj&+3BCJUeYwTzduJSr{Xlb!;4Oed>?-@8c$nT%<22_T*pA& zSr84xfM*+XS%2nH2`0~Jt%x~fVdOI7y7-0V`Y93JjPzvCKO%egqW&F}XUhhF1N9zX z1nXq22GB#V9X1J&X!A6d3t{s_<~=`w z30Cjg?cXgy+a}Q!myk&8YmEng?*^w z9pv=qn#7v4T^}emvR+k28LgD!5l|kEO?+%90Ah9pV2t z`4Kk8OgAu^OGfp!pR8`B;k+|{16L7#`-Ogwb$|0M(&vM3FPpq|B7qe{Ef~pY^<0onZ>X6lP}Qa;xU%FYC;cLL8Oo1=iUV| zT^FrE@@INO|I(6HfpHXeoY2JeWZ*+KbLhe%ee%b!h%Ps&u4jG) z_{Xjn#v%Bm0ja)SUs8V^nXE1Q+ji?|KVP`&=~#d1UR0Jd=)uw8N{du_Df1mm%lO(? z#pdv)R`LpwlAG$N2NkU$+!!}(pV31y>-BdLlvpKxw{G3HF+=YP7A=H)r)e4htbB~GB?Dg6H zs((Rx(Sgd#r~Sw%ohf;et~W_7`HY`3aR>y{BeR;pGt6sc7+QT?FpUjno0q%JLYg3@ zwAdE_WX1ZXopM0?L0Q4fKj@on34fLziLA)o!OM=KEY=>+mmcQl+>u96f?Bn%2)Pcd z1c*r9QuWE29m?ML43Z=GVpAzMiQHNe4-(|7>oMq$yeZIkILCd)kooE& ze|>fBe$(c?qR0*b_vU$Rh5f6Lk;~EaG|o#~pOfY?OqdROtJ_jR#1zSO`G264V9+&} zjQ}!0XQ1z#lc{|Dc>i&K2k>IOaT`C>NZjbfLN;G6LObrZ1-e`dj>&C(0D={pgj^Du z+*!-%gUaRr6I2y2yE}ucPJ21_A_HcKD`il*~?Eg$;T0~^`(?1)(9_J zX^*+NC_0aF-%e>&nXj$GB*h2_g#W>z*&o~!-*E1rKe#FXm5JKUlR~=TB`N! zM&6XR*rd~6ys51dJ%7=e$NtbWGDU6W!+gAhp2gGknP9-lAdioO;bprn-gZ}m+t^h3 zyJ^t`-Q}ijB>pnN?q=Gp4RPBo&!89twJBFB_RTttNW6O_ccObyP5z$MyWXymxf_M; zxx3zU-R4vHer?i${W{%~n0=L~o#j`uski9JWAMm7m8L?H#(#^HW^KGd!G)t`9JjB4 z#QT*an91T(;XRes>1G#R%fl+_nuCp^A_#gsoawa!=%GQ$V0q#I$WuO(8vnVq-&e^8v@9MM7pXa#!x! zu<;M6_vh)H*-D>dch$p6Gf5Sd>Y!xqpBKo6elv(qvhh;rcvOqjm)12 ztcW}`xC7bTJS$_`MZ9wNKs;Q)piB~ys4%CS=FTT6{C^oJNJ)E8;Nx|gS~7L4VS`v8 zg-2D9PC`k#&xMBrSH`Z7I`4my9>JUVOmoa9f>H)59ye$E`5pQ)fs-kR;Dq_})318N z-%tV|JLsG1094+(DFa&7u)^|b;S-Z{I5|T$jD`sI*A~((aC3~?5k{9>dQZ>(Nt`}tl zaoWPK0jaHQ!~}vK290LD1>=qH6UF3;n0s$44S#rZ&fb@;(x8^R#rFg8mYr%HFHrF! zHeH{;_aJ-(?F=JdL_(6-Jabh zJAch?jcMn3o`tp8n4pnfJZg;LJg*Q>N$P)swDT}v+^^mk*iu74WF)L3u7-tUVM`|Uyu>{i~7m^9sthotTvuG~uQcdpjaTs@2lm#68=U!YK%E zqECOLOS2Th+m`6wEfd*{<{Prlswt#y0PpQ_;J?jZ)GF=g)GdGUDg6l6plrY$*MBLN z6@i{7R-$yB+Q5@WpvA|9!!tpI>HIybj8Nv$>!m)8z37=$-7Nm;ixU}J%K*NkNG-^- zPxJ;6&V%oN|+NHG6iyC(=>eo&Te3blTQT0oqk%%*~je?#P^YpF1JHd zViArGIJFnWg(-xKY(`#)&uP|-ycT83GBKg;ilA)!w>!Bu)zdhB*P6B_CZ@?;+l z4$(jIXrW?(;raB0Cvh7F`m`I}P?M80a{u}&sk8U`Wm6kExaVEasD#Q8<0hM8T?PYh z7h?dyuIJC}PzHf7$NeRkj(^~{Mf+St=a_$1Q&VrU!=US4YltY2kv1!3qCfwD6Z$kl_6TRY}VKFu*u zR5@`^(8BCEKk3q;qM>VF+q@#As*sk{bMmt;n9(sGgX0 zL{gT01xK7pn2;`t_YeY?4n&3`GTQ9sd%XFzScoGQ75eWS4&-MhBNO6-E-b*5N>#AD2ZNMijS& z0YMQSmxLik6t}7$L7+yL&?iO|w_avJ%rloeE=Cl$KAJ(oLYJUWMijRc-9gDXm)cWC z6qg{zMFh9?6+)RKmxfzL6t|)|LMR)ToMJ{4x877jn;`)|BLg-vHkSdcC=|C~=|Zv#12i}_myv)iCJ-?&FgFS>Ol59obZ8(pH8+=W zXB#Ph&0Jek8%eT$=U4RO&e<^Cb+3w;*a%~6jBPv~u(3U}^B{u^Is=FSF}C;DpUf|- zTh&4>kj+M%u$8K=OIGEjvNE$;sH&-SrxGEdQmB+}&@EBP za6ej>GCFQhNmI!;Tt}<5-g3!NDWODIT;#b_td!U2M_7X5R;{RHc}beEBw*IGf)to8 zrm#td=HNBb#9T+HbmWpDR7Uao3_3Gr!wpVziO>gyIzk^T>Ih46sH2HeU0&Obu|SPdMXlfMV#f;5W8uqQlw!{Bte?3ya~LV$OnpZ>J=MS6i-U7q9#04Bn^$xqev`Ciqw;Tih*^H zw}@v2PsErFO_HEuO5A}ITN4{17g;AgNs5Yr)ia@%#wtT2v?rC;idCG7G)x6r6cuTJ zR!q0%t)eYs*Q~DE+GgYDpa1o*7F1PzdGh)4>f}@Pd;MlKn~kq7s(O3;_vC22zq9p6 zCB5o{s@|Etol;ZvkE7GkCH32XR6lX+KmKikr%(8I(=?A695I+Nm@xR8!I;6n8{6>r zVb}JF!4-p1f6$b{MLFmVgR_3u&s|sGIA?JE)2#(xkB?@P>BXj6w&a5jC5B&i)AW{n z(9MaiCtZi@ve%bx{pfmHw%w04Px{2qI@(Zowu(0W|4tk~4XVzPwZ83tI5xoeamV3N zH^r>%dih;TY8j}PDaT$n@lm(DQOAo(*D&g)?uq-VKXTHiWiFVTuJd@+0+(>@Wrz2o z!+X9&fJe91cF|w=w@#TSckCj)Y3?n(7u_UBoghASlZF@w8i5l1=6 zc31tmufLOJW@pvxOSZ&epO2Gn9e3KaX}6-bX0}|d&sVbd(+c*Uugl&g!hPM}JJS;X z^A79RuGeLM&YlofYw8N6Te9cwIJ;JJdJQ}O0G@zdrnXPI*%#J-zo1P2>H78fIhV-s za$P_AG5p`{8ce-&aAwc*1{&M8H`&;>&E43x%{O*7wr%5$v9UI`ZQD1W@9$RK`)5Br z)2C~u>YUTlJx?#2cI-=+uFQ2$3~x1)FUEZcmnPl?8FpGd9C{OGUi_%pSYOOqUvl?cT|^-#sRLNL0BgM zj!883t<$#_bKf%nU>1AZ6gXxtX!}ki+Gt6ei`JKPZ&p#Dme~y#uQNEt+as-9XVppx z5vUh7si90aVj2i%iYM!#gGs$xh>{?)E-@q6Hyu;~8u)I?PAzg!Rg8+!q`ab%?tnAN z4(h7{VZ)SaR;7SSS*dJHAUx+$Asw@q?kd^^o}A?rJkFyBhrDr{#IL zf;l6rG-wnbb49d_mc!a5;%4ox6zsmFUscc=``y=nU%U|_XG*Caa{R(tt4Q92Hp_xc zY8w+!L8lx4!4^8m$mWa}`Fl!8K}?iMC(4g9av}{{4ghV>wCYse3sJ=)FqNlSE+*m$ zbpo4)hEZE~1ILQ#L*J${OTkXZI#TUD_I`Of#*CFNqZcCe(^{bqdwZ@TQDc#4?$2Y+ z(tvhS(dawLM+dBku6LYYk+8jHg`-fBx8 zf`evG5J0V}eu_UD>Zr;nP?Ms4R0)l$oM1(WVwI}Np8nCcHwC%sgH&R(9tvKDvd#mq zu0lGP3|G%9(ny|PiD_1-OnM?TK0!HRyLzex`aX(Uy3;t>$^ti_nigFce~_gzS;0mv z)h|8o`i6qz1Eg+Hk`{GuD7h;PL_0IkSinCI0&&7tVLn!)p-iW$)U`t)%k*a zTR=Y?!u@F9g!2@M)nT~Q_!&0hO+YEduE!denOGG1#~ipDmbp@aODXahDW3_TY)WJ)0)$EhvOoq$%bjB)-8?U*n*6PHgX z&U`YH#DpVq+S@lX7eU(0QIOI<>-vztZU80@b?W*A+FU#Ysa%`$S`RTI7YXXoWG6Uws{t!Pmou@Ta-z?kKT{f)X5%9t4T)RLuzB`N+lmt8f)9?`9 zJpS`#V{e%d8q0Fjn*5<20zzt0<1VuPA6qNM-8B3(z{-2!TwLhH{wFlpp7FSJq=0^EN>p>rq43ikVM-> z(fWCjGPj@MiA`Blnadc3eeSqxwBCEn*XZc!|Cg37bFaw(}CBS8O%HhrBj~XSy5M_k=aIR?zqAqC3$U z72x7iQ5uaGq-%7 znKgr0StZ3_k_Y9}u$u;*ca5A`d?)e>An9#%+t^rcLawc%2{7r8oyUom5+OMzb@ zt{^|=k8X+uziB!1D6cye{e^%81H>l5@?M;0k_uY+w(Q7hC$5srNR_bs^=(|-V;kz* zM)wfW%QyQby)goSr`3G#`;ewk&M2-U1NmPeJ+{CN3Qc?hrtZ;U6_JsDZg@_@ijnH= zahyyws$et%D88wX94?*}FwLbq3RHs+Odun2MM6|Zi+F=^Br7P0R`WYhS_EdEX z`tSj>(#BGSrlU5$8jXR%14IN6S(kQgM1I@gf>I_A0ZK3{I@*~C7c@XQvM?qMlOI27 zd?6-)e6SBdo82rMPC#qPldDD8avYH{;WW`)ozPGErj~UbLv0&%nlN2YOyVJV;NJ+R zQ!gI{OH?=jIoU@jKn@|nMWfRWu~hl@;YnRobO!xoYGD5p;~!}kj?20cfZVoWA?}LqIo>OgXD`e>{Q`` zo-70Z(XfS-@>9_D`5tu_K_mf zwsTE@Uf7}ZnA)R*_p%>EiZ%LAXU!Y40c+uyI3kxcbVA*3oD@DS8w!^rzpV44qR77% zF`3AZlrB+{L$GE6f6?($>tzLn7PfQRs&0k!8g|^;hABj{4noo7MszlXlX?8D@jU-* zG#v65Z#1CV5Fj9kEi}V`s{HfK)> zsw5J+MUjkaE+fQZ5JFfXE=Iilv~8pvObtb3BFPd@Cy?A1n4zW$%~&oDk7IVszw7)( z4rI7CVh?>3fp$rF@PrOakWlN0}uQjZ1n1a-5q z8N!NXW5DN;A)WjU1cuq~^0`h_9OUi-ioI>s8r zae0+ix{WQSmEG~h7W>dOy#tdAa1^PNd#fqQ63>bFef1RCmef27-sdwWZDeL-0p~KT zHTNi2f>bNomJNb&oIM=Y$)w1^rEcu7j8`b-7&k88ahXPqC5Ww2B=|SQhJEs#xK(@; zBO|Q1o`ln(Y|+?lhIyOp`Fqy(ry+iEMW<+bWt=q=s$cxWsN?V-HNbl&r~OE8GB9ebMoLWVcIWJ4U7?vU3>9bv zsBH<7V>jz}5EHr!Di4kUfDg+uLNO&y6hY6RY3-0}l@5`!PTaLsvM?hDkRTU7dj18C z^Y95*%ZG(!ZwTsei{5N~eVpX{X(OorGY5U0aWWStCRxWrefB!<=mIBzr<8Ah7}}L+ z?ID39=yyg$9nbeG*Q8AaEBu8^Oyr%a&X--;^=iw~(iCX6gC0E!s4bw#av3fy8CR{gN?VqPQCC)Sl`FrTYLw-xINBQ>J&FE!h{-tGX_2Hs z&DdBuwsE?D-rcv6WB={Qgr7@{_QrXN?1_QPCgQ}?&Vw^m0hm`jHGdd?RsGnZ(i~`n zMOwOEb$s-P=;gwpbgtS`cnLoem^nLjR z|8-|5C4oT*;Ggwq>vwM5nkc{N-1h!8*VOcrU2dZB)t0|Pa6xje@kE@zW~Tg;@5NgO zkh7_?K=n{0P+5w-_v+-so=&u+{_ya8btCS}|DrXeP&>5e^=SItVeguvsy{KiYnTzq zy*H7m7cEt@fZV(1bXc>XpG1~uNxP_RZ6M?5LGPmkuvv>7E*f5dfAawN98 z8EOv)fTK3T$(v4rz*9wgKCyCP6Udflh%MC*9?^>#0amuRox8WSWw}2)^X&~Oc9q^N z-CDY>2pBGR(h?o{-f+<-UCiwlJvpd^7g$^8Dx6l%-0WMpw6Jq)#?5(!dR~20f~yU7 zZIE)$kdn7AFMEW2v+Cg;=0Ted;=AKZ{?q#aw10+hT)ug^xOt9gKU#SC2~@-mn>Q-+ zcX#H*HUDY~GX?*$-~4;T`F;NH!$M=D>+8$WF7QK^vm`+O%s#4vv&Qs;Sa8Gh=@3%m zFvTeviP;e6Yced%P{T@%KEvhYDP>m3*5jvY4R@ zAPB>+h7qewb9}Y?#r4TSa-ZFSrFp*W+F-tn7c*34pJKNq=qII)O(d2BQ{OHj1@pnvC;QDVkM`JRyYfT5eR>2< zhWmen%H4|Ffjtq!e}pbFguz~>M(!yl0o`{BA7Df0*dC-li&!ORWU^^7^IPx)8sk4N zuDZ51{KzqoEne1X%84DRWxiIc!twO}da!nh>^`VeKUiySns?N031X5#&#SF?YnQyK zl%Lm~-4}dz3MuJ?v3$~tX_KevwQ$N5wsfMlNu@XVUTTSP8T zMX_3ntN=be0p5~fAHauQ<{%>vg$D>GN%E&g$e1DsJ>iq8O~;?~I(=@&wM*y_j)H<& zs)>Ue90bRQ-D>Uc23G5<@qJ58&n7gidm`uM3>y|%G<0p8!vB5w$Eb>(|p zyfGBTKkahb630ddk46Vg9;*d%b>bA={hT>6b#i>i<@Q73$352%XR&aAi=K}@)=wvQ z`hBedg{!yK^7~7EfScJ9@VZIF(ix#EFn;Uw_x|iud%05BhFZ#_y#tj+>-3vg?~Yoa0Gj$HQmL%&5pWq=ChOTFjGB?WWsS1* zLFW%tX9DQm=Mm4LFEde~;_NHA@14sy_KY>|XMa~|*xD6|ZlFghgvy;#d8J|PbNF-k zSu?@W$V`EA|s}FN{$wRS$bk zbQFot?Oduw(^FR`<9Kk*u$Fi21wdstM40OMop=Ic;rzdR5cPvd58QvrBISBg4B+RN zNFN+H2P@P6l&G9c%>Q2}P!={;_W#HwFd$gjnb;ByA$|gye|z#JSuYF77}AYKh~1mn zGaH}FqM6wYcgtE0O<0@ZT#ZlgrieA=xiny{inRn&&>&%I78pmI|Nb4Urv3Z2tN$eH z*VfDDyWbt_UU#i`Th3eCrKDqJS7HS-<|EXk0gUpX@xnc*H9kIz2vBT94oX~d0kz06 z%>>JTxS|qJZis;?uStSy*ozVn?f(j*ho29wU;qO4>K#M}f;iLv6YP)#qCqJO&La$r zgG9s)2@&MRAI@{7E^H;df-^nlFNv73&^8C#AO;eQDYJ!3u(qhEYO;1jrfnc()d+?l zSK7re$OsB%-QQIMP;D+8R~8UV9I#Gdp7ay&UIBjq>oHO*7b;;kh_fUwws)zmMpGR+ z6$yyh$Kc@n=*plEl@L>lDVc+LCA_yi=AjI*WLtkH?23}Z4S zCRjVM4GpPI_&SWkg~gkDX?1fG@0yC01R{6@1rkwg1SSkIF2(nlSV~oo6b7t>04r*( z|B!d!wPVu#l#Jm?FMF&R5t(u@2hn!Evd(KP zG%kQ|tS!r0kl0wkUcoQ503}fhZWxbZ!kwW#m1a`n03qaqI1d@T;ML*Ee+;&_O(7Sh%5^JYc}LJ1tu zD+Gd&Kkc|aG~T|`ext+56L(z)!Ub|o%DQ5})ekKOU^29ELV+QnL&70?wBMG54_X2( zLx2mEA=1U4aB`I$frh$QTmPAOHLY)?q&!@()`Y05NrS*F3QBVv)VJ~%h6XYDD>vq? zJQX)=wCTrN5X~3&Qf|=bCxY4W7t$AidIE93L9ISS^V8%|5huuY2nMwL5g}MaANM8_ zP@KRlW*q2GqlaEul3(2&*y_L;6Cs1=n}V|*hB&z3H>A|8@=g*r3B|^iN{W&_uDCxl zzO4f7faRueh@{5*sVzNTFBT5=3l{}ZX=xT}gbs@vqcC(#R96-rroS+wG>{Z9{tD`# z0V6SuLE;}23@*R~-`{0ys|zBz-JU|P>k4x83=A2r1m&_=d5_QKcXv%~E_+1Y>Dg>D zU4u33^UK2zitIlAf)hsWGYa;o$QSur=y!kjAy`X{_w%z6{A-MZIY9L9?;HP$b}TQE zP9&n~85Q_1()fnk7CKrS!ZUY3X2&uJOsGGGoIa-d8SCj z#-&+W_{%X{eBju~?a16YmwvhiHGC^y2Gc@iJMbFN;dM6qTHfgN z21f(Ux&(2=*SEFVYZMuBA1R|M`_!U-MzDefq!@!c5e9j(5JMwRO zjFOa=1mfre!!nLL$)7HO?28#IA6Tlqm|0=+sg^%2FPW(QYjEljZ9|z0lZ`D6iZ>&3 z_HuVJB-WtJL#DTT_kr()KGc@OYGHA1Zus}wvPf}6VK&r6?Jq_2g}?6F=?EBjI)e-d z9p28UdQf!U-9&)#b?I$4<^E3cSXDecN|^RT%AQE2DYPDmNYiovGu+6(Rxb&;2$Om! z2o^g*^`!el0gBjk%?vJx{8+3ivKqzmFZN#)&niek ze~ghIAjqd|r+)+EZ+Zz}V@^}reqR}Kjt*3clLw-~x4^m1h_~Ww4$SaPIh!XT0e$^8 zJ5wwkTvGD@@LVO1b7dooEnA(8ZSnaJ6>X(;4^>(Awcg0u<+EF_zYCKGl*THTsCWOK z33B1t>+_7^|7LWs>C@SZerB{yVj<4@8&RVkJ--vSfwAVH(&KcO2v$kf-^~rHIYw-4 zHU(=SBNOvpv~iR~&*+^oTWEdxSZd-o)R05;XCOTZAUIsbZi}yc-QH4Ty|&Dg9wVz# zweNgIT*VRIRbH!{m&=rj$-(9LJMHVH*}cBCbqmlQI`j>1vcYk;1SIQgR}kH~t~XDWBIuN$9`;dnh%etZN{7Q57XXk*eZ$kdBg3s%rx zI+fuNM&xmY-yUY^%@d+$)M4bJs)Vob`W8u?xQw4lH#WV;=CeSRgc5RknvtvQ-CDQ+ z{I(#g715j#E8(x6j)5l%xPEXM*;o(q?25rtps1ML8YMcXCQWCRvXWj`_mBJ@oWJ(o zsx0qgxvR~)CcTmH1jn>~{XAZ!lxvuFh(m09vDrw{HYphe*F@b2f4J?vSjo5@TvoIu z5SO;~smNzIx|yJ5p6dR0nT^8jqTW3T5Il*KR4{4vQPMPN7P(}+f+tD^gCBKMJ&4r8 z;(6Lv|5f`#yQhLXa~+a~--(bBef-yhtUSt(fM4)6Q~h?~e&?DEPEw3p$**VQFyh@n z{-aX9AH_T`ybL3Es1c=GNH|AZQ@VwHh4{-G&0pDs)oc_%qn?MZuG!Mis61US02TeE z{>aOnbw;s^-ps&<_?bL?u|anB{t<6vVvIctzI7^r+EEI|#FT(n7lV275kyUW1ShFS z!&rO6aeHz37_Uu&N&op^CsKXnhF?9+$tdnWb8Xk#mSB4oqMFUbW>KG}FGFKOXXl&j zHLYg+5jS?pTX8&BB+1{j-2-YXfSpG8S@^wYNh>?Zk^t#Jo0-P!2z9c=r#F_B47?jd)4k&DVpSV3w9%Sy9(TSl~Dvj5J@1y0)n_;N&Bla)C=$ znpLD1ei*A7S+aWFz8Vb!hKr@dwVWhG)L@&lw!`mMF3LYM31dBH#(bENway@^3o2`CCwMKMn-PU3!PV@6#_don$ z%%&a>oWq4{;$k{C!1#J?UZqT^<126Dib{XJ>kNKv3CB8cr8HNt zL8^*PQ&(}xZ|+@n`;Xm2^AIKTpMkjTbb*WckhU-kQZ4hDR6%<@T|jQ0hOft~oBv7X(-?_Gn zevh2YSSk6O6~V`KZX}m0g*tPhy_vz-aZ~Lt9qqg$wsqz5Zinh4^RE0xj=_3?d(D87 zhhxvgeN9=C-qi1S5^i=u`yRL0PObPz^wI)~M72JyK!*T)z_71{#_ZW`p%7;5=F3Kh zk0rI9CgOXWwRVw$&F8E1BDb!7klDY{ETbym-F{-jnlZXwPr4%qU2}V@A}uBK^kU|g zC9`w2JD*{I*thP7`@Jg!kP7p-IGr_QhB~!T}9xk zYhJ^x(aPbZG`>s>mV#P@9mZ|J$_~Sus+8y0{Z5w|bQ6aVR6Xm-37c2L%;(UZ`qtPA z1p?ZTic`UT|LJKmF&6k}qq<1}7;<;j3$aY^r}Y0~!c;>sO7yTxTv6a9t{7kUcRAs; zod7maWLeBy_&X;2W)}RffUp-={QlQ}rG{?!=)e(MaWRc=-FIO4pN@P;JnX;l@&Bzg z?3)%ZNB9;wQ{%ZsFj1H|{=Z<7or|0Kf59Xe2WQHz5G}wR@^_N;6334X5>j>-_fi*W zPPo6l2uw^9y%Wa_~=}#R08{{tMDBl!U(g@F?L; zf?g0308)5)41Vcz9uSW*sUEF!ilpRM3^70fe zG(YaS=k`|!N$(@j_6hZ!RTCR$9sclXsSgwkoco;yY=4K+0xqc4+rRnuSKxZa^;bQ2 zpfZRfsWK|5Au7l+A;@EkJKDRr{q7#r=LH7f)3m#qq<0GO63U^K9*h9Q5oGIg`;9ap z#{dLw2Ndc0ZR-yp_c|m5lq8%V&H&mixcBimVl{gD`&5w7+x>tJGrhKO>IUhK+z<+46(^ z0?2;2k9^7R^k{tQlYLzU&-3R^Z`svseSY;Lx`YV%euB*NfgY`& zKy`S?&g34n3Dj5jI}$0^a84W(5MjUy@5juDJ@2#H^Vc8Mpp|~%9u6@v9WW3v5`Teb z;9VPk1o(Tfy*ez!<7c(7e;x?JpLRshR?j>z5F`hP&)NW(sBlmSduV8hcdLzR_%HqY zM?ypS=re%DaSV3+iU@D?}4U#>7_3whaU45dYud!~MoFTyE6=#IS z9T(M*^iItPT(%?uZSlPyMfOYnkZTdwpvwVp<#!bNLYB$0(++nonTWs|Ua7W9Kc9L;zC&mLrQ&0oFrJUp6stGB6 z>b`FB#sgRIJSGOpVswPpYjF~UDirzSObbb-*ga*P)*}aAnos7GVgU9hr6F^6tESPj z<`@Q3TC_b<1gOUZUdDuCX3-pmRm(bG+7%u=@r7LJ4hPfA zV0)@5g5$qT62DPGJ^}vW%OII2Y%f{CL+A4>C3xNzH7{Rcc2C5W{QGjFro}(ZX$N9E z>1E`4NiaSV^;2>F2*=nUR}CI7p_{Z+N|6(~BZ*l}O{C%?<{)px5J6M-pRp<1yDaRN z)lQR+_{A9h-PPu+-SckQYzO!27RxWtpYXiEI<5WV7aSC}6cr#|Shiap-CLJAT?>8! z6O)nQkkj=sN2{_HMG`2E*tM2zzDTsBir#tN7%L~si%H9wd=+X@4Ij_q7fLVb z#pssROrC4H&jawiW8(9rtCRy~F=h*>e?WI`g${d*yDQZpI`T^@Pm|wTffIQqYlhU6Pw~A=yhKT?;m`v|F3C z--G0J3}3{QhT+hgdetoi?uUiVI$xGO>H9Eb9-;Jar3ye#x`iFH1{;vWo+;)(fF{?- zAGQ^|K4<)eRfUqqCTdBI^e>_E*M_>T;t`s5wStb^0t#Y&vojYS9&?1BrUZuAP%bax z4`i>=u0AEe`$6Isk0c6Q9({qVAZFQo)Wsyx-NSR9{NH|&cdySos?{{(TX2LAJ|y>X zz4V(iLni<$F_b*H#lS)6S&H8Z|C?f}_%VF#V!6=trXwhCtPwI4e|gTSA6PxrNaNlF z$I@^|3>y2~bOM5!ar;oG&o@EN-b4t5gd6>{Dc*qvnc=}z@UZSsp99XY|d%cyJyp5siz@v ztC^3D(U8j)9}TQV@#zWKr2w--gg1 z_Z%497_I@>3~sv_Fwr>Ip@hE5uzoNJ2>)|!&WdF)>oORtq5T1SQ=&qo)jK}sAX>)P zB?qv=<1$L7$8IJfT7aJgr9Rn9U$mFWbr;{$5@1or3(4ScEKwvAk z=-}2u-bx&2?@r!gKk?5QtqQe=O5*{trOQ17&S6v#N&d58_de19iF@liV{!o%&gSP#q9+C~V3QfF|4D}iz2769}fyzu4bgwf%sX~)m{^OH*SY@3oToz=ZFxm_-L6+?XFme&8(1R6zJ#6=^1SS zO;4(G{P$ab>GW{b9-!%2gNx`yjb;6;0bpTb~T7`lg%8+*}5YFx^2z=VTV2i_>TapTX?1-a^Y|63NXlw*RyUP1qsrxJb zgn3ch0q{H6C6;r+k#1Wdh({Ym^pbPM*bM3HQH z-&Zg~t+=A@`m$S5J!6liy$}<$%eqY*fUI{n?EG-<-;94Uch2owp#; zTBvfsIdh)_5_-4BMWu*bSXG}DYT;2ew`*A~sC2Ar)vZPprWSuvTE`Y*|DJ$Yb=QVm zd&frJUf=T}s4&HfRJ}$GT9}8U<#Z$kYk5Imq9vlbO{WiDcR3-}0W(#%Lxhrd+??)_ zEWoLejXG1$Na*Qc7ZkXQvo-|vnJ1vHBDeK})PiCybK1u1pskNH#Q)hE?gner9ht`^ zUa|c9-CM<(m&p(oE3fG1IjOJbQ_7j{<$19k{^ zu3M+JNn`P5U=r(}|Ghmwp4MU>k{ZFrFUJlbXfgQmbUltOjUD|EI4`e+jbN;SM_XWA zK5B}^C9dOTu}!%RgZ;5M;<=%|=XW=E7hIQdwoV`J7wE?;>^i&qeR4Hf>XO@XGNcFg z_HMQiFnedS7Uxo?gOyA>(|C$`2S8AY*^GN8V6}Fkglu!wVMD{WG{PdfygI!-AL4p`iDDa7^9?LB1x{q1nL)><~6&M zJuSxNt(S?3$oTeanBEYRdNl7GTn2N|DX7&BRBOp&96};p;g`Q6Z6|qJn>WUc&YAqM zMIT4;iHSw$$xZq>0t7Rd9YD4#Q<-Ly^YMUr60KfibMbcY!b*rqT3bqQ~HXOB?qovo$i8|-~Y9#wR;!owz zD*mQy>>s7<;BM665K}E$)Ijgbs~i<1@_9Hc3I_Fng=7~`h&ESZklc)SyjkXC$!2=< z-yDiO2>ZRt<=t9sQGgwU2gGlT1>1IgjoqU5 zl>{l~_V{h*5Z#$|zl!TLhx0+dg%|fS?sz2O%7;WG*|Y4z6F~IFez5URkYrpM>48Cg zUFPfi7{f-KegE>i%hYUv{r!TL`Q1Ddx)Yf+rHsl-9LvxAJi+Bm@zG#BX)*=TtAP=7 zY?FA5@tUmYa!wIfb-1C*%`_37deNbel^&|->DaO{p#k1Yn_DxM!qe>+@WI&wg3iyyOxn0{{Uy9K(Rx8sYj_K^1M&$O{xf4TpjomKM7duXMACC0=bBM?TmLkppeb zfS~W6S~OAn!ccyD>-GbNqsHc^?>l(8;%h1I4 zCK)8oL!lZ=uy{_Xd1YQfmspGK`-O{~9;j=SV&?!YvWsTonnEqE^;<$@-Kp~uIm4(! zPaZ|T`w_6U=kc|IqOY^g>X+ZrmQ)%*FQ9xW)dchLQS~yNam?REH`qI_aSyfIR)Jz@ zEvlA6ZPSH&Ix@~A0#{^-Es7A6W|bm5D51L_zgfc{s%j&Y>@^mFVf=v`E+L!+S-pBo zJ2H0bAv5fF=5B#a33U#9sgmdEvI<7e z3?Wp3d%jpg^d8D=Kv0o#HQTGOK|j(AZ)Sqtca0SB8pii5Tbj@{3E%H>FtFojHZtI_ z^)K+B2f`R`Bwjp~p5Rc2y?6Ls^sqlkT3DoH#3zH5>c#Q$=fA0&fJt_H_!7o*RtigASeV?zL;k9m4Gw-r4@u1h^CN43$i(<*`nn>`BLR8^S|Wblviezs!0z`Q4NoeP)O7u z%t4o(kUcDmqWuZ=Ktpvv1ODpN%I>z3S2A7oLEqm}u#LjgQN+vots zZj1I~oE9uoir>bXdKFp6Rld+!YAk2b1G>zQn`>|w{N)n|NfFrfs13-j97Z zuA{;YQh7^d17_UXy?PD3fP;rHbS-LMkd8uIlLQm2T_izA5L|zpaOQRInPF>}|=ig<2}G2tl^< zJrCAyu+M8dgN~s8xHUx=#%lzCxGWN2ZQk1;NKfk4)@?8TkUaE+ePqp)WI79r<@6}9 zW~y%TohsbR<2TKiY{~;kEOiM*iBUf>ZjFP9KBU)C{vdSFpfeTJVr7Cz;WQnUBd#SM z%KQ9XOHz*g+&^Dd`xB%5hqqm>4W>m(Z(9P?rcGH?)RG^tiLjVs$juJ$4aZS3f^b6VSD?Qvg8JoW*%zF4sG<0EiaxDUoh5y$i!pJqp@muAf(Hq9+ZB!L^Mqc+E7s?l(`c*^iPOav zM2WnyGcy5!_1%C|c`$6%Ts)FCL6x+*?)YO6@rGEOlYKi;Gbu^o;!Dz6W7d2R= zRWR24#ri)kE|Iq#ic6eA2~fa0mUUx6u87^ z2T)O7N;}~)k1zrW=BV=MZHpq+H5<$=N!1B?N9YB##5#O70H5fT0Z5&EI>HCui*S0i zSa6<0%wRrjg_NlZtj;(g!g6h}?}L%2;JUPl5U z$w7r~)qyVN_^T1`p`=IO&vDf*b**x|2W(m&C#-+R{S)YT5uD8AgxVCHIEYy}U6l}f z1@95nk?7;mTm{~Q%h*fa6dSqF|tGsmes(M)}bs_<{Pc60QFs`MLQ2hopWZZoo|h z36cNc_#Wc_KYWDz4W}x%eph{d&wc<)oz^46Ox4Dhpa<4TFbsi#vv9Eg=P_og4!#8M z|Cs{E{qLFVsmgq)=&4FL68x!NXx~pjB=|r0f39bcN;Ckmi6!j*8@N->^gWP4LISu& zDzWw-Lh8VZ4*W+U0S^A39U=)$Annip)BNW)5RX=Z>_5$a&H}$Dl7gqs$Z}x(XQL6w z#Uf$*y;I8aifP)^G&7J-9$gb~t+0}Z5WVefCZlgo!@@j?GjZ(jiw*Rr&WJ40{@!GZ<| zGq}4A?t{ArcL=a?2oT&MxCR1*5ZooWgkT8{!3h!|I6TNb=iGDu|NXk&dTVWJzOJsW z?oIcuuAb>#{kr6{ZwqNmw%ggvSYJBjuQ6vWKf?7Yulbx3;n8pHJmIVRm2+pC2IR_1 zX5_0*tuL>&ZnJ*fmip=&E3!HK$ij$)X#E=20n^JP>)SVv zLMLQSo{)VK{77JmriW%8MebWrnp8v4Mv{~cs%cDwW=$wOpME!riYH0jS`D^1f_Ts{ z{)<38_e|}KOZOJF`Hh9UMTOJ?s55&n`snA}$YoWpTIy1|Zs82bSJrApdxkv{J!2Iu z2Lk|}Cwd?}j6tuK4#7-8s#c$Plgf*z?b86Ju-Rlnk0Kt=z&m$d+kuzk)a{d5iKf_Q zShBhl$i4h^iNJ`*WHR<#rw+Taa++$**6jR*mZTEF{HZ!<9SEL^mIMpREGL^mxV^m0vBDA zC_eW?1X7|D?JNsT=RL!nD1O`=7hO0?7EMP|JX4C+O-HipS(L2yeZ(j!qWHQ&3CGhP zV3%$$&s8DdCG**)jU1cZB}pzZ#ISP?ve-rpxVq|My;_uC;`?ev8=MH_=H(J%cpidizlq}1|hB1rO)Lz9CP$-eUOmW0mFt|2Z zkYycxQ5lbfWZh<`yS?X&co#O4pi#H!r`pXcpK$iP<;Z0mCG%1p z{Bzs{z*~d#99MTu?lsRic{t_B3X1xCfqz~=cdXIy@#{Wq2+kf@x)-E?7!c$V3mxww z;L3(8RbW~t1>s4+XQogbi#=UKIadvn791rwYKW&G7EN^_k!8YM)W?5sCdxG*HV`2C z2q|V9iIA}*+qf+ZejZ;u7(yaTnH3a+5RN7anEGxo(RY}X62Qqi&4Cbm6M~;r7BV0= zq;=7hkywvsPex$3JoD2=uY8(KlR+&%F2$9Wn7xWIEJ~7uv>y~8$<)*>mdaj@K=q6g zY+B0+Uk1lZW>!RnLDsUW>h!jx5#94gs;H^zGHDT1RXuOnk3F+;GkoYz<6;#f>vZNV_HGP+aBE0=n)7QMGkJ_?bbWh4f z!XFomf<%%q$R#>o3BG?XrYvt-H+!1CK;F+e-{WUCozIhg^;S|j> zotmqCtWedknygsYV)*`4&u)PIwO{7$Iu*GB%7;!txixdaepHbHP8(;SM1KF}Sv>;- zO#VC*xykc=rhwSK1!Wg~pLuYzopUO;=j{0WeA)ZPF@~rLsbtnNe}CQ^k6Kv4LbT12 zE|049r$^7NQ>zzf2tQLj)0LEZ+Fub~>VV|!cxdCq%S(}km7v4fzgkc9qRsr~oVTS( z_fx-JPm|-j%#Rv`FIIN3f$q66U9KUL#Fv5*RGlShtHCY3dMw^Kly3}#vo#gBF8wZ( z6l$>LuZW*z83qVneum8sE+>_LTt{rMu4T7>*#WzGr@-k^W+S-!y+OaG?Z)T)bPkID z(=xryFu3`pJQdZEHo~U1eOm9=Y80y$edjQBHMULZI)GF#sRi|z6Udfk{bf5f3>u{f z>lPWUIvYJb-~zu4jCvfVK1fpnDGvF{r>MPpjw=g9 zj;&-92hgVkjWGqTJ75ZN`d(VWSO}L&BU67H@nA z)qX?;;;ECbv%9lF&`*OjjmP-En(63Uv`z5_17A7BY=7U{*aL3iAwmr|=HJpnUZclY z6EV^~$(`NEjTt>tI*7qg`4%`3$4x(Irx5)$Ed&vNiTumjky8VpXYA5DS{;)U5js$R z47EX}eUDt&chx-P7jW|RiNKcu=Lx68TG#n?`bMdkoF$-9n&(YU1H|1WYvOkH0;FQ= zs`4@?)`3kKQw5j^ElXUJ`(@_Bh1kkhJXbXnTc3lWFc>&+u)%9X%je@cg{>cI#f|Fj z?e5~K!9S?!B|Jy#^(k=RzAYm+i!)Il5E9D|uay#Zr4R388EdZafCpIlFK*UF?b)8f@2sqg|yuQ%X$UO1$A&u;BbjJg`5W3;-y zR=N(sj-1U6DR3QR&A6!la&vQq3CHEe#Uy22Ld|(?e&C(KOJ)Cg7^h8Wp5h5{TpA|c z!5&*ak4FYS_@1pCwwVK}mccH)^`>oX=0Be1a9eRQV|0g?fjUm!cAe z%IHuJFu>;Pw$?UFtV)a=AH{o6|D2(~)P3?r(?!qi$dREtGm$1a8WFFk-FkI$A0g(6 zw!`Nh<%6~?@|Dk?Tg_BQiXgX`#Hw%k;W_$7Ukg}X1#zQR-+;aPt05;Hc9G%lYU z{(Ri!;}$&e0>{1fbGJd|y)flLj<0arGjQV|5OcXp#Wl(lqh9m{qt z0Sy_?b}XZOJF7z`9XRl~H)-+t&!Te$T}IxhzVtJz3;iF-eK=KuQt%OKazl+2%uC3( zACr-by~}#o^7oEvhJ5sgej2rl9=xi#t>>T_gz057j-?o$I_*IvhJc%iw0!fIPa~82 z%Ta-<9lmTPqi6{k#wbi9tI{7MD!wIJK&i<(6lqmu=eX2ziZv%0@00H(vwDjNcM!~0 z^6U7~F~?PraGTr9WJ*Fo)$FmB9d(t9H*J&8^!@Le`WcR}2#MEK{I8xbn+PT497GLG zRO(m8xcVY9mZypb3z5V8ECy2$Np??GkBUD)Bx*t9*b3Va3%->VQn+#1({oKpOU&mDtuzxA2p6<{mdmB4lgwnV;rol;o(Tt-P zQ4R-tUW#z7>c)aO#QwshN^xqGN@>rnC{Nhr#HJKSiqPYe0Y=$-g0~c*A5j)e6d*x0EZH4@zM-XhwQu(=%f=h|@~=uLIa{VelodQ7%+H z?wjON?w?X@YxRiXm*x%H+L<+D=c*A0A18^Kjf&9T3+%U2sk3e`5V;JrfXpr&t?DO! zyt2}iRmb2F&(@#FRc9;be9)gd2{Lzu%@l00-|Lb(Cv7u77LpfQRGkP%8+LnB6y1p; zPw80Ftx<&-)bclBwe@`Ab)>dYxGl%_cE^u9S3C`s`byBrvVat3{MtGaDPl(la!7rL zolVj(L6QWTu&8Gg~JNhH6$3Nd>U8 z89vX^yqhM>@DS2W*>_ps^}#O4!Q~PoQrg4^6AJexF7rWy1=H!-#DEj-ST(Ft=XYkD zY0}HFf@qt^oaizE%QBqkmMbhw&>6B1o=*J)gj|8KiC-~4SF=PJ1$mRbUd38|n&h1p zc9>}nF~_>ye%s2D(JH8zz_cu_e!r=$rWfhskWy{kuOlBlzfNDnfP5z+2~MX=P7>Ci zg4ux|KQmu{=wHq&k^=$5mGtjY(RhQ|NW#5_69q{^w^{TBk#({@MX{s})00-4j~KTE zHEtyz7WKVYZ{lN3SIAG=p-LZJ4CV{Cz%3%}sl>Xsf~k3yl@`VNT9#6{ORAUI#$HDG z`OA-^+GG+31k4`IKq*jcej@49KiZ*E?&cSBO5R7Gkv5#~w>ARi+a%5uEt53Mv{O`W zGo)1?wTY=&s*;7{pS-mLzlmAZ$!Ni!(B7&P+R+~fViK%XdVBghnM*<{1CkypV$$6I z;Q(^)GREgA({G6@fEG9i1v#Q_L2Z58XWoZM>zE=soS+(2-b@p)h8Z=%nkj~PE!EL>x2PWU4FG(s&Bqe@mV31-v@l$@PU zYgQyqfGFUR`btg(ujEuXww{7<>U3e>sa`{2QOla$6}Qw}ZPcs0EcbQt^%iDgMo*_i z##Dnw1n+IkOjk^u7rnYPWQ6=!q)FwK^D>S5{ZUWtJ^8yyrb@)+4YS;*_{n_gKN>&5 z4BTnTrHyR9KoYK4#OCTD>s@$6O5phv$^X$rg$Whlp?7?R?xf&MHy0;LzV9PfR(XxS z-o#9q*Yd+5aHovD@M(CdYR<2|Jh*B7ag!tRb`~|S38rWbwskG>+T8osQQr?tq^RV^ zafMiH&-kW@j}Q1wqu8%iZ~lURo)9;qEFw=`oREZVLQ3(C2qAiBERmIZOQWkc1R>NP zXBiBH$(J&s|5*|k;dg(%G9f)7% zZ~>*VeQWbL_mi)=eHl|-=v$=C@%nf}KUtQlyb-5&FFS}xQt$<2haQ*K_`5OF%}$Vf zq?`TN;3ywyXG7Kf=^dGCWXj0gY>HOu2cH0wV4%{_28I{>wcie%^J%Xgy6}6RO7!B~ zAM9a#?+PEMEE{w z6<6$?r+>Zs6rAz{sK8tL0jbqib}{?;eoPBJQR?a5uRF%KauG2EyZQcy2GA(EEm_D} zxuboGh8aTh4XP*^zJL>qC#n#}y3oKwvPfiF`GFftVRlDE`K#Kio20s;x3Y7f4U~*e zCkW?vh_0_1lM+88;v@1vI8yJdrC9-e4j%6NKOTKB7%cffEFOsU12Oq4>GK!T2XlfS z5*iQWx0K@pvVS1I)#Vf4~gHkJ3OG@<^B|uec=4o?e&+`@B03s9bjTpcQ>`QFmq#MVw1R! ze(mPy@-I!7dMNeJ+xy+>-|hdi0*(iP-~W^64+!!={>;+{bN$Xyeqg#h5Uamu->Vh) zcenXxS-uC!-ztCi&2Pm1z~lah3NA>ho{co!Gad*Jm=_FY2D3AO!3<0oY>JNN_n}xU zs2C;r*}?4h5f8wBh@`%?kn(IgqQuVFNAoxI1+IYn1I(> zLk@G`M=e*(UKN;=^r?bPi;?|8+@nX1=wFRu30OiiO|)v3Vr9P7>x3Q=>V+h8!!j@ZE**2q`vnXuOum49n>}DS_)*=qr5GogsKJkH99iw6u`qI(*4U zbeu5Wk$~NRLsT!(G`XK~IQWeF=)g)WN`)L`_c`l9gV~Z0w5h!;T+~3rpN9$BnBl zJ><=n0=8L5E&S9NE?suwCBP_4_ay&tqaXT+Hc^gS(mOAvp2thEOR3IE0?Ov5I}vJz zFuFmDHZkNAAU+-)|~xy?D18P!w!ulEF46pJK@3J&;)FQwA_s&1eFufk{{T zUL?`rD$daTUkC|?`I2U^0pyP*`zxEYIlFX~2xeCW;czr@xTR=rNUzqSJdXCQU=I8h zHKonApOzdCzG;5^F-TY6d*iS$72B(*$yya9HRqNYjrjOOGuky=SSo$cR?X7=&*krJ zVcecmX04CvN;50J5kvuVF6z%C73Y!-0@*X3-4bQ~EVCXgrt9ubL}+Ym;6)}bSzaXw zOQj3ins0nxzBySNj-#EaoT(9>($oMCgv$VfP2I-Ff{OhfW3a)f z^dM9mRFHeFnxmuJ1DBl&Or?gw26eD>d`NQqk(8v;6Xam$f=IKAN%C-svqL2LxVfby zc=@DxIl$Z!(hvxQQ<&;M7r}jyxvxsW!okYTnu?qAk0APVbAC?bp57ftFHhPMDm>-u zEOZ>FqwKe7mvoqIPM;6eSa`!y=yrQkPHUK`TfP@5B>J%B#ofni_Cm*Ivq6J?gAZGI z2Thw}VhVu^w1MV6wwy(fK(J54v_~lh!*|JN-nJ>=LsM zk{HKg9mlXA2ZiThzNJ%b%4I7+-sZrpDPnNPz(Rzd7L#`7K_HvY1#CB~IT zoPCg1RYPSR-fg_E|2-!dnWJ;qnc@PCJk)F)5xSKk*{kCx);f-JNy;QEpI;zIO?Yv@ zS;7f83o-mcX~0Dg>dmZ1o~uS=Fov@$+dsos6Ef^ZG(WG^TjBN+@D-)(4S#X|)0>qq zP*8Y7G>3NQ+o=@Dr3-|>AOJ&?Qb8bkw1VpW{pE_pVZ9TjFNrV$WoT^Y&7tREfEb3C z7+?Ot{b{{;Z*$2?X=Uj6o(-r%W8_>k5(*Lk^5pM>UX4!^tlL!E^ASLOUMr}}j9YJ_ z@{;uW=$yZMqB|^`Nfm(M6Tx(^3fd?2qG&%SPJV!3GprisU ztxOD`RT%Bwj6$Wp&JC9&i)6*U6C4eP=S|iMHA%J-@J%}?aF6F>K5L4L_&TbU*poaXQM!%7B5pO$v z^0=O|DGxot_Y)OX=ly($Pyj|*6NEdM%G&6D$<_DQ)eM=TetmYwN3DpT!=ountwSIN z;k2R38kiT%LLAkt#OHMf_>>G{)Kk~qq`pY_`KUoNV$SFS7xy$A8 zgrHDb+y;Y-;01Md4XJMKl!|Y2Tac771)p@h86%%x60?&A*}>I)Y_-IJqnNRG@W=fI zVTLx>JpqfMQQ|SXVwE_TMMrrQuC2g1<*8OBD&PI(x1!JDiZ}rXdbcmW4JJ$2_`v1E zi{?YU_Ac{rpsH)RW&GpB4Oiuisy;s*9Cr%N?1H2DBu*=!gh$20K{_MHR~N@d&=Vtq z-%~fE-7?bt_R^#^xy98rtA}tLzZqrM3H@Yu{aNzbKdy|#=CGj`2$H&nm&KJQK{ZUQ zOI~U?$0Rxcak;pbj8_Y`O>4cRivS!l7vhtwYeXmC#-F>>wQwY9W`aQBXKPrd7jAbnWdr)M35rrD z%hrdHPMx%H*X1BoOeYGW6$F+}cKr}S?NF|V!9~iwjA7SBWY-NkcfzicGAb0M_$~oY zAP(RXNT6%0U|6VtUgjb^3(O(NxPaz0qS)qveu)clb_mbnpyuL&#PP|4EUg2ztb;vx zv7U^h-y0N}Wk&K~img!E6ETr3WgaFQKX8GOzpgH2jhnl;E~W50W{#=z=t?`15NZ+> zRO!Og_}EO$?`90kPs4yq#_QOX$Lp7k1wd~4>uw~4E`s51KBvxL%`^@ir&i$(gsgBW z?I4Q=H0Ekh>N30Cp?Ze@enzcuGYkeZ#;h|z^=**mmv>lx{``w)dfU*6LGb~*E3EMJ zLg4gy&oYrKWWurV-ku1S$`d`;X)s?&2-Ty0S2bUhBacu?_fEuUT0+eky@&2mDuASq z=QPk|5%he`<4kUMD0bH>F0woo*K$80QvTWVvWCLdgvhx;1Cn%k%YA1XfrT<0QCx@E zTKh5j!XNuNyM5N(McAp_`eA!@@^iDTKFnne<{QP!_x&l{(uO7H)?8?ROngZyxka(U z@ZFa&?iZx($9I8H6(k?SutLA(AApYpBq;#7D3>9ASfAZhCLm5<+y#ArjyClHlms%r z9!mbSF1O}Vj#-`dEdH3h(jpiE(=|ecT&)+rHZcJpzzj*H6^g`7A zw}h>``Noca;I#fo(6qj;>&QBNdlXxfJQWVFq5*OT>CP&ayR%#qFFR6+s-Sq@;P+#``gOr-6;BjinBrX+w;Wqg&gjPl3{t& z=eZ`Uv6qbk%ZSNauDlwn-=Swhgy`JqA64kyEJ}+v-8Di*w6KR~%Hl@TmACqA8{lds z5X0RoK<~d{60E4iNbrHyd6U-u06rpq=7WsRjD30J;V$HZ{~0(T6H7G-kj4jM_M4gh z8}k1ho&S)@($o%iZ$Q#mRe2>r2TH!bDLcd`yl%_mVhX5`Cq4SCrjgN>Ubz7MBAZm(-s-j9({5O?DneHklC{TwJQlR6$KO#sYl zs5vFq-)II3_J<=dhR`sE;Z^4n3bm;oKY!812HLBI=r<*FsqS_38#&pJnyua4PdTD*Q>_9 z9}OHhcoQ!-TMQ4Rd=7R#Yi6J98Xf_{>kU5FPaC;ALN7zg+TJuoZsu`)%IrJ@QHZT}G` zDvAJ)jx@|;d?;3MB7EzA!&!rNS#-9&v`hU3Ck8rknQ(!3DO^Tb5F7wP;722I8E0xW zviYJnK$DvnK!Xs8#z;f5+)N2UTDbP9d&0j0c7y(G;-M|PD=I(-S&14g<4bQzE}h3zG_lhLbm}%? z;}j;a8)w6lwx)F>tvm+5jeML?aqW0BI0mixg?K41C*($_1L)(pJ7m-1v=|Nq(c-j< z-NgrjgO3yJT9pn;p0LQ(tbv3kKO4rGpGEmt0YR84v|nB29M=aQjhl&z(Do(zn=n#s%r&R_q zXeZ0M{PH%?NyxfNuau+PR@(Y7C3{zrd1_{npzj-7IY`$yUr+tJD%;`_r1qw4S$Ou&D%JiMC4HT%sLgwn+)Zz2F-sIIu~0~m_MfW zf1TO$Fy7|o!` zkS)Fe`x>KWbNV(scHj{_Oj}vo=&PSB@i^r}8(^T#iSrfziT*EO;QT{^&xwv7+^01T z3P4Fs#DS;kb{e;}6YK440ew#1xy*?At+=DHm$2(`dS=ds-ZMwUoI+pQpQkwk&_M>? zoJzp=^7z#dgG^4B?~QZRu&?Q<%}9ws&hoV?G?Zu8({9oBHmxvwwxr5fU(M(yvXY+m zbaLkYH{P-mBg!91g}3Xc0}Apx>GTF~k|xj28D>onc-ucMm`vf=Kt;|jvHNmml)h&s z+PBxMh)iQ{tfxpmXTJGHL}yXyL;mY%LRTAc8>W;h7$HrTsu&@S4k*8GW2$S2wc5q+ z5B6mY5N8bfx1)9P|GMzY3U2#1Zl2SpE1!Vl`P2|$V|Ks$$=-$+9?`h_Z%dDd)e-U+ zCp^n#g5fS3UPM>XYd_%F36$oa^ABG%sE}u|WKAdGq`17?0xEJrWMJ^yGle>~&b4$p zR0fxa4Ffwj(<^xTVb~1_4=X{@IzQpK&=TB)P#Gc$9WV2h_CZr*3>^i;OL9#$L`LFX0qy$dFc}kyKrf_C z)mJh=cAJ4N-A%!ZQ>HoEo0g(-59r+dbA5 zb=zpEwESs;e<v&`)H=$~B;{HtYhihTUvcIlCyZ(#q!t^2Qg+KFgmg}g!ZJvOFj z2=>Xm=oq%V=~(P`bPCYxvFq-xYUij5V>V@*FDTc1KL*IdUYIVq7gYYeqpK0yW{Ka9 z)OYYKz%B92Pl67>^VddUdd1lFt=MfZ8p`Ezg2T?&?O!QMaASYvH2)I!2T1Mj?{k;uN<*|*P2CNVIPwv9P&UZp@h;+rPi4`(Lwx|0i1h_ey~OamxjE*?o=_`R@;CZsN}^ zA7b~Be_hEP(Ei4R&EbdLz}C0d8#2|8jkxD)jTn#yIGk?GKq#{Ka(CGIvC~sUj^gKaP8;Fw&>$Lhc z;3cExm>Us&i(GM=#|$x#pq9WQHSK>S5k|t^6Gt6}^%rYv34-@0H~JRB3Na_q2}8F8 z4SJ2Wv>_l2fInfG4gZq>TREoe53H@1$q-8tGwD0VHxHj-5X+M+rGaymP~pA=g}W8u zo7aG_(X*V)^*zf|9I$r_O9`*uF!fmcx}eo54zu?n3xj~(C+aG?A@9-s6_q=#U{5ox zJ5;zTzI%q2YyV9Ax?lRcb(Om}Av{)EcZ`WuJVW>As&oL00;c$a?vdc#BguIxkF%bUm#*R|Lm$mhPb)N}OY@ zA@)ud{NaB~-my4t{{5;LS#w?)_?bPLppkOsc7JK*0J8VnoZ{MK{Z=k}?++F=s?A0d z;wv$~o*&__*CA~;(Swy(Tvy?2??gufJG)I8iAOmUGgCUGcOOd1z0<8P>ncYFdRz*b zVe}3+ft7;k4R>M&to=Rh_a5!0#cEM}2B zP*$!9q(8fUT{&&O;}l#uZLu>lwzZR>AaufKV31OF*I)p9%q?%iFOE(1Ja0jRgs3dHT{Vn7RZ7hJAJ( zMw|n_wjDVv@!R0od3?en=g$7J;ww455u`91fE=RMe(3HF`<#ij7E4w*S_F{&Gtig|K|pM_bD+JPwUtrYy)}3@Cp08 zmWfyRg{9ETzANnJvE6bq6jVX&fa7X3Vq^4_6`G2UXBD0N`a%D6xJB>a$DH*kOM8Kr&sr`zRw2l`JN448wCdxLr2kJLotREQ5uP zN*;T?jDW4Up?}fV(dmWKkA=Dfcpq&;Dy0t>8EGoTJ%bA4&>x1>rAwfL${9!|8f)jb za=?`}|5>wEYcQ`?yP+{qrL({Ma<=s7xJSGU7L~RG z2UlazO71o-DwDnX{YQhNH+Tq-EYw>z_0Z#4RTn5-d2Cc<0G9SWIk2^{4}mjS>>l32 z(cI15)xyN#pI1(%w(zOWB$yDqY%Hm0;IzQ=EJdva7R-o;*BGXGNjsr+^Jr3dzSCr0 z`vplF3#udcHQqeZ-5PG2Ilx*1x#~in#$00_mCt2>>m?EH1UPQzMsVK!ll##sARG|k zl46XlFddpUgc(DMW}|=xUuxASU8|MO$9zZkDj<0J2F)=Y4GB}K$lJtdm7Dr49}1Y` z7~p*(L~rWGU1t<7Dq%AL>p~)7LWv96k)>&L!$K|#ue4wzgIZpqsc{mqg`--aHF<36 z?btUQB_f3(LgId!xt+=Pz3v-F6lx5VS>St}4j=?K)T~V#+Y>G<#EjAEY3v@ZRo(Z( zcamIuA{aPk-`q9lp|O$OsDogJ`wM9Di*zHUv_UA%bt(PS5M9Twy&C4;*WGJ9b8)RW z4tJ{fRMN{b?OM1_UOlQuHW#vZkBroo2##O})vMnGCgfy8?YH(3XlchnhP1qiNTGMm ztv8M#f>nezPI7Eg^0v}c0AB)=nw64>_%|mCl@InV=7e}h1Z?n}yE+wuRXni6!_vX+ zr+fZMEZ-$W(A#Z3P&tRVUg|ojTt@eYu6n1YMK_E6NGDeb!%t1y#XPv3{q5Ux>0i)X z3ewJy<$IalC4|IrQqpXdO6h-D3SL(Z8i3-t!u4u$&x$x(RfNX#DbP(@1 z=@hS1-SRq^-BkFwVmv48T7W=}vBCHvTL@&R$d66CB8gFoVdY)-NqSZwtv=i;qt2>w2K(U9*#(pLhHb&P#40*n-@+wQfe=@*?IVxGu!vBXCB!U)oJi~aM=Pc4H34HIv_U# z4UKtXL>xB$YG$ObA89>lwb^@aIki5p55E%c^C}ih>AX+`%uw9s^5w6Gs?{V}G~Qg1IX#HYG#2g@VCa~y4X*u_{fCKc+AiL|Ef>B{4CG_AzhaL_q&ad#1Z za^j;w?-1?DdCd7s$Zp$TZFOhd`r&&(__psCqF?w#Z$?2z3If-x5f#oaxDgCW;f2Di z(s-OiMr%aACxh-s{O=Ry8~^`rmzM{`y2XOoV1oP$3WNrWjM2b@$%6pS#god)fYA_6 z5)B350Fidkd`&g}!Vlm|&HcgxV95X{;|0BE5uie_a&v>wvI%e?Sb10)*r^5~K&)Sc zFhO;_{Di5-40xcRJOcDoH99N+TdECR1gH=Z83UY^2Sl1rM$^DR4+%)Uq{9N4%&`!J z8Z$&1GXOpT{t1XrKz;)16VRW4`2_4I;64HW34~7|wiq)YkuL){|3eQ3v<`vH49>#? zLWD&AiOj=G%0j9N&+N@Z%F4^~FH3Y*UbcS*NtrDfSr}PA$Jtx1A(2TS06ZWU9i~re zyrASR1`*tFr(G1S#7mS$PtImTr2qQb+*zf8Fb1LHi6o=z<09CxERbj}>hM{-20q z0$BfHP1{l=faVPNH@yGzykI~MLTId?^b3U0Y5-jSh5($66(rh8g4Gfrj0OY;&9PCT ze_CYy*W!QO))Yg-{ctv5Hn{WJ=8;?7cveh9VV%lkvA zbn188?$c=F#zw6B-63D5SWeYu!w9$xO{3$vD{ac_wpJv|5Y)RxK=1-!NJ(PAU|^xg zN(KK&H&Jg|W5vrvhbBp(C14N-WyrA}WO;H~>9Q1o<72UlW+!t^*oN8-+h0ZCjpm{O zX|Uut@W*o(Gw>qkU@SS@koyg$a+i4K$N3HtGD=TP?vy}pK%pAr7&KZhCsvsAYKKB*Ll`P1YuxX$ceMs6bC^~AQk2}Ad zFbxDhAg`>SnUV&GNX`VQ_dg~7#WmtrFzi26^}F%^)+~Y!{uuwwPCMTgmosPzNJ^=4 zTL+!z`dy6!S^ywPdF%@RZR1CBn1(S-io%e~(AS!H&JprT9{GA>)dd;sEW|O2G3$IL zoPD1yafu&xuFN?puB}L=mfx;4#eKA41A{e9J zjU-T^2s|H=p3&4PloEbr*=0_QmDM1rBMCGvN0GGm^i!cM@gdEgToz}eepWps2-jy zrW6_->HqtX!1Hu5++9U|c5cFYE{82_Hk>G&@Oayd*Tdj9vOi5CV16lO{rd9q!N$KW zu|#Ed(pl9L`?1;vyK?ve1Zuv2@IL}`KDht(bZ2}pPAc&<9KKu3S0q+r1nNGe96usX zdxV%7j1&As0!2N~vG7x$uF;2%F(maEg^x6m7dhdq_de#pL`=YLbT}B>L+sfbOK`Q5 zZ9or2Ko4o)_;mrhbp{mg21~H51=rG(mCzLpEmERO2on{j(acf`xp+WB!gLCrjv=ss z;W)B>G~idy$?rrUqAvY7M&&VCjSV{?Du}fW%Q1fJxCya$WL-=~NS0LTQ>f zqniq!0}qPfz{x2!DH8BCA&8|M{6fnl>mnN?ud1K2o08@ROpVtyvC$#?d;RR9(L+KO zwl2GhZ1W4a>-YMuhsQjEY_^j4%D@@XYYx%Xt(Nu8YhKA*Xqj}~smwnKj^Cvg-g!A^6z9bN6?gAqQh<3g^o z;W_$#^Xn#V;9q#a@|<~F1ISm>VFRCwJ1dGg;Wo}tpTDpU@ergdz8RurkE-Jjl^>}f z(M2ie7Eat^jKa+3dtFn@Wh*Mp>bi17=XX5$$HbuYm?sz|3jw<_Zo0T_jM(zl7dLg# zjMyh1N?uxn;mj>v@NB4IkZwZBW@W%!QfYu zSv+H2jQ*0ox+itkC3E*@c@tVUcfN^}iPLdzY&U{FliIHN2390*>K#n`50)t`-wiQm zRK8^4B;AU+0^CDygnxP+G^!oI~`O%X? zKq3siZd5W1Lhf@IRIZ15JG@B0O`VH&a)D!nT=wU6n0CE-s>~1Dwngf4y?8zn4Z+yr zV(YC=uJHV&Udu))$uC~r`SS5sfuFenunh?bHKk*lDP!&3+h!YcDC!W=<+EBlV1CusgB|bSx7*J! z&4nw>%9;mz7qUpSA+xCP&gmhCzK8!X*T&_p`R4&&3ucIbJRGHgeEAOCU zm!^*;Vjet9|J)A#Sh-s)XWy_8Kvk#5GG+E7vEHYj@d8jRqojFv9}}uX zB)nR8X#Q$M#2G5lhgX{PTgeALPc8zCmah+z^PtpF+8UgO(E9U=qHN{tlSZKRQ|GV7 zKlwQ93+>jXS}aCUOe_Mm1897-0`?7_00I`6x>}@!6qdFe(-rDD83x1S z+c<-1Bu!t$O2R!Yq~$r8eY=4Jm)9?^fb9d6r=m>lkAV-6@S*af+IyVv(Z{gS73dWU zI0-!Lx#E7+dM6OJj=g@VPjurG;rzkZ$aKX0v%+OD0f)W2Jh^?d)kfZ0MdUJsUl%X4QF!RB*fPGtR$t3-!_a@tfoc?t@*9ITCH%y$Q&rYNSa0MOfq} zO>oO?pia6OUWXK9Miwds_@ggdZiHa+a=efcGfr4PbtYaZ>%0XfauPt4mW>wb_{iP z?5@dk_(fYf#ec5$4eKPgWj3u=(XTq>z-Fm;ds1zeN$mOVY-Q!ghP1L8j6Z*VJ^RMr z-NhU&FFc*L+MofAEcnGYNEG-D5#e&%V>!3Tk@Tu0FlP~=u!~FZ#(wEj9lFN1>APq| zm&$Q0;wv_Nr!|S-Lt3W1p-Seq+n*Gv-OW}fp|h2d(xx1eG}W(SWzr<1{?U*q#iPSj zur9b;%1N$%UBP(D#B{xvineX$z6JNPKi;G@DX(eYkO~FFW-+e+Zc6~|jLX*d?sL?7 zd9*3alQ_vbQRxEWJf9W5+zMyV?ICbJU%X6y!8M#~8074>J?0q?Aq^D4-I)pn(iFzk z!n4fo_Xkoh0O4F7&f;K2t9F=e(|WNq*6$t?W3hW}f05t}gfCLO%X6M2+7w}Hy*KQp z3jYq$n*3wc9&;IBfos^5f{rrgxS{EmUH2Daq%{(YUyKkhV!3hroIjAr#rrz@$VI5^ zIO=BtAKJK|GA?k9w74wuAoaVSGKjOyHqzw#9(X}mc#K3~b2{Ia0RJP7sM6^hZV#L_ z2x6~?%{L8H;6^|WWRszAwdlsUiC_^OyOQMD;rr-R#kp@2NrV@8^OX>wbf+Z-Km`y1 zbxMh`(4^@?m+HJ^88Z`@b=*mRnP~9Dnq)Y+cS8^CyS`nmglAyesXk6S<@fkEJZ$b! zGvn_kVQ%-(Bx3g>+PNnG)*h&M-+w6p6a9w4`0SzldJQKJBrcrKvMK*dnyU_Xv))G= z8hn7Co6;ZH(RVUiqD$~9MzXQ(C&Fm-8{WB7pl^v|y%HsdXCt;%tBLw-YO0u*COLfi z7>~N`&(xfOm(9czp&q;-4aV04HxtPoYqZc~P^OO4$rm2UlaAIX>z(Pz-89Z?pxErNvi6x3dL;nJ!4A)` zQTtis;({Do)?7K;IyFg4Od@nL{VTP@u2wVf4MXaS)`+@Z7Zi@3bKQSWvd-5?+YoXH zL1+umTM%2womcLyUgxYN!O%oKb1>Ry$}hR#h%WKc0aktC*kz=<&pP|VR zjs=5zuPScEdYcJ1v3S4c9 zd|8xeC+9lTYS@J(^HRZXIH8KS`fc$%YM3*d2rtjPbCCYt5zX2QM`A zVKIg{^k-<;fxUpfPWV#!)U;Xs^aFqgXA+k>3xNS(2L*?sVzeB165t~Ln{2nBh7&X( zgZ5;ZFj|&U322}`bLf9W8IVdAfy8I}pPog)4B-BcEQ1dC%+|9B@Bkbw^w|W65dTgA zBCTVD1Yw9!;r%Dgr~aIzJdYp()Zfd70nYxf>Oj+Cmro!G_*aR5C1q!2`LA?wQ$Wyi zQ$W~R@V}Boh6vF=rX@v)Y5?q!cOpbBcOt|kAOBJZXa7_bM5w4iJn|%{Er%i`YJktL z{>!+Ni3}E$Dn`QdX?;SBq~>$BPp-IVtpCb2|50Yx*;rai#7Uf>|Iw5F2?(kfnl#8s zj^tBG0)@+wc!74s&^}3jI-0{z)50rH5(xmk%8>|y-V{i#Ks&Q67%=SY|7G98q(m}i z1uE*#su9o?J(sg)nHeQgZ5gRoMI~zQ+f`y}% zyEQ2X8|SBflSD=f{6{=#Z~7EZ`kWL?-C%bWJ*V7HDLr?&ct zRh}ThIE11L!BkXIHzdkqhRZ=PVmchw5~Oir)l$&pR5DTk*9o+l;C*~NfUX>=_*Y2N zv?TH*ctI>|T4XE;*dYA| zVP^)93lFBB2FWE#8;t^POFnCt1N%4ZmQ>UXR%8P@Mf?MTSaN~aSPa%6sT|wv+Ye|N zg6~oQQ8VOBSW#D8rbe1DlrI>|ERej zFgi+W*l%ha3+nt@982i!!LvucVtWH!`;_KkCZUHWQ8Zz*SfwZ?94u3)^kt|viQwS9 zq<4kal$#4nDkFd5i|gTNmF%g&WZ{cs)o2u{TxT5PH^|BI>d?Yv;!R_9S=KhBvN@m} zw25bdkAs-1GY~l{G=&`Sa5hva>Z>uhMfhq_=F~IDV!dRtCDjq0a&zu>g?g%L-H>w` zQP(_kX(+I!G{Ryu1gU3~SqfG598cH7aDD-Gt^j_T@rt}!txefKd&;*r_Wi`_cN2>} z(k%POjDGzItKt$ozh41@S=o#y|;t{7cHwP z7Nz>bh%_wz3?GbmkDuKVCDYf67gC%99bBS%qmfJ+#{zuyDCzc>)Ud^`C0rKYYz5((UiH) zuBa^gd3~Fz?0abGbN`JGrL*D`QZDL=Qd1yK7S70=vjUdXsbKw&Z)mg47MTPGaQt3N zP=C_7X@HaXr!0_j*7;yS197=fh<(B8`FSg_y4v7Q3cj7bk10-342nihvar|R)b!V& zl9Re632A6E?|7S%mO;bFc;g7j$B#hS8Ho=m5zMhc$_h0x#o&1BKr(qzKxw?HO7n-^ z={!e)OX^b?hmob*Z$X#U`V|U8pousHc#yI+i?Q4os+y@W zRLHmxI9wX}+ZBgCIwo*jBsVYCXFsfQS2I^M+U&%22TL>|o3XSuNg(ac0v!!!Ef2E% zK+0qbgg@()%3`agN^K09D7C=XijQpa47^{@xsxuUeA6zDzIM0H`tHgCv$yU>l}L3r|_D>ZhIqTtH8#|?f3v|rtBrg z78))G=8ZH{qtWr5nlPhcvmXH0MrmkYr0HKssD?H}1dZHm&Z88%Lh_tjverB7TYX|0 zRA!J9>SKCemFR`O=W;!xkHH1@4D#B*gp)?+$3MTNzK=y#;{J4Pt=L&}lU?I&!z$}+ z55$lQhmVzp;ymU?s0IEGmved91v7uTngK`6fb9i-b|b|TU(l?ifeniNb|G1M$*caa79A4Q(vjy zjCOSU`zR!xh!B_Gzb3q75{AWPk5UzM@6V9Y{*l#}Dgf?K+682E$I@jA@7?(AMI_$6 zzGG?_&#+;aIz6v(Uh0#oM4wG5@XK9;)6YQQiy%T!DuT^`k~AIWRm2tg&PBRGgYy^V zIlQm$9P|yl*c3lQ&)vM5sx z2xLVmPliSwG-e+h5Qe4~Nba7PNw(YCaAsSB}C zb@1UdQ%vSWxbIuUs+1dEd%&{8X>vQmG_@*w;vdd_&E+(9`{LF;$0j{Qn^rDy!*(ei zZij#Peq0X>nY4r1{1H6G>5$;3Gmg9hai1h;8hI8ac<*`Zb&qnNCTJ#HcXS5zB7C3H zWm>aJaIbvN{u2H+7HCGTEs)=~^l$>%M|_&Zckh&aG~b!;DZi9nJ7KB2hzwhMW{k&g zqQ+%*jF8g+HNM)jibubal3ry>e-BfsGobsK8=e6L`K@ryLTfgW7?%RhzQEgI zz&dRmgx9PV`3CZEJ?R1cq8xUw@B+#sh5B0+q>FnvG2IU0B>rT)&pn{aw`A#A-r?Cb z2mJ*~RyL6e{e1xD9n9FC?v#p6S3G>VwUw{X{w9#)$!YTe)e$6@x3HK+FS~-YL2WbM zo^8|Aj=NT2RW`#>;|*ElJYKOJ`~B1Psvy}!UxN-GCB-&8JxeukE;lz-Yc{|FfIldO zJ8$`;UF+V1A;+`YY&^l9CKS6GJ2X!P#UGfb#zUe_fj8cc`J1tj#J~k=8?1}6sC<+d zRo{HjW_v$rrKK0XqZTS36QW10Fy2 zgr;2zj=U+Rulc4;I*f(yCIv4Wgg=k%k$3-*TBfG67%n3$oHHM%GNHA*u^6(Ys=@PyqVVr$MC>w@-l_ni!R0}~QoCM9H_2HPA zynpTMRTw>>;_)czgEr>E=o|$t2FX=2nvjE{Cg*;Kys|Hn`pkw)qE+M!c;vstWWAM< z@9O{TwA{t~#9l}35q#g%qW>T*9R2{5qy2yo4iArCUS8QN^bb%(-w>f1`O_9!0}&P@ zR1VlU@VG1e6~+g_9t+(qmg2jgZIf4HtdE%KduWE^KRVXMOhno< zk{S(@mXdl+fZm+_#*gnV9eQCsLxl7!hyS@*yUtb*$78D5i>GVx`{~eI$zU-yvIt|ANDi~jn zCCLve1;bE8w2(glzI}s3F|Q=>4MVTIY>B0qtzBIiY|}(UNhJ9?h9d*<#qg;Nm@qy+ z#{Dp-OnWEkd}*wi$AdfW_8gE->FJcV5@74r6mnEna7T{fV`qNC5KA&#KsFu~xE|ZJ z+j-Z_RK0dOXffMeQBYs94wZXDXffUiHd8hY4ix^)qU)&+G{2=%3CMtXmmd8M^QGuF z43J5(Plo3qahSM8Cs`RK>g#umvmo_vciht9)&XQuw0eTq{?4s0@aQjAsL}z)(I`F= zK07SBDTzg2!g67Y(sG?0e|@fGW+PsRPYGn(to!^CuRY^Q7R3*JNkvY*NkzdV(gnuD z%jvBb(h|D^z`ciiOFj40>gLLYuT)0UK?m8My6*-+0rlC##K>IbxMtnUJrnst@n;*= zVF66{?^(naY42x9+i!>zrIF2aZMeiOxnkxXrvcX4c}I$Cy>QzXbu-l%jdJ0EIvk{n zt-tt#13Rqp!{I3A_{Af=-Wtx{Of*r>dye~*3*BXEfC$SgZwV_nmy?i%LjHozcLAk7J$q0L~F zsvCx!3q@vZ)x;)w${z|MNY~56#!5;!jLJ|Run+UvZN0EG!w+aY(rxiR3R`Ol0>0|jkd*LGHrmjsg4qieb zVCujQ`{(ulTz)(}lS6plsT86}eJLzn{@p7{W1YoH3O{xx^sbO!&*_`luzhsi?-v<} z@J&|vT5$acjb1zcd&|wQLSU#`mAFM(3su18xaPA%!dthsBzRQ6NP@_5HS@cq1UGp7 za4NSpSvXzvvIs}ljpP*%0r*!x^WwQM_-09_!5LBZ@7J@sVg-Qj4?OF-SkI%H55qnu z9)#LL@D>9SOv&Pq+FjGh~_aV z3xMliIji@W6dl0bGJi~}i1JTsPoDw_#%H(AXM+q)i{T@w2>>Lf$b<>O&CQ!?0!afr z(AINW=fVt}uKB%g&S2?Nw(=c?z8Uj8!o&{3J}3teqsXsoKAOH?`t-n$Nvl_%rH5mT z;>XH(bCo;b_9hde8TGA&df)ifU(AFuio62PGKNeNmrC{f)ARmd2j`dL;nV$xq5!8U zWy4(A1VpYFTK8@Vb$kXyX|@Ax_TVWXj&(-vL8XHOwOalSDo z-yU4pquH}jpHipI8R+dQXkugP^k%Qqq?4m{5JnYWprhGTW>-`7aa-5KjZvCf<@oli zbVQd_kAGHr_*j}l@e9=t5w)pW%rQG)U^+jqI_3TCl6(YnKBkWk5q78kV?!2DL3F;N z&JYDYLb-pLI#Ww^{l$m77a#XyMi?M8cNwRZ@ z;1eiX-8fpHgTa2!VR}>~kh=|5EDeu9K5eG~ zNWnN80S1~0uT*CStG0q3zTar~et)eNk&KB)Og3MCUWznp`kUN=urgi+_aQcevb2nIo+Y%HlspZPN!>#LQduEO}Y%g76u(E|t%TZ**c;LP-u`?ofc^Dg4-7?qn!_7!eQ)(& zT#<83rksd&2dCg@mr)rBpOzfn z*)R0^Qj{f92=xTAfOM9~_&QaO;={$tmtEJ`%od50zfm>v)|oaS=wdnS5|D6TMjv;B zhnR`yA0g1RW1-cccwmM$ORD&X1nA!i#;4MjQaKEsPk%A_>mAKZ(OU1Wx1SN1Yi@{< zjl_^QJ~&`x-+g96rObm5QeZEYlQ>JXnZc1n~{UL>7HiytE4w91W6@W zNUZ1r|CYxB0?3RiI}hWQ0a#Oz=JiYB!e_Y(IwlNB9;FdKjVXw$695NecoMSooLdd3 z{ZLeQ0u_nVg1&a{i@+H(PeF&Tc-TVK4kFeODuDgY(3bV-S@`=^bsh#ny1y$98G_mp zQFojHoERbyWn@QX`OE1j^l!*JaySSiy zW2F=KfH>N<5fP7PBCCI{a|3_!^nh-By02Izax^o`@|jP?K&q1(PBQF$@{`DlC#*Ym z&#mj|2eoA^zyc-|hSLVeF8At))(^$zk0H@FrUX_JfXa?Y7>pA*U&ZXtX95Mq+TD(l z0g0Ux6(CrxkT-^_9nq499pKL?@t@~W3S|DI%hK45XJMajDDDC}YgMCw;OCm0i)L*j z?i_nZ<;}&!Gg&~S;{!TTkVnHh+ec?p>m|6j!t=1k7HbAR)7}BK7}UnG=n0%6U*-vR zg~R%OtjMBgt+q_MJ4#s>dEhBm%i#B;<}J+oN?^gIeVqaSB!vA>f->LsBbX{Vm{=m8 zZvbqrs>SBocb_>Uve&aY;Y-5&A0ww4U_WC!0rb=7e62-5VCxuokbz~>aMk^vjkUqP zTj#9w#lK^LlOYWq+k;-g@=b770KYpYM-R=Poh5rUEclM;Ga)}%w8i4KLto34SVfZ1 zu7LBHZ8HnqO5&W6evDXPMkkL;Rng-Nise1Ssi}KL?F9CR8Q+u>wZSw z$PL-JRh$d3qAqm(thDjvf}9kTV$bkL&+5a^dR<(<db^MV|W+a*_sO6zoPf=-uLk1mp2j+LGuK&YIJ?}PRFVt~Uo-kFTa zU@%O8TZ>J1nZgwP!wS;$wXaUK=H20xS`R?uv@>6;!=-CT`Qo&|i_{*%&iniMsX;@V z8#gdrujXR~#go5DLr-i-5kbuHv|>P(9OgSI!i)pAU|TL$Ek!|1ghfY(-Yz8a91f|} za%0C9k~YBePrKdW;uxCF@>N7ru;k@vp!IX#Bn-QY8KB2sH5*rPh7M!+Pog8Ch6Qt{ zoNE8X`kg0t5ZF0%V-z#|j+a9@w_tWga}E%0V9|1iX$dRgc{In<8ON)m;xBM!*2EjcAEK)SH<;GU76Ywmm}Ax*uHU_Bz1w zPHLTKoJT}`uMUG9=*iiQ>T+j@wG{n>OOVHrEJHSNuB&0qELan#2;tA6BM7-`msns< zL`;8SAkuO^I^Fuzc7NdS1r#LQHlSA;O%oKih7m+r=f1Jn`*&WylS^0GL)FG9B!-uzRCWiW9NMS8)8#%-TY5s?AF(jh2wJ)qVW z&fC`lY3c?&8kV73X7ny_mFGbMw-ngcr1@yDFh!_YZH8unBN;7aRq)V}L+oFXzd<ZckU4m=}3;FD8)wXZ~$*siXa z$`+0TbKbbnq)pDH4r%lBXv#*K!43jBpO$73*rlk1( zIg|j4z+8YKg*6Hm>Ah=F`i2p#AY!gAN}8Gi<9_9+j%es43Zg%n>mvAZ1w%Ll151yO z4}%;Mmv6dfqca#-pAp$I(7Kybcwgvth47U5VAT^hTw-xhRe#=TRKdowXt~$CcAdVG z1{aqOS=X!=ndH1TiXt<@rV3ogg;VZqieiBusDQnF=6osQI%d1V?8HMeKaR}9hryD%{~&=g|H){ z-5NOU;5#vzyJYvcT_pHgha)z^#|GB6)OYD9*1y^Gv9f3=14JkpZe#E6Q z8O!YNtIzyPsJLNl%La65P|kJb-AqLy1YA}f5h_ZX4Ar?W@aPTFE+zc2DV(yB*pMQk zkCAUeXEMIk$k97fV{D9GGzc);+pzw^^yHe{*YBDn!bgbeT3{abqhpen>)T{SR)5!I zz>*qMH*Wkwn~21iqc{mQO~M1SzafXZ)1@0r1mX@WfPJ9PEEGuK^&O^$u$2?p=kgbr z?SXbvSHY_wSJd5`e`WN7Z6LjGi?ttnFIAtXKmcv6dLFH+t;vik znKIQ{rUL4qfK+tkZ!kI~4RFe{G7PJa5NP#2E65$WehC^ygp0a?mn8UOTJqpr$~ZXg z6N3f{N$jczpAdA2uHX#gKC!3v=Q7C4Z{g_W zQ#`cAUdxy0^7!9-Da0;%YNxNLJcpM7d?5SkZ@FD5^Z{en-|o*hdzjt|qLVwZKc6i&_U>N_93` zy8MFe63o=pNHF)q8I~#twMRVZmyo%=SwrIJd%CMZv%W1$Myc!%uUf4zu{1=gE;%c~ zwcJ&3j#8u*xJ0$~I?kq{y!Gk`%UGaM zu&|N?-7b`Rj9D!lQJ7#$Naz!Dg);KfwUl0$cA`{Pqc@X<`1 zg+4BM@d(e5|5U@%GdKyD_t)r=DdVi4Q;y8FNi<^ziE^*{r`L5+iEvp}|jZiW#6Ez>spyyy_WH?iGjM)mMN-S(clW zG_o?y_Pd%HbW^et=1G}bP^lrgl*Og6M|^$Sl(Y)2364^>!c;3T8Suk+j2`>mFs}_E zWskzvl^c7&`i><03A3B)7{x`2qy)S5rTsJD>~xw{WBq}Xgu=mGyYW)u5A(7lj_Bl+ zD~^_3mf<+tr(w8!rR#%H%xxeSc`0)=wX;foy6>2qtG~~&vUIa#KGw*B8#ee&u9(PB zxCqxgA`4iLG^T{SCuTd@daygmEDkz(rf^6_F!?=ZDLmAS-r2Tb%!ZhoSeDNmc?!6` z3em^|BrNldK`y_%vPQsMM)>}Nl?GSY{En+lLU|AT#lq@jFM zQA^7J<}Qg*CXRnFw4tm>bts=l|7AX`+VAvc<;bjq=RUcO;pSno)}5Ai9+jPxe&rz? zD3>c!8(@akl$b~upn}=EPK?;mjNlCQso5m#BtMa+U61T&hv4duqB0AG+REEJ6x~d# zE02L$9r~b2 z71?}5+!r5$yB@C=j9_p5v#a zgO14O<>nH}YI`tNfRNjfZYBoLkwLuznLY$M6h4P(N>Z6ckRu8%{A9nSA^Bf!2Un-9 z2p`Shl*1OYl6n(OvYP31eohPdn~uU$ZBsF%w#hpR9`k*rb5js)P}(YZbBhp{&C?DV zG3le=0n;B4Is_n(x*5j+u@VHC%UmYBeY~f#`@pRLpmCm8pzl+Fd3G?*PGk{fs@oU$ z3_Tbz=+iuk^4J_#7v%5C%aYrgUb96S8xo2418ouE8q%;Ck_Mp4@W>08DyLWrHytbj zd}P1JEK>~Q$h*oLialHQZ>{>Upe=Dd*XfvLXlPyVj!^$J4|rgnrxMkoHyft8ffIU7d|UD!vSg$W)u;5P)&gr&HCQJx=pNi@&9+bN_{u#L{d2pJZOCH|eTb-W z4I28Z*iTUkp2%%uFN5t1Umgrv3*9Y;_4+>o?N~?}z#NgLY-?~OgK#{dd^`!RaOIk! z=P+#*R^qX61Qzg%#D0YYQ*v_%^uE*;2m>j}2?Hf^&0$G-^e%XI=GB;iqgiTYNu{%TaSgr!X0La;v)P&xt z1Vr>`z`waL*_N#Gzp?q?7pCeJYK_@lU?@f*2uBxzmZqP4qIF=b^_hi6ZYX7AU{MKRe{V5;B+Y zqHL#bCpXDZ2RrQ!e?ux0G{)-wjeBjAyp2i-(Fc+d#{~(oQIUu3z~hmfaie~i%QL^j zJ!O+5SK_AvMW?n3Ar@<6$HD@-tv%yd1?%T(7U*9jy5^MU=-(*2vXe=c>EAxz_B1{2 z`IZ!vYdwFc)a;Kh(LeRy$-Nui$qANf-K-DwSEd#I6X3Nh@HszTBVZT)DT3{6g+_Qb5^tAD zr8>Ydq}3dWZ>eX<>F@-PKwtPwQ$_r_A@D&aTus}f5zJ(+eeHFDQDBDHL+@{4coRvk zE>oDIQ_Q4?YykdpNU)YuwI*?7h9g`naSJTmwIS4X?` zgOzZ_cEC_O2BTNw#`4z^boJ5@BRVycqE%HhJsd$9XT>g+>X4->-2>2sv+?3Ra%J;M z8v~y(gGsl+RpY7wi~MWq5+`c|chje#$Hv>pF(jcAEAT3gY zL#K3$bR*r}NH<8AbV?~mey{gl;QuXkEq}hiJTvF)vxIr}ehuzh&bJ0x^}a9-O}2CQ z-;`R0%-MjAq(&XkeLmL2#;3ZdCo&1jT6q@j5H7{;L<-n7+J0X&h*}~a$8jE4`#`>y z-t_ZL@#T9}Wy6Wz0YAuPSCR6%VsQ@(qGrG9mR$xer-**<&0p|qx=>72EM6;LrRPlm=hUPuYNgdJ2AWwfGE*!6EUuk( zx3*p2`Bm1(SVzP_c5aHf8f@RC#d@v?XVH0$9^U(iUF{|)n^OsB_#VO1a2npB_x#w_ zIk4KIV8}r`%8akZlN0d8@Sgd|n#^N)=zGCdf2MPKez~neVs!lZ2vItn`*9jIhxZQF zR%}F?gj$fHj{Vju_};;B{zF|q?Tu6Y zhltvO_t3-8D|VYGBC%JPe)!$hqxk7)knpu`tt4mHNgAC-&c_O!)#@+=)dh&q*%n30 z>VP@>Ly{xD2Nnz#D+sfee3UVgBb7q^yifjszkxdzq9;sckJD!d#<39+E6qTw^$-ud zb?P%FZA7V5*!W0Qv1Kes5fbc$eXQ81KIQ&FmNL51K*rGY*5kxDvgdjhyi!*=wx}a{ zD>%j#$f|F{HnpZ58QjPQMlcD+w%vx|+W;3p@89;qvm;x@w`XiewZ@J+UJKs;@Hcnl zcn8GX-u?~!=kW){65(jvJ-WpL0EQ<9YsKFS3P zVS6vQ`iFKljo8#PYjL$Lbvtg!>_NA^{4C~Q`@MVTp<4q{;aYF5>_gL0@h1Y=Xli#7 zTBXI~7;KGQy16pqU^Q4nB_HtC?a5KR6!Ck(F29#N{4i+)*I1q$=g@GRn&<>p(%+VI z*xDgt&y$IK5KHbdS;Db!OIp;yyRbgsas7|5K|(|Y>ZOWPDb;b z8#=OKugog4eCtZ~pdt-|@PrtpRgxyfA)tSu)vw^7jGMATWDQ5-)*5JEPOaMncPy^! zg4SN7#zg#>lOXDyu#xbA-BTQmOo9kIsxz=^$P9Y>_BQ*QIHdv(repB@5B(hv@O3#6 zr)zLZ#ihu&csz=@XZ*z(d=Qa}8DfcAIo!@GUowFVyoFq;R;0rI0r3srPmYdkIjDC= z_H=tf!#5YuL>m{T-*`xpt29*QT*ZV4@hH3Ey5AxzYMmD|{u{WEf+e1F8 zqG(Yx>xQigPE=S};ao1Iji_GD#UaLG@Ga2?iidC8r0cTlf@$&l0WXa3c*-id1D$Sk zX@0dy5t9F~hCru>FNn}XF*gHS9n<)vi9vPwIEkOr3PJ@!hSRoCvKJqjgfrt4=5RJ< zl?-y>yO_YWh}4IClHO7pxH{jG-lZh4@>(phrgKgleJQ^in7@P|9X+hCuB=no6w=&*mgYbvlRuQb&=pNz*C-aJA{a=G3h7!XxQqM7k&2!F^ z^7}|b{qSlkEz3CLro!(tB9~kWlD6-dCg47~-UjitwF}g>2kOr#er5Za{nNIVd*iMk z@&oux(*pN_BGZ<)F#`?so>T*FYNGN zx5b6@bFiu>=LTjE;H9P3_NenrV=2Od&TWQ%>Nr&lGX_f?T-&PrAv~SQNHtnrMG`i>vmTiOO!*%dvd!V)A}Q~@!*|Z3 zWwh{f*C##*c-8CD=?C2z#=yKf(9~;uRT@&de|@d}+ve>SP3c*MAhDIX-dhbt!aC&| zW!+RJNo`)ecnIW%?JqcT;uhJdVjVjgU;JB}((^Uu=Oa|9@#Da<)|jq0xQbUx<2CkH z4{a+bqEMGhQVP!FTs{xXNmm(k9;{HUNM&|+_va*p*jGIYm{$vxT3UqDyw8#m8a0gL4!~UsXF&N^X^0;!qAjlz3jb- zprd=Qx#Pv4WbZ0Cq<@Y`b0D#zLW^z7x>nl1i|uMBIFh&Nnoa%;oo3>^tt|R7J+WBR zUybfvwq4!tkhlPuS^ooRmu%EXtk9&fT=D@+J@CaKjCj!pqZ%K`5A5{0;pmhlFK?4F zS^p55#f2}%>{4JZG3nZ3ZjTT^2W|Y^HKgKMIen{B8})u3JZ`(k6^A2hhu8jHZw4dF zvuJwVXB~pUc1&|7b7&u@)1M!y#}DTV@`=pyYuX;pB>rd%8vTHhV5%dlU*D)m!1W_0=vPut3`k4V&@zc`=0E^M{bGVYz1xBAREK*DcM1T*xO6~)S*W`an2oT zQb&*gkagR~8=S+VzG)@4L7n(kaI(6cw^1iM!HpkPEY?eaNdla7oMvsrh^SFl}gNFiTx=QzJ+K$RwA{UEYF zPLwlOgSTL2-I+4!m%WZ=^35D9D20M!uKAALDM%oR$w}}mX`2AT0Q!~YQp5mR<1hH} zNM2r4SOxsT7QD%n?= zW>wLWS8*~b#_@6pEul8WbB$l;Lf`BDxJ82A6@)-hun-qk7cN@4Q2tg_%>Q!ypfhs2 zQCE-iRRe$PTl6d@#QLeuVVcG<&bR3m%*rb^Wb#+dtHK!C7SdbQQAdebS`crtY+bvv zrfUT1!21ITRYJN0K9M{LOl|!=pI^Al)Us@C^>i*UW~kAoTuvoZSRtT#vLe4p*-D(p z3@*ECZ%>+7>Y}~uu+KJDNw9;SNS)@ETK`DHH!XHGfpbB9&NQlk^oE&|HaDU<;;olJ zpCY>Pc|{jKd-G{BevL9BV}98l^9F~7dxO;pBY0L#aRzlRR)hhMK^bFd-=cmE&4uuD z-nEO$&`taICbB{33H);LPSZA<$}DX7s1Y5SMpeCemi-GSGsZ;G0=?qdGA$WG)8mG? zZ^rm=<9Q_eG6rZewh(HwDwI=oAWYgn3QN>v2V5hcq(i-fbr2cpv=Gra*+UB!>PNa% zoWYpbxJ5CCo(q-QVsY*9_H+yc3=zSkPi*=v~S(p(wm*b-A_ewb~-}o~zjrzSMNIIUA`hdwlmfj2I zxUN1GCh@An_2Wv%S*_xAF~rztWDpL$GpW^34Cm1|E8^iso|Z3nF|8uB7}MoBj)NRM zO@QH#V2T?5ZD&0*x0n%EaRAbzRAWrs{;dfnD0^pRFG%LJDoQ5V5t$G7b6bEUYf)(K zv}C9!uGJtfv9l{uCYnq3E~yWTABz&K!_6Y%xv8X+Zg!sD>(V=!pxr1rgYj@jz*6b^ zN;U9AL`xVKGgn-~-7ulgwSpvOmcIO;4^l7sxLe0Rn(YVRt9D?oSHW%vC%4HMzGXbo z6XX7cS%%$gxK`CKk}XwAgV(9gq$6J%g^ES?RK(nZekHt=X~R= zVZSU{3j*TuSnnMM0njw zyBG-?x%ZsmuUspboq~j3=6HSuPrqd_31aCT&PWw{@A7l>YS($&WHF&MURmO9DTlLGtE`rGlOPzL@E`al69<^la}Hf59MX6GU2=HYt`yg&dN zA(d&x!Q8z6bacL8lTqg+=jP@3`yqb=7ZCnwr~DhZfxz{61^7z5+>ZhHO1wOe0R)79 z26O%W96liY^XPvAKM?+T^uGbZ;}`oh#chHpeG0pfCBVH!2w`^o-jB74$u<^ z2LJ+k0^tBiKu;tb01D^{g#%y#J+S~?vD~0X7_d4gKm+=Z26zns7``VMP5_4Q35FAZ z;d_GN1Yr1{U^oF7z9$$?0EX`gh7*9{dxGHvVECS3z?=XL-y@AW&|b^^IAjf20|18q z35E-R;eUeR0$~1~y!Q7c$$-7;au5J;88;z(9PW;pPL< z6AU*$ke*<8*n#u}!vnzl+erQQ+4BG}z%Kf4=kfqBz%F`B01U8;9uoiq?4rlSOAh7% zw$Wn*0T-WOfNJ3Zw$bA?00!7b|0SSic>Zm!{`>Gi(eMDf= zz%F`B01Oz|MvoDAX@G6?m;e}H8$Bif2G~ZA34j5%(SHf39Ufp8JthF=-zM$9Xh7}o z0K4e%8UO?AqQ?Zla6xj__kt;;(18QP34xX#mG7x7nv0zqn8O!M!31_#;>EoaZueXL zoT;tq6(^|gSKb4GLF&JwxF&Y6XIG>qhdD|PqqRZb1MDPPCnHx#f_aO zez0<^?=mLMN=YD%gDQj72y<8Mo^OPEE(C7l&`2Htnsm9VS#|ELj^`p z*?s5l3JikJk}k)Zj-E5xvx>Kjr2WpxZizgxIqW+o$+X~wZev@HlxW2aVQfc;blTW? z9WUeGQvh`im5Kr$$cD@tM=wcQ%c>Rk-=6F!r*@K#q70goL_0Mm>X?6{NQn9SDhQ4b z-ZqKXH}H#9W>S_Vf;qyZADjRIwjHb_NhUQGN`BU=b)hOb&3GnK04&ibxXz9`II2SU zFDRj?m_fXgiT>3%)6k>ne1vPZLVPbBk1??b~9bzLweYPRE?_qpk_BkLX<5ej(}Y++^LioIr@%QxdfFAu|5 zIVao{uBMvyJv{_x%uYfN8B)4B))_1?Y<@uzMcYWh;(#d}xLcyt<;{G$jkteZu$zeZ zyt!o9kU5p;`~LNn-fcEt1eQ-(llFTSU`XwHO^jWuZGPp^vhM0H?=K0x8`sbW^(!!O zF$5kgoMaVwY+-QB$@)(2-=~MpS1>NiTUl#6#O;&NV`q;tSbt_D`5b9Xd1`7Fpo2Y} zF*{Q`T2#TY_0;;LA__abeh-xagTs+KExN3crc;RpI2kkN9up_$2)7!2;jp@Psw0?A zNcrdeV~EFs=`KYx@dcLTc9rVpH;EZzNh}%P!=*aMSVzZ9q?QIfzb$%9q@RkIs-HK7 zwR|u-KQ0N4$q?1Q&Go|b(EGS%=M~IRX{nn){zV+j!sx;_IQ_Y=ZtFD4oMWdzF@Tp_ z6mPMtr#^e*G^VwUx zk4xB7^_2&+E}ty?1TMF=M|EW+DeRjk812G(Xl%WPE3WjxFTy$)IWZczkdlH z+VScHGZ~)0yN7phA9~rg`Sa?-y|2-U$cJO6H~&@ej5=v z>DMHq(W+}6v>x94@G?xVHy;9ihR2W_M_Mz5_%I;&F;j7Gbl<$aF?cH5_e3dat7T^? zM_^7*@sIqqU`vG4MSwSxm{I4|S2DJ}DRyQ}E-SpjlPb4^#|K1NLfvxM zQ_JgnPfhW!)`6yh=`%l>R=%<1!!p+vo(TaN0?|Jpu=@Iq)luolbSi_Z_@$ z{gFeM&)=CyJCpmQ(k@I4GZLpvP}TMK-eW1te`XxL%1*|t&=I5wq{V_jn}dvRG5CGG zN^K4{YR8!}$NOU<$NO3|d~^)%WfsnbV1XlHg*0d4FZvEWQIW)R6ffwDuus_(A4Jbf zk~4A{f=6BLXj(H}W4Di~iCh-afoeE-tA%N72k(}Ae(x*yg$CiZ4fn;2=kUSB z>28UArctGi=+CGf7B)C&rHt^2IZ8#n5*_ST{1<$=3HT<2#8Yd0gv7HsgOcjBpPePu z%d9DTRPy%rB@OA$JS7d$fCs2PGms;ZLm1+AOo3ySflfNWz}qvOMOrtR@n-P6=(Gfj zBYsm=e{J_qn_}BolZ6~4nvv^9vooQQ@P`({Fn4~vF5gP{scc&t=^|0u`Es<;rsI~o zp!2q7t#juEi}&xY54wZbr0$!)72fT$*pf|!D?~{rNL+416rQlsK%%*}$24*`4yTE( z6dlbrUNMf5*_Q>Y1*lR=r$L2E0BzyRan;#k5uEF*INjl*YC~W~%Vixhhnt@Dw)<*} zI6ZXMUpKKp6Lb;2=(7z6lzoJmpF(>psl@*F^X#yt+CdX

FWJ`xyj9BX1GS{wj-8te3*sKyIsYpofKi z`YsDy`l6b$Q(B6?WB}^y5OOMkzJDh!1)@)erjwCtC7&99DjRzk<^}av7usl>RoRwe z#N6S++~pw6YeB5WrO5AF1jXQPJqUPPQd>!%O1$5~;V9Zw+FJMGA<}VD-AH5L7W|Der&Tq{Wa0sWzTlh*degF*#`YuFr^=-9M4s?o z?)Nuq+jIg`d;a1E88(*nZ@WHnlmglmYjR%FJF(x)zbz;`N4p{8jatHCc)&`+C&)GO zV0z4Jz&E#kC7pV;&MCl3b6#`IYl7I$)NdVaGz-EiziS$ZuUVXUF}{6op$o;h*Fd0F zab~eFLl7JEp?*8O;a9{vaLz&6Wl$8^2WN@C*)zuaHVmq=moeh{6mZ*w!E7PUYrdcf z%MWfR54v8P4|{8W-rYVdtWSvvh*3uDW>Au)o460I7X|GkK(1GNC-_T=R@P9MC-tKk zU#*O*0^{Zrg7}FsmmI{4a{I55@TeVlb8mSIdNAS4YajgDUd6=ag4ItTLq|38YZh=r zo5rXYEjY<2DrE`x2BorB7xjMh3qi$T9utMJqCgQW`&lAn&86sLf}#kz>LRW5W+45B%nVk*7K4 zqG!y_OK05;l=fB7x@6bJHbIS?)p1L;Tl{d*(kOGZx+-o7cFB_W$PC_7YxrJI<#g%s zJ=W3%rHt9bc+>ynF8wujmDBe3irt?Wp@9WFn;tQgyPG$VpEy&{m*{3N-JmhWrA4qr zfw@yFzd(~+0XSvKu?YNy33zj~P@k;x{0Sz|@GH13ZURz6G1y^CNKzD}+g~-txNprC zQMP9nHpb$<05g@-+ptoMGB{)cs<3lCh8{HKAc90ju${lSP4Fi<2N|SLKAdB&7y1W( zK;hYyJMH(fw&xXZi3PrOT6DKg0kbQX8Po17yr)9nf@SE+HuK}|4|Xl#{e;60_d1b& zQyDbOqQ8Utdfm5<_L2=XgN)d_+sCUOm%kdC_6C8J|cm^84rG9|5lI7F> zXSR8g>oNr@;QRcYp9RJ9-|VFheJ-^6<}VZ~kV%uSMF0LfFs{2mHk|_U@4Ti7O;#*m z%K6`cRrP@x6nKz8pl}n$M&ki-Jda-D;rTlPo34H*lR^m{3iy8GpHJiYI|Q39$+?n( zI;kU)6DR3wB?a2QUuwOQq8=_OEt3M6unl}NF!P))X}W=eG>Ny80y7DwkpeyGRV4*| zl42D-V!c!&#Q;K5(%&ofl@yFguevB`{;`&T$?3+ZOyC(E`FB+H7;Ohy!!gA#-n95u z4h5Gm9TdN34NWM1ZGFj3DKi<*p!QPY*y3ojedjF%7h!bf?-U7EOj4l;X}6r41KRRq zM#DR=&Z!4HExgs%__kslyS&med!~Yv?e|+H#-kcq2m79z> zC9WWY>Im?VceC~HW&4*)Zc$Wks-tog>+kGB$XXAs@3Q85e!T|?+JDx#8MkN4Gdjc? zd24^QmHJf+?~65L7UQj(;S|`RMN0#$m9}_&Glqw*#fe9d`_cqap*KUi6L{Zzp+1=0 z<;$`@D}_|^f>2HO<%Q4%rG+QPDCZlgTI?{7qZ|vc;kyB<(n>DfZX0Ov&W0kYb-P@( zmZ}ohL97IG)Wy$;SyU4mz6s`&^EUiBo(bA}1T(+XJ_`ru$9dId<>}la$n&+YCCR@DsOhAl z#`^LJEK8;#U*wn=5SCz0`Vk%V!$jHVZivfxiyF>|^b&>YVEH}VVEM|9GVQ~SA9wct z3Gcrw9bfbLIQajT_@a<5A7?tovim~-{p0;zpeqtzam{-#8@X%^LSgQxsCAY}v-{mi z^Y-2ijO+_fzaJj#4t5IDSH%OXN}jVUMRmc_&0x3OPS=qaA6XiV4PPaXb8vXBJ}fe& zES6d5Ghx2T{(Rd&9hzCHT1l5pKHi|3NQI`F?tfnNqOAK(`HQm;BYbWd@xL3Xyg$1KQJAU|J1uw35vU7R4oF74CAnJay z31&4Lal0ru3a)u+Ftnj-%`y-=K`oUmly;yzN_)QniXodahj$QR1b_lP{Pn@%mWO+ViN1G_rWJbtT z8SKYCq|6`pMR47s)in64kV^ zCD+}>Nd3fdAMtF1mhFkOVvjl)`3x7ank|}b28K}uQ$OlVGUf`}e*P#CTqIz^L?{SF za&Z*4R8NEna~VEyOCl8V+F7)#uTQZ)EGoc&wH9aUrW0gdJ8tQn-5_K;tLS5M5)QV& zGC%cUxLV6vgxi6*Ln%6xa1Axf2(fp)xha8BJMZ&v+NxZQ7@T*rW3rn80%VPuC}e|Jm~NiOex#eH0NaBNT?xr=?ST5MfxLcjcAO@N0D5nZnO774lT2L*G3u} z8#j;yHMQVtIiiyEw4xGLnq5)!=fGiuV;vPzBn2O5@wL?0wSK3pFkjhi{zjHvOUZ$1 zReSCUstwz@%iwphg_Jw=rg%))gk`(DasCf0WitI~E9|H9Xd6z-VjD}pz)WBYeN;wE zVNW|V<@N2^`!>hnNg{mMVd@gfTMx7H7|8JIIZtvq#3I2W#$ zB3n9aP6#Xaaqdn0V`OVhQ2g1pZse1dX7n1f>+ibxUD~K=*E2{gMX+@+`RyrcEpTs029EnLgZ(}prRc?~tW&pJI1Vrbgu*a@!rq=WUKm<+Rl zjm065Yadruz%H}#es<}oE{ER3)9c6k7tT?flWa6n5g)&36%snl-B2Z;sBRi&G;Fc; zLPZxVX1-Vby@CMqtFG zH}{mzwEId-x8WY2yS1Hx>t_~yq=I?Rk4r?Ju5GRxNGjEMDzgY^v2epT*k29FOKe!h zQE$<`Vk{^kCdq3}t@vt9xg~`?NopQMZ2MsD-?jhC4) zG3z@t3sa^u20_IRb^1$Ff)N>%nX2(geTskRekXXBRq(Z4Re3gJZ_g$*la0iM**t)c zRg@Uy&nNj(jF|GnYW-reb+|*w?$8l_j@l7c6q%Sjr1WS^hQP$MPV@<^&}+1g^zrUv zI1HE7PwbbA$>O`QEZRlgYb59Ht@Jd$@FOLCj)W4b(q4u}NDkk>SAuzxFSj@`3d^@l zq9n{2$VJQrDGt2U%U8*h$7h9UPQiFhCZz1xoN`gcqqEbRnJD@xSk4#-lHPjDN_GK% zFsh`bih3{X_%@GNhpPGfyyrI^J8cd z0@N?{=3yd-5iwh==IMKMJ}Sb&rEo{3|O&(A3%3jgNv8=H6;f-a6N&<^D;)%@pFIc*i0TQP(g&33vKw>`+5Pq&NkD5GvN_3V88FE~|IFuv=H%i0 z*RW~T)pOWrzyan>jO*dJlu$72*GZA(TU&;k)r-DlRRN}o;)hqxPxMj^4&=7C?VM1` zqo$=H`?X18mhW7rMY+hZCk6%iLWs_j;2o0^T@ET;2rtQ5Jf+3Y;C*ggbuiMc- zyQ;k{I`R=ahA%RA8whicueEDwHZ#8sSZsSp)(Bs&xY?G>3`C{Yt>iAEzhnJVU*)jH zR~UigKIKNvzDf$mQQTH-Y8L)u*`RFA!QuY_o&_CVg5}$1KP*`;rOD@Ksul(3ziEbzBD0Axb1Xvq>!nkzkf8e*{*Jm$&9d$vr2k9%9LO5^e( zPY$-ye6#-hz`&BgiFwI8xsCGQ@B9yrz>@Vml~5>AHcRvM*1nAw)^H2jK8Rz(Y-1v^G#jmbWv-FU=KWp`kgzrWT(cYceCfMc1 z_LFtil=N4Z((!Ve&{VjZz0EpRz4x=S6)NcySLH&CCN(i=+dm)> zO{8V#uS6X&#Ms00Rw|K}DPy-#K84`Q#KodkJ11VEsD+`?-!(tJa*{h*+4++O-*ed? z;zCDQ>EE=a1kABR3myeu3OicaR$z+fy{{Df)FoX?q9@O--|w_iD%^DL_l@k625n8( z?K;e)Br=p2HN0JWFZmH)VA~)n1Sx*Z+*ZY0%S$chH}Jwy?1--#1a+L^J?Lh@#(ftz zs1*Jqu5$teeh?3Bzt;Eq0y1@^=mJFlgpZzwB>rWP}H%kIRk5cQoU#H%11 z&RT;p$+}+D=yO$qwZXxG8puE?12pXo1Jx2V|7EoO^<5@A78yvjKNP&hBhf;#)mYN( zKAGl6+thxZ$!A|0b;q&2w|OUwy_q4OZe-*4;~T2SYF?8?>+y zUR~)DXA|76_;b)J!Z%4>2EkGG06+Ai%EsF&57jqI&$I!)r1y&~#RI(P$N2Qu1u!y; zkeA=+`|QYF*Qwgl={Qhl^J41LhKKwINXsU%Y^yxI71cI^#Zng-m4@ zneih94%6XI!pCAVj7Cbs_tuzPR~PnU9khDWS`M~g9tjyswqQ|M4YxctBFlLQ9eYQf zfluK%(3oeo<22n4we%ZTg)96aBrFj^lp0O-V}I|s!sjF$r9lLFD^z70FX+#mD+ETx zRs_1yu3XzFj*Nt{P-Nub5V;|JUgU6(>~FY|5pT%fJ_N--7+kS;U-35st>}{94;`)EYk=aP8M>@omxRwas)oJ$6=D#FXh|gru(SU3Kzt{{OgZ+wTFH$ln zjUPb!;JN9}n{rj1*2zP?`#CiOiZe}fdKB-~#BqU%Cz|TK-mPDkou7IJf3N_tkXvrs zix5$+^i69RjfCc~)1Mu;IKK;iuLlKQG)CC*mAp#K^&u0bh~;#{G9;+AmV@B-BV~O7 z4pACFu9*~M_-c!)3qI%=^ytdG9}`1brvVO{94t@{%~+#HFL`*&SLN<*3syuZ4p%r5 zcqQmBe5Q72Aq7LdV1ySk3@5p%nY9?HD3aat5}`*E)O1K-RGjb{1*=Z-L@Y!8)Sw>5 zOh&0{4iQmif6?uj4QL6z8b~U{z=Z9C9Y_{i{?90$c^)T`;9W-I@II*D+3$IQpBPdW zkz=m(@MZn7PGEg>P{#MD`n1qOr4P=hV#X*Oiq}NcFn8nl*8C5;4Oc zzK5AdDuzlru40%kI42O+zY)VQT_?x3TNE5tR&-tWqbM4Df`^>YE`&dh<-wvKqmVma;~#s(yjMAmDC zeMd-y=1-hZO7BwiMw6X7<36RC9lM+hp=M8APA*Tck_mv78HOijE&ZE2P~Uy(wT4kv z&rY}(UnSB@1rh zU_PYvi`pPCtl$?b#U+pP%gH5~w{HINx}kDrA?BM1HE-cS;Hioq_LX`MgM>Ooq zi!D-CJRDAS-*pkQf`z~H<6^Fo)H$$K3<_IaH5X1!o-ihv-wH5kh(F#A)I zJ&Rv-D=7oH+wLF z_*^pRgI}qkF;Adg;E*G~6wC5(Usv-`dczRQ4$qcF<(Og?aBsxED}X-XE(pzA#pkYA zKv5O)cK3Y3TKp#a;~TXe=r3y zGKkAZzl`)Fy|e##V8#bRD)7-NuN=gDtsrYThB}r^`mx*c!3RPC1`eC=tHP^&R%k0y zVq}6d5&IHK<$wMI2*u6**FB&^<>h&j4>&-)Ns#%Rzzywm>;U}$^B$PV9)%dDvgvpQ zhYkCsK?w!8gCZ~|6=kEMQp4@%p@Ey$H=2k0beU#X&7wFSLZk6)UgHpn2ttSLw8PqnAG$n{-DwfYDXh;&RO%C&Bx40J zf<}Cnv%ircqNcG=B{Y!({Qbn(W1}Mr2O-~Q$Am#hDdLl3a&YRYrQ*l1lAZ7^eS;X}cmrX| zVS(yHhntVf-yP0@Ae##kQ^6qQ@E1WgW;ff$htu%tHiK8}Z}{PqPeZ#jIA98w__e@1 z*|7rL`9dWsHmpTRk_Yhub4iXqGXVG&^MK)+)R`a#Y`YlnJIRg2@p)NH(Ce({#uPkz1*&DvnEqcB$0793kDmdJ-D5fZ=46ZxjTa|XKwfIkE;g)tuK|E zbVQC;d5$`_Qa@Js+<3)rn~e***B>^Y-_5hV>%MF`R4N$ycseRL$Dh)^N6LG2-V2ti zPaaho@dpd@yUVKM;aM*8GZV?UKo>6Cd$c4QUYz%ilkuNdS-TlYWO>`6QjijI+kYjU zu5?i7=E>Z_se`bEo&Q$BA;wg&Tf(`GL`b@?YLS7vUkvWLotR*uJjajm@bCYk{J@+w zkt*ID#Fa&&RZ#DIFd(oFCas_B;{+SdrBL|8dh>Hd7&>g3i0%lup0{?+Al-BD|Fkc5 zT={V8evj+m9?;|-pb>Ed>q>{PfnlGasFY+Cv%bIiquJi``fb#LZ$q_UKKwY;xIN9u zdj9fHI?JhzwD~<9nOpdfQ8Z$~RMsSf?t?wK2c`qZU&pO`I>EF!rN7p=pclZu4&TBP zl!Z1eHuJJhpsZF%k|OF}`rYH{#YMSquiOM44Fws+-zOWrKg7%au%#8dc*9dRG4kaN zTFoed_?7v)pylZ~P~(|mrIf9gotJCd=_EoN!k^amm(}wvtJ<2Y%9anEgJ0g25_3u) z7v7aEJ7f@Fi>-AD9FJt>+T!Se=Sl`}ZEbQxwk+8CY^z`I9vKsS{@qcdyi>lNzs!U7 zF(uuQRe(v8jL=7qtE-HETEkW0W%FUotLp`a0a*{6Z7Plf%idIz z4t#SK-%#mZsSB4&H!drVtZ^=JfM;ladt5KTm1 zJcg}ODDtbW_dLr^Quu~FKlrdDxX5yOz=gAf_PasJM67POr=GSl8!b{9)=X_+mUEJO zW107+b%&#(z4xz!gTY3$=(~wQv`SqX7Cff8X82qKVv$37e-(S?+vEBnIgzw6m1~dc z3lX#sO-hwGn<~MCFyY0pTXU_F{3evpOE-8a=SsmQgfL_BCACV@PB1D3Et4=EPu=8kwf6D(x1~ zTS&14<%4VF@wLzK=t%R~E%^fouSPt=%jorgKvq}~IWJ`&hNIwQG0uEr)Qg8qkV#Sd zTDnLsPrcp6Wpz;L^#E43Wg(sGR-ArGxyupdaCVY>487a5BD!x%YT0s8J;y)0TKR4? zqi@uS1S>tZtjx(<(QRPx3Q8{+A!vIw=CepQ!7k^;zC=mqH(aqpW^SK_WqQ|60|M4 zT=j3dVvfTqV$Y2?Z>Z`$D zQINOBWs_n$VdZ>CjWjaf_P5L2OKX7}vPAJqzyE(b z;Uw@f1>C>4t4Us_XodUdCNlL_n-uc!Nf^T7SoPlyC^`{<@t)83T3NrK-~@(|jY3io zC$ayc!1?Fa!l0!4UKaZLyk8VYGXLCtwmwgY(jW2h1~Q&9l%T(Fzg5dnvO#h^4hcnv z=H+3p2X4{QjGMHsD2)vT{DcO$%L`pSoe?DkWD>m$rCQQIBSy20DTM%$aLt$!jy}#0 zfjVhX5(A|kFO<@%%KK~q17<1jvjq&8rM%A;FkqJQ zK1;xWS<3q)0skW?^FCX^fLhA?YyksmDetod45+2N&lWIXmhwJZz<^oG`)mONW-0Hp z1q_&_yw4IaV3zVeOTd2xW!`5C7*I<=&lWJCmV%xwU_dPeJzKzlpbUDpfB``n^lSkG zf->mY0tN(S(6a;#2+E*m3HYy|40^VJ0YMq`Yyks;GU(X?1_Wi$vjq$Y%D_9#kFF~q zD1)9YU_ej?JzKzlpbUDJfB``n^eh4Y6_i21TK%WY0)jH=*#ZUxWze$)3<%1gXA2k* zltIrHFd!&{o-JTNPzF6)z&rrVvjofoz&uO9Jb<7KdbWT8n;-OS0Rw_E=-C410brgj zU_ej?JzKzlpbUDpfB~%^^lSkGUOxy}s{fuKAohcRrFu*N3>a9e#|XSMz*;>f00vmA z#{|G|JyjD>$RJ>;{<{VU${=8=9uoiqEY)KIVE(;r(?7a000S)5<23+=8~j8A)HDcK ztH+A~46s&@34q~#f&t1J1T59#H2?-!s{ayD*C1f29uoiqEY)KIV1T81OaKfI7x*ax zG{9OtUIbu(wR%hd46s&@34r;x@#61u0_qy{Z|B8734j5X>c5W!${O_Ce*u&==(zy{ zC~FX~RN%)C1!$goFo3!SJvU(hbq#v%!T{mtU-^B7=PO` z0Gj`4!~hB#1mbvl{v1GQgPxCH4xqL{&j&CEP~4#BBbWoIZqV}~%mI`)==m7t0O}j` zd=PU0^$mJHiaCG+2WC(I_ZoqL{t$rc@i_k5E&_1<&v6VCIp}}RW1z}G|8pP%We)nE z6B(#;(El9CK%s;F=S&6)9rQnkGEnItKH&WMZv{AjS_eIy%jz6Jv4ft^We%X)LC*&> z2T<;y=aZQOsCUrw(aZr9Jm~ps<^U=l^n5sT02L20@AeCljD7?X{>5`RyezR z{H3jEOa1hHaV$w_W98Vaq~4f>ATbeC=r|4{%T!|Or;O3UDCW7~TXQ%WCyhfXLA#b9 zAes2QCREn6REXg%(HusgAG0Zx{~WJ#3nqZg)1gXn(p4x?<%Vo#&wWL#G7$r@H2Klr z3^pswhe1Z%$@QAc#Wg}C36mrDr9`TDz|d`v|HNC}%uqU|kOA4IZxYhMDg^HsNV@We zi?GGB2r_*U4pO*q{Z4oEUrmZ_Bzys;L`cKILL^OC6Dwpe>iQn3|8NfSh?#t$Ko7<) zF5Db0wgKneA?w6dN(@Sn<=OrX9}-{L@NVy)pJyj45d8lP0-N-1)lgima}$ znW+_Q>;M{z*LXJ~Ew1KCBD-a@Eh1OrSE}L7@<<>Y0wIlVn1K32*B3Eo>EupCDr;%N zQv&vvbFfMhOqf`Tgc`~2x)aP`EI&Z@CUuGS@luVQq6iz!S$a@h)KewZz9T+_Y)i4>c?hZtF_dV?kzbHu;7ErcT24M zOzVOy5?3Xov!7SO;1GD~sHA|}-Fc+6upV-SwD{0(g@LcQ8)GIzoiSZr9^QL@Ln8n$ z5%YZdS;ZD!g(i1hetV&4m|&E#U0Ts+PO@5u;UtKL_veq(Z2i#vRaAb-&Bn1H zTbB@Azni~qv1CW_+v!2-BJk;AChK;V(yvo)?2)tE1|P)5jVVTb=0%Ksi2LKrS4?r( zk;qYs$X^r$PzpC+ht`ovHqj3@*|APx8#g=ub~FCPm=$eg8d$GZc7tTRb()8 zYdae}>(LzQn$*hPt?@hl)F|Tt?wp2Dbw}McywXr}2Dq)kzAvt|NDO#zVo8yhQ94_6gqHyzpih+vo_)Zh=)15uRoR4{4I_Ff&{*&D<+Cvzr;9&w?@{2o()OqA)Vl$@CYkVyKSrj%omB*T zs7yj5N~vpqq{U0*g@pjh6V$1xMP?TsjVx!i(Q?wlOrr-s=JJaxc6_RvTxQxbOODf| zs^o;6fIb%1^{kifbVZ>=ao|WDdqasK430UxWZUruuXuO=sStd7e(s^;A~!YqvE2==Y9aa(rQ!EMbyIchkgny1P$18jk;``%I9KUwR2GeT8o)K?d(~xLQSr|3Kt!psEjX}Zl z$BB4|*1T^bBBve9Ky@@D#l>M89H~?pGcHYx%lu!T#*}KeEmPp349I z|3*gk-doxG9GqkCDA|&-w?f%u9Gi@62U$_F$_^D0g{+E_WECkz_LkrKuJ7mE{U86& z=W%nr&NPwNUXP zYf*V-j(S(KV_;{O|94QI*~|uJgL^miP%!*i@#^vF{lhfwHP=Je-{i;Hs*9a#nR1fD z8ma}~PmGfKTUi&@3JsKcBrQZqUY&pb(Cs7M3H0^F!x-jJ%qwpul`p#Dn~wYyQ{ zPv;g74X4*{?S%H*u8ki?*{;h+Z%VCvczHjiaK9m+I6O*?LV4!0hU=HZ2fPOBR0q6r z12;Se?8VK@gQv4Oi@!FqHqnzb`1Kf4(y-numLKS9jn|&m2yS$?q|6{OBMGS%$0Vty z8s0_`KeuPPQ;V^CYTc`O=_wa>ps?w@{| zZ_xVv_2^gsA(EEU7B$aClAIMky*#9o@P8}kdPl%H^__%ml5qaUfOl=c4KhP^j#N7{ z`!`yh75SEy^NbpP3*(--*-hrT>)JLnb?&+8nx>>`#GmmDFw^2B$JfdlYm3(%CP+Fi znoulsYpcFIS!kDL$&<&!CVcU|RYXe!Myy(NSLd57k@mT@i0?|Z248Z%IJDf#P&Zb5 z;~U6#tB`W!!_5m5mRDWxpSE84xfU;~8eqv|ZT_L~yAv}d6Skv2w|sw_ zep=zl;MQ7?rd*H4q}vTOU%U_&Y-7D1&2oQ)??+?bzDM-dME+v%;hNiY(`xN&iP;@N z^WF{Vh%Y01#Mii5hQ|5U)hW?*Z_iTl%Eb3^$mMqDS0^K#?+VMiy^=j2!M4ZJ}5cU}>DR#t4fcUxDhm9N!H?gRCc*y@GjXv_^JMo*Eu9rZ=`E;*GI z+|!OEyXW!b_ngwTybSu^nkp)FZY!QBRW8b znrCBtbR|!3)IPcTN`?Hbd{-ar-s9JPj_*4JeB^w+K}sB z#rdFIQnUN^rOc07374nyKFvL0$LHWOC~GbYJVlx;CT)Q5RPqp4N!Fa1Q#=*F!5;nC zR*-cmtWY?Ykdpu`@qo3Ikq#u$y3$mi^YJp?y4zK8itPS7?L(NcnFX#(Z6^#wvJ49% zu_fM|9f_sm0hLc^iKdR_+n4Tg8Qq@@oVeY@AeN|N;j(7hOL9}Tz2d%DGv!*9?<2Ro znx{mu88k+VBhhpa zxW@6u8J^nC=qGo$G3AE+j+hj|{p6Z)!%g+Q92-_Aw^Z)w_lU_K%8h%iMSGr^9(+bu zU%E^rpRW(TFB~3Xx%|v+;~5vHlD(>F_vACDn+9)dsWBgeeRik1-pEr3PI?-l?MHgQ zY@H6A38WX^wU{98Rq19IlYb|Cv0& z`pF2;;DZ}LL$_>BiWaACDPa&Oz|ZvNrYAswhrunDvA1jxdyq({m-zc2xC0OLAUXCa zv%n$NXAMDzeZ>OaMjE;+vS14VtAH2C^*^tc#&*>U31J_|2%N?mAF427)BF(>1SoKi z=yTkHEw^ffIEb*1SOgfbA6NuLu)+aytXMA@Aj?n!wAfe~faOo31b9iXZ)F7NuUyI7>`y7Ke6$C^z6LoFTM?^@mKkp)Gi1Ur znP%TD`temB7DO^DeS2+Tb&(8Z_uhA#=F#sFpp{|a#64~1%sPV~K# zCYWbq!S@kQo~cxq72JGxkrfTUI(UwInS6tHnCe%&DFFR5syF5AdICDFmx_h8sit}-~GW*Q~ zo6PF>N|gjrI>g@ejUiv{YliY*>soH+{M7h2HFb=q}i4OBr&a##eOC zuUL7)Gu}(u=JzAI>BaN%KU%t71PyiMtE*SsM?0oJ`P~l3pfd$ki_aI)U1={0BS>tzPa`bj4V>$!>(4u%hHBk2H2yAX zcH_yxrL&&JBC;4~hvD$7yN#Xsu5U1>Go)xS zINKU<O!;ikn=oUQ0{M?^7z&|1gY-$(qb&9kLyx!X8 z-rMarZJV0Y7<^`$-fV%Ht#*HzX|`^(_(eBXMu-@ygEEDFpf2_MpSwTh|;e zw}FBh$XKSZRn9zwFTo4RmJ%MCBKA?o za`USM`AqT3FPjb~XR~|eyouk!=~=U@Y7+I+@4wXA@!zD`@j}(m8NakvZ1u}#(COV# zRIQ=QUQ~OKiuv&-Q2e*cTKTVSCALF^Z?ZLye{a#5sV}qpBccx+4?duZCIg$!EEE4O zo}cvodGy8GPj_5#l_wJ(o5Pa#)=y~T`whl|IilgTcKx6EU(e>b z4@I@_6;+A+Rvy5Zt0wQ7+6iX{CXS?qe{w+HXP8(*w zeCF~j^2uBte3#`ZR7+d2wf@pcJ@Hxt;Lp7~tC}SY@A6XeNtsT* zP`u^yhb{NCZ;D;F=6YXwHGeoF*ICq^fjWj}G`Z-+D>0F`ulnei7w+kr=bh0@|C&i8 zpo0EVmLixkSU?kx_;#f{$*7V^A^+sjV$^FH@mIR{-jaUhJ&%3V$E=_3>Tb+vEOWWI zbjt7W(ZXf2ap%wNnA*(X`DbR=-mtdJ-(aD?*H-6yYU6|QufsC#e(yJybi9dXIRv3P z_brWAU(OeQlU7UlVS05ZTzQuJ?DCT@0llYGsgy|5=?R!zCGzOUXvw0<56>$0z52G( zr$P4FZfe>7iR<(;-@E8Ru3U=T1pyt3-o9)G(zo8DTe%H6&!2f>cz@W*jiMKg#d*^8 z=azW%O{gAN@V-s=URhV>IFJ!(IUUE0=io)e%8nT6kR;w-oJGFHcT&I0~SuO3Qop{S~o%h@|Uk@~;u}LgyTDrn5m{*<6E@Zi- zw+wr6kfG2KFkIgiDh$F7xKOaHy`m8zX={+YINLsmqr`dppwGD+X{MXoW znjOrw#!{|Y^ybd!f0Cuw)nuA{ueAGl{}z?Vz^owp`Fnp~j&Ce|nlEF1;fu{6AKI6* zdN}w9Ife;EpLw~|#9CYDzx)Q}r*~ISv^}V3fOeLw!>CK6fA`Eq?ivuwx56U<#jFdSvK;;C?A-`>@p*WRF!!|J3R;0@{{rH0{VxQ zC%gSOZZ;{$t=F@Lt)m2s2(~y9XWV&-!tpqhqN?Hq=-l!B<%~}w?eWhYwks}8Px22IViL8*T zIZ*02IQGGXFIQtoPmRwWkP9hn%WY=3ENK}pm0dezv7J;q`&2+uvSPPEUL!B)yb4 zD;x99$@j^gYJ~oJh)N z#dZ5EC@v(WNk*>X^R3+ed=lKW;#u7$ud2i+hP~{!YrWf_e#}Z@+P%LZBx=fc4E394 z9XFTs&a0@N6(OFW;a7gFs1mR$7A#Ts&Wkfcn#V2cWyB+wrOENyJWelZwQq5PLZ7F$ zdoa|P%E?6SfJxVOOytNgfsYftoRaF5GMmHKNvYh;uGX?sVO=fyUN75t8FX{q3awB_>dR8>xSZ2^3NW zA||vjxCW{W4+^xp|JS}k0D)^*B7wm5D`kPe^-kr0z_q;Of%vZx2NrZg!HrWi5V*c6 zXwaeHz9|MY=un`?{a@P*xPbenpgo6z`=+2fhl2a2pgD(v`=+2bhl2a2pf!hr`=+2X zhl2a2pf87l`=&CWV~PTe)Bk-uXv?ACzA5O+q2RtLXv(4BzA5O*q2RtLXvv}AzA5O) zq2RtL=*OYpzA5Ozqu{ow3>pI@Zr6Y&JPK}_f+jo)?wNunJPK}^f+jo)?wEomJPK}@ zf*w2y?w5idJPK}?f*w2y*DW;#J$MWXZkB>3JPPiWg4995tx}LXD7aG!n(!#NQ3{&y zD7a4wk_ZL2NkJB&;4UdhBNU9TfII>nQ(Ve`OhUmeQjkh0xI+qZ2?aMuK{BD>{wPQ$ z6x<#KxrBndqac@1|20R!(r>^FjIMxOLZRV~El4I5jIMxWLc{0^NG8xK{Vz*EGNEB~ z1tb$1Mpr;Cp<#3d;62hS3#}OlTNg0m+1h z(G`$PXc%1qxrBz%6_8747+nFmgoe=-kV|OrSMwh+0Fns}qbnep&@j3Jk_io?Doo*TtdU>3dkiijIMxOLjOTmFn`vs1j&Sk(G`$PXc%1q$%KZ{ z6_8A57+nF$goe=-FqMaf(G`$OXc%3AcnLJju1JGyLPPM%|9*dnmq5ei7vd$*Z~=yR z2{c@SAzlIv7h#B(K*MDi;w8{_Y!jltFr-!5`9p`3Lb5Xt*vzyaXDq%MdSt zh6^*qOQ7M(4Dk|ZxHLn&1RAc*5HEp-i!;PapyBF_gm?)wT%V;urlH{iEe%o)4Hsx> zkZWjpnfU4p0$>wtslFiOjKtPE$q3SbI*Q{eq@_{v&}xXnn4HUo9A{`^XBI8SZr6+L zY#urAp1Uf^a!xP#=_#Kmqb4!>rzZzdjg4f#chIg(x@oK0kGMRQfsna2qgVGs254j+hHR9h1xkjsgbh6>4*l*v@czBy98)ux$SnFe|W$e@G zH%NMuF!V4%nkWtv-|Ma)5-n+;)y_zt5j)p&YKVopJ6j~W=dP9^LuPLa9fhG`T>7_2 zAL-Q-Ld?lN5kCE!7wbR1{$h7Ma<^VVll4c_%eVCQG+0rtll4wl#g&PO=gQ)YXK(7% z_-?9AXx}LL*`JL1(Vxs&Uo`lEj=hiL4#%G@S>E%MZxqG{eDOJjkb5p5BPb*&qd5S5 zcLiIfgkTX}9(@*h-W@OUJOudeooJBBy7(EH*GTW$m;4K@`IW;ijdgKREYCMe{cC}J z8k*Vr)}VGbk8flHKiCAJ4Ut;_zWad3WDr8kLL@TGLT6;6-%8&}jPvQKaKi`*o}tb% zy-V`Sa+J{7$bKG> ztDN3f8=pM)=wU^Iqgq&1OvTNgD`%B6_q7AZ^pvv;zm9B$UJQ89@M4PVtfPu(ATOnOpp`2e+CXn;o)AuDhKo#`u5W@%*)L zaqj#|g6Y@E$lWMPHRqB@;pI=_3H=6ln0}F17EiC}JtaqEe_`2c8#n3P+hayrE?5>T zR3x}Q>1ajm8P!PQcYW*Qt%`Vis8wh2Gqa!l#jQ;}X9nbcR^o7|(tEAi413#~RkQa} zi3L?9Msn_kJ|*Yf+E^+5;ra{nHA&~w*X-^+DP)*v0OHdVHk-k?z1In>oaXH_&E2h2 z2aykE6})C#Jm#Az!@qcuJS{xj!dqB=t^Lqe`lq5i;imPcfN}e$kGx#2-`N{FQSn2* z)&S#rA#HZy^kdzauS4_pGvY3kCd5B-SI&ivSyB4<$dgkqE}oB#ZP6SBtM*uxeR-aH zwc2Y+lC9NaqP64NaL$J7RCe+N>vavLof8i&v&kD)u1{-f@a3q)rS7#q??rrMO<#BU z%1y9Z_<;Gmq$2&#y-A&ITh3R8=Q}lq63lJB_cn41#5YD;oH0Bhnj4U`b-H7%w74_m ziB-+dP2SfBE*^@eMX!c8Z@z1#$9QkBd3rxlefu@?JvG;~HIjPSHv7zdo$o^yLqP>w z(=o?f*1u(s{kGDiN1<9G~=P@jLsf^tHG&yM1g7Ry0Z+ zkaSmC$&^$JB91ZTshP%bY3@pC9-720j!#~1J5-9>w2up=?)KE4J0)1kc&uE~Kbhv) zCpTZMk=$GS=r}!XnblMC5ij)McEjGQ+w&OZBl!|mS;GInGliDNf^4TJK%=n6OaekJ z;pgOX@d?1A(5>7E(WpOow-7ef2C)l03f;9DA1o6+ASKk|mnlS#kBz!6$AG<^B}5GX zb3lR%wAh-+Q8PpD2fda6jsCNo6PBw+=rleGn~nngrc{3fCG-Teq!ZMZ;v~YxWr0D> z{VbvXwWVgOg&44m4MMcoooXS$7O-@aA1PL=Mu-mUR0Ce~r!7VFM2M9@Mjpc4lL^t_ z^PsU1H~R0%-QTegI2`}MI{yxafC3yGw7@lp;K2Y7P`Hr^0#dl~5fW0k0g^1Fa3dr+ zNa2P^@{q!fkx-Dro$;c9g3s$f1U?@=vjY*3I6EK$66Xg*K;jI62uPeG5CMs^1R@}D zo7%gk1eS8v-GyhB)jML_p%senA8z&K8J(#MuH7kT_c)0upBnL_p$ffe1*P zEg5h&3^dLch=9cHEf9h8BAhJ{0g1B(A|P?LKm;Vt7Knhv*#Z%eI9nhB64?6R*%%0c z#`yvfkT_c)0upBnMBw}kXA49?;%tEkNSrMY0g1B(A|P?LAbuHWoG%aoiQ8Qu0upBn zL_p$ffe1*PEf9h8M4T-U0g1B(A|P?LKm;TLcQyt>pmDxH1SHNDh=9b|0uhinTOa}w zXA49?;%tEkoUh_+fe1*PEer^O#`yvfkht9iA|P?LKm;Vt7Knhv*#Z%eI9nhB5@!oU zK;mqH2%I;AfB*lD#=sdM&^TWp0upBnL_p$ffe1*PEf4{Tvjrj`akfANB+eFyfc(!E z#uS7=<9vY#oWSFD7l?qw*#Z%eI9nhB5@!oUK;mqH2uPeQ5CMs^1tK6ZIA36x1@wQu zATAw9oGlQ6fdtMLh=9b|0uhinTOa}wXA49?;%tEk$p6^_*Ux|uXq+z)0g1B(A|P?L zKm;Vt7Ki}mh^i z5daE-{%;Qgejmi(0oWmQ5P(KuxHo_d!bbrp1R6F79S5Z0;{X%_4gVWMM*`{p9SKyx zf4D�%UMJsz(TH!eA2tn`jHFN9mJ@x? z6$<01uC!B^DJ+}3X|mmZNnd#*Y=;C(gt)yxj@!$Ao0Nz8D*g60TED56|4pxskzA;i^aW*dk+AF+^P0goH?Y zipe%FgpM2KrX8W8#-qW_OH*oCDl1J8|2~vAqDkNt-upNyT2{{l#6{8*WY<5^xktF3 ztH3W3uO|))IKe(Up&i4L&}>0!>xAk;p9$Kg#ZO-4Af@=`k5|YsC%9oj~h4YbvL1ba=1xoc_(=EH+I1j&P+5Vz1KCEigb zZCNkax_N|8zn2j>>+Ujc9JLW~De}axNPFW|M@<99Q@g2;2JNF+5;;XRve6#t9(mnd zJ&9v>sWqtk^&|uMblY|`JeJ;v7z>kcSzow5YMynLD0%5upOhAw=QwpwCjJ#7&X>5^ zHP_P_dDrS|GU{^Bv!03PgeLb0}4kHc;ke!p9N$2UZHexK zHB`d-y9IN?Y1&WiD@W@jrfRdR6;gM6bzXV7t@D*$Ns)T{-rV~fnPs8N`}a6M)_+b7 zqs`|{78E?E6+oV@tnI{XA$huKyZ&{CSF*kE*-6!;g@!QUtV7dx4j<+)k2AzSseRyF zx|%3ANrJ?npH9y@hD|61D6~FmmOZ+~DQCpZzWc6y#f$biy_oHoE4dkE#rwwga%II| zMv6uUNwlob$kc9Mjg_=$KYG~VcIK#mLR<4tQ)`htmU`JCQi`MH%Sr*o!<}h&NjBtC zYYyWuh1;llsy2zNE+fZPx07u`d#TwLn+hFpu8X~c6($Yn``w|%hOP+ zqVXfP_S=ZfSykVclM9{sjWsL21N(8e4TUf0n72CTi&*G9G2)H68-gmn)tQoy9`3E- zDwJ>Vy)I;%zgJpl(Btv=e6#f72UU(0PLB5U?yg}wh5eU}4T`m{i^~`{dt#KvT|pqVoUa?(yjBeDo#Q8>)Xw5YqM@N|Nb!1soYy&)_HvWX>oG7BiEE5(Q<+n`Nh*sO4b0rC#>gh#EpTqmbBl%QQo>!hRs!{lm z-T!L-7_4`me&+!HhjQ6NGHm9!6dj>7pm9K*62htkD3K9@TbKN$@N&+3F{)FTElPNTtrC-ICggy|Z7%YCah{A$u6m(OF>d9_Q;f{7BU4O-ZEyXPZW^S@%r zW0|JP22Y=v5Ggm)_b~OYFKu|SWyM0pb%tm}{D#RRW8sPTvjZ!}c1m)ujM3^Z=8=rp z>mrx=zV^4uGH0iO6}qDP21Cy#<{6%oMsQsi z_|s&`c1Z;M7t5ZJZVO3eC<_ENoQX{LofMHe>nR{bCKz`zIo}O)^%b&>()VEOT5iZv zZCqOjQ)$bG24X@Y&-!a5YhQn!oj{T%b%65kSg3y7uJOH0{Ddn`GQ^n|Y4 zOG+(2_1hkKS`k^F-BD0jM*LFZie15+Lyw=1sg!{!A%8L(3+>pm1TJC%O9fe}j9yBb z_jznA3uDhJ&>t;{F+W~3BGu$1)YV%YZ5sObYz^w5Bw3OvyQh*T{iY*)NE1NKY2 zxaeQRw4zv?5j%fRoEBV?{s%D zyYkNAuGJ?nJmb6{AY@OqG6SV*4k>CffewaLAOlrbryJ94l0hnQWvzmQa)v&6E1|=Hj3xyUqC?$?8U{ zyJADZPA2`W(!LTsn3j2s#o)V*QF_9++Abd3Nla&ZHEEg#2zGR`g$W4^C5j=Ykq`3T z3uK5HCQZ~KPa6b3-xIbGzxav~p>w9c|0vD`ao@y9NA992Bzmd zzq=T>U@!GLD`x+|xMyjIw4Xt@)hUU-&V z>YMMYd;YBhuE#p_t7}aaeH#-G8Usi@K6LI*;Z?5eMDp`qGHl5AVtI2{zAhH;#O-wN zagV^p=XMxXBui%bB=HqX^Gwld5<0DN;@Xl=&(3j;yAJ2ge!@IxVI^ddxpQj!lnb@R zlWEywlOOxO6~awaQiJT2Vos-XXcC0kKemR8y?Ne1dEkh2!n=IPRTeq!de3p@QcZhZ zbd#6(_jNCnAE~-8uX&e`*bG<13!+^e0ba{4!jWsr3nEG4!PF9ZcRt^l2*|aHEiW0+ zWqQpvdS@#=hd?73GedEaEU2L%6yth}$crniH|2~^nr27llH`?L?FnBuW`3FylCp2F zyxeZm3cV_8a=yGRz!NpUn1C1fY$us&v=7hfm6BbDou!Bxttrv>y(GJP2@Ik>66qs# z3~eSC7|g79$g3i3wFyoctAq=1`Cl;zZFh>dvnss3Ru|!g{(@N@<_s<|>3nD39rJ30 zq1|@V!q@-nukO-L^zn0h&(Epnt}vb>4=&#h?@}Ey@iO4-!OEN6c)r0<kBK9|)+vk&^p&xY&^>dvJHB$a1-njSn>&p$~Na-&}KiOR&pK}Jd6@%xK?+FaA= zz42TR4+Ky)@|z!nF(0oBiI(ouNs^RKGD*#-GF~?`y!)ZEUC75u46LcneTkZp3{Yt4 z>|CpIECX}(!Jk#4+wzY~SQ^l#G&DlW1alB*W^WOmsS{cgrE{&q`EIQBywsS2)5a2k{D z8fIcJ&&I0pZ<}MDa!3oKzg$vE`LIvIx9wCwLMl^F{dp(3O`|&EaAc%yeGk1O&YN}b zvDZPmOU(Iik+e7bS4fUMylAx391;HSzK|z|wW{imWlPm5a9A5W)>9!&ne#}U%l}xf z_x^r7wVwj}M7VhjSMRkh*+U{J<5HOl*8GlGO9q049d4p~1S_@BVTlpD-y?2O8i_PQ zaPaiDl%Q`ZHkPz~EQr?^F~}fA-nmsVAWR?4`dmP0%Z$ zz4Uix38=q&2?d=oj3UIqi6s&{hvDVNSPXcv%QH;<5N*{rqUa8hEWTXk9qDJ>3wPU=T zywA)1yGQ+8qCuE(aF8nZhHqiU;>CDjLhMG5anhD?Gx=h(;pgD?-Oc!q*5Y3)6fiQh z--S>~kDgD^z6~B z9zB>*Ra)Hrxv?Q1Z}9{h@8Uxk*L9>|yVZ(*YO&>;RoY9LdNRd^eGOgaBukWjx2N`Ky;o2V~B6Ek&?m1f>-knv!pfI{V?94;H+!KxaxmEHt;dA3=b} zj1<&)th7h4Kg43{JvR5$g+-3Y_d|{oV)9}Jn@>{Eakid-6I!6#eR&dG1H-`WF)8$M zFJh;u9XWuXO0Q3Pb^P?imfk}a_F31VwNybL=H{&lQIsS3(m|qw(`oID411CWjG?a% z+0w75hOzVRw0Wp(LeY{-HIW8rTVnCty&sk9dagVooY6x!^`t#}tyxp2c3rkV`QWb@ zoGAIy70rvdj)=GC%FHS@6nMeHm9akZXy*#;dxfnlM(lUCy2iJ;=xc6ZKYcnK*qtys zTsQ9&d3Z}%V)2=#7m7I1aaPVRa|Yx5l;25%y2qK%%v*Lm?(1;D%w?T&s^$;*27?Ne zqjJXzZscVM^ob<-nIT_ExvRvt+=;a#L{`OIrfpl5PI!tli#OK45hHd>bcwpKuy7|r z#KkN6*R2b&_=rbcpWQZmXT%GvQF`$;Y`N%S$s`i3voDAz>t4leR$F(O^_4uvXlfC9 zup6)W`)}#HYMv}@t~7t6VY+5<_Q+;ATp0bK$Gtum&3}h{yZHuUrv1es#@Xia(4(+WeM-S?UpDD z9Q5lO#4&M%i*l0Ize?|-GE=*|Y_X6#M6 zGR(y4Q5Ny=(zlcYTU2}Yh3F$*EsCi#K9<5_0qG~~n|JrR=Qhh*97OJtiN?}T+T4w@ znh0w}5V5Ct&bPcoG)D}-OVWSkjC~m?94V>daM>TzW+d(ydL!{l`dm%)j0T6#T}!Un z^F&)sZ7TcD(spuBo-8eP*F@6xVmvI~l7{odedGE}(PJ#6q)oZ5GDA*E|LLBhs1Olr zJ}dn&jY}6ppH<`}{~Vi?BT*IB)OVxC!#;NVXPrjNQIq5HRZOuYp5_$ z3(f#=Aw-FS7l1^_WZF}Sa86yi>O1+8@o3n#e#XJ@irq}AzJTdu17~xdnOwi&p58 z$uo@CPgAJ{o7{AqZHx?+$oPCiBK@;9HL08f_fVyD1Rl260+~xsN9x6K@>PW3OQ{6n zq*G;51Ya3Y$|uDc$G0!JbvtLb5Y#1n6vf;roDc6JU1of-W$=v#u@GyZFhcrVcQJBC zQ}jcWqaKT6ki4#a&0_NGiAQ*Rt06*sQImqNNY&3vjcIQ_@2MHdjmf@+%AjXr>)lsB zSshkH8!Id9NLY-xTgvqQ%nEBtow2CNg%4Q^&%F%vZV^$F<@Zt9B2mWUYTvNQJDkunqZ+VNoZxkjI#6DB!Zed3ib z#kpV+$}C2k(SS?BMp9Hl!cXt;yT!Iy9)mlo#pr9#J;}aDDwA%=PKy-3)6Co@@{od^ z3pYCB0|z{WYzT2g*u`ZBN92HDKqM=SW5-2wz4zi6wI?c6-19Hmz2*VTw0yT zD5MnB$dc)H@9Mtsc1~qCsZ>J8TlbxMlp$B0Jswf07urAD${;J8*${oLlQZj}_s)l~NtrP{?}l7;Ds z_+T6S9d!1<_rdm^wmggbPrjtmcZE%xo$*H$hcQueaT}P&0V~r zJa01kUC%!;JC-AKXNo8KV`cuEnxbLBMvPp)?wX6y$|1$Abyx3*0m2yiPn2vwF;STb zL9KO;-}VosDTu8$93S*M&hsC?4YP7(!ze2~pI==KraJbaa_`=Ha>NqJ?3=kT6ZlK0 zhf*Y*fDsdsczXoH!g=7YP(H}Jo8oliW80AXQGB|v&7wS0z;;t!^8<0&<;uJpmn|_5 z%q-^Ht=gu(U+W&dV*PA&I#V#y_va?*^g8K%vgZamOY59o#T2P*yEIN*2A#D_Wna)w z!O;3Ptu{V0p2aeeAoZ)Mz16#1%3R!qW?7EZSN3oAR6lkvNiF`-y(fLoZ71BO*le%w z{DW09PuazrA{%%ynrt&xtemX1v zX7pCDpXYdexNf}{)^=G%*=R4yUM@e0kYAJ6yCcYvtSCWEtnW6e(lABCRgI?KOyYLVhy4x@vXTE)xsFy>vkJEqS?yh! zt97ik=~YGp*VF9<1v4k6{ZLgg?ygU{h8N#?i1~%={S5u>a80Gaf{!H2?MUj!HahX~ z>!BOBUX8?zS=R+gCn+Y-(|`V~LAUprV6nz>P~HA!ly5!TIqUY;FUH4}D^cbK7p+cV zimBIEsIHXO~4l;t}wnf5nxzEc@49>YIuV=c2e2ggY~gxYgE_P z=^sBPoO=2cBc2BoCHZtJ6eo$2%w7$m*I-!EXqETCe_Rn}Dx29jQE}yC4qs|}71a;> zVX>xya}Vt%Xdj69xV3W)=ORA5_Vb>$RKUoK+;08)-XqL)E!vu~Q}%=Bi)*7gnIp^` zV_MmhwYNyg`6Lp?Xzx%a1qPni7+_8Rc%foLL+r!Do{M#?0n)sNOIv$18%zDIb+L~P zC9LAoDY9aw2l=}jkspJPfg+emUBTBWO+Yu}t-zaV$UMw-z`h|WborLHMLro=9+oEY>hqxG z*7;7E7d*z7?$wjb)pp&)v+t);KC*L&urhGf%Dw9Sj)+A_Rd`GD7+PH389VjO|TgD zy7>${dgX#4)wrEHxJXi)Y#}X0D>!P)8I5tFHXp`tqoYNSAI}+BEPNn6bf!coAGX@I zhs9jdV*0rAgMk8bhpcPvOSXG;TJ5u)D?UN=aGvUGE75E6pX`e+}|m?-E^PFtnqW{9%~=tmsjw5FK_H6nZ`$xSymRwZrtzfW_{{p)WH$JY&2IgNX>tH zo70kN>8L;T3tM?5>b-e~1$SNiL+8#Q+Sl*OqRFct)$U#>{VfpMwY9qTna;+FQ1U_i z{p_|x!^>@Cucx_6&MQX@Z{uBRCVRc~18*N=9^t}h*Gl;817Tm%xrhKtwLosd`;*RjUe1(iPYABB?Uz!&p5iL`IhUy% zG&PXs9Q0Ko$ewY!Di&L;??o)R%_+6b`MOOO??@Ie#fpgK0$%=;c@~WLGgb*e^^H`>7|Wt3+>1Ew2Z|vPrLhQ zU7ioT^iBBn=dv$+XA~#9sWaE7j=aQ1mM_Q`A&e#tUhF>%TO6L@5qs3zD=HBtjOA39 zV8)nmzR7*=r-c0^9dC*^^1^o4nTRTH3O^xv1lYsj;5RSXYbrQFA-Ng<qhedveI9h17t) z?~PsA`cCI9$+=S43r$@+=X8$`Ob~KLzFc8HHIDs4JoxD4yl({--akb(ja9gP$=x@| zIRvBEk%Y)mI?KjK5o(iOc9NdDv6+pQdm6I(2of=?-y%jED0Xr`PB zl6%S;RXLYSO1kmCJ65nB#MvY!L#S9UscAo%fEfjDF4+QJKD< zxO1c0Jk-kcMel+6+Vpg-u1(e2=X^HF>Drf9ZB1sVifyYh4#@O<80}2P@is-7;(pZ< z=uiIa$+RSVJzY&t9VqlAUG~7B!k_zdz5&1WxO4QHlcl(oI5&KuR8hA>|bje<2kJe*{1VKp!B!0#X3SK>P(%AO$AU5P$I$ zNC6T9A^qpFF#t*;U@8SnG9h3l1xzF%U?K&~uOVO_1^O(QM)~tuIMUy*Bw+*vGV~9D0y+8zK!Ggb_!CozmqGkPpFpPmflnY; zf7lZkltjSn3B<}EVDtn+We_lV0)dhU7(s+U83c?VLYxc&zUTx3B@r-z2vIT!m_Ymk zN+Mtc5n^NzFoFnyk_a%__djF?B4iLSf(QXJ2pBGKuH8l zApQX*5io)XfszOqL4-g_1dJd;pd?#5#5TOZG z1mF(;yKDuTHbuY)A~cG zKuH7&Ug#A9B@r-!2!WCa7(s+UNd$}_LZBo9Mi3!T5&|00@*szyu-$ zN+NIs;$Kh_0V9YID2ad(LegId`Knn`e@KFh>|46w0L(C-5Fj@*70g&(!;14K? z#2o_Ae?dtkd<=k?NzkW(*;42zfP{|%e?UnjQYQX_w*=TETP}D@4I;7li8?}5XatUe zl$MqM-@SA!My}nKr)WQ@ef>Z@@neSWkw_wedtnn{ob1KN%SH^*KUk8e>j@`cygv?4 z{dMpb<@@&Z_j@EHb^4}RyIk5PXA|zBerbpe#l{%cbm<|_Gv1G7^S7+*m)K=FUsV^U z((~22$1S6kMO*)D8j^}fR+m*_4c}xSU|N zRS!r%+|!N+zNS*~DWOtn0C5}GP8)$O&tSIfA`NBSm@a4Nn3D>PLghT~>YF~z zSxi|vNr@gmwXlJ5ux_jt*V_W(^=IntJk-zLsd2Ft>Z}_TxSygn*PXx9UztWCRFM|{ zJRaIIpzTZ)^=azEF>w166}sS4ySnq~v;3JPw~P@$^Z`+pb|xxSgR4*N!F>8$Sq4dt z`{`5)?i8golaGD;-Dmhy3#>5f^N|lS1XHbe($74UAX@LEqzmTZH07c8NWEJop~08R zm)2KSaZZDaNF_#TR_0`INkm4*nMm-tcLUGP8_)5lli1zW;$l>h2`+hQB0$Yx`U*T+ zmPS%?PXjzk7F=RwLV1B(h%~F@9l;eT^N5%e+(Va#kh^XfB$751I+$ObR)e3uxwU(+vzAvUVwtbS z#dmDlhDyg;M{NDZJ7QA7bW$36Mci-c5`D57@WtZjXfE3`wAqVLUmkC;1&^VVyzVDK zG8Rv@#2?F>!F1Ah+_0sTePFoaG}V`T#1ATV6&Nh|nl0mo7M9{C78r&~m+D?q`73G# zpJ@Dc!L@0X$wzhON9&^*>xKuq{m7}`F7eb4yJ}a~x@7UXMN8Yq#4-BeiYLY@m!zyS zy-B;DI=^}Ft$9s^!~BGk;%(6%!vycBMc%gBKIq=2eRGDsnJC%#5m5qxLjqNXZ@m!X zHLXx}v+K3A0-jenL~dH@XAJ2y4nE(FAr(Ar_FCfR8ueY4>IppE0Lr0;%eBTHDNI^Y zC&*{E@W-V>{T&;aLQ+SzF(1j6rl>4Ti1`kO3q~e%3W9vkQ-n}*IX<$xBOpf47L;Vo zSdPVO%YK&Gq814x?_lHirhLxEk$m2$wr+E_uN|UGfOeWDSW|VoCaV zqaLXi>0LzbuBXDs2 zrt#q=nIQ$$K4YoSz9WM8sIBwJc6$r4#g{hw!O&iVe|_nTkuea@Mg+c`YXeO>o*ZEOE4 zy{ha~t+(Vi5X?7na{ABo&zomP-nkVkRTWQHZfW#Xd_B#^S!ENZSg;=P?go$XUl-$T zJ9RbL<1&mz*_?0M#T}R0HKN3g=gi!N5tA?(?37o)5(_2^J_jiD#&Q43#t;kq6ken$ z>J9LI<8hxn(c4eU@N288(1Ej-i(OiR=eYLq(3l5p@(}Y z{v1PM=rI8jy^C=fW3S`9>HS~_cA~6#4}GQX%c1JhNa~Z{9`kNH%@)HVR_oCE;Wb_< zgcQl08ECQSPrUeP_r(|1nU^x#&B1R^y>k%$oWX3|&}><6&`TSF82_4^%qtEDcBwo1AGm}gWSxZO4E z>{$wr?M$D2VRUJ3l1QC>+*2Z%lY1Kts1$%*gP>#p2fO$-+Xl%M1mwO!cw8(Kl+C|9 zjbR~)mZ;2vd>*LcrFr%?d>DIS?a*H{xOYp#rJ;G-erI!^yS{sb}=3I6zx^c!A)p8=*ZtHD^$mu;GY@JbA+>mptZ{1*XJ0UQxz zBDIyN@Q`N9RLFIZqI4j_P~A}O0dRf~4MB}m{Z)mqYa^WA1oCPd(ex&eSKA1tH-Ws` zMl8JveXaY*nCfjkZgo?$45LxN`*$>EUT83uAVBzA^z91aPcVHgK0vHwNZ5Xj?@ zxS0&(aY)<@V>lcVHp37OheXW~$m5Wp83K765;H>}k3&Lc2;^}{#0-Hv4vCi`kjKGr z83p8VNVp7vJPwJLA&|!*!7>E$I3!kvKpuyL$`HuokVqKuA+fF4k1Y( zkjEh;2?X*ugd~AL9*2-55Xj>Yk^};I93)9LMw>t&k3%>T2;^}HM?wbjID{mDKpuyX zBoN5s5RwD}c^pELKp>ApND>I-aR^BQfjkc3NFb2MAsh(=@;Dsfe>xs<2uT8gJPsjA zAdtr)BnbraID{mDKpuyXBoN5sfUBD~00Ma&!jV8AkE3uT8$ce1kR%Yu;}DVr0(l%l zl0YDjLr4+`j1L6zID{jCKpyvxBiRJpU6A<56oqT=em%MIWyEc+{#7mwh~H*@x>s z9<}bng&&Vv_~FWrN3HyD>Bp0oe)8lWOLE5}9$EXzKpu}Q{$wDJM^=9_kjEp-Ke^)( zkF5V>AdgqYhQFLusdzc78sZ6B5kSF`94k_<1hD$X*xVV*5fecpmP;eAUVG-`ySr+= zD#+(b=w9gL#hnSv>y$J8X}`npu5*FH-}T_1G&_VkWi2uYauFb>9={$e5|7Ozq-TRNI-gVe|Dc?cfNDDi$JzIVb7nQcRU)Ceio<}{b^w=m%yLlqk=k=DM5S)TP zbK90-qkTM8$tm&|b2W}tdQA>1h`5YO6&T;EKdi=`T{5VTq4@Bpe<&CXUu@<5Tdrv{x?7=2Xbb+|Oln_v)c`Js^m9 z^_~~&vjk&Cp``vhmu-@Q<~jWmV(pDGkBB&uLJhh2BCksMGe5SM($IEEyka1q;L9^A zk`yB`kl?IObTv$KO9+v&EUi28Qb5&%OVN_5F!CPuV3pq=4#|6$`2|#y5(Vg0OB<^1 zR+~F=*U6guMVP87|BT$3w&$KQe|qKBEz)_)dt35b^IZHROz-7~DN5oGJuEFyiKi)> z;y?OdM%cYdmV<(~%!D1E=IyFWI782@`n=wx!LSe{LeR8!cY8q z2M5J}+$yjr!PmaJK)8{lE-jcG+x!ZXc)wLJ+3(OC{n5MYe+R#r$eigN6jnZ!sN!bu zCo|(O?zfY#b_IhO``YdMo@{Hg*RWHk zX=a?ymDn#@VE31aw@Pv?>RrjFyFyfLd$gGi3S&HH#lq!;yg!Y5Nhh3N4Y-BTJ@0a1 zN2|<7UCG>iLd?Zy^msKBKmV8IKj8aEthGzHV|<+FXyt{Q?}_#G+0AF3@2pV$dYv#6 z(o@k`|KLNtQJ+fAQ?A@UJ92+~dF1ta@{h=2LPAO1trri9CD%UsI=gIhrVi|WCu#Oq4eM>=eAY2Fv)S)TX*dSj(T zdN`r^I;s6RkKVfhoj6;|j1NA7&zjlJr_D%MsC)=MG84$-FE?Tz-h8?&x?&*b_P5_t z-%=@hoHg&uifDt?y&5moVeL=Y~8i)2&{0Tw z7H)F7L?(OEGHA~4;K-$|o;@AO479kZHoGTT%2ngyN%SYS7VRwjaKqwxbOR%Hqk)lR9A^d_7&We%=)8Y5ld3N%euY3~bGiPTl{4&L{Kz0FE;0P2 ze)auizR#N8&a~+!E@Rt|8YS}Sv&O!hPu&x)Oh_B4?vQ&VHsEO7{V`3Qn{kj;_1j>N zle~kJbfT29x8c5S!=t5!2Nn`MDm{_aq1QUkvE-&&%sRZ!d9RJS0&zgVEKoT>HZIDuX+BSNrcCUZ!Tv zT_<4M9VEF~5;~cr4c(v}@ZVVV-l} zbn1nk-oQ3CF#CMz@ALvMrep3N?sYM{AK8b{|JONc+IEeh@g{4m2gW@mX>T^+`89o< zfZCJ9y-r_47+{$~$)Xkf^V>p+I2$r*+xl$IzG!y# zSzHY`s5O2fcH|_jgK`e}w*xdq)I68vrUBR=FbJ}w{9{^d6`pRG6lzizMtU0^*w--| z6v9J3X*x(4Fp-Q;VwTC;x9}{s0^o3QYFcm|Y*?hlV>f3Q0WM+<3@L)ibZ`>8L0l|* zU_`(t`wMO($)3e|1}^tnh`)tcBwHWu4`PNb;!7%UA2M=qS;+!R>dWLSW}>L!bV5?2KQEJ|Dz{D>%VRq!LC#8pA) ziWXOe7A0W>!d8^HD!AY32o458KT2Db%%Y&wRUwOll2?TRHA-I<#?vT)RTxgA6jot0 zjgnY}!8A%^6~@x)2n>dy^oGbP!lIyLRw0Xm(piNp3QA}dvM4B}Rmh^Cq*ft|g3?-r zEDB0&6|yKmZS^0(B(o?exmC!bp!8NDi-Hndg)9n6aTT&CD9KgGqM$Ta;cqBPbQQ8F zDAiTSqCnYIG>d}LU4<+PN_Z9i(V&!9A&Y{NUWF_QN_!QuC@Aq&$fBUsS0RgnQeP#r zC_sMo-wlB*3QBzyvM4C^Rmh^C)K?*kf>K|FEDB0}6|yKO^;P%>j8b2PEDBU#MYAX< z^;P&6jZ$BQEDB0}6|yKO^;O8Cpww3(i-J;Lg)9n6eHAV_DD_n`i=vL;V927N)K?*k zf>K|FEDB0}6|yKO^;O8Cpww3(i-J;Lg)9n6eHF4OKz;RpSQK>x{z4XIL*a=GHX)0m zj(}gtq7V@13t1Ebf_x#1LO_5oWKjqR?u9H0fdYFsSQG*Rdm)QLKu|AaQ3wd=g)9mI zfxM7KAs~nsvM2-u@WS<+fZ$!oq7V?c3t1FU4np}`ge(dH;X5IVLO}RV$f6Jsx)ZV} z1cdH{ED8akJ0XigK1`g}UPh89@1zAB^T9pEQ^ha+hEjXB`^+iX0Mr!pk4L9RsPVSlu>4x5REcqEH`r4~`|zS!b7!Rc7M zKb~Kf)4Vxfkul0V_p%06w{>G*-j&bYA(+?K46E#^(iP|R6pLGS#TpSZ9!bgF`W)(W zfKScu`YkWH7)5i9{hp}@ z?cpWf`fBWlzlC2in0No>`@1;kgTje-xyN=3Wkee6*}XfU?T&PE^c0umRwG}5w})}U zZ)=UP#e+)5QR-DbU-`UJUPVZ9$B!n?G0Rz8qWO87Y0&G#vC(J0Rp&0Ht~x!sUzk4s z#ozL*a_yl7!r4HN@6L1WA4snT;>*XhJmSxYCVwN&&ojth>V6QgHeb-?{oJ@QBrYfC zgW=1% zz5lh>t&c~19$oJ_;J3eT+H}zB(zg@l)BgA;y8|(QE?YerZ8@G+lc38&wOb^6^)3;A zHEjRzpHDh`^Myk&CLK>7UNehtR` zC0?Q&PEMTaF6Impm|wotv{ro2yzj>BY*?zfwdS?5n5`oRcrLi1cUm zeqTM65G6K!X4U^@@wMU}<)jAp=hWx-AEvJ@tn;WjPya>Fp&^_&<9!&bkjY+sv9(`- zue8-4>vZri?YWTffx&mPe{5N;eJ_vuv70{?Vo)==C|vcTgCV-H(b2geI)+nqYI@!nE}x77W0Z*V@4d~u8Olz#d4%8=CocNOic zX0MN4n;o&Zk)jgsp(wM&p{Wm=H}2$|j%J^DVa1o@tnuE<*X*!z@%?nwUrg*wr5~=! zUBA#z-x8d-Z@^90G&A*~qd;r)LaER^x3bL2TIqntx6u}2)+^kyLTJKlc8Yb?UZ~sBq_UihSpxi6! zk%IZjV8w7hBId#2u_x=%azbu@=LQBH`3Acx|G4WahJUSn0J}Fv>N<|?u7CSl%*7mb zZ=@>!W+_~`&R^d;HcRADG#~V-6uAWe``X;J)BNDQky|DOFITDr>-nA}#J{Wm^kXIM z`WDR(4>R#59lvmFFYQ)KM|iUK(bZ|S-Jh8`^0TLQ-XvSRFVE4IG+s#8d*>kcm##el zm9@c7s%LV{&r_X^Q)wCGOv5qF1YHpyrsJQH*Zw=X5_-H&W=TSuSix}nM7+sqzinAh zym=fhQoYt=Whi4(DWvB2q|W;-uTw_zaCe+GYZh)R)eKj4IgN^8U^>Ih7M)yk>M0Y( zytk#CEvF;)=Hob)lsML-c&2b?xkN{$Yj!G^o}hE@qk2()uspF~7fS(^=%|dpcdohmw)%2edc*b*BY*9H$C2^_!dFbjZg~GYa zB02Z+Ct9433TE^tCi42XdSe!BL@kpw21}A&+_uY`!-trLnZFkBGuEt|6Yg+4t@)6i zu1Z%>_lHAd?o4m*g-Fli+a&c)2J)^R7b#E-C_J!wdP^|N?ixR4Y2uYohx}L9ay9&3 zHnv2jw6oZDxqY7c5cy78xYys;=T1&hSs(A&NPL?UFX6q2?U~GiqOrR-q1#HK)o*z{`gx~B;=P*pEN7Zd8u947NoAL}k!>^&Z{`VM*tQTQkd~H{VorVV z>}xI;hf$6hdHM(vbGDg7JfDzCW6xHR2*Q~9O7jgqXALP*<|8{jY-PMa13A_=lB2}W9w!J(bS(k`6n(Mmt=j?^# zcnmL=y$8#;vRT{genaf|kjghwn8VmX&X1B+vMbx2S-X!HYq3bKJyyy8Yx9|7p>=A% zpvBz#5xRbp(fzVNWzSk#ip=!U+_bAoFQA)z_tie}Q21BN(LGE?iO~}8o>)q{{-GNNsy!xWaLL_8VWJhw>~=4- ze;?L)oiRTe#je(osC=89(X8s6oALJIBK!}bUoR8PhS!_4*g3z(n;hSnN@H^6{Lu7~ zmsHv_@!R9BU*9(Pb!;5e`;;!`J*18bV2mnfsDC39@Td3C@957vQ}={_CYtNKXe3wY zfWh5>IpL-ufZ-m1VydXN!Nyb5UoisTVtMJi-j*A$`Oou@~l1qm%Kaxs^NCe5G!+;;jqr-R~Nu$GX zAIYLa5Q4A=0O{xen}Q7>eS%gUg8m>`bV#3|b%&rwI6}p?VC?a|aDL6d@q2V2a|&Pu z)PS%w201>Cs*aMp<2syAE7vrmBm{)C*_dUe$2jiv+IPG*9DSq}hX4I5_!vV{Z2z(H z3r6Ppr4IsaZI|r)mLgtD-)>4U)=u8KP*bx2IuD(zBot39c-NV8ntbD7uCq!s zY`?Zee;+}QL%qO6ydzY1zcv$>(&}9%GkZND;?=x}+#}q~+!+#yjwwy5Az2bPla9t^ z72cY^e*Ii&%Jp-OEiD=v@+}&H@+|^hrtNb39wZ$$Qd3BEkem6h$@;TWyLqHrN}c?V zn6!sSJJ?cvIz&>FNK}Uh+&+07*drsC>)14QOh=!sWQ&yh5oUUg&{MKaod4JLSfXS;n|>S^8uPH)$WKK=rnlzmtwb(2H|Frq^^T89E!oZ# z&fnrY7&Y-wGBCx+x~;iByFH#pWu7avdsVFOw%mG6-}4nqc+VY?v{U7Kq{~`sQf#UM zi9e#BTE5_1k?~%wKTzR4@YKTwKl}X6wAXm4_khi>zag!AEBN!f?1t1G9a=3f*$w|O z{fn=(wF=8B-w;(n`dwSQOtn)Y4w7y)cKK;9kcaOlt zCo7NeXP@NG+BN##U>0?>wfU_huzaN9V9KLce@{+L+%CwTXoz{)_sMbf@Vj?R(-E`N zgI}Hz^%EagRej$o@jWX_v+(a|bwcTt6gRyR|ND zDa@l-zj1$XPkTdjLAw6RVbeGh#}}u6i9GKZT=i1QebgS@IjpwJ<=SIIIR`8g2hU}~ zq1Stqzn3&F$L?y2*Ni#&+@8z$)*t=!)%=*AiWU`Oz~AF8lNVf8O|9m>$>Xnoe%-r9 zXJRq*`)prfr%G#(|4?U5vs~~g^WZ_Hi1X{k12;#nQmm1VQ8k$~UGMA&v=rAU{WFq>l# z-*#a&A)n9Ljg12Y9iTn{$qq@#O^q>NK^kpSRSZ~Ure~u923TaiWuxK+SYW+W-INN0 z7F;7YDq4U==J7Z6z~D)^CT>)$P-bdXfSFnc7-$F^G<^l2>Emfh9}8q*cO+o*K`|mA z=mF6$qC7(bEimM98wt?E`}1Sf=K|BQWf0AP*PPe34qqBf-WJoa4-o#)~edz z&R`M%EmZ}*BG|1FbROts)9)XlvWi?0-&_2U=jeORRxm(D6J}(1b|vqo8%!(0-&U-U=n~V zRfQ_0L}^vQBmhdQ3jY0}w5nhd0Hsw0lK?2KDwqU7YgIwFkXksH1VBkuk&^%@ttyxV z09sZ5yoN~t4Wt+jCIK{%VmO!t(AY@t!HPAQ1kgZg;b0O#1F40BfBhOrEgVb&X#Bq< zfCf?w2bTj4q!im2fZ#pn=rE!6bkNSOGU5IZOg*AXRWM37~-#!NDYe z#{WwKX#8&y0I1OX`z)9Q*wmtdw;DVW%%&I(*;IojC6fal2{0*l3p^5FQrrTM1epIK zS8@^n*p!M!@JxV7X(o8lNOr35y`Gjb^< z2Bl8}ODTa(xo5DH64(^yU@0ZADc-?SN?=pmgQb+fruYX-DS?eR2%ZkG5eH!@B{+b1 z2p$ly5f8ztk5NHNpuuowXd@1SM+9udLGX-#jW`G%60i{m!BYY@#X)i@B{+b12o`@} zBOZb$1#HAY@T7o^I0zmU2Bld8ODTb^8s5594ZLs_ty}RA)oAeKDd!+vgA_Jk0J?SQ$hkGUD>^i^-e*>8I;*W|p3iIdOV0fprKN0jH( z^QG4B#qjPkZ%F2vH@c@=@ZyIDkj51>try#GRG;_mP&+j%;{kv9XLZ+1tpwGMnhu-` zI*`wQxG`Vv#y0I;E&PPoGMiFaCt(B0fQ%oO8BF`f+=-=hJFs(d`qrjavFz4XR)gP) zulrq1cPa2-+V`VH`d}Bvl|#(hNMlB6hir>RVljVS!?`M&kXT-89fhNxk~%+rdB$BX zRw9?sBluBaJ65qi&i?1HlRl>NL{q<{K#cUXVRVbxZIH$(ZwP9(=80+iaBr(MRV1&z z(o#~P!B%-<9ZON@X>;n^*=buWBIQb`>CKx{EvvbcTav-KZY^oAY1 zBea`i+Qwr%c*;S$W-RaHp}Aykc){H!YLb!Br-**Z zNTIpR6kRr<^DPpLhd}ivt$9*ZQ^;9)3C3IUJc+ah>5rSJOPZ`dRjax_@-KC!)yUj) zqTuHqV(jT->xq(& zoWe#)!+KQ*#Dy-*J1%lE;UE6EcGXHSmg9P;cHLaytZx*7!FI8sWU6LzfJG$Y`G}-TiQs8}_3sfwOe&*_x(#SubepQ@G8)SMTM~A$S2*UHEuGrq;q{tR zg!s?Ku?Ovl#F97Xt%-~;)w9Pt9(^+j8ut!nc{Q71!YO=ynYh+D@KS5fo+;Mwx>6$k zhWzi-D(lAU<|g<1tu^Y7+~2GElyxxD!oGL5F3*nrPvMw)pGA7|AA#q!t?{q+m=R+x zl$D(vG9x}IsEeDOa4Vph*UC?FADsF=)TKTyleF<=d%?eQASKMIEh7L*twcdRLm2XnYl@)--2GF=;lGlsZ}%i}W$PXTmIUpPdcwj8y9Q=w7BGk}7;5d!}&qo}kv7!c-C5 zOIG^rRC(9j5?_tYH=O@8q;%rlqwr3%wlw>rQ*+GxC1X}+Ggg>VVg|PCAB??gqmZ0- z(boD+T^67I_U**)=VZ@6no%2kC-f#JRsI5wTO{ptVDU3SwiiNT*A+_b+B5bAUQA`) zH7=+jzWrg4)2eK)l9cgY-_V8qQ8Z=&4xDy$trug?y-mXI>WY61k<~1fQ7GodW=KS~MA7edR9l!a zKGxD)Biv-IyHz#t5k`SQr{&|aHCEg7T-U&}KeQ~@>u>BcV;5pgOrpDCda~o~X_KPX zX8jp=?o2IxO$lcnqMY;E7M9Sh7h37F@^qt{GkKGvBAlfpbWcT!v^yGdHTt~0;q^K- zEs{B03@l>-rDiRC7)`#HVIoL7%4!E|L;Q+q2rulT%+A+ zc;P*6l|-5!&4pO+ql;Y3hkhuf)I9C{PVZ+k!kS(?=05MEb8Ve*-%14iRoVlE?5j)< zp0LIES_V&ayba0eC^NU@a7?yH4Ug11EY!R2RY0p2u{eMCu_~dNcomAMX7wCD$1LR8E7?Kxw6ZxMc=P0s98_oaS+VFZjXHCcfHJVHcq+Y!y`=H^Vl~0eiv!OhNPjdsd%OfhHM-cy|lhCl;uCs|C-%A{PbPP z_0#vi{d6r0!u zpv}uEvA#itC)G6Ty)>x<#HL=I|B9POy7o%D4;^Ei8b7hK-(kl>?O-;sM~cbsYpBa- z{^J)Xr2U6p9Gq)t`}+N`elYJBwygN?c+9}s_@N>B;%`3>Tiv>fpBjtNC_K6C*ZC!1 zUk!&G`tqN`OZT-!7Vph9B{Mg5SoXGwFw@+X>Pvfg&%Ld;_DCBsYMr`(*u}mu7MPtF zpeO9QO(xL1V5Xw-M`^fAjib{n>CI4;h37KyNJ6gW)QM8(Uq0P}w^`TB2CFJ{!*s&< z+%w;u&?e1J|5E7w@%y4(+;G6-8%xK9-@6%^x$geX>Shz2UwuQUe{7r13-`T;_Uz`k z`ifC6Kt4(-ix9*T6~G>~_#d~{5O00`Xo&2>ZrK(y)8B71oA#U9RLz;+aSv@BTPN-f z(IEYf{Vdq3p8Be80k?i^aZn)G$;x$Alq;prExC)98#L^|a#0$LN(Bd4GC^`gg*5+E z98?%%RPZFS^vS;p<1Mg-c?Mq4m810Uf^^W<8)t`Ir31k$fwcD^o*S@sAcG=HsydBX zrG+0d)`j5#wWs77-?>AgY!!^Acou5Xkp@j3D4EI%E&{|IDCdQushoV^QoxAuKy}qa z@XO*`RU|ep(E*LcVyE!*45U$z)FB@O#nCdbV_67ZDRy3)mz3a#WdTNoJyc-M|cqj+*Xu{deZ35+~hiU{OFz`Mw~kQ=tA1uZzP%`RKC zx$N^k@7At<<+8_)2g=?1Qu_F6xCe&iX@bSioCJ|sdsDs(=Qf9K`>+_7j`sFj=QB0F z76zvtwoiorROo7NGLE}O z&wr}d3c09aB6XrISvDe&h`H*Xx$jOM<8ro{i9?jBfpRF#n{ipIX8Ik+-!wIupNmW> z`jRAj{LK!tM`;J|gr?=x@SC6SQ86@CQ#5t`p<$WFo+{(Y`B;T5ypY%W^^vPrGb74k zSQM=F#r zD5>JGS5hN{p#{vRV2t&6%%oO|6;<=Wh^ifM(st+eeEH($Da)&cHYZs+3p!LUIrn-! zt?|%iRIn6ksqZ{>r`FN-oUBFY>fHXQRjP@)i=AE#A(LEgLL%FT3FTs*;NKd8mRhLy zgd)Rur?mcfr$n|lF~D7Se6G{5;f`5)jHHgFfI)TB0O6suu)z$W#ZURvB%f{;?awbg?%acAT+Q{N&U}P_(q%9xm9=a9GLo z;OUxTX2tE{XSVfAQ=NRM#eN(wjZeN^RsK}GdTZ*G`ibYn^R;K+K0X%Qm;J@9 zyy(-^(zH{P>L>mMmVNy3RIB3RD+*kz{O4j;|2oE{|K|5$2|P^X&J1oEtbb83)zkI- z*jBmS>uV=}c1&~>3`7Y!v#p8p%`&VnXYc3@oAw_zex9B$@+Wv;faz(;gI%{Q7w24u z9+%bpE}?(W9`3JYb-sWo7}Qm1XY*ud!CFPHUu9Zb{|K78A2HBzXZlR7+R-Q;!ij`0(JFJq%7YUo6B!(D8q z8>d&9UY_~Z*Jn~^)i|~&3qa&UNOUh-1*~qVGI?_HBE<+Yv9%^i&*~7@Bm38UNl>rpJ8bfm8)`pZ}ALU3e3Gb>!CY+96`hw{D~R$y`w{ubs1;S><@1a(*J= zxBK&lCVaCKzsG!+MP)U8+o(S2tSu-R1zj$BCYfBW34RfcQ-3xuWH)`^W3KJr{PCKi zTY~or{$}Y#zS2^I)bzhip+blK|BjVbN@R?DSHFE}@lxvx6Pe@B6UttmDI`P`SkBqr zTjP7=%>FtVOqd{DZpW~Z1|MSngX}#U$v+CelNRWSLJl9Vh1rx6-5~LSMJ6LQNPJ+C zsR(F6CS!w=+aU3QwK)#~gAx!0^aP}R{_(!hqOc=?nm|d10_FtrJ^$!JXi<0(@LiDW z**ph06Ug*zT7c4lJkO>DNqk@Hoy$3dxtLK+9Q$!>lVWN~1Z>^~E_g>Z0?!+|}r|IR|U z5DpITZNQ}5DoEl3n{u-N-3Cm`-2!YIFez>U5+9h9y9KB=44iVc`AvXn117~SK(qmq za<>4_226@ufMx?Gcz_6r4{VBGfMo+F#Vx?G0h8hupxA&(aSJePz@)eZ2sR8D#rDrF zz^?(5;ufISfJt!+lK8-;_yyQCU{Zdu0JjEAid%qM117~Sz^nn2;uav*fJt!+kodr) zxCKajpsho33y}E0{GWLUz^3>GNPJ*Y+yW#%Fez>U5+9fpw*ZL`Op058#0MtDEkNP} zlj0U2@qtNk3zGO4(4hVAc7aNMU{Y=uAn}1oaSM?6z@)eZNPJ*Y+yW#%Fez>U5+9fp zw*ZL`Op058#0Td8%tHV+#V=6Fk5NSi4*(J$m=w1li4U57{y7cuD!`<;1xb9+>q0pT z-9mCLki-YQ9h+x2NPN&#LAe_Gg(O=bi4S@R{+)#+KB(QNn9waG*8)j=Q0GoL3*AC; zEs(?q1vHei&@ICM%tHY7KflN%KFAeQu7++QxfV#`t0K7;NaCv^xfV#`t0K7;NaBO+ z=)aGGBtA$^ZkU@SKFA7EPD8(tWD6wmK^Ba17CuEJ*8)j=kQ4fMmQ3PXK||K0$XdSD|CLJ}YR4>=DVL^c4p+5;Q8gK!JLP_}>#1!!;p zxrJ~Oz#y9dT=9X8+(NhwYzlnA3>sYX!S^8!!i@lfYy@!C2R7m$+zK%NwgP$h0nkHK zA_gq{z(#H%+zl{Te7Juye5r#M0lYN8YgdJTvgR*Z2#%me4V$_eWw0XXn%d}QzHV$X zsKc$d{D-HE_Da;(H_KvI=%jSi>8WS#=jU@2Ch2jd@IU_jYxul_6~|TMoV3^zcEc+l z#s#*y9aQZj9MAWD`rqkNySfPf0xZ|k_89IeeaYd|i7^L_qCG-CyQ_AEGw9*u94tGP z`%a4AUn#tb-BC7f{P-K48Lej5+cx518teX+Jemvi$GlndPwDDjXp-UbJIrCe$BXKk42#8^$W?DRQRVSWGKg)nhvRg8gbCRVI;LtvB=#BwRcDH1R>ExYO`Q1tC!`+hf|1BDF z^6d7quIi+%SV-X%GTXUm*c)I#jQ23@lH4jEH2QP6M>1?|GO=cEvB{n;H-2{*CzS!c z{@Z1mU$HGRDj5EFncT~Xg~hV=Qo-LMLh>h~X!IL6_2~6oQ)%>-ZK(CV!OIA|9z1x! zim$^<1h8hPaiv!QQR5Rzp5JqaT0BHP7~ikR(9qTd(5E-(i4A|nHlqKx@KzJXucTZz zi^?w-eYLC)&wd@cyT{7-`&qZ1$AV{YGhO-Vi zU|>XMVQQ=xJ2UUor9Sg{-LE75eYx=kg4Ox8*prQnYZbfyYOHE!l+caD^7VXv<1t@b zF6xpLGR*ODPOffk z?7H0454pM0D%E<{Yx|?- zOa6Q+Z9Lg9psnK1*!V2f!I@t`e;9Z7mCkoj0fC?Hz`B;`;JorE@GD!y^)%-jt3)z`pScFf)z?d_1^_AkDqWwqWoZUk%t64nBB} zJkAZQLK|J%B`5Jxv=}^SBW_jUCOvqj$-dFGJ@QQR2pkp%-2vafN$7y4Z8nl;wWbJc zA^s<}IAJDI_Z`h`q#t)Q$wZ78sO{a*&rR&r zwA!2qPp*DCFrcYP1B%BWa^eIlDtQyw#7f{jsuL>viQq70>4)nmvZ=#W6xq|^8j5V` zZ~^_dqZ^pP_ucaghB1*aA8Mn=D;5;YA**4VNqK-@Cb|A z$bm~()IJV;!lJfu;1m|MivzE)cc${HBle#faHn#C^&=~sSh_m)JS~@hfpK+Asj-D)Q4~gHBukKA=F5H2!}RC z>XSQUAsj+Y)F;Cs)JS~@hfpK+Asj-D)Q4~gHBukKA=F5H2!~K3^&uQWjns#52sKe3 z!XY?OAJy0lY)X&=;Sg%1K7>Q4k@^r0p+@RMID{Ih58)7Mq&|d0Q4k@^r0p+@RMID{Ih58)7Mq&|d0sFC^*4xvWsLpX$*s1M-~n5d6#Yz8(Z z=z?$vHBukKA=F5H2!~K3^&uQWjns#52sKh4)-=J9`kSyF!Xad${stUEjns!VO{kIj z5DuY6>O(k$8mSL!nouM4Asj-D)Q2@qsFC^*4xuLM!cg5Q)JS~@hfpK+Asj-D)Q4~gHBukKAuv+^-xonRM470sOKxliHYLD^HBG3I`VbDG zM(V?wCe%oM2!}u)hIpOqwu+$|mxiRpI#PUZ4C zEx9$x_t17d{T;E=>KtjHlq5x%ZaI(|U{{b( z!;Nv~rFviIZtZEq3-wHeZjmEYhM&^b#W@lJ?BX@XQb|KE6k4G5;AwSz1>sYScG)9hI069M>RR zKCQSApQ9wEfxF!9#QK`rmy0X!qiw&2U9-Gwse~Tiv~UUL%V=|cf^SG+V$7D~P4DZt zDx2O{w>^qilwcF-H|iU>*ORcX6zg1dU{_(FXENKll^eb{B=hcpF+<`m43ken)YBSL zOF0kHbA5?uXV2U%_(|p+X~*Y|J$^g&ZM&|AT_lo#j`;}juOHjNkTr?F7x>KU=G+(H z|Kktci`=(6O{?zHw19Tr*CDYHh4)E2Zp<#c@^mBe&Ni0mZ+YQI(0Xt}i0uRqDMj>f zOQ40{yReJCe#1N1`H5dG1~LxxWluj*a0~yzj+@u=Y>CdFNjn`>s`;R!H8<>c-pv$a z+^Z~^Ju~r{r3J06CpE&{xMGw;wx`ZKeV||2kyT;Y!2ZZU_S=gb`avZrx|i#XA>sC354m8hAD`{hz87DW8O z`Xl#5L|K{AzRC)wGZ)r#>UgirMih;+b)^>t%!IvLCDk7sX^8$YQ8gIV<5hFgJXrPC zH``k={mLdCeABaAKYp6ECceKHtS3F^t@HD@?^|`krJsElh_-DlgIfgRXJ&eDj|MYp z28MSS9v!`Rc_qUkz}lvq*grCAW%E+8AUa;ypGxHXplWS6k51}3?JKP&_DV-Mj#wA4u*-k{e)?WIn7Cx&zmkLf?y+zmJKS(p8j@^Zm-avRkbPN^;co(D{Y5X zmtGkCvUi=5#;%LGrn|Ug+?>8ie+yq#PV9(z_FJK?&DhnyzAb;|<{4hn63>G-KCi|O zt?!vt|9ZCc$3cHQozT~M9c#7PZWgJ-Kf?&4Y@T8}^i%5kt*QLK{&;>|Az_dCj}cR+ z)5Sr#FBa;p{$TdBEt|LmjdBq+zEAvTO$uy2&yE?7owRk8I-!%-=01G8GA}nJUY2Nj z`)vyQq|pVxKX;x#J=N0YES_w_9H2h+>!&5hGEPx`t!>KieM_5xiFI9D*43`VZo~P< zYhntD+v?b7W|#B^{OfgBmdgrGTCC6i*>83DVH)S`m)klYSomJLT0Lj8)*-63I4ACm z{~q#GVCQ2t*9bb@o27?WJ6`=hVCQzxl<&$Lp-W#adL{=l8jeo1Nu2D9Zo7Nz#fbIk z#Am*I>(NY{Aq$J@^%>%W%|Mvlr&Fvb!2yh<8qM?NUo?HX;xzw!#WT+(^qutk)&Mzw|A z)_aT>kL6pGWUaEbGQMS*sa>ExZJC~9CG}F;HYV%lJB4>~x2*R?e<H<26^(xkHL;A~Y&k}3 z<%@{^`NMdi&*II~L(laJ*7I-urE)%#UR1nnOCCkr+1gvo8*goZhz~+pIY6@ z$tNqmxMHqC<>P}>7A$u(oNi2Fi;J5)Gf;jk_MW3jL`K*2(0EsCcJeHf+O?&XsKHV` zWAD{R+bd2*oIUeOE}Cs8i^jakwUIki)^{vI1bMoyd0zdkAK{rf+~->SgrHErF4OY$ zhxhI=5$|4~?=P-YtmOt?4M{pz>7KZ@ut)Al+jL+QRm0KZ4iPFx&+MF)3*4q3VkKIR zAJMWC46c_ZQrlhqM(T=?08kMq$&eCDmAGLyNRf(MMZqzxSZZzmTndn#0LgP6%f6Ag3J=oKqEW$->VvchG@u%Q+ye>TK|wws zKtO4^fcO9<t(tw+ya{^SSMe*;U;927F*_@n*m?khd!=R>`-;&kTfFE1LV6h?}M z3XPu~*_EZ)+ScUqH#jqY>5xx=xDcbvhb`H?CKm6^O#GJZS*?r@D3rdJpI$97Gi|UF zP|`Wlz|3_$GE_=WKcTQm^>ub#glfz76E$L2w$XVfuMj>Pa+KWSlaeLTN46vr#f(

5%D;=9@_^Nm!TbJKS{NB$eTg z$QvDZd=qMAne@c3g}+(Qror$d?+(?ZXL`nlM=O|9Kb^%Y8i~m9D-39QSsIOSlFU@R z2%MwUW4hEBteq6WE1(M)dRJ(P1{^$WLVKOXY`5u#Ga7IUX9ncb(SmBDjj z`G*Vo@>Yqr`Nyf+RScxGPlSfl?wF?ym#G2Y$;h~LS29#GB919eY?lO)5IQl6(d(+w zHT9MHn61E1NSZJlHM|>kkfg_$?ADc7ov3Hf(sHVc+NX8Lwff}}>4+reA&(bn&2*h5SCv*Lwyyl11OZ`S*%nw#s|M`GEgUOv3K!|6|8;IhFwD2B#vS1^&`o0*^dWLtGKyC=|! z?ajkt{hnXbdnN2MNj?Ow*~#akEklzF%jT*b;ic|tca9fi%)h8ouIwdF6sD7kt(4!k zH`Y!nhg%n&Z55VKcr##hG`YLuxht-G=zdk#)P7u=&1)y$2ii_6R^DH~b`Aeor3>QE zo{pI)=>H;pq+voR=imXOh7Wr4C&Jrri2h*^SM8(;QuF&gXMOfeVCI?cZ$+PVUo#LX zDk;8nr;t&08rSl^j_fx$_CwbLr^P|R|-u7;p+vn(l9j))3@Xhl~9|(B%RO!|% z_ve+mhRXZ1cYc-LWLJM7DEK}5%M*_17{NrF*BF%qy32&p@9*l@p9YUS*iW>0Y0yyc z%}_6jm~Bin)1SZK((u>GW!1ptchT3qH#?+{-BZ|qGhb1nqtgG<9tB~xw*1T?Za-iD zV(sh2p6_$+23M3U-=A&#+LK%sZ83GxNA0BB^2LC-${@d`{P=WqcJ1>XK2Q|H*8S+s52*cIEhZQHhOTW@T;VpeS1 zX2q%4wtchDzUR632duAa&N)WwtqTB-yYy!MapfJ1M%Q};SzeBs1xF5S+v2mksf>8V z780t*Z}w$hTrc%LcYMI`R}rN z`4Rr3V9fqWJvyNB>mjD^3L~NYO!^T2GwgyR<0t)ZMExhnN5&8JAFtvM5QPfD#r)s@ zQnj{>%Rg!Ktz!+v#tfQ@fRo7L3)>hJ3jfqw*(9l}LL|GBh6GG0(tfQegS>lWbj@b|LrkL71) zT6;{^TiEbj->)1k^(raUPAYs^`M`wFlQHR+v@!U4z6e)W><_f4QB*zNz`Gfi$5A7c=cnzs!hF|Y4j@U0XUl2 z=WWW5UO;cmIm7)iJ>KG2B7y_9yZh+40pEd^|ArsIVt5OJv*8>SbI;T+cHs%AiiOdfl;(`UC1-+jkp3%~+_ z=P=oapk6KbI_fmQybdqx_c{8XfD?Jf)n6un_kV+d$HU0B&yIE1hN|1q#j(}T9g3&2 z>3r>I_vIPiWY6i&fK&|bNgudeSj~8^au%}vlPDr`P-4k2pBRAwSQdi^i!50>xdBOK zTgI|iU5h{Gn$RB9OU|ih%d2UrnJ7g;nUwslT1rFr6J2tsq6t?$>oqIC06WHfY8R!{ zSDKjvRg}zI6J@(K4X0*GyOkbvd;XQs#v}$0GygU}Tv0!a( zz$|0TcG9f4Z?1T*)V}U}0|x4*iY1uFd8SBXdT_*+1>`cRlfo&7H>CgG&ZB*;6Oy_Zed#1`#tPXJcI7Dsh+1Q&g&1vyRw~ zgelbnR|7Ew7*YiE0$gCMy0h>pmIGTEmcQ&bd}-hZww+#Rmv6>KL+CkiJCH^Qag(S` zcy_VqoV5wM5(EiqtQ)sb!-_Ucid%e@VYk#uAi+zlt8w5dq0VF$&IBrTMyo<@ccoQha z$3=L7jun}2{$u+2~bZXj+17D0A--eiR8?Y0$^4=IFp^Lt1%j{CHWLGBno~r zVxy?@m>V^cAOe9Va`aIO7!{9)r%CPy%nFBjD3LNkW9f4eYC*Q?E(|*HX0VSfiF77L z;E!h9pp9@E1vAMH#RRHjqA;5PaUxx_6y<^uw{W_>1&omEM35SW224Vb;yQDR?BKg) zV3xWz0IG?Bu5-#>_$7v)-HYbM3rRp8okt`026^IoV`DBINLYO1rktQfTsfJaIh*h_ zQ8bBDC-AL)e=~IR{_P`dhO~oRQGy(l z`6S+Kl;uSDmc*y86*kP)V~nr4a*;@mssSkJQ}(93g*##lJPQOk6t%BI?hrfE zS+GViG3Lu4-xsI*``^UlYdkz6NAj>pKvR(~j8_My0PKqy9gxGv;N{5d=?S!cn7Vr7 z1w|IV+-;k1AmJL2Kkrkiv_OBJ^6YBKP>Q_sU|O-NzOw-t_92;R_&L?%G-fy*kHSh7 zx97GZ%3a!RvNeT|s6vc})<+>{Vy&&cZX$DWG4{+v(*@2#Chm~tUEjIP66iWIfGUxN zSF;YEaMpmY+`AqP{GCEA4(GKOkHbDi;7aMjnk!?-wlCb`rI_emg3j4Q8mz86s1-y1 zVf9>_*5kZ<_ntOA84OHp>W0+P2Oj)JwlvkaYq_QC3^wU#j4;nMS{~O**mVMPNr1;J zynORe6NVvCmCn~D;o)$(NhkONK+sZhQcFshi{^k3{UozBRlE)wMKXBNljaa$ega-) zGVx+dujk~@i+rA1L7j6dJ*E2;;79s|bd<)KdTm!)=mXX<%C^NRktp5{H>(9%0 zgry{}%pB6D4oC~wOFM!Pu>ltbUJpCsfrDx(r#=FyR&M6o4_jw@K~H4{1WEPvqqgLV z3fETNt{vR)n-mc{Bzp>h+i8}r#k2LK(KqEW%8`Q>f5dtC; zd6P|R6pE{aaD2X{#(g&8=-cRlsAr7(5mW4+!xE!f6zU?8uiY!+@W&5(%=pQn?7V={3_hV&f{B(|_b&=gv-2D`k zFVUrBT|0`?k2^er9gYOVbWlDjNxN5FI4>U;(`$y=G#7PgNxl{CNwX2Xw}ik;(;R4G zV7JpOOt0GEAR0%SAjjD$r_*9Y>{SG06&MX&%1}cM=Cj{4fSm%E)H~jNJ(lu(6j~sQ zP+A5oGwM9S@fLNf^$uOE&y-0DMOnG>d2w&@CG5%62Da9|{r)O2gt!OxT-|p`hrkes z)@V5^$}MWXo(H!s?&KlWUV1>zrvkCP;dj`kWhe2)K5F}6-yO{vwYnCpoB{97U9@2O zxh~=x1ai19K)yTz$6jya@`2HqhyV-w>Cxxy$RwJ zydR9sB)I`kXV6;kgH=H~A&*pd6P01Z9~D|wXeO-itWf1M)vvYvLg-1xErAKgCui{| zY}^llusD>?U`7}o#d`!04gFac1n&6j?GKEO28+Ki>CVXfDF5p^|Dl!sdnxbMlyO<_ zK>N9rTXqzhi-wZET+H-1VN=|8=Z@Kx?r(t0^&?v+%^?~Zk4Aqz=0cW*(^xm1g#p3C zMf+zqIIVw zwzs`riPxa~itJo`TqI8CRq?~5g_)`47fy45@+MwY2K3zNn1_ajg=awdt>*jcWn){@jo&KVS(x1Av}hcdzD#uAE=u z!PX}0WS4zrh$BEny=~(L4hD1`hf9vQRy#dy)wPm(u#;fydkeH33du*{X4Z`_Z{Ep> zeP6!vn3sTSz~+0Y{#Y0lwC&Z&k->1CGp;K-JeMaA3X81N z|D?Kr!{jb@|Gk(;4lu7%(L%jRY6Wz;*Jf{IMDY$0IL&*$stAd$?uQ^87~ zt^OsNn36+cdp6HM;ND>ar-JWx90v|0>F zEFv{av=jTaz?K7Uc#BZ-A<`S{Df#zlmZ!idsK!ZI>`q85$_Wjrz$O@kO?3P*CNko5 zxQ8>)$RN9Kz!>rk9xgvAA+QaFc>z$CM4^cSR0TiR$}2Silqu*5G<)g&)xT+94)+4C z^H$Um5YGAg1JLb;an%R8L$n<%DZ4K_#}J_B7pfz5q}TD(aGqzTC$le$Fyd%zw~?0K zpkLmz_RoxPreTs26T=&faU0$|B^it8bVTkli#Vc8IGQe!;=TrNmSZ!enpN$3S$fh= zYZfmQ=%7YvHaNXRsk5TQ!L~iAtDGfk%4MILZ4tmjWOrf2M9cqO?i z@{&GXrV(Vc zXbTm4fWjF!XFeSX6%CBS$immzC*ERtp05`zeThr#%{$^2G0;?{-P*Cds?(i)7x=Ek z{xopFI01uUW+I4jbJ!`Oc`UYn4-_Zw3HVFvYceNMlJu(r$2%B@jyMK|zO?MO zUTG}u}A!R>%M9~eYhsZr+av_uMS20|DKt^wUrhMiytxEM^5VS!C(&@4!wHG#G> zXP5;hPTNZ}TamYO{n}!Mu>}H8xcp1B93(XqQ34CSJQk<4@rH#8q@ewKxHi_@#u9om zBR~KF#R(TB1`kQnw0_|UO9i49YSRuRs5iR4%;-%aRCx&hMed6B5QbUpAx~>UiWZR| zuxYUf{uie`mU>X)V~zll_Y;~lr=(t&ED_cp$}B;83!Wi2vXZIKm=q zHBO*z+7_gSa6l)5ThUSB(ZN9eak9^aYXA~UiDv+9i#cS`fpFF!GFDKIf}wwjdQuJq znCl2MM|2`g_Ns54Rj_)|_Xx{N)b|#$c}hbl4Ly1p<73-@>iC3Zk0ziSV#YffFPGf(iASBA7<>1xUgqxF^!R+mjN#0A={bEkMx3Pi?71SWE_ zls5UOMjui-Xfgz&(+vtGu8T4*76-(DuSASF?TjbZdG;IBB~fP^MK^-tZaG-wdH!Z} zHbsrdbupNNKZ_)CM{qO4jndHUoHUq)^Eh=9D;N#p-CThnzp(*!g@{uy6KRR@82;d$ zXdGM#`V_Sm8h%R1ceQUG$h)+K{AZ!zXAsmp-x?$<5Gk) zzUbU_lE9aE!F2pS*2w+#Isia#^WUM4+tmB)LC^T?MauKtqTa46BTJ>Tl64^@jdGZ+ zNc-j`vg8_K8kz5M_PRFsIaew{Uoj526P7}pIY^5ooTpzj8Id1Kj+m7^Tqt#UJ&1@; zl#a+&&bv*YsdJU)8WTh8_q4$HKK^OF_AuGhA!J<>5BC>j5E+LFDrE8Xud-)j(REbY}5tQclkVx z>{~$%A@0hI;)_GK>VIcznb&v9SX|wYi1X1jHGTjOJrzMu@C#Lh` zYDZxG{{V&`p;WRF7$x9P!|unli2QYB@RwjPmwDluVcwdoPh#M*L5L~+f=;NkAI|*h zgWPAe@AJ*4;#Vw1%(Nh~Rf(9hf}EV&l1lBSlVQ2H~%Rs~_&!oi6_MHgEDHqCLbNdBYAw~cpk^DL$nc7NQhF ze8@vwrG!*vBr?G@!81I;--6blC?nR2Fg&#Jys#6Z__#5BSpg1CYfVupYyqMv8NDOH|0^RK=k71?u4eG`D7);uIZbEKFl?}EBGm!*@W z16-|p8mo?_)*+_-Iid|Pfh!a~J0i~@RbKHTl-T1>nl55VBrqYYiVK`NA$wtplAxDZ zzcNI)TT2Z~*i_x?zWxl&))SfLns^X|IIJjC zOy$Usz1rthzn(U7AXo40ef_}Y_IlTph_i{{Nx|F!{#{}?`!F2iu&L&3U7x>=zqSa% zx3s!gUi`HGvVoo=d|?ucgy(uvsksWH^V<9zYvIH_s4VSD36z%M;J+;T zMq%To7Smez`yp_Tj&*j6?w1Df^N&BK#O;5+r0~>yFcpaN0uBtxUthwgMo!V z0wap7+eK*w)G;2>yy_eL6k}!1z?$UXa7#+6A`6H?XRLNb74Fy|JxUj}y3^JSDoz1P zI4sgDRHOXR->!)p8TpwrI>&;Ozos-b5H(J?rJzfj!(c!Z=>f={ zUaDk@s4Vu^j2Rii$W$u%M#c2fqp3Po63s!QtB2LiP()k|o#Y&8*!3MJ9X+z(;q;KM zQ1N#*dW*^}06rdH1kylOoY_0tK_scQq_^1D%*4Ru7{(grHpbe8Io7lT(knn|frJaqGIAbZix5VqN%3&07%m1>3% z-shkm`@J4YgpVtE$|dEL+L4>Y^gNW|)k!`o$g$8U3>xt4TzyKoSYdl#2>_&<;7P|3*tfiSK{t+0Nb0ob36uyp+?ipIS#Wn>(}%amW~u#P1azgF?@Tc%yp&0gx1Ff#mp-`ort!zHnsLw zeo65m%1U-F!F;QWHhL54v>c1}pYyCZD=ZE%hGfe{rUJ9}d#D@aXF!KF`?M&|fsis* z>umCGhy$SpEHMcw!*=>duHE=Tjq~k}Q1jkX-yGlQu3Pr)gFJdX9vqoc@N=oC)v&&F zssS-(rP}Bj1F%#6fQD+$xTIa9AdO;8)l-o~S&sQ`%d4u)9$wNTZs_!Npcc`~<6@7@ z2YGE|PTvr_e?xv*QGj;u!sr_Zo#Ts75-hAgqS+KA!$lR`*1`s)f3xg7AHr&CdOZlI zOa?!TP5$B1Dxgm`I&E+y|5I#Tky;6UueDl}X>XHE!^ZM_QRioJUmU4{}wa{0p90CUw@yP`NZ*!eEZ_)0&(zV#g&6Z5G?=#~GD zu7&8RmU&V!o6Y26Fjz#I9s49)IvDI%v=^z>_pU!})xE?wpDsI}zRWVaNk|KBv%S}F z$S4bs^nNZotfV^ltClI!X(hchZOV{2v(>|xSi552FU6eKOA`=_avCmMJ@N7VC(teR zKh!_S54-;#0KYXxmVcQj-H1vAz17p6zYGfGrve48Hz?`PWZpU;th;%@B!8?s?0{3%8H0USw%e)QHH=}ZtpG=Ow))fAn@Iw|N= zh)7^j?lAZgkq(}4qksa4Fe1oP`vk>P&wuWdPx5; z@ExH-*)PEy$b1l&z_$H{v3^~@9Yr3WA-U{c0$^K1cOXSs*^u*6F2NBjknkWOdLTE% z0sK8*6eKujkduKvMW}&e1Pt5fOC%@_Cw+Ye1_u0uMjiw>djQ4w4ERkD@dYq9q6gFl ziZSR*BC{aq0o-dUHUd4Y;4J>x7sg!Z8gZAPBh-%g4j8zI?uLUbudXejW1pOBKurU- z-~!s-U3$Ym0~p-^gJEDGuYm8iceBqyq{YKhCMdWtuFfD`-+X#^Ae}N4u>A6}k>DF~ zM_@sEb^%l&dB9a2j!yyw)EQVqkJ3xK8=|0+I1W(9_>G4Dl_BRM+V0FgyxUtM$u$DU zPkDu7ePS>dkBBbfRhz&Q1wyDuABWrX?x$N@96cig#=$m?PFZy9Wjw1buddglUcNm( zqS>nfHwWn;hMY0o6CCnVHcR5GhA5VL+CFYz6`l zDk?Hq1R&xD6#w&75*F;UIdMBCRnOK4sJ{2fN2RRy`Qo(_devVJif2c`0J|=0ITUF1 z>(Z5lpNRiv8sp~sXP6}S1+e=Xoc#WG`n{Q07@oYKF!Pi?@I5FrqeziwfXz{T{)4N5 zx~)z#wtZ+UA>OTAREXH-z{LVCzt1vy58edK zr=ib4{sy&+05<4>>cT*zH|E54gj)hQSbdZGAR-$XK=$)KV0EGWPJnExggk;in_rNDL{Cs&o6Jfa8!_2piqet|JLkZ;5u0jPmT z1L7NmSF9rs4`D#z_9yVSXfGES45+7`1N~UuV?yY^PtX_tWSwtv$fz%9e-h%}v02RC zcaSgmFGunxf;*fJuiKjeA$Eb0Lk9x@pb2ah)ZZlHg{y_*^X~cWSPU-EQ>3qL0fn(n zv`j?Ka`Kt_H;?{?jR*pNLlqXk(XqJvpbp;*RGsn~4NEY_&M0&FXO3ti4UDbCd>$r! z;(Dx`CX!rybJpx9J#Dh9_;RLGX&9Ba0IL1u;?vyjob$Oh^YLkTQt68GQ?oIDk137!yvm9Cj}DYQw=H~< zpTj_X(SAHB7eNh{Y7(at!Q~J%Dv=!e>%PLM-|@u5%jUM?b_shyp@;ynmw+<@RcGQK zVXjD8s!RqK4wduQ=iifF@FIDi%^)JKK zcWGoHaD#5=mTTP9@$&UDrIzg|hi&-p-ZSQ|4h8PvLr!N!OZ zSPZ55nthju`;9A6Bn9@KH4-q=^x3%R?9wwfKMN=qH|=`E^-p3U z{xh^L*X4gKwdqz4mM$2VAYv%AF2lt%X?-#iVWCBBP$ zb^HnNA?9)tP4_xH^eU3{re-knG+1hPw(1EO|ERH*<>53Q)uU5-0EDiI1x0ZaQ8oM@ zlLG{s5$j(Ai^+IZV$l$6pnpD)B*+_VW>V`g% zTTd!k=38dC`*sLPqzwOf+U(urG+d7l)?ujedo0{v4=~-HUCG|xsQd81MZuUN8sSY} z&`E{8NY7WbB1h#|0%ABz zlx&QLyX9^RE+OTQ_8)i@BniS(ct_$dSmch$bXDfC zQapX~8?h)7h5Ht1rk3vu)gR+haQE|zLvr|h);V*L%Wh%g02$Fwuwm^S&%q^BE6;5VUvhEE{|e+ zItaZdR(;Cg$+P2U|1n}lk>cuji)=!JVXxzs_EPhZ#eUrw=<)C};9us4-7xB^EcIHo zU-vbP)iACrfDi|b3^{e3>bW~SxE8f95A2M^vYr;PR|6UoGi`_@*^(p>dB_@q5=dXv zzZpi?yW+U@7}_b+l#N-^g!Y|1`g+IX&Ehct=nG5Jgt#aIo-b~lCpMcEjhj* z^wZ9%E(U4OsEQaQc$)P(i+LY?kCkg$ElMeDIP8qp0jL#H>Xw@BJTYZ*f^IWcE_90~ z0FyH&(Yu-3a&Z&QJ<~Ifq=sWS3VX6XD!p6}l-F!%I$wt(kSm59)GUs!=c$?u#}Q_( zHJXXb(aADXPQaYCrJ;kYr@}Fe*31|IBg=Y2e@8Vi#-HA!oI*+8r)o;XM+MwPdsGPmlWkxT!Gl(-^8*IDX>LdPQuGv%E^b z=$ZpAWmEa(s(sKGGI4wJ9T3q2qX-r2X7Z5_AQ_~bjN~5jkF`x_Y02n2dezt}ES-Ds zv)h+fgD#dJKZ*-?_kEiamp^mF5a?+<@jbmo>OhvZ zfUTBZYQ0`r)U;pp#M4&*2!Z>(NUc}0om6MX-c^5iYZPTuARIQ6af}UeVQYy19WNTf zhoZYfG*6%$e@OiGlK*&5brCKe`fn>md9i<09Bvo5=b+a&@Ph&21_m2pZ~Gl6s1nHu z25DYm*(1Yfi`M8Z5ZJbAqG3WTBdP;S0Q7SH+w|{&6spE3H4{j~mna=<#AlyR+FBhSi;4^P%Ax{7L%jkJcv2+eL2_i#dnjM(B;0;kDso)({dMBRbc`7_;9H&itGW?vG$O!46VJDL^q&zOpr{Bl$DDpQpX;_aKIhf4j11P)LV*z!o zv~uM~PO5juZ0gA8NfYaI&FA3V02}vTF~7Z>JLY1`YbY4kclmiHEGeiFoH7J!6tHu? zzI4A1dax)VlM6*aT*4o3jZ^H(ACyN_X3Gy7PH2)RrNh^;8`zGB#7y6Rq^boHVIX?P zoWf&ctF0ct6(z~8Y~`^HGSWwM4w;1mA;+RKt&``dF@$>^D9s8WI&^bW0RxSEle~U} z$DRH(w5AJ5Bt?^*7v8|mmw5{#xW8eNz%a+u4cX>#x!;m?Z&3ykE1$0!VclVjb%wns zpRYWM28Phc5m_E29~F(vZzCRVqAZT|^Nt(inGa0$%}X1&GmiN<1vJoNhIotDRT56U z6*c)tzvT5?;1+o%tPB?&03CN5nKp4VSgg~3G38QuDQVN}k@d{@6<0TqvGz2q!~|}H zqGE_4cD?f360h0Vz>Y1h@&1@Z6z1*d9qJ3MJXE0zUlUy=JVARRq0mAwIvC^ki09yX z`MmvFS{J~LybDD-)(dp__CrY_(d0!K=ulX0i8MFpH2N#xlh4u{1u$!prI??EQ$Vkn zDClpv?v;~JjB3K|w&2ULgY8x5gpq*l@qsk0OnzyreXlw~v45!Ux^QO#y0SA5ds&GM zzcHd1ycCQ|BNySfo|1{|tGK_=E)RFYPN_|Z_Uk-9dGc`fPF=A0os;io!0u~JpdxRw z-5r)pzfmiqXdx;R3s4l&Yya79+TR{;^j68qggs32!ouUmNGt09!s!Rpb4uakbej7| zU!ka}L1J|5wW8csgnOxsqsWiEL|GxYfj*5DG&v+&7H%s>mr^HU)#B=hvHPi2h&^tK zMG9kQ=AVGbX>{T^#$-rGh&=NDN?6H@TyN^FF%My_uz*y!0;t2QdRG{oZ2HT~CH=D( z@50WIyc~>f;Ci>4?6U(gKd}MPf5Pw{YP(g9FD$QDFT#h^A$m3Yc(DUrDUDngnc0SK z*KkVPI{YI(w5e618c~K5O@|?aTUxe!q!U?6;WadzHJhSr$H{YHx*4RAA!1x9LYK)# zC~b#GBUV#t4pzBf8olTC09Zy?UzPU=W;2sj(aEHX@nswnVi~ok?Ka@ z(j!MKXU8l0JC#JyxGo&`eoG|JFAbO+b1bwKFU3V_a=7NQ?z`sZ-!;JowXci7_IfC23G)vyUeR}$ zKFcz`cP7*=mxsGmc(=dedNE(q5*XNV=GEAOdN_8x+DFDsk3oW#r+;jdIUtBapsqEs z%S>ud177)JKzJ?|FAm1@s}NSBcOn_Y(1or8Kmh?z$_C%J`-4*DL%DKE+}Wz1s?T&mRPvM91=c%Iw& zN-D!u?~TAk&C3}jeGhwKM3{`r#&JT0fu04gwB*6s?Ksm)LwxCC1|~foa8i#4?8RFHJO_F6dS$tC zeC@)i&QUB8;o4arUlZ$D9=5if{d$;B-2`o$x1c1~_Fqjb6RD0+P`F-fs%8Mxx^E<} z6$_E{h=V{rC0W3ZMNOi(t_fr*E?&0T8Jqv?_4cPR7Si&mA<|$s|A6(G^2we^jg>NC zO}jT6c?m(@9dkZsy$n2`+9F- z%2O5<6>o(g^2fEas^=OC1kkaVaDf_6Unzu{13QZ}js3fl`RfAV87aCx{xtC)$hv|> zDN}AJbAZ!$3={uonAHe!^GtRitW=yiK|4|lw9!#<>2J2|l6tn+7#3wxUH(?h+%0hn z6&m}tU#Q3#?l&{FTyEYf z1A&=}_KX=f;JmP^kXV?>z=5Wfk#hbj2Z__Ot)pA5D*>B)83T}L9ku~Wx7}-BZ*hyt zV=SgnS{24X7yaW1Qe$rrld*A62|AXM-W*vr60k2_=W(3}&y)9q>Xcuq$R)YDkz8SAPxd7KeuS*9>Jo~CS&7oW>6!or4AM4NAOCr~v; ziJ`57P@^uBEfXDk7|WO5d7;HBGtQ#z&Y^6klBVAs*ojIjP7&IBa7||*gPM|9$EHII z#v=`Vq{3MUWg>~z%plr-sug5j=Xa5S+M&uARLsNGnF8!|U+Ud>_C&dg=e!6%Bf^Vk zC$ipXj!~^{O#C@eoZ!M!&yKU8MBFNtsh84`y9-mhXU&*zH$1M|^)mW5q%-$^;W9P@ z)6T&FkLH`Ebka*~$CYW0ci<0EGrG9$Vq;_OG#^njSX)KgtAOLz=oZSv(Lo5_j)0d} zp@5m51`C3@hc}HBAqHG!S+74VN={O0^rkddLy~7=`Pmw9 z8t7}=2@LhyArCwQ(zt{Ph>T6*KhdlG3KusFAv8Jo(L0jI^Avb#XW30H{|(E8DGsoK z71u58U%wn3mHCgBWk;-^5c*RY4q%E}rjnw7uHj}Xkb;9V(FBoc)I6VeRXWfy!4#PEcV^@R+N!Kk{uXvb=7mI~WnQwn_K@n$ z=3|LW+QoS7U@;DTrn;%!>t82hzxnJ=$wtEbqxQ6PP-<<6yQC) zEGl6z>x$|*dsO_WyLT=@dBic23!oY_L;$?o9kwAfKyO$wKUeK1He5M)vNKs6|03z& zPDE%t@_YG=)E;?`niO!Ix|7ZBAa7yQEy4%v_-$;yhUCFpkN-;HNjP6URaT9-z3^dG z-G+scjN0@e+i(zMZgPtesaK-78$(p;a96{n*z@(|y)0!Q;QMAhc`XxI-0psGtOf9s zNTZte7$1I1Z`@w_tBW=&7{gK!571_S6azbBne-=)rQM_87yvB)kRQKld68@}`7(rz zcG^*3o6EbU3l5S=*bl75tHnMxVt4Am(M(`_pC7-9FgiWa#wNJmvy#J*sdaV>8 zVHPkFiA7v3b4*bm?Kj@ps(|0m9eu>kVTVhOB?GNV-evudSsOOtTk&M6vBOl_;6xAD zTYqNb8~|AUyUv(`Rcx=&lB2c}Y!_N7L?qnX^w}2s?=Nm?|E_?At!A|)&xt3aqbVxc z0@rF@)vYuymg)*$9@%g&+LIT3t{5B{S6)^vB zw5(iY7@ezwYh~UOWRbzbTYlcxu%AFn-dW1c$^O#o*6${)_8rReY1m{}>dxj$?z0!+ zFGkz64Dvkm|J|6w%cJ9CxbaTRaXj5>*_L7^Bzm zmKd6z>u*tVw}LV*ODw5dSiWm4aNR6?+HR91`ivVh%uKLuzY9RvLuK|Le9J#SYVw3) zbSk?QXOQj}OiWh|i}`jRPZlAK1+*I3Y6-Wftn`$FJ%fdzFVU)qn8znnJ8#5VJj(=+ zWe=C0>VIBw!_TQz6lwCq?+M@|OCp2M?B=ZZJSt+G#lfsR2eIfq7p|d!p5q$?NWmK9 z1bN^oRb~IevuFWblYbz|NaM*@6;=txX0(n3ERKg|vtRfF$f$0yIhc|69aU3B&2=l} zxa?eXZ|hlH25hT__+4mptqHgrE<10iqrRhPyHQu-J3OHSp8Wt-I4+&&^EJgTqZ z{ZNA>CA(D9i^;Z53e1vHr^8x#yw}=05>Sf7FlPP<9t9h%tf;QS=AS(&B0=su>1~jO zNSYzrVG$q~#gwG5U8lIPRhK=q`I@RpE?p^(A9#ZeYW_Z3)A%CKi6Y@j^&j@lO6PI5 z8iPg#VctR!M?#(Y~Lta^5T4&^x$Lll2&Z!mzr=1iCHMiKeubu9a_da9JAie*4w zv9~065(=97PW{jMi4gQ`hhSUWZdPbo=!W@s{4G|2?YU02)fLRvmjzvB3%Sm@f{D>j z15n~&C21asBLA}g1E-u>bGu3x?Nit)?F=g+^1z?UT4cNz^}cIg<+3+8_Fw>qAokyr za#BD8F+ERl&fm*AS?=+t)j8llU;e{LIky7^kv+G;@oyNdKo>nC!Q!{l6E`{&+wL#6TXP7D$TEQEH@zbxmc89Pbt`jRg_Axv275Qcp5 z{f&1IN`9F@9MnU6`?(kA<+Oup(Xa~5=3QGQTUt2gj7Tr1vw4gPwKX5t<2}01VDb~+n;~nYH@-Bat#QwM-6PHPfU)fri;?e{SQf98jh-n z+gNCw_;D!d9c3F2jE-70D8PK~ceJ0Q@%E)nQBB_#t+yR!D6M}^Dq|(}9}i}jJ&Ojp2a{<6Oo$kCW!Dipxebx3!_Vm6X6nw0 zl%-rV&UZ~Pe5ql4KyxKq2=e9!q)G}Edmm!9$+#Jk@l#>^>?KN}p`LM>&IPC;3?c)1^=MHrYy?1vLDE_$FYA7V+pJ;ooc8w2(`0tSFg&0pW3?Md~IxV@3qL z`I6P{qNH|DbNebZkin2rg6Hl^hw(CTW)y*5vmeYIBfTS7y0a!Kd@c`94BxKH?maG| z$r`R1aqoH)ma$iAzx9&2;cJ1&sXP!xvTByjnhwrZ>H>Vv+X3W>u9PufLk(avNPe#x zRM@KLFZyxujXU$|(1Q6)&pOfi$TqQOw0fe1rrYnM7uiX@mH+w$EGrtJc3d;Q% zjM{1jJ&Ovdzis|&xd#QUeTez}Fk;>b&DS^oN<#;{LZO50lU7^gh*_^=0Dfc$lBRYr z-K!U!QJzA!b&_)@5-iHAuB4yn`grDIFwa%S(;y;3X!Es?_E)-Qk&oK= z;6D?m=4asbCoL+)(PeOhuFgu7P^QR)%__==m(t}I_jFE; zaQSc@pu(~o)d8vj5D3@y3!*cLl@^c5+71*}?^N8bMHzcX49?rq!k4kME-zgX*btmu zDO3W$!3=r(21mIA2GJ}Jo;y-#@uK3sc*%Ov>J;;iP|E`1fWRmkN=GL&b>^AFe`CLe zg7c12E-2I-N2SE*!e)bpX{ao*PFT?&s-Zo>Q|Kq=8ODCccM`>Nh6L@9^`H9E>5B+kiDsV%dp2$axg8Eap`D5<* ze~=418{2;&7cdUCAG>9NJwG)7l5^dzlS4*H+eaq0P~Et;0*g&}i8e|y2ooBqvq|0N zx?4hI*t%M|Qau)1j7r)@RY}?|ireblf7@s4I{Tdac*5=Te&f9-@BP^atY(WHT_w2a z63LJih6Vx|k{X1S5D`xc2$7Nu9!y#p8Y+XZz9yn~Q5D1-Dux0%R`~ zC0q|C0EG=c_vj2BPz*$l=7%@T#!dkE;$q7UZKPOg%n5zncZRsHZ zH~$w}hVs6aL=cJ`4v30!Eb*_$=pQw0G+p(s8k z=w|u{d=5HH2m}^N^M3$hK%Ku5hCq1|BD_#=1O`AT4lvfy2N=2|P=B2D|2T*O{<<3g zNF4OeP7q5^>ca3l;1utzu|QB;3tC#Vq)e`Lb)F-Tv46_9{E5CHh=_wUm^0=(d8l&jz0 z?!WgdVW?(gVPYooXX1a`)YZ|xfB-^GF-aL903<050>}{#f&a{M8-I%Ys|(=Yp*koB zGynwr(=Fke{?)PfUjPvLiyXp$elImYoH7eM)-jK-%$S@^1mVcSC;<^ z_ZC$L&JaZPEtk|0L5USepH0j6C@b|5(or^ zBYb}&8z3Q$LSqRb0K&|H00%UN>erg(r2!Hqzf`{^5Ks~z;eYVANC1Qc>bLlhqA)KE zhS1e-tPnc-m;9Ug2!t;JMm0T&hAD+P*MzkkJyYZG5nCQsCf~|9vXB%Tequw3?a>;u zT}U#{&6&}|gQvSeU>oOl19gw1ypQj913uUC)cHvti1C0|9eL~%CeIIu-z5hea`H~n zH4+t?r>S!*mVaV;h;DO5Uw(D*Cfu>dSb*-nU`^Llvd=Zfr(ikV@D_u%SI?g2=reOF zm~AZH!8Y0VnJmlfu?prdy2Xbs#aKtC8)Wh7DYqR{CHYiep6?y#o4wM_)e#-6>m9QE zo&OQ`ik4Czr=~PTwb^VD?P-3g_j(q6fW0<@2D34w@PFzZR;oUYqLijBR_jwf3Jd3) zNT+0~bym98qO2916Z&ELv6M__sC;_pn0b^^aIA8_R zRlirqJDtFNIaCc93BeOxXAqKm=t5KU$a`(#y^*(?7LRcgsF!U@Bj8%vr|%UrZ~DTl zXQHo3P^sPOuT*!Syk`i)m#La17Y$4=qCr^2A@-_PJI$Ko&#_wqbm7ZHp|HN)d)CD~ z2Y*41PV3c7a4O+r!w;f^Qbn9bsby;?V4BEyTjfgJ%ei8jN@_rcR@%8bR5|SvYr~OH zQ{-Tb=e@1~POQH09N@|J^82%-v5yczILGY9jbg=EaUW{_a2w%QLUif=5yDI&FH=b4 zDRqYHX!x?o&5cwg`%^iziB;KWh-ajB?0;Q%d^&Z<*Lz=_<>pFUgSJ-rlYY9=5*yp@ zT#)wiBwQ@XTR1iaK)BWH^>zb1DEmVS{p*0YAEJugx1@i#ZY ztv}AhB6$>7;nsm=F~fb;($6;)(r;<(=-;7J3xENcL9Q$};kiANmvm;mf;D6yh zWSDJpY|B&g#!OmLr7_|_(Dp_eq0z=TOQmq;t$tyCF$T#%KP3g0?hW^Da`M=0IiKjl z4q<=Jw^pY%syMJ_1>ij>+ED9mMZE0~+W-Eq__kU~TS&Q*& ziL-X!q!k~GQT72@X&7>zqxYP6El(Kn_23v|B$DPT&zQABbgxE4)=_js;?|pjtgDwD zS^{{|0Y80?rv^H5Pd=+O zm{00=v3$V}5bryG$#`_GJxU||ZYhu5RfeWJi%EKYO|}s4=y3a-rGKSy|HLR;Gf7{u zV@sFnNVwKS^lhn!*~Tf(q36~r!gTpt+$>&uAPvu#6e(XHKO23>asEx*B(Y>!^tLCN z=oP{Egy zkMU&c2cNNjYvS;FPzRIz;zd7Y`g5JF&_!=&0ytM&>KlV&9LeUlJ>L7qj+@Lhf4&2;40bvZsL@s}O3@FJ(0`Wf&v^iU=_r%OzHi`# za?1nuGF)Z5WOtgrZUDN`WV@Yv*(T?4{%e<)3g2r^63@Yxn)oGE`+Qu^iNeX?;cS}Q z^!X4(l^^URWS0CLVDsVJM#)&jHF&{z#@4kT3>JBJWz)ZYp*roT{}jh{t!H@Vu&8hJ zY*1fDfa8agR)3f?i}dSxzGgPl>&0h+@c!n#0Y{FkgWB-Cnxah}CqA?Jm)6-*ZlA0? z4CZK+Wr0`EbKgjos{}dlScQ;mi&;%&w;OH5__)lwr+X^AD4fvH2OIB)cfVXd^yoA0 zDxvG(OQ^z>&^nS`3E<1&b||oK{PKbAU1^X-jHXViK!1gz9hcjDCk7%hr8Dn5+)GM} zeiiq+B|2rG%o&aPH}uV)kPKC?oUiUpaC)xKOS z<-hrUfgjz$$7J?R!|{hPTfAY0_MVf`eKz)!M6x^23+22RH&?u3XsVJldptJ8d}EY3 zjCX#RxPN_LzP%%Rq_Y`WEV4J%JsHnjS{O-xYu>o??KRfjQ8jz<;K`)Ne3g`7=-Gj+ zUc{)1b{O7xgtfk$I(xAL*-$;iFW@*!9pU3ijB)HH zACxAV)j9+2;l(p`_V$NAmzme{E>%z1_b58Blz&@XfpolP+S5`wO`bNe4OWmyk9>WV ziKv<}-Eh8Am^Tx$dGR5tUN=2$bXSR^NM1qIav|?hRK-jS9n&SXlK2qKgeNhYSV5hv zwk{Qz&gq0`#o<`rKlr(pphjD{~cgHlOb%z2J9&XPOS_|)-Z^mtQ| z#(x26b?e?jE;16+rj#zR32P#o<;m?k%PNDtG***Y=5G>LF6`v%o`Oz?61m)2%!0r0 z_`#mf_2yA(>__<@uhg*2u(OZ9`-XeL^HAbu9(-TyRJtL?-z%@CkAFpfP@QB&fNMD|meqU5=D@b4eUT5cfe1=1Yrb1Sy{10a!Q}Gx?m)%G6qo#)Ee6$yAlEuJ%7fJE85%Ey)*n9ug*qh@g?RB54ExI^B(^!=u%r9 zWhluu9~8NO1v@IZc;-(_7?h;BsoPb=37dSqk9eezGz}w3inwOq9*1K$FUkr?#F=sk z6djtnKloCnkxgTNrtKf1{6&INm=z4S5E(DN_=PEn#SXC(FS)D8-r&1zNj_e%KbjXMn5j!*aU3lSd}~%_XY}y` z9(&upJL+^cMb*`5z-y`tP)rPDdZ0^wpNRWISzc_IXoGF8z6nh7NA}h|Vgq1{R>H;Z z)pn)*{$|4K(X?iYSF}s~(toVj_tIio<38Tq6`=l5e1oHDKHxl3=Z8L5*2GiUg>)SN zo+|261oK^Pqs7_7W8#?FIvy^o1j7w*T$-917r%In_Q%FVzfL~rj6^v}UF2;rnYsDG|z4OPdhWe;`- zyob(pwHQ4+lWU^67r@$iSc{P1Q4#s^qI|kXkJj<2{Wa44EEH80Aq>e+*%i^Vc?F{5%T^aTH5ART6IM&y>nuxdJjQLvz>{x%QKaHp zaD2J_A$$2tvz{o5<$sQ=(q&WPZnhu%J_L8wGMy^Ubv2kgOF$M#F@-WDrAjH9MjB`E zf4U_8=!6L}tx&&ZtIx+p5%E#xe5}?E=ltnKU8}!(prehs)B~3FVQoL$p{){rzE1@C zRATWar79En2k7;62xjDZh_Fm(dFZ=a&lvAeBT+uVK6RnbA%ChDn_as3WgB=ueNhTf z%+XHE^o!XP4W-s%$cICbUu-RmL47b>Y+ zzE6)qVCo|nv-5rKk-WYOMSMxVH+PD|#z3aHYM#Y0Qr;cudYkWdZ zHJ#>bt0j_{5ch;_ohGgXzL~VuXhOS2JdZ_Az5lq)>A{b>AYKsA_iLG00K3Rjc5Zo?r%c|e=YrIly})N$>nIwh7Ccs|k0wG&I^ zUXc+m*-pmHD+x!tM_QZ16A_vRpc1f6O zq?Yh*L*qu!_DY;Z@LcEWXlMa%LpFQ1uYWJJub1M%n@j%6BpMu>e5>DB1ll8MoDB-Y zN1Pflaf!0BpGvjM2f1vSDOkB>W8a66^?A|~6*rKh(;zZtip z7_yk@5)Ej*Zsx?fWSpb7In|Ral^=3^jCuj?0>{~HEK0ktt2DQ+GvC`0=Cp}xF@Ks< zi!6S6zpP+;Ci~rw#$G2dRfx9ernPNzM_JzoHkMlFQd!aNef)Bn)oKscuGBus#<*Oe zfbxEs`iF~;u6emJchw1sh>ab+mLX5Pvg0hsY2wIQRI&_lYU~Y%(?l#$l^adm$sOgp zQ*^46D|+-3Y|$&2Ukp~F?%$#6lz;uYo$L@-v*_sRr_>PNH6NpMvoDev66qO>oe_ua z(Tm7QmC6vM>iD}CPYKVavV~2*ks}YbcWN87qIu8734SfobU-h7Slx2>UUFh9z0tmD zMXzjRg5zvM$6m(~aduiax&0l|7lqnC1Jef))Ye&QY?nZ9C+tB5$Tyd`7k>v+yo2@B zeioEI3n+DT;P#?BXzY$XF0m>@IS0bpM(3WLy_LOl^Ppvv%hJV^vU#3#Au@Al()KJR zKfr2dYM|n1KX#hPx{!TPQ3Ya2^;Sl{*k{Q+pu$G-!{Z*02hSyE%aXcjU zV@2xWX4=_3eU7_R*ulGD1A?A*v0~H_YigGIn&j>G7&fG>WUF!C{C_DKvwH6AJh*+o zS>8$5%P#w*goX?$yKEAx?!WLQ*T{^f&MWBqp6#n!r)l02optWVH4BvjWb}O$FK61v z4dduc(yYMN7rj~Il5}JQyt}d&F0+Yj9fZPi6HbdWWX=Ytxh zl$5n~c^PG{jVW3GR&08F{Sq>;n(W%H!^UYRW}XEGD;<+*M*YZUACJJnVW zn0IHInfC>4rhmh-TKC6wK8t_9M9E~?2_kK`0=BkwqgQKAISP4(G>P2>To7T8R2|NQ zUkpMnYO)C!zxz2l+ZqRD&y)6|(lzt17)GWT+rd)a=Iq^7KuzArJbLgYEm2+KB{8Xq za4By-Zs>7|5w{tolDwEz&7gkI&ZP8k-wT1u(>bXg@qa|MtEZcpwW0f3e8B)B2*ZYv z{9{+pGcCA9oXGO2$?$6)kc;RMhQEh_AzZPiA7rUexxiX=m z?l|+LIB!i&qrkvGx+M_wQi;+@TZwF-fo!-=&3}Xb2`SFMdBQO$M*Jdd@d>vGNytp% zSlZ7-WxMICI>lYtZw5CmqXt+`%C^Nz-n=iBR?tF zJ{mk=JHcr&el-McF5!HWQk}a=u25gZRDXn7G<^!ItbGm>5Lw@Dy?LFFsGhWuU%qQM zdty{>Obb89GI=O8pTjTQb-3qs9pbTQ;X7Q-$*uFPOfo4I@AYWrVGC)_0#hCrx|Ao% zkc=++iXKTn;Ch*F==#0}ArFSA247 zjX#tCOc;G1KYMeAI5@~5PmUF(<$w3tDsqAr(>Sf#tYuZN@o$MQr(TzlyT914+r{zq zS@?EAME|$rb*7|5J4BnhL6`KtJ~DHP3wRnzA#FBe9`y>o5Jbg9J`hc+L1TUC($q)W zcQPusjWcC;8)A#+!lwJf1SaTq$he+aBzVqIYnJ=wEZ!)g9b_ivPAsFZ5P$s0CB<}M z@3tUFQByzprPai6EPJ$qV(P7_E%#BPG3hc5&Uk8CiQ<0h*AHD0*X~XCa~ih~(Kj4j z&VIDoE$+doOJ1ul=zqRHUk4pN%>Leqn!ej(6s|n@88L78)pJyiUTgaYZDMP(ZJAXU z*-qclc0%w^+Tx2Z?5ppe9h529auaP$d?jB3}L`=X~UV;vRBFS;1lDn1VAc^hYG^?>>qr5&`-#Uvwd z^d5UND6#3k03t+`*^|)&69P3fmth)06%aQ#F$ynCWo~D5Xfhx%F*cX66F?UPGB-6g zmtl84Dt}a**%B>`28ZATZ6LV2y9Rd)4h=N!8r6qvlxd9@wvY$8rjEpSwjEv0iWMnEJ zM@!&eW_U6+puGdg#+v(I1QC0nf#aJ^)WGqLCx2^W4UlrO1Te7xnAo|QIJg-Z0nChy zT>l~3*mDC!4V*#709kr~l#Mme0iI06#@5XqWNPO4cFcbs0hC5m046Rj4%$D$0YX+l zdytWVH9*$D(F|zycA}AiB|zE62n2L=`>zy~yk?G$w%iO1E-o(g238LAHuk3cRI~sW zkbk2YKndsow08y?1AaFQkTb9X{@EElJQ+a64CL^qUD?LO(Z#?X2zWDCf{cLH4sQ`o z*2X}4z}w*fETS%>@6C%@pVeU}NOuVBus20PO%kS0giq-|1D{Y=41& zIGKK%-#YO0u(h!Tn7lOs^aPmz-+tgd91NU+07rW#pr^;b9siBsnV0~^AR|YBADANn8jWl&I2l@w8+`LpA{ zeZs;vt^f}@CIB5X8zX>;iGvBi@qhN<`QKR-3_yQX!T3+;Cu2;lH!|-$eeu1&KRZTK?gt z{KNnMaT{2HEZzPhyouJy@ofQQZQjoHhmK_ z9TO`(BkP}bkb^kL6= z{X^LR26}57$F~r`ThE>V6Mq|f_}^n@X9F+@{WkrH*Z~Z}{~%5PgXrIggAu?W{tw~+ zFv$Lc-k5TKqqlWpQ2Gb40vJ^OMqF=k27jZs^w(F!~#@{YGz_|E~zf zx8x@Of^YSM{srICTl@>Y#asOincqUKoc?wATSwOaf^Wsx{0&)H-hYr4(DdKMzQx=A zQ`=k5wr{GoG5#0htr~}a?(Z$3gQbCk**^s4wYEM|AKD^xc>qFYsN-S_V#Zg z_+vHS1n?jH$BPySbOjp0FU{K+@dTLH1+?GS2;sTV?Tzz7U!>e?Fw>0}=)yYoi%sio z#VKcIEK8S(FZD5r>wlVe$qC!tXRR+>d+gQ|HMp_f(h-Rtni3ht%>TLtpN;pp!zYU`{|!#S*tB1n4CM<&UGHMN3pqxKIEPeVyIkkDnvx6|EPO7t z(`_ZkuZBY^du%s26xrKW(f&IT+M&sEX(ZCToe%JFF4gZh2Y-i$R#E#1y2E{?oc;DL zKL$CXit!BLi?YI0tF7iCKW7&^pQNFA7)qcEOHzHFriw3#*-P(NKY{WNt{%49kKA|4 z=jrh=KPh|85LydpAYeza&CpjI9oRdsuf6tNmAWDNHH-u4`>s8@ise!;i}1AIhh#e= zezj#^IWjal+>^ zukc>e__dnphr+OA(-W;%6=Q6H22X07P~m5bnUWzgexE6k5u?CSx)7l}S=q(b0?v1O zkr-bYxVRLcGnJZ&5G=1u@@wgCjCK5w;VND>D#cX$@qb?W^ro=AOxB1pPpBWw?=UJK zVv%w}z4TitEn*!64=G{OVl*Y24oe$DIz5g``M){LE|wHzbJefkO(ZK)B#`wK=tdw+ zls1M^RHE%c+GVL=!p+M36pkeetbqvuU8!4QUUcx#4iw1n_9^HAux9yC!U(H_#vZa5 zxj?~R`hQCgyEQn76qE|MDQ5c6PceBndP3v)lDd$^4X=>5Dp<2&)8z&|K0SdM0n|QY z4WBD%BeG&^MpS)T4X3Ha_=2TsH!Uekz`AlV~?oQ(HtbcXQRXxNJLw=_S(}amj4)MA_;f#O( z%%B&~4B_#F&$8@OdN#7w92$g5PtmI%XTuphhU9`NKT4^b#?)@`+? znqHTWD|VR**$zg{Jx52G!Nu8RVkPCK`0`)Q-I?vz2o&dcXM}r=9!*oG`Lg1EeGuHy zMt_Sk)dl<-#}{M029w~z*=J5$2HzkSnpwVW0DejW<4^^6VKc)Yp;6VB+rWJ)y^7%_ zwDVZp9eD8hQ5@xa#*h?(kA?{q6M&H@{q%Ce+2=NVyhyS^WgW`MQr98LGmK{n z%P^9A4*T@NKt^|-g}(vz#E)G6HJyCqwyC`}J!FIC*!OS5T_`g2oqxz; zTR^=$k*pzmqw7y3%cN|!mO&qp+jqNzN!6cwv4T%tZWj8h^3{SE@3ld4dh{N_565+kB!rV3J)oQX@`ZW zJEIRa2d&oNszvzIgnekvq6G?NMyxhceQWsyqJOxRY25Yn z#`?iJ^$JpBFyA~BRiMU5c%@=1C*^1B1tiWTtDH*|PWu*zBP*S2g1qz>dfXl<$z-yz zRCapvyFf`0RN2dAF2AMeIr;07OHI*5NZ{<3AT|+oJgU5iWWPe+#~&eM3+$=Ro;Mgp ztjxk8{KydfCDWtVb`@k-UVl5hm6fhztop-3HofDymepN}N{e#u7BaCv95(h!zR+NG zlhGB$2PL=Ns%1{wBZrsfs#6<7S(iFy%vEmf#2QqCEK&E$`*uUbel<-+2)mElj zPtv27%C@$H!zNaLjFM7LEsc>g%iDUcMj9|)8cc&oz8%sKp$%pDh<_eUM09C^(}6g_ zCC)b9M}{Y~_ifW}J-Ex8qqz0^=4^AVE%KgV?pArQ<1Yl7*{I^E&~mS?YvdhWR-`ss z?38hm0MZm|;>M1jg(E6%Il(Cwod2Li)NHU5VDSJNx69rrgS5pSx^70D>`1RTUeuV=xe({%c&=mlYx1 zR%@(4a5n4u*pWVm07-)l&4CzrSH>e=s0rzU>A?O|a%nJY^bx)0;g_1y<*40uY(IjY zX1=pNDT?iO`u-ria6FcfZ^$2g{UoMH2_DLGFd3gMqD9qf*6x#2VVo6XM_ z)B?K7hI}m$aaeiVg@>qkg>A1Ev{amVXhbuE!_$Zd4K8{j&Cnm@qPeH{HN8T~i~(R2 z!nY{5?}L{2GSHdo{n;H;%`dAnU9TD<>E|;N}}TG!>H#-vz66 z`lT3WtLBSkOV06`%Wef#(dN_n%X6bz5>&J-vyMSu^aG%q5{#(wdCTYJORdQg!?t*| zeSg^lYyygsn)7q4?#(sSWfdIw?dX@jQo01&MOTTlmkY>pl*mjNZvhIJgK*O>_eCtr zx{~)Nt#w!fw~B%f)VuSMT-vetuYt;cqYU;_=^it zs5#R!BJU+$YMgLdkLDDyqNd$MqT8#~9e8N3Ky0 zBgyINfFIRzCM?LX>)`rUvCfj5ElF=F*sszN!s|Kjw3UY_q{0UGd&^ouUTH9x{rR$Qh)C6 zGL_G-5P9_+xz8$@3%T4oRT*%SI?4^#*yUb8Pazlk6?}XTzMklh5vwepF)5FkcPtoN z*%jW{hPUg6O5nkCCf;8@3X|09PZg#sF74~%DMf!jDM&EP>W;Fp%+#5%Bg*m-!r}w1 zFXLqqW_NnyCxdxTsNC`oVGq^#_64iKCT-FzS%_Vi{G_1&`)Rew!tH=8|@ z_GXf$vKY8rgr!org(ah7utfdhcmmy$@@mxagzX)_rGltu_HDzg7W^vG;zx3DSNm!# zK~wN|k;Ym}z|E!s2#VZ-g0bTwr7`&wG5Vs$Su@1Of{T23k>$1?ql%4rQDczP{&~#% zNQeD^iCPRBA_+1-Si>R!F@JVt(D$x>k7YB41hSbcRWiDKj?nc_~`8KSvHyo!yhXGBj7YL?Ja% z1#`z>#YUl;XjGLY&RK)YkhF1Fq%vU~vH7oodwNDy&`MG7)0v&+&;~5U*V9#rC|Y*i zzU&W+f#u(#FR|b~6MxidireJq_vqLZCOOuOUTpRm6hbp&_hy42WOnc-#sS^I!U=fVl4B zGAV9k2{#83G8Ye~RdUOjZH3rR*3dYZP(>ZmIJcz7o#hWV^M86>+~^_561ufi(A&zW zXq-ds!&;=J4MJvAwa2`;Roe5|;UD(3^U33ula!rXZ(qsqq>~ko!?q~^`}y9rFfX{Q zT#+9;<{~jAVMV_)YPy+GQ4SyQTz%$ADoOcTGxa=+df-MYwt4liIj8p2KRG1j9f~}5 z*MAN3xGPV$N`C_)w|wVF2y%@6xL7y-8VHAnlZ!P=8{)ZtRmZ#e_<3UYqZ`3s_Hrpr zI2C0aw5uJX^v_-2qrR8bsf7;5%FrCg^!S*fc9QoDjsXm^zVVgwXd^Cd%Re9Bf!_%@ zXpEuo)rq|Fei~A;PYi|#EE(yIo98{k>#TIB&6)Ah<$w86KI;wYmPHV8>wAm|6#WwJ zQhkD1fFaLq1%J1vS{}PZlsG~Z*nP*CXL&LXb@%w|ZhIEw71v5!MKUej~&`bjEwaZGL9q)Ik0R0#Xcri94 z@tSUMd>mnO%XHK)qP`1{yk$-eozlyA7avYZ_@2QzIcexwuwU9*br(_TPgp1Ku=O)O z>?er0$9YYKZok6~o4v1CVd;VN`1l=NwbkpXB!3mOH%HG(Iu>*>INn6ghierBH=$B@ zw?Yeja2YYhH`Y^9o`xopiKUyjZI1M`zbU?LT6fjrp*j3u*$A9>W^mcC?GN(!c{zTf zKhfsdmY%}O(nuuUUDwM(ISWN=bRCcPiDbN7AUmJW;8JiksKIz(SPb7YJyIc5ky?rR zll>+J8{_(l*?FBd(|@JkJNqSb;-De349x8u@yy z$esT^ivR=hka7OJS#+Igds~{jABKkSnet{a>(i2S2cL&bGub76Z0V-e~k_YZtzoFClCojCygf}?ll;A$*8xlNi@SENp) zU&CbdSDWR*i-pSgZ-CtJ1Y<%LzvPBlvCo=H<;Jisaat{m_Q0M(yZc;(7mC5&zh0=wZ*FpP{oF5d`?FZnc zlPP-BAy#y}FvT|Zqakqs6>m~NFtOkeH5cHqV2L&v9)*tWkr$@gBf#DMTjGHpP5>qO zkQum-%NP?h@0O|1>iJ;h_kR`6Ha#_t_zJ9HAoVfn&DEX4rER4lon*XTgs|Vql-*z@WFele57>92UUK(RLn~feb7fONZQs+qW<}JW4wAR?zkaF z%?{hq!HH?FR3w>GMYTLUn0vSA@n2Y8%M=3W&3zj7@0dK!pFd>*P=9ZuY)SFsQH=OO z3M=wZnleeKy0&$|s)CAl2g0t?4T5g8tm9y$)YRY9m;3%57itMx}YH%Z5XOPWU`XqjDvm0qydVifdwa$GX507`;+0te3 zgV(sLPj}+f?jy_xl-3rr51;#^Qc^e)zra3%VYNh&Y33a+`D_)QxFKH4KM(q-p+k)S z@H3n)XF6Mg)Zy~Xe+q`a@GoTLe%mP z`KBy;wB2QJet-YK*^l2(Vv%YpA~PEeKePBmQZf;r6HPc_i9woioCm{&6))@~Yu=&Z z`_229Wx8^?X6W|BTI@rsx4z1WL&@jHCiJo8>`8psI=SkNxn!XEHofTK2%1wd5(2Zl zV!*h;hwK}3Bjprh(vpS;o6kCDB;A)Mo^g%7y|K{TCx3w#)Mr>2jc$xcCtaTBDJN&| zUQ0!FXx}2+cQ%uC#kkL8tu&N5@CU)bRLQIG(f53c(;-jU8_jm_drbUeLLWMC1+Dt) zoq(TfdXYn!yy-QnP4_|sFLMqKODq&6r{&Pq+D{c9yCMu!h7CEv_heftr95p3Y`q8H zx1G??;C~llgN~GUyOhlz1-a%^wbx8Bt~pkcr9vJr_~)_H`0*fuw2+=g3`Ap6E*5JW zXQKq&7opPaW|=1!A8I3#x@MEPJk;(ix|#LqZikz~@z@a6MTpnV<`*`Yk=TlaqcB~R zp37gcyUCxbX{*WDj>%3*4h8*W&ZWj{W2}yl)PGYw5;-5bsnV-IstTaHUoMy}XtX1F z%+!O$>L}2iS$u8H6hO_&$WlH(^PR9I@d@l?k$eY(pe%>_Tj87k&-i3%%7*JD$Y1H2x_jQ^gce=Ax+~5Z!jkgo|D^qQE)8*?)DtzL&w%{ zJ_}k5n5Oh&F^D&{CBSlr$1JRJ_~%G2+L3x*;$js|!8MC-CsiUiq>pBv!t{OWxRF9k zs77%~qv-1=p3G9<1v^NIl#r2=A`KivXn$}wo?+7OgJ`2R9X=p4`WYcsZ#w+$+wnu6 z`WOzONWyiWt$nolkI+3>9K+!$mqxC}I&#E=4L9GR=%!27Bu3`#=3Z4s!l5L)jGGsY z!Ije=jjz?tDnfeH>>PxHxrVGcm@#+HLI!JO*kfebnc$;Pk)O<5haZW&Uo_qsQGe=v zNK>NdM>WHJ9$q@!{}@&bh`hBtJ^nK9cr zS-Q~{Is($kE!|=%C@+@34FH<^3Ww*<3JBlI&0pYW97Cf^g7%hstPUr=tMU{*g4V|x{w$x%5Ot%H`PflZ+*u}aM+46 z`VuAF(FB*T4nkw<5%)tsuw14kGIv!r_ zH4%NMJmO(GH2*xB8U~q9O+DjXIk87aorx%u;Q0+qvUNG|Ga_y90{|ihVk&cV{=G=E zaU%tPMD|D1-Z6w&4h68wg_^qyt?J=eR`6>|8$$GYyJXaozLyQU8SN;ur&U?K^l&&G zJTt3SrVmqw-4Yck+GiE5)_|V7gL1-&`zje1E4_H(!@+h?H_8 z_Hkjjct+)_jNzoPxZ1kaARbxr`z`rb>&agV9BVYSq4r(%x~J_B@Irny8U9WNMd7Q$ znF%PD8QD8(@)8SRarB-P!CalnBDxfUUL#R(RN$Gu0rao{I2wiivxBfHU%;R{bE z^QSiEngX!M32XsMkbeoYg~CHsDm(aY1LY=&D+eoeif%t6M8Nkv{;i~*6q*YN?JaIAT^oK}TB;s-B{Cdd>-n}}nR}SrFMl2om>*hRG`Bd}I?+#8 zpTBrj@yP5ip1fWuzWL)a6tOsz!uI?jp&3eLA7T2`w9vuRXA>rgHzBvSs_%!*nT{5O zQTxFn20d5$f?gyIUTU+zD^WNpI_d}t?Nnl5m17(yr3yL^j}6(Qu{!!sbqK65E~VHJ z=Sui2TgLXIEPvh{SNQfDgf)UquvbA>J29y_hq4lLiP5C_9}n7ub4|4A+VZHL+f|Kg z5gla|w5jrO<2{y_6?}Cx+4KV91D1+D+Ruz&-g}(FpgRTU>d}vn(%rP_1jqsi;TF`v zCVEL6A4tLdOj9u`c4}!&#cev>qu!gg@bnD)T0%511b@$BH?LTNE0v6#johL8>756g zDqgvHr}*8FZ#8CEwvKQ6BIsLH47M0}R|jZW-U7cMuE7A0c1!HS4Qg0Vk~vWxi< zP=B0=t_Po6l=zT1BBC7)qHTX|Cp4-1v#b_o$MEdu>0%RdTBo$T7; zFs6#Vfl1{bQsf7(PkpSP5Fu91#`Ve8Z%=T@BYbP?^iR#zp#N9?1^0)kslX0$_xg~t*^OY*3H zGZgiPDkkoeVKm*RlV6REwn5z#Bei^Ko@-_{kMQ9>ZpsLmBs{{uG|zA-3V%_*In^wn zTibb^jnoo283D_kn_C-F_q24M2ymPc9D4UyDz4BSf83bSBZdc4OPNla6iMwrxB4l5}j_NyoNrqhoh$TPORR z{g3}{y;Wn>OVK@!g%R61!_U$=i1gv#fyA*tLWN3u%RgO4 zKci9pcw^&-pB^stG*r>rTi1NnE_o<=4KMTK{osghDWu2;cDYIZuD&T5sNO)tyTS?1 zes+>4xV%1}fmv;+^e@)PIy#*w@zMH=augAlnZ!0Zh5t)F^`XZWzzux`Q{%vrwgh#q z{&tWkBmw60o3^IXj{TDJt+XY`)UQUKQ6Rg} zZm4^aE|C4S-i=lI+gKS?tzzOF!KrxL{Jmv*3C~LE)gWIrK!*K%ES4s4KKd#;m9VuOy?h{D zSENkG^>c+fVlHHwCYrIE*BBVyg2PRfNgTp#jSkR3(_Jz=mm0+v*|<}*h=_QKt3SHE* z=DDhRWmPOWvV6;OIg8oeV58i#duINsf>J|6Kr2}Ng2mSbHf$!AZdo-tG^tdhGHhtU zrn9GVo^2R3e4RM?U~{=}Q{P1#t)1P%&o4vG&GludL$pS@L_~8xO6i7-D>BetP*VF# zm9YK?Ky|u2*i0=r!_Xxf$xNkaiUoDkC` zH@>MYe%rhkpA?E~eU?@y#g%HaY1-}hG?2q3fIk7PwA|Yk4l@&{@Va~Kkkd1iYFBSz zwnrwt@J0Wr0sULf?>D2v9CxIgV@b!K)YxwB%W@7!{Ipr>t(d((MD)2im~JZB`g8_N z1-l^8AHpn><*QN?=b=e|v7=#5cNY*L&74o+#FcuU5+(~`XrquSY7 zSF5DmJ`~mqxmwFg3*JZ#q<9&ZqZ%?ffW0L<9OE>0Uil`}0h&N{i+bnB?!%;LR}18} z@`yqVI0PDWsb=gQondloeUMv8`{6dN`!rVuA61zY3u!#gJQAo#Gv;ElPbhR|hWBg_ zXf8KjM3{@qsl1B;tN5p)$RP$O@srIHOJyLEn~f2E^251F*Ne^7og;f;gU}igfS3S5 z=F#1|;O~um**p9p|K7R>9kPeTG|D|W{ebd|19%z9CRVszIFu~}RZ5;7oHM1C^ zFSz9k1$6Wopxz|+8Gr9Pp+c7mq9m=3&78wOV`+0UNXyH1ZK!|{v%cLsk7`cLG9}gS zWZn!*6B-aLIo#Y;=FCg%^g~`d5~Yg$!Ctt$k6|7oh`Lgu&rK_11~u{TQWSnsqeNX`v)k|Ax}ekght#@p}BrPIZnoASIx}$l6hwT z_y8GGD!oMcj;WvyJL#&`;Z!^>?RO=s-Z}J0=a$EMOm{b!yVP=}4j?=gJ8UNx|y=?k{ttWnv(y zClmksjySS`ksd$c3}6ey-N}v4i!Jb|u29zZw)*#Bc7yl50q-r?_S&!7n5MJ(yWl19 z4375L?SMwpb;EBM7?SJ8@Lo13`@z9l6+#O5tkNms_?!jz65$uYo;eR(ABH07gMWJV3){@=73mvR`z8R@qD1 zTj&e@wnp+VV60r9?dKj?s*vuQ6s}h%W!hU)uTOBDNoA|8Dg~i^PW4NCOEc4H*C+*= z`&;sVQN!#ze9E;RE~{wHJpDw9O=O0!D;C6O*!xCJ$MV!f-7x6?gixJam$+_{#6br# ztz8flYJo42d;lhDaT~!^9iQfY8dP*c3b=Mk96M`KuibQ^gh@)bQ)wE!AzgHx(zG6X zNa|7#4j=_a#@Wr|KE@6jme>D$ThXxp6$liX_!L;Q-+^2F;?q|Lhl2H}1`78^{QaQ2 zH18aLU?o}q$}&wgIFSCwwh3nutEZVKAet?$)0wEbGz-A#oCf)Mz|10vEn2Rc$sU`G z-7}n&Q$JHse-?A}^&t243Z{!Z4(1r;-3T zRS~LOVhlATJI*ym@m5cn%u~_LjNrO)`P5B>ENTuDkI@cIk(UrMvT{;p)1OrZHWKnW z3e)w`*8nVs1@rLB{A)1J=_nW$LMK#A2QrgaqHm(f)|uQC2}<*8Mq0H9p^DbSX(srg zEf48et~V2N+TP2<7jy{6lKyL^>(g0j6C3v5aFkhns>50!D;9M{ufnK^i zx)iu5tSHCtTpm~(+AmCdlegHfvMA30F{W58&zWY}g{riaPbSdd?dK3?wT^!La_ctP5X9GdN=(IZ$yCoMLR5PA=$o0;2EMC zR)BQAKgOv0It=Qg8+k$a#^?@1Dl^M%<0-Dy6uySonW6ewHBXd|ua&HFH}5joB(7BV zbi#2uWR&`bKaFj~UBiodoaPLw-S)BN9(M`Xi)o{Fsvogu zZnBB^UyIDFdaU-TFd9nis2ceF8T7*AE58k1eF)k2Mre3gQdf+;9-$PTK3yKM+CB$- z^_)r_h~B*V$4G;j;wh3t-SDK+Z14nPAnYavAM#@h!D|m3zp6BMH%d@W#c{zYQvtH5 zogBHJ>7@>IfB3P{dulM#LNUz){cQt2fR28Y8?ddPuDIRn6w-V^q7yPIE8UUjQn#ZEMiuxo8uwMb0-=7o&Sb#E9-TBc19@w2F zvIquS-j}H|4bWNJc{nSsa@8$=%S?zCNNbcHZIS-SfumUjC|J5;N}NMNZ|ksKHP#o; z8JLNa*QGuzPLC4&w`-jb7kS+L#=Tppa7>0HAt$3XlPL`mY;rvfpw~U^2S8L#+nfG6 z20)B!=MoP1+!Nje)`qs&f>c|kvcp%zL^D=e8e+D2Z^Z8R_WOJo@a!Mh)5HFDx*2q} z0rEn^0WGshF)~ORQ)DfhY`cZl%fLLxwAQBZ?FeFY0Cd2|iO{SV}jy3dA3>CCzh2`kR9H-}CB_yZxEjT$g@g9Upcc z&pQ*)iIPLBaWgN%_7SwQKY$2}wzl5l-VKY)K4*DZ+ebtQzdgC>v$D*A%K#fysXqLg9SIPO=9nmULu=fuiZ!icC>wou^|FHiiJ_FJkm)g`*yc%ti5aV zhalRCk2wAYGWoiR{D1k9|Fvl%O$bQhgRn9FUx}dIu>c_*2piM?O$Dfed^EspX-Xgb z=&cWYf+%<(Y;0-qlZ@!C_}YTurvI6UJ@_%wx_boSz_=KHx&?n!n&@DRj9mYlPN4#{ zfGg^*VbDjTlC|0FUtQJo>jkmS36jFI+V``yb)wSsLlY2LLZPrq-s~c6Uj8?wqS38U zS~2^Y>g!Y8-P>GwTE^P6R$P@$CwM21#KBJQE^ibNU4eng5s;J=mXnl(n-VJzd2s~v zHW@8l3K`T9ltVP|4HF+26krdSW!K8zaLKOt@l0M^0qy<+cD#jkfrfH%25IBs3i(1k z0Yirv1L5ma2U2qnXg~!!h?J(>Ke&Jg-&pP7W4O;#04gF!4UmzP40w!l4M--1f@uL0 z2C5L`(23u_k4zPW3}{Ir$2vIrG(d|kY_YeW8NkEK&CR_Kl+bXeEQv@0~L{W*LHzgz=U-3ST>2(iKuqH zoB~=BVFb6Z!CqN34`+eY`wV)w2*(9wWGE#ph=y?C>VY+X;|l`0 zd7-;=FmR{?AsIjNAe{hq&mOW7AAo}J12ATR0jdaKV=`7C0kiO5OSzTgXcrep6IU?q zFIyy|4w=V#slPSHIk~uli0o_1de4)$*^a1Fr3-E@(4ZtFb-$nrT-&Nm3 zvtfwfKETmjdCjBXyC0t)pJsP-478Ntzn=y60ND&-xh;QbMc7gWc)m6$e_bAc-rN2oJzZG_SwZ0s1zITESw(#-399h2hzQ5Z7V+|p% zdqHy9&aa-T0BWVj)Bzt3W&9_z8EW8Kfm`_BE0qTjzPSKU>hPGsoee1W6iA=ID%L*x z)D}SGp+e`?HL(kjh#-!9&F)SsOh8Oj(mlX;Hp$HD+t;OypY{$B^Tf;X%SVbU{7=%- zHT3?`J|s|qVm=4WabtYj>kCki?rf1I_}!bxAP|Ckc+!Ro%x*g$AfOo)?eRI{?jD%4 z*gxw_Gzb8Mu-2PE#1J5I>_A2avlMd%uA29V85dFbdecA9CdUgmnhx%>D+?%P9B`nw_foM!U;CGlvELtYn?B zh&t{)Y0EqH{j$1jMo?Y<4w_mY0);1<3aejf#PJs3{IL%=-8@TQ{ z{6jmJ@PHjOGtV}PMjwVRo+rmvZF6!}P7UDOYGWj2LWbncUD!xZVIL+NWv(D2+uqzK zoS@a0E(NK^sHr-W+NE@Z420nS#ab|(yYT^$hi@wW;SG8O^-JgDFNCxtg8>+qtv@KA zxan=l^sXP>-rc#-6$(Bu+@WIqa0K6d~| zI{r=U?61Zgh>jL!+ck2!1d$V~>$sH8dgTzh)nC3*1#G!@aBUALI zJ65ZF_{@yI4p&7?W-Av>&pw6v5>MB5yJ~0Z{8CH4R7g|(^g>Fav2mSNp;4N+Zj_2I zEfjQ}(Wvz$c-YTlSo*FdKdJe(lTtt1rD2+0G18bOkUWu=g8L^xO+|@Jb30H6SbbEGleTasT3&yfnEkVEkg%;}IB& ziVVo5!1z_xJTBVT9g@^$sWSirm}0%GqaSykbLkE6#mI-sg-RS7u6i_9*SLwj4NkR} zTbyKdn$0?2g8n?$O^O5*EUzSd^S}ec19hp*WrXO6J@Q00yG>D{_V80y18eSW;wKV9=zofm?D%{kcUPW@$(=FDn z@idg*QtW1e*Krcc*JqTn0CtT`(qRKAWYgRF>mU^^VPk%3QtzdF*k?3{Pb>lEhn01L zR_skQZ$fPE={ZkcZv2X;KUD2X2>J(I@@`( zFs0UK$vIL+U~Fw(JvIwzDt@FTQ%{K@Jd1m;#Gnqd@IZG1 zCcARkcuzy0EVixFBdT^TZ^ZAzMOZ1g{8?k_w#~p})saS`+Xent zj8IY{N%{p#xTYISwn3pTs4z*D=yn-*9S@uNS;(hWR4|_EDNKv=5-o5qdI`RfU?Zwb z3l4$Kl?aH+@>*=hK#N#^<@Za65zXBCYd7#cL!)rSG4Vl4MuA4~?8h4KyvPOfn@Us; z_cMzL{S#7j6Rcs{e;uedgI0o@(3zK!vs3Z8PFqAuP13dTJ-vr32MoHTgy^-s z6eJGbYqv-eGEWPuQZ))^7N)d~EPdgreS^iPpCg+Rw!O-=~DMoFg469(_#6cp| zvJx(kr8)A2N;v|UJsV6qlX}RaaFRsw)PumkFzjP&5$0Zie9Kr5ZouS6oj1foi|n6Y zX$B}}MSkwyJVSiD8BO>dO&sI- zjXR6z;$x2g5Es3KPT|#^{^6_bVmrbY?M#SJoLugy8-gq}r7Y$n5GgT-978}GcA$&9 zL}84F`>R(ix2}<4JG@B3H#VDl8hPa+G9TbTE{FS2vAs!X^%!Vs=qeVvF`2xg-FebD zUCJMP(<#bD%woaW_(Pnoa$%thQrm7x?vIjr2Di&>9Vr}jpGqCFl=F%)=uyQnBG_yk zuBnwW`bN+!i#8N<61QSVEuj$jwS`)n&`q3z;T{^YhbMne988MMXc^=eOk%O`pU-{iW+hODrgttf+|CR(3+JiLLNjr9vd_G!Gndc)mO%S3R=gPX8^0Re>VTx zK8$Y|g8ymEo+utUen%X?z90mpwZEBvMJO^HS^Jk{riSx6m46?Z)k&yp8#HOnNtM50 z*00IKUc`puI_}U7bY1<_vCz>CQ}Ty^?)jZ1bYlcI>I%L(6-y)|x{lTC_@bHw7(PM$`rOJ^qed$o~1x0`P^lWt- zg@Mb{6}mYolc|4O7By~;d(zYb{vyewKAN$mY@}eymCkbWv|CQugC38-wK18=A&Xk` zcq;b160r*7z{i1Vcy+ce3vK*QcF0Juyz=iXW^#78gm{_uaLrj2JZ%zA}iQ${| z2#>F0^h;_>beSunPjno5@vhtQ}TOFuySfxXgm(eb8$^&#Bj&}IA7B=d_O1+Yg z+&kN61t(8D$%k-xGZWwpJ%-s?KGg<KNu z6*l?;VMdv9LXYedpu!?&iE2h_vZL=^rqd#PJi{)L&b0NlH({m^;O?|_*+Zzv zhxunxlAOAg<^tv>$NLWVvu@dL(vN zki@UoFlP%cRt*BA}7iZzAx|vb2a59wsp5!|y1IG~a zdd8jrCELZ@ye=)Q(^tUR6taz5o+(%veO@BX2`LxXX7%ybil|@zDTqwSEq92(d2mjm z^@?TK;Zdp!Oa|??!;q@AD=NA0?Wt;hW~Ji9j9LSzZs!Fjii7C=cBQQ$kB2|~I+4SP zFuBI<+)vIf#=Iji^#%o+DAO2qxzHS|#fFQbhx|7a6I68XWHMevV)5DH7<`i8!u`&a zT3rB=ZbJyl#>R~#&A^t>zg$3uk`N)mpSGVZ79)I7TK3sQab zZ6bqDg*xQu=*W0J8zgb~z?@{#sjICX5-AFk)Q2;PF5c=YZnAn0j)pqV_qje$dPB;Y z4cZc{mO3U~me8qz1wE%yP%6BpiqME{xEEAi zKlk5s8o%2SHMT${dI{tmz=Zk1N;G60E>s%DkJPY>w^M&vM@+^ySC?hJ?PLb)luH6S zTN%C0;T{)3&C!xGnBqzVtVW&R_AbXf;W^z>f|iUy45TWg%!e-a&2+U^9zJzDp!f7^ ze!arwhG4+R5```%pznE$DMa6;!gTSWeXRRp;b>wqsSa6un~T5HvuG?YW^_moT@|at z>^*@_q_?*$pT~tlVYyu- ze68SC(TAq(V-RfXB8$@U7IvSxkBn$z9fVoU&Ut7tR> zltLt|ydKfiH5o-udi_w*cz6DXG?eocd_TRq9KI89E>uY_+D@w3w>Cwc{>Q52aRx0j zlKY{#iD%+5Z1>VmRNof92gs9`XW%OH4|u>K2ll)>Bs|cnVR-)V~HA~sr7_MWUztB02KPe`U#k$)$3+GbQ-`&#`D5R6fpg|AXf)jgUG{-OkHg*65>@Of#P7VzxfGqs7YPmI18H3Z6 z|C+2JdHZy+*}}akZN1?I))AeM%dT4X%y{H(JNe$hqGRUP$9~8{M`vae3B@3=?VuB$ zQE#q4xj$SA@HZ>fWIo_CnzV1{aovZN<2>GJ-XNUztS+hXz4Y8y+>~%3g~#~sGS{Aa z^|@jFfXwyS3VASd=>#LVtk47PR&0fmYcUiqIH}&4RxNUIhj&j*HVo%v7Xy_#^&quc zs{LVC+fdKgvbT%M#mf)_3d%F^u!u^zlqB4aD>L~^Mw-(&q9 zA`=8&-AEE2leYe=+NgiNCB`KiZ;#$$D2F0h{CM9kohd{!v+Az{o3)r4J?KJ$n+#Ce zTKmj1&==bI37{m7OevTy-ZRTO7e=?u$@R4xA zE7Io<=Ww;07N`U2QqQnFvWd}WXF){bu-*!sVDpZ$Mu#+ERz0?+GAXpML3aF>4YfJn z)l(tOatHMHmk?dPB%QRV+ND8_3A!?0=)-ny)XH%ti9 z>FVR|uaO7lo!J%XZR~U2XQ?iA*qO7$5$jb8)gtZfD0c%M&u6cjyS!-N4 z&0NpY0m7LG4aDQF@q@fKviA0;8SrM%(a?_kt=g81j(t&SY>uTvv=b_VHh=1N)k8r2 zJlnB{;oiPJy}_%REqBRRX_}MhA?HV={Hj9?!c}*3=sB80v6DZs`R`qz%C}y+W05fD z6U3ddn~nhcAMFvb20Ot#7A3P4J=RT6Et+=1%pcgnXzmeYrVIS<6z}y6PvDl^scw`l z4o8{F6`tz+9y2`&ga00fN94Q178aJ4G26^pUxekd&9WPHHP<>$yMH3(HY-geI=69J zM@A8^eXB4r+9Mq9t~g73zeEg%n3S^69`Kdbf+zrFyUZ@6{_OZWU7ezu(pCA_5iM@L z0R`8^@j>vV!;#RjIVGJjs13f=f%4UTlHJii!5*)B$9c3K_kfo_osbM}D6k`xaDj9b z0y!bvuNFjBu-n2il7F^4j9twahC!TE=+Xv+zfuY{9y*B4M{DFiPfV9EHCMn|^ery2 ziYovF8KG|=m_~mMJ&B1K;>i;umXmAaWbu7Pvw~Z_v!3XFFs=%OnAdKuM?4}Zvp#;N z(OexG9p9u}x}he2t1!(;3*jjo9&3)6)AbQ~YwC=C+5uthLFp#*qQ9=pv2KwtjjeMg z=8H}Uav3!Bv061W~by}*F>+d_=l^=dSZDDChi{>Ki;XkLNHO|isV zWFGUq)#QXs?K(Q@*O6m8X&sV}bYlVO?0t=mf4)f$Yp+-a)m#4*A{vRp!s>2Xd}bw6 z_Zdi!M*Na;U(IYK*A^0-1MhOPr#}dIDA;JoZ%tVfDw?9FYySz$D4>jL)dzkBBkrPLIGjt3rs_eq^u59?Se%{KSrdfOPQ56;qvHio7mL5v z#A^M$i+WRFQr$Vn(omX1+_ryt5`bw)jcj2$c~`${)iX?#px|wKAT;NJxMp5JW`!(F zA#{aMbW|Nai|nx}D0vOFnd!y7gtsi&*UJb{FW3A9-!1K*AU#75(aRpZWW#1$yEZPpEDATBTtIP0Q*&}hAg6K*@nOCuhF>Sl;a4_UUhnfBY{Oe0p2en z3ILDbX5Ej4qudizhQM9MpjE@yQpHTetgE+CoCQP1kqOzcRyxI~g7_X#KS6nY-#O$$ zg8(uUYsku`p?dsvKYK>lThGbTZeBO3OFR+{D(asgVjW{Iz^4Trg+1l6TJs_Y=opR{ zy~uuoH-5Co8}#0~i&+=&?TY4$neXk{h+BNTqmC^wSB6xQFC%^jKIGd`nPPt+b>=@}3jRg6P^=a#;odIe+I_>&&*k3fiytY1 zmcF<0$hQA5W@^XPS0f>Dzck?HaNJQa+F9{ItguYMK@&VdTTaNproZz-y+*LT9Az+= z4YU8 z0a5(N?EzKT-&B73vXa0=K1JW=(FrDhD?RRA=SzRE#orI2kj7CxT-4HE;w0rqvu#!w z|8%agsC6bQVvIw2+N$~V>sq~zqPDU`0DyyN1C2Opg+x={d|6w$JU^mjJlBpK#tGP} zAH6S8>$?VI3r5+7SPnABQJngU!-)HPs{Zjc4qAT(DP@O>8Gm#+Ho9W5JNqFjX?yr( znXimHl`}5@wG7;aWlp7i|Ki5!+yz4Wpm0g8^irY>+&mNM3_J?=<{$ntROi8mugIQ< z2}W-G(u6}g!-}0h7i3BT{zL>GB#%SJkF6=d9~TCUSywsgKNHZfjjm<*$b zx~2m#prw(o6)&odK?RNV((GNa!lEQs5mdC2;#4 zu)GqFG1)h)U580ZR_|GfGC-`|$(;TaapM7C#^3LmAJu@+*biK_(gk?u1VZy#H1=wYtMGUWi;wIkm#y zUsvh#G3|a%a3S~1vb(P`t~S`;@fCL(;VK(_Teu0j%jLjDJl?1i zx@we1ql`Z5q-sjXY8jlBckl^uxkzDbn(KEBZ|6Lh>v*&Gj|1UByrwq>=zyZ-&V5N~ z4NIJUx0^=dr4jIT2;CezVvS?g;a$G->5stbYHPx8HdaGLq*IJ<0? zD*(UQxn?s z;`wC6I5L+ng!*Uoz6?wlr!xh3CS9iTW$RTbF7avKZ6(fqq zn3VLt#g$&&!D&9u*IK7mo2r$~m|eo74|G-l45w|MxB^H8WD{kk5<)W5eZO()y?#-&FTP3_|+K&Hc-CrZd?S&dVk`_S zLTsCjjBu5>m;k`#AYKP$einwWyLqSt>UVM?rU>;D!i*65U{pzgo=U3CT=CfMDNnG0 z;@;U18o{0!cZ$GNx4zsg?p9R3b#av^EcJR$rvjT8$@)yi@@3(`Q9qOa%w+EVqHbw- zbAnIDNudl_9OwK7qZt;DPN~eK4~hco_0~TVL}d7^j}CxxhpsCg(5ZR(i;hDMJLpbX z2}X4Uf+jdms8Y$2?h_zo?Do{Zv&E7>T=}rKBn5jUsnlGZKlK;Opm4v|DLItgI~VX^ zy&#;8Mojeatz2M&JT~)Ni|HRhF;`)AHCxxMH6PlWw4~Stv|^^xE;TeSi1RF%NhVs+ zV%t&&ii)4_UuD~=c{N*fXx5P{C06^=ODvjJYB~ISb>^l?Pf#71b5G|8kmaA&%j#v{ zA@Hq{azXROB=Q&wCrwggf3@X+SKc)S?xr`zD!~oUVP_MGA=+OO<4&y!>ATR;nEtwV z?bMET%hyRF6v$d{1>r(*C#RpB9Yqs%-m$eg=C1(6h1!cX$njY7NGr2es82$e3^_hX z2p5bk>hs8+7IQ@W{rPegsbPcW^JX8c*iB4o!`PFh;tyTCx?gIrMpJ3A3B*v;#IU9& z@s`Nc5WP3N)-4%gDE|VJ02hqSC~vAq-VFu7*BEt~e7Y&kl^Z-J63oSoV}+0U*nrvc{S6M0zN@#z1w#i_-cLJaH)E~iyRfXu57Lm!0j-7=ykaReIX>2b#mqzQ zF(C|KU||10cB8uTNxey2R8g@3@Ba*dWbW%H z@`k-{WoXPQ`TGl>K}S!EWs0xomCZJE!#QcT$gFF%uhM3EJpOouo7yonh&|sWbVG^+ zy=7=v?CpJ~ZqPj*Zt6hywNS+g3+8}l!|#qJc1qV{!+teN{vIk09p$Ba+$FD3asUT- zHmYgBC;_L~S2RH06VZzcOtlH&bgP^?DA1#e_K%KQqb10LlnDgr4r{+o7vYA0N1^0d zB0k>|$K|MN6YhRmQ8Qe{C2>sUpgG-Np~aDAUxbXz@SWYaj6boSj*o zaSlJO`5Y=?FtSj|?9Br!Ew&6be?LDBFhWeG7;JZ^6SVE$ddRz_dPHaQFoJ-We0wA- z_fz{MVYM5ti-@g|Y_EPrF2)G^Jm!Jw+0g;Fou3!gnMou!{?^gwac1kCmc(Ne+goie z^l!K+U6&Fsh=yYpL%(u`FXS>y@javpS4sFvJUx7?uQ#=L8r*NZi!q)(9P9bp^1jZq z;6$p}+O1BHrO$NWH=hFszHQ#v$GWXT4~>^VO|;-!T*Dd*da3pTYQlqpYV@lD%biG! zGKb@Wm=Bwnj2(?#u8We=2R$X?<8MerzeL;r!vxvV`eT{VTXl{E(|@*~+5bxhLPH24 z5`g@4P%Dk_ptmxR3FV0YXZk?{(OUmm3r(>6XZk?{(OL&`h5Cg5GyPl!tu=j5Xp|F_ zjpM(Ual;YLB29Cb<;QHLevW2N2s4qU zG4K2=|6K|0P%M*|)RHMgDpVGw^u2cE&Uu@8K7P*1!+!SLnta@xbrXQ;)!HD59*f5f z|7}SJhErYvsj01ntd)C2N0K7EAif$v;IB#oDoDDdss;c@LzBfKN)QXQ#3F(H3p%Gw zr_hH{+$c!M5f9u)+yMd;KrIQ1%_tAC2?9(TFV+NG{M%A6qs>}VL>6NpW-Qn!{z#}G zkj60*S`^V#k(XC18|MrPtQ3WE0}EOcNordWXfX=}$;z}3#3}^rMiJ+M*^j5MuXv;u?O-fr+Za%i1}+%Z9Z=p~ zjeop>P~88)_XOg}gLV862+DP;uE|5nV_`#wGt31V0P!INku+fS4$C2yj(zhRC;MzB zz*ij?Xd;&mLk}?o1`0~h`-MqMGJG$vSViM?%?qHME(kPq1F>rWAqlPlxi3LFxNqte zWCPBb2CAtnNfZO^oai`*a{?NNA|Lcw1qko|ZRljJyfOex0rmBFBxy`{y1A*P1LF;0b|oUS;9(5HF~HtBSrk;;gF1A3#|qfHwl~Uo0Tj zvR$@jEzLz9QAV7bn+KUY(*}|#)x=o?ySok4VgcveA5`4sswWaBI_rJBl=}^0+5ZiB zB43cO#pNORR8(|fg=Qcyhj;G*bAj@*cMky43ZMac10l*fi1^2$A21+7r-?K1Er9zh!;npw5=r?MF!9Z`V(>eH9}Qr= z`;G8TK81Wxr#>PAM@aIB89gwhv`Vy=IY8o76XQAEt3DonBm@o&rVUzNQS+xIbk&7D z21W+QKb0yw41PonFl^YI*kwhO1YKrRB}~MdW-vCG)?a{-uX{l^O^5gV(VD1kQqPJa zS~ABA#3uJEV9XE+6kOHFtIWz8q#t0Zd2bruT|o#GQY=Kr37-F6FAVGvPTbdS@(Uj* zWUo#A7d{)1+5O-GkfQsyrezaNKw)*JKx6X}-CYH<8es1GJw&J3P77`f*R?o)@A=b! z_$C1h?Fm^;Q{8eE5zzB}{H6jLLWp}?YinW>jvp-u3dJV((q(DKnqOUx^9E2MvAX=D zwZy`EaLsNp4UA;^n=J5)AiS7xKgFN)$rOwE0>R5O4%;Il{yb*qCX3Q*QuYnvgL#HX$NPLjrvzl;5L#15gB zyhTZ(#jv!ZH9M@WwV9eOXv=)I^O+ovN&7Ws4BCA=vs{0%-uf<)U*~?F5k9WL3 zdAcqCs1`?Y%Tly+;25Pjww1IwOR19-f23d+mp6M$;pVH=p_8k%qy(_XVM51OV-!l} zu6LTKz0PD8+ojzRV!zo{4MK*&UsCBYoW+NCw)VZmWb~0AYkfsXWH$pN{m~`k=h9IA ziO*&t4^C5DT+S2LC40(y4s5%*)!k`H%&5fJFe{dg-4H~Re;&0mY}=~-vzLwAGtVwp z0_oQN4NN?eyF&i&BN<>Ibh>nBAH2gCeM|+Dr4~irgSD$~^1vr-FjOB=J=<%VVPo!w z$dAl+_{N=33+TV-F_k#JT3qW$PaOu1vMv4>`|nhMNx#@}&b&)bgOS7~ZK%&J3GP!q zXZBSMmI7Js=NB+cPLUix?arV^k%=Hw4<$;%gX4a4g#x1K(Ien+TLg?nYVd4rNJ>h> z>ef+QVGO&=f%fS6t)YbcF|H&Ik>G(WZot3ZLyFhAwzL--zf0AHOMks%_YA)LcfPZA=zVvVr!V0*eTGf14D_Q> z8ipJ_DF?MVXAFQZo_?VXv75xrjZGVjn*NV)wa{OP%}PAGSO605o^*?pC<=O|!B1Chh8?F6RTD&f2n?nadn)TaAnAg;n~TCYW=hh|0>p{e#FsjZ!eSiyy|Dw zY6pUH3Xk-c=`$6%Ut4upumTwz6`!xVv6A_m00X^9$23n`yV9g&Q`yU+(FAvTBrNfY7asd4iaFGJIf_xJh-P(^Qy%DuRHse{ML=Th0IW)5 zmVC1E3r`l40X`N7zV%@q;mo9%MieD3p55?akuhMigy5kE{!V~i9?AR7?vQg;dAD5k zojH&hpI)Z(KFx7*WaaA6N4|WVnwmP>HX}`*W#-3R6;&B3Ioy)%?wnFz3fdD=Gb1!i?{)e)+0IF+g7KL$lcip%<1ea_G9^BpC9X75B4jY%C!7aEu z!5xB2@ZheGobTNG-uqwGt@^8`rh2A(P1mY5Z8NK9MiCA}?GvCKCU`X12K={vU{boB zQ$qcjEcgyqMDfpbO$Xs1S;rrre?oI+jYLSfs*WxNv+3P+?tX%;NpmT!(h;APe~KmH zdytL(ZDpz>%U60oZ2V2O0bwgU02m4}!TO;ci5350sm;XsUhk&!y3(;1=f2o?a*`|| z-tXr|3e8Z&Ku%78gPLDcyk@rCP*cg%(imkNl85m)$EYBy3L>b_yurVeXkBP7DJ+Rv5fUK23#^V$ok z`doaUbHr)o8pibLkFYA2&qz!BSZRh>EA`u~G!M{0sWD#x1qy$CDh65?Z6zL|nS9wm*2TZKh<&yhh?PxBMiW3PO>nrXRdU;LxkgeFJ#Z^qf; zYactSRgE!5DvwU3OgmeBXf%HP?sYy}oM!;!vY=debEvysVXRsM@HvUC-P@1SzDA$8 zxj&rV^`fhQ=2HwrytDht-j(|8 zZk<~YGKfsSt3lbjagBS~-SJ{CL$rW-R;8YAB)9#k@_22q`n3w$nGXMs(B>_C&D%xW zZCRammV>lq%>Crvwmj?M^Bx%Z^{1A9p0OOHE&^W^2uIXFt!B;V+s)eO)-0q&l0bCN z(5-jII`mhS!X5jNOPC|hu150w7$mw5!CBXC;4_pW%i2q-J5as4$Kx#YcX9c!m0yf% z3Y5h~(u)D)H8}7kt^kV150OEZsr@WhOqT(WYDMhZsPJksl%7z2 zaw!oth(Dv8DQGjA%P_d8Y4LNGV;n0tozBb(FuDTLB2PX0&-}vRUdSaSvv>MWz{AdyMbDjc6 zmb_~%U8)_;-{4NFs69l;DR@RJ95d@W3LLi%K@}Xosh{nyHbOS_aQr;blb_2O zVZU_OM^$FaRG&P^vkmox69$myUhaE_e^`MnnqR<Ozc&w|^^$=#Wjg=8nv%x)#8s6R!YN7#N( zF9mka3Hg{k<6ZUn8+GE9&)lKp0tDBZ# zFMTIt@xr;VFiw(GmbD6D)7M$j^gbGlxd5Sc3Y=YG0ji*3>pRQ^RTh=B$jtg%wr|$z z?gn^n2p4XnRNf8-yBNmG5T%drI800jpiT7jCjEx@dkj7!8m^PF+ITT$YPvnN3LVCe zG*Fb^DC@E_EI@SWPkHXg*FqM5Oo}v2cM4x<>QKqd?YoRVtYgjmB3tuI;q4z%8 zXTA|tvvmmj8=r%RNJa4@^7tg1^7y0#I^T2kf}D8qn$B;eti-|7YNGf}j(i`lRiSwJ z!T)6YdB=Q|&;l>`z9VLKK1LwDKd@C!kKJT{`mq89oSi0$*Tjkkyu<-Nj)>wkaWesX zprLpKz(FAx*iA@mz+Pyu=KecklM_e{4UWMU!vVj8qD>mSz+I^KvBVWvahj9_fK<@n zHDNKFrZ6EOGt}P!oV8i8!LQ1|`X+Btpd=I+UPlbOX;K_`3kAsz-ckVKg8#?@1;OMp zK#!&`AAu53;Nng(Z16ipLsN>(-*z4f8V-0$94OpGF9&Rf0)O0l$G<28*_w!?SqGt@ zIeFQ^n0`R)rgtv4P~dA=@qf@F;CFJ5rZ%;|Tzk4Xalo$@Kp^<54$!`7KojTy1ttXi zrL+J_H@$bRK!KgK-`~Mc9|#Q%9=G`qs-X#J{Fl`Ef(y54#1u#g4X(@)$8LImiV7N% z1Dub7_WpJj?{Bwf1GI;N;uZiyMg!?EIoP@Q|7-byf{&e>Kgk$|9#pBP?TRDN_X3F_jmuOv^0b<2lkj+jwvqmFnzJLiv@#LjUa?L?P+iefVURw>P*$o;id`Um%P zkBLbR0jW2OLhdp_)imf*DA%T;qOrZoL(R3l<`x^wJqWvwWAD5jBCVSNQ-t#;{|eAN z?D~~TS?J988sIb8JO%tj2Mm8-Psm?XsGDxjxk$=l?z2Pi`OOJ!ir|-0B&x(+X=P1Z z{+)<4?ni3b@)g7}-7f+oD{G>Z(iv`S;j<&F44&wc>2)cJ_ZzeLGb{>BAxIVKm(8nY zxGm+|OHltvs@245F6!O1vl>_F4}TH;qsYzM9!xhC6-*#D>!+rN8eIlumS-&baS?Y==uN2N~NtTL$ZO$D6ZU#C{ z8-#Ybe97flJ;S=CI#3^$m&PJ3pz4FI`#vU*z#PGN^(!1vYHY3@YO8;2*FGxvS5QH} zT^XDOMYY&5`?xl%`?sV`oW(lVyU1j0$NQ!YsbLja+*3HDuhKUMdS zewxv|k*LrVORc@)y&L9I{09sj%U)sPDEQO|<8%sMtY7Akzmo6V$6)bPrSlY_|RKrO>iQe(6^48CWMZ;c#NO3!?x)hw)gdVYJ`%}+u*+f4ZQdh#v& z``g6$qOSpNzCjWWx#mjN|MA!U+yQ>`_BF&ngxNEnPB_FQLJ_t@Y0BasS(Y-9--PI9blzG(cfM$;KdpGiX$B-{KJgh#=}1lE zR3_7EeM7uUcTBKIv}kwqr5T}sRt-of-szyu^Gw@H|IouhD`LJ7GDn1S_i=}iXy00C zrdocqn^L`Drs2BJg+BJtN&nd7_a~k;Lbp!l{~~Ak4yDV;GCtKR_+b* zvW$uYwHtAkTCVHPCP2=nJ+zCBQ3wPX`xMdg^e+8mlP=2tjgkg)u3*ye#k>{)B~)oE zz$g+sW*k+PNbYCcyQFS0Al@?*^=jFM^^aB6a$<6^^vOG2kf7eiV36!X;k<1g1cjfmBWEbfG#rO*6sQOOC#mM9KKJ2hJ;aYSSDFO^1LiH zuU7TrVg@6R;!Lj)^hRs7#938kPG4oOz?O1CRy3>Dn#OpKVr`o+77ecXQcE1C_%ksB;q-WW$rb!>XsNN=Tbf`IfdKR935--Q)pI1ArJ{j!90x}+p9*9Ob(7{*BL(kc9JyF2fCKx zU>T7tud9GvsC2VQckbzRvdR)AAjUWH(n_=fjF2@zJ@naaB^nov;|Vv7PB|O*3|uZt zcJ$#zrzI=`(Xc}x5fKxb0K50iUbIpSJZP!O36KV?!e1hi-P?Xx4LRS&ud7&S$f*E7 zG`A)jw4*bW^Bi*~q8q$noP{9bS zrZO1E5ht7bX}7IF3x=CO3@FB+;naoH6n%>E(0eLkr;HH|r!kwaRS~38w(b5kE$QMY~S~PYhWhR{-k*LyMRJwNi+5yP-vvevF zOfb=<8;6;O242LSra=^};B_*kt4 zlgtTK+DnpJ2c_Z>Lx`C+1j$W8F))0q*8okpB6{Q)egi7!;AB!b^ z`M{}LO^7<HTy7y<7sxG53j&aah@why|9W;ZoO2Ou168-F`4}0Uq@PU#j0ZZF5T5mjh&ZAo zp=^X5MG;Ek*JB^ynJC*Ybzi>wRC>-CRNpe0qh=<<62h`U7BwJTP7{Y3is_n765KB| zE*TpFf0h3T*s6i*2^G+BZiN#9jPf#(+A&@b?zaP)^NuPu_NsjLvm<;u zt$6X@Snrjs9shC#`_6eg8%nD;>_+<@nb2SRV6hAin^mBCpj}cYG{( z`%_QU2QVjcZ|BJXKb0lSUD2TDNA1s3a>aHn6)!M_6jKj8 z-g+r1LbSA0vpS}iR{Xh7-|Yi)DY|5v@zcv7w_t5~BML2&&yzN{F+`2nR1)ykiR;Ku zB$GNn$*R0DfNEa46IT43jT{xV5SlS=wu)#~Mnbv<6+*fxz8&l#I%SN*`-E=E<7e?Eiz_^mNim%T-5xADAo&RJAtG_c{$jGDu+sEA!2 zZXVk#z9~|KJJ`&r<`nnar;aa{$}%#1=%>e^?sXM(00rbM1!6P(A zaWcYY0}<@1URwa{h;%~2SqcmFEqwG(!<8|HG&eXX6We+C5;j>cb<1M$+M1h`lV`2gzs$9}PNXu5`77lk8v>(qgwWXd{g{c7n2aFuyd zD_D4S-KI-rq2?2VufT;xzpZ#o9+`q3MYdl{K&p_A3RdeCzv8W{%16`2o^g0z>|%ZC zy^)_PND5X4+WLd}b4X3g?yB9}JcOyBV_~Z4-Y~~f@i69lQg;^U=Hi62xu72e3@^{@ zJq+lu&>HT-!GUw5TI=ch2}eE)qxoD&dptqEtIFlhs*}wX7-|bne)~(Drpj3}ptVWH z|0Z<ykso`=Af?``R zvSD-UrU(+H2rOk#HI=p`=Tm6lZi9)$1V9;C1_^*M86#AboP=mlrRt1OutsFof67Ij zIF%ba{j9(4O>^2FqL5CJHR0UEW89wky5a5A(31*fU<)-a0~*zfSZPNPZsa6k>H=_U zp^*m^RVf^))D6F0kEbjGOtTxrm*kYhCUtOdQ) zD+ImzP@aP1TW5YB!qUO0f{AGbQHaeYFCK+k_1W4J>y!lOVi3?b7re#~#Tva6CaFe* zbqQGQw^~B{ccr4+FO2TQ`r_uiM)RSBbV*(TK&0B30b?k+?A3kBnM)avzU&8?(5XJv zZ8a=TS`1Y3U3bZTQ!Eljy*+_Zj?6wu68!#?mC49u!#4~oAGV{~*=w{gy{+Iy1obxCwDctEwwj6hUNGXQeRHtC4a@;0 z&+FPH2qt z(JSTdI>%z+7ZpUThbczMM|1xUD?hIv52V)Mz9?#Naxp z-9-CZ{kfQ9UXZx~g$3~G0JS(;wsR09%hstr&4-;z(E8vjUrRz+Q_(>?QDZ3hatGw^ zs{hI*(88=YcPdIwwIX$SMgw=iE!Mhtk2#AECNai*u5b_#X-c#HN#nqHM)>Q-%tD(O zKFu%6!=B6>^ETqNZ^w@f<8%?vu>DJto|h)qc^>{tS`cqF2>N~~ymjmk@Kf$b#&KFJ z(m8y8sH(Z5{s0mx%Gabi|HRTZPfwuFawXxjl{ox?CN*?m=PLB#BjC(wW_x_{w0pN9 zpZ1*kfY?qW%1!u|>pLDY+P8d&Ydh^b-go#=zx;gM#B{rO#?y{|_fpKoa`kNEBP8nQ z^myY1WSKiZweh&j83t89C|e{*6nyMdU|S!rq6OKK@hWBDkB{#4ZNNs-xn|f5!>5&w zoOXafFULSDf3Mr4Kjogm8e~0;SQ^hV>n<9LzuLNgel@wNi~FjcX>|2`xE>RN{$)IZ zgY2{0b!N{_Z1+~DjuAG&Cb4OOj$Q+q^xmiXMfuFh@vY^HWos^5_Rb~Zi_YKmE|Xn8!YXd#>Gx06UJ5kzm?5QSCP zM)>4M8TIMp<;ajODyjhBJ!O}$D?&9RWb2W^H|}s18+qONFy&__f?11}Nli6}Plfe) zpLlw|ODaEUuR*|eBJ=8S;N;rt_P4AJJ_X%$MT<>Urf6nY#@YBAT!TyI)X`4;+FGSQ zXv$`n{eCW5>DChP4A4L8 zE=Q7#CIGU#@dRruA_R1%kxg{!k59%;ykY@-S$a3B4j_{ zA(hrEzb|2hR8sOOa-x{3zLMFb-st@JKxo3B-9Q`uTClwWo$EQ#3 zZGMeSu5{sGKu$^%m-Q2Ff}CvAg(0!{Jx#%?QXqLIJIB z7Q}!nCI;ZG0)mBpCv~v-k5nV2NGNPPUP}+{ByP%wRkgL^^Y04 z-VR0HxM04SbzgXNgDxM)vM=5s+ZN%6>5cgj&jK^=X+5;5LvC%?a|_VZ1*_2-m9RVZ zHJqwOeaDrC+W|Gdlk~+hrByr8M`hcUeV(=jrA&MJhD9fpB^=G8;|8ZR-1%I8r2DTp zv!@e1SJG5_y3{V6Q}U0RLb1PI8f}B4@s&5fROflM$l7$Q%RGsAzaDLZYAFP$8h@>6 z39jMD{TUQ4|Fbs=LD`mo{iEZD`*}3RFVZ9xPNm-jWrlTh+4#7ZI&1x`H>NUw>h}Zy zcjg>}+a_I^AR3k*izi9t{!;=gvwg?q+V6KV^0*5K3sdE2zN$=;n|$Q!;%^suaFNeR z?B^PIzoP7FdEmq)V3{OaAEbazn7}%ho=sM}p84V|ENoGd^OnnZpKF@8!;A8`;P>SG z`V}fSOv&k2)&v9lhop0>AIC~grfuIWCgZBvGDR~)t0t=~q;umqT3_N3?{z{^!SzWk zn{^0n(Hoy53~3tjRHvRDJ)C*tNxGtT+d+4m1JVg3T-&W%0IOGc3y>!@f56vGppXdHoLBy91^3TwJYHN=yr(0SvZ>^t~n0uX4YXbT^ zpr+eDPrX=q-p%R)xxb`Y&krQrDlTQ6(0@~sp=OUJ_3fLQB<_*>NidD3U87f#iAEE{yIxpM9#!u$1);jhl z)3mLnmP03W)jazu*nd_?_v0BOshHp<7!&x=ZqhO2{`f%F|9e(%_})~k=j-*&?Gt!1 z*CoKsv){QkyUV_BO?j#k({m(Cm=yCiwTih{9}kuD$(_d=#0vTjLK%KotYahK<$^pj z5cUU&!T8@f2z?@6SyH?pXOgvz{F%!)Qn#$b>aUZXK;oLiFUruMUm6N)?^uS8Ck^Uv zA&7UU4yk|hc^b)7l3%!3K}=LLyWxgcbYA<@uRtwXvOtiHK7RfDynWI}KY2JXuxz+S zIG~xbt_!#=bOr@Hng@L7dYsN0QyM7|Y!T_q$R&THmon=f{w-v4W$oWP@bzT5zH&b< zw*z(yDF0(eF1x=v_=5HZZFp};)wn}MV#QIp}jw#?Br{Sygz8asaa4qEA$#$-9XxIl(FPS z4^6r~5%cDCLt*ZToh(>s=8@X}reQax|0~YhQ})mq`JWKjLraq3qbe269fJ$XY0M@^ z`z&ZZ_z8)VWT&gw@xGTo*`W5-<#Ypo-@BdNtL2L#jV}9aQt~yFH=e7ZGkwi<+F5A@ zG(V5sVMS17heDP5^~`VQBR9*dgPsDul{Q!d?YQo>Z2u0C9D`Maof{@QFGuI&T?6Hg z(BBXntV8R5UbSs^m!Hvfx-eU9@wLJ#iP~J6d8)pHcXe7(6tZcoMgDa7HTq9M^E!n7 z`31{6y0}54-p$DMsgwwdToRTacRUUl8yLr zo<_aNmk!waZS<|7J5{TLw^mPW-a7Vc>qFSZezbkGCIcK-48YjfQ25RxS}7UuQjS@06; z)4JM7TKm$mqZMKNP3)P(*=!=SCnlny+3c71$Q^~{g{^ATlLhAD+|2_IyqOzqf!(pu@t7+@<9n=;Xov0x>`6L`vmS$*a zoD%wE>|TkXb^QaF4QD-vY=V`p%a-^j)|)mkr?KnRFHFe+AmOOMX1Q9w-D47`b*Tx8 zBaGY|dEUN^-pYpIlwvFSO`Y&lIE`H2zb(1z=1Z-w{-WbRA`w24Ub7nv zS`AcE`RCfek&3_(d$if}=}jzo4}_$0<6h`0H2MM!h~IqhHs>~uh_s@iQPoL!?1ZX4 zg;z*vy?gAa216`8IN*aq#xxfeB@0~8+4dd)8NA|C;6Pz_ndb9wy(xSLfZdy3bcQp$SzAS(d;hd zi?BXFu|h0vMm#$~N*jCUN%q40clg>NLH+lG3%p_Fo0NCu*xVnLx6VMz=nV4_Wg750 zm4QciWq$V=7BY;E;bPi?KSfeBAl#AFMf_gsV3KvW4V5O;(M#1i-I4W0yn5+?oIGmrUy~})*N}ue4|Pi~USk4jB3E^)jf}K4NCffbXW(A5w2hD5O8VZ&tI1E}!5n+o8Bq<{v!Wwgf;>EfXvWf1?~5KQ_wpI$qB|p zK*Mgj3J0P>gE9Pos9@y`AQb`wo0_$oojE<&DHDi;EpM!5u0`Q#?Pf(`podx^`#lZu1 zMxZ4o;(Px$8ffj}>PErG&Hmr}lw6#AT>sgp)X_~^k-`heHO!ZWW0c=uQ^)xM2%-^_ zNCk*_#Hd)?c>{@cFJ<4Cju+1a)@*cHehA5XlpC#n@Mqm-Pl7{vz&Kh3*;S(U3nCh* ztO&|uKns}SM4j__oMuc1mb%;-hP!}2RtCrdEn;jGtQ<@YNiD}_B*hi3kq)u>#d>!( zFB*BSWE!A)4zGX|6Nf~Gi^~sn^D|Eb7SsTx4y8^QM)E8nDmB;w;1AXw$#O)ZDguCFDY#K;jr1VGh?nJ67+KS{0ZECJ?9-d0@u;y@`Nx|%@f>^cm(P4l15HuT;pG1h~s%!jG=(sv+qY_ zUH?KzhQ&vrJb*V_F+%N@u?QC&lQ0LWNQbmD#qd%P4O-C|bIAdqi8njV2^2xFNELF? ziOlsGc@?|q?k#E<`mz*n{GmRSdIE~WqL?IGfuhQqKT-2zBa0m(=PgPh<%~kHMyGJh zVuO*sAmI=KBJ+0Q4UR^&7%CJ7PX;s%_4PVBSHR2jo(gM*dL1A1?oKhIuD6ezr&IWo z^o4zIw$Hj=ZwHe0s||!-vlBtcbmt8x8umZVGI>o^un)k7M&E4OUPtVwC6*2KUerj) zHxHX^);2u4#~LgH*4n?9tJkyoV^aM&t|o^#9-kETySvOqIJPIk$qc44m3RAsI3qAr zNEUneG&I@y@=A`DBrA@!PmzF0A%PWm-3R&dct>v7<-Y@Qh(mGnzJ3OR0bDuBIOdA_ zUfi>Y`MfY^^SLTACer6ZWo`hR^@QRL%@A7#Ir}F zZgLlZ71cOqeF8fvrMrL-15+kmlog+=FDJhUl7RdYVT-?On&>n2teZSn@4YUzZd&$g z9+wbet}@~G3R0zj$Yf{jUni8liLMP#O%R@bJk@+K#P0owOAPl2LLdmM57F$4B)DV; z1l#bY)j{J8qO?uo7*2dO3L)B3{Q~V;EfRpz7RNhF`8Wd~o=youlbl$awywI_m+Y#v zQ9Jq7lPgUkbOH}5bctK95|Y(?Y3x5VHhhE|>Z^0PbUVlf+dqi7T2?y8!JwKH1`QAe z%S;)4Qh^q>X1{HR(hAkjER+yYk-^7-L$#LK zEfi0`+DcA(p5o8?a0;%$MBmy~9krQbx0zv=R;5fBIZ`VK|9nD*3h1p;Q`ss76$)1? z556P;>7`$&=Y^4WUO$h#CKS9T_=#`jiPJtw$39B0&x(Sms(O@_DYrOJ$#GfY<1Cm8 z32x%jZk5<^ndxHGzdTAu!lFWJCD;*g*bs>0x1(QV&fNtvG&5~KTJ+4tm}vHTTrbaB z+#IMIHoTbcIa}uXcUfn2Iy_#=`J`VMhmd_HtU+5jiToM#^V#Bd`KWQ}&iqM$amr3& zM=W&h>-`$&&ryku<_$Ig^NL(`xa89w_xItzdIl4$^M|5yDX8WEbI}BtcqmO+vV<<& zMfl#!s%qZMc3WOylu^+b-VMi?fF%6#P9Jp4O98SrEK0w~x|ZsYlReYgN;3QC)H0IW zx5i1&j~g1~mn)Z&weaeH@+aTc)ObqQ@XIf;CL9?-m*(!e3sSqsF7qU}4@ip3_MOYA zbJh2!pR4(tTu;h2EFY0a5QzNj=G@Hbnbev z`HK?=UPJR_K><-jl9?dF?<7;i5Z7Lxr0S~5rd$&2cx(@EP{&W$WK`8o^GtA&r#EOf z?xEYLwm)9gIeG`N=l_0&yI`(Qn!%G=QgYe_$fT1|FF^B;e#l`5!{phPvbIGVh2fC$Q_M@C^B4VFC%yn^f zzc9uLtyPw_+Mgms!OV78CMGg(^!#ua9F|V(k+il4=-`tZ_Z_r(;-);jP8rKL5=bzk zfm*te626a$UU{lNIpi8jKK15S>FuwTmDma zg)w~>yVV=m7BCvujAP>Y%v(Bd74;q$4-R2oe#gIj)Rp@V8TF|D(5WNtmsd8*8^KZ# zHvY}tM=xNimh~;ZX(0Oww_K}cNp2CLBe5?$x>+x!Vw9M^ly#$fgNMv&n+k5e38b!D z!EpD4ILKxow4u3TKTU>zS7*!T{iC?-JVx&alS5uh)u>66d(U<6Zx9-6YA<+@!M7J=8aE;Vv{{+R=47B^@RI%+ji}=xn%4q^Q=x8qwkU0MZg`*$Dou1h9 z4dd$F#7%O+I1`*&Ba=mrBEHo@lgQ~sF#ss=#WejCyMV1}vzjuw;ktP~WftbN?6z}Q z9S331c*tYzOKN-(c&8sGWSRv?qO8P65fgT(jOnBz@wot0j|-YE5-{1TpovpaQxem4 zn(iuuhx621seYA2W~#^QDF#d(SInmVPm`9k8wZrI8P|wTD&oLFMaOT@oNb?pEHKm}7ul2Ql zJ&igbOeL)P4W$*aHOw!01fr{%>Ajd%b^26*39DJ@q<@Q}$>Jv86Q=u7$YCT0_R{KR z_y+_EzSZau5+xbq?x-sB!hTvX-z^8TUWEG6g)pqGPAxaHzxTFmp9#t+t4gH1RNuGV zPrWHy{HiFUK^e|k=`OJRv4njR%0FqR^AD+4pg!zGvj$t%Hh!akGy)L|V{2NOqCbz~ z;WpHPgXC0+GLANh5?3)TK$>jZ;kVI~7*Y>XFj2?C(Ls^7md67x zLw?q*a;kk>LwulOa@%Jcopz- zR3!$`rMd_w76%aI`rBbv&UTF@5v7_$ZMkTuO0uyo!YI?RE>bA7u{faZAnS%OIoKpT zRvM$qCmmOSicygc+gU48U(>NZuPR10C&tqZzhdxM7=)fQt~r4KhiHo>TwhnF`;agu zH>=1ziY`#DI6v_0n2q@j8k@)9?m$ie_Fkn>nvH&ia^M@|rEYq`5vRu=qGWmKY4kc% z;MmZaN9lPu zc7MPYJkBAjg0}%V%ruXY8YcIvj{W&ovbqHta>r6~DCmvZJNLp}e^J;!XQX=&KzBcP zq5@xXnDp%6DD=4x74LlekluIoR*F#|Aauc%k~7Qtf(%!gX@)3Wl7{{5t|b~jC#>Jd z?~@PG*}xoa$vGBDV?}54I@%)JAoVXN(DogFSV?kH_ZS$&9%h{TmNaeU!7ai_C?bOR zV6w&EEs?6lk5qHc5cRZrz1mePeDYOajD3}0Euy?HFbonsBrtLGZD*x&F8e-`Q7R~c z{v0E03ud^NPv+Eh$yIZCd0L17v*$A=3GRC}LkWeE4@O@a`SWH)1A(54#6TE0is3>S z4@gb+S~M~^tu<1DBQNw53!-zO2s!556@$|>bNUFYi6g9;iO8gsFC+LiaCS1G7v+}%U?ml;1U$AbgG8x}{y<)VSPv85o^=RK;8?>`J(SN~J`UZ9TH2?UY zP)-^29&MfG0r5b*ynOmdY^v5i<`kUoFcO<4g)RpL7X`YqP57kv(`yp@&JOY; zX*>_hq$;osHH%Ws=R32M;RTHrM@>>14=T+^whYh==lU*pYbXVnpR&j_01*l!#t+2T zHJkz`vS>_oK3XXi0VPbj6+c1q>OZv9&t~QucavuQnj8*-hz<9`|0qKX_SfOxB-!Ry z^_O`hO13!#sndYSR}kBb_)da4YS3>bp-BRPR>2llK^j&eI1Q5Uh4}^*N4Wkl*;502 zqLV*^BoPNrvE|r<)p`C*$XMUQEx~>!aq)P@3M4LV4eu_~8g^J-QOt>8s~I*j+N1E2E87 zYQc_(9($ZV^f{4=KzVj&pMSn5ScUcM6F$FyVc3GiJuH%8`^d*)7HW<6k>Z!T%jL>5L}basqF41YIFv$U>X!5$`HRbC?K?pg8^c))e7LVz z|3Ihl2I0P;A zVBsH9FT%{oBh)GU^Zm&?)mt&2icTv5yP{cv$kAKga0JdEWY&pr!f7G(64yRH*yA8j zaT8{=BtKJdlbgjQ1MkMyDFaVHAttN%qvEVd33tFVja-K1sa#pSN*#TOi`AT%7fsAi zAa(_4xLo4|%Al2sO+Nu#HJq+#mpFL$EJ5y{5mBC4t=>J>%*TU?{{T%$Ex+I41b>*<&^e8dIV?8DfOK>6{@G#cg= zRZgHjlGFIP8}g$PJ8*LHVHupw7Q{&qlC|&am5(i{T7nqtfpG3`Q$b_=_b9`*W*{Fm zMVZCE%W=_n8IEO&@%xwQI35XXw_XG5r#@33Nv@L+-pyzFiW-{;G%}z-`O6f9^%S|- ze`Mm(7^fBRd!u-x4O(A9~Iwfo~#A!{FQ^H1m*X+~uzP?0j+Z)M07WmsOdKHeoX z9%ba`fT{j7c!ir9Y>ys?C1_t`@{S$6dZ$91lmC;tBfSywHO;osK^04 zG$8@ROSXlK${p%4*QD&xtK$J9-FJ8?&A!CPS62P6-SqrU2!lp?D!B$tfSV#iTA}8| z^Lh3Ah|nQW?o@R)#JC;OUl|Ls)tq(aha7c+i_HCoN ziBUSxjE`=L7)4O(p~j6<6H>X58KB0k{;H}%4wvp7GSjJ6;3)fiZ05y)%_s@(7?m=bYc0xKIi~s>#^tsGrffO6dAN-t!Y6^+!h>aMzJhczSOBKm3 zBlMu(!J0=0$J;VP!{yiENTs2SHR9wQoyBH*U!f_zLw7L~rDe$e0^^XHL~%@Chf)T2 zWOrD4u}C0UmC5G4)%HJUOS_Y$dz`iA#+mgBa5R1A07llR6DVEjv ztoUC{PGf4Q_OB7HGn`HHBM>vJLB8VOlK9_c!e$9>B_GZvAI(Ed_#{-nhWNJIUQ!L5!(E9O+j+^oM-pnJHBH)_Qz23G(ZZAQY5t3KU4+;t3LzK7=p9&=E!` zgT_#_#{Ya=W3;_3cIH6jm>L-AO?r}$9Ve*NEdZ#Zn=vbRcC&}5qL1*?nZsOyy-Y?D zqqe=Q&qi~V->1pOqa$X!9sz!I{LOELcW+;54o~R)gtp>gi4nPAUw-|a0}v_vJ^_)} ze(|p5%u9&wi6YB(pC%T6}k}gjO)us z|IUyZ*CEMPqQo3QP-S^VTGM(F(}&1IisFzoG?NdJ=$|Hs_7bmlkneg7vB=sXJ0}FL zG+uPT80A1sFnKu;9;C>~&^FitQpkgm%}4o}55<^|WLFCJ8sKg(I48z32MJEKz3C3y z|HZnAWt|LC2k*4AURR zY4#i)Kb>v{AuG$=+ljXGZOK(X^HZh-szJS|(tU?1#EO^g-VE^{p%X361<9j8BEkSL z;>E2SLVqqw-4}s7%ZIBQc()Q!kptg~$=%;k?o5geSUSL@x`f;bsYKAF!VBLtA zolE(q9J&p)kZ|y(T*Z8PI7a5yN+zG1%{<1BHt240lw>R>V|-*9d+N-HUMq4vRXACm zuHi_#qs>&{ua(Jn%gkECZ!F731sZ+;Zy|Mu7ZHI_^@NF|%x2WsxaA6ylTpm}>D>T6*4 zH-+>9DPx=v->s#L1mk||XELN@i0ROGhZ9#BQQb(A$1ddErv~>_0qMatRX`?#2(xq7 z-;ZPUoc9m=?kPzyj;Rua$&#>Y61Ypss4GVQ$mYAV8nLKr33u z`@qmJqEs{fk12;1-R1So`)@4{@ut}#0HZzJ!~W%8(@jEagjH-rWD!W7o9W8_eh&;J zNKY%2X0uD0FRqt^AMIZk_y2Y|CVKI*Lav-3S$k=kQ8WY7pB}k#{;kXtJ2(sZlI3pI z1>Mytmo#C#P)B10>sZ)0qS4$(zwvxh>@I{{>ibzP6inooB5> z?pzSYoyp$%_Kg&D4a^fKimSKI?Q-FWX8Vnb9-yL3S~`fhUOl|!1ixzXeR_Bl-N4yP zN>*|b(SNw!#|D9wVnxCp<_?q6l`2FkA0Cm3dLAMGPn%EILyZBW93ufmn&dsrW?hfT zRkVPo^Cov5hGpri){MjxK7;hJ2D9AZ0~=u7#&hHV7w2=n#}{=`6q(bJW1n}oO6HU; zf|=0Yu_T}ZKQTfVm(;vy(q6kx=~dS8&rbeB#dW%B1vsu2ND9uV1!915adgx7FbiR2 z^KgFVkuc_Am34>z|1sg+OgX2J2K(3I2hg-hyzxQ*1ZooRu^0@nCrGl}Z+3?rGKn2_ z_T3R>hreLtg-R z-p202w6(ylXFL6&d1-g&hbFE;bW0II)^$Rg=!0!Wcu#QEgRFDnk*{+a>7_w#l6Q$y zJ3#%-`QZXmA2U*yp+(wJfow1dC<@LCr6X<<&X6P*fQG%KE z5?!qOirB$odcm&W`-?=uYO59_{&#pUsVs@U#p0TkiBDUL?(?)Q`{c9gvMy|T^XhH8 z0goQ~?lPzQlgDMME^Hl=n)-=P^KmSSv+w?Mxf4q4sMNEx9PP%Og|BTUkgzsaAD%k9%BnWX% z3;dK8Y@HVL|521Uy1pclHK{qahbh|o{q z;jXkD+E%lI3#4o!n1c+LBzYX2(4{Eqtko96vr;0+P`u%wG+VyJp2QDr2i>bQQ>UkF zbxW$xZ#rX>^i0sWe@3N=f^d2M<>%HK!r%Y6ggYC3?Bt70O?`Cl^R81TkEp-Dcy)u1 zTxp4`prEUZh+v?L3xaWRi_e|!i&TZ<=e3?!u{rbVp}(q49P4!9Mb;0Nw&VkYbiu-o zHYKU942?wyhR6L=Tbb*RHU4)$^Sb-3>i6%7wfCK6Ux;+5Db4E0P+HW9lW}j#$!E9I zKId-!x$S1n?VNqNX7|lz=g&U7{Vd7C^;9v1d_(Fie7S0(-Hu&#B*$dHMX~|I2UA=YD%`_PcoY-<@aw-ASv@+ibu6 zbChi4laos8^DR`nZ9uI0c+JaOHUI9>nmO;v_bJagRpNCom-a^)-TfBzS7PN8Pu24e zKJT6^J@1ONhSL7&`#-;4+oQ8Te%bE&b=xnw%`^M7=iAS^ndfT5@-Of{<%wUGUzf`8 z(~|Ei??xZR_3x)C&$n58;`Q#Q9$M#ZK6%T$x}E>^jP5 zzORV}i~n%7|GFR%@=v6F$(;14%6{kCX+WFKDV}`(_3V0SnOBq3qAKS*`}Nu=pUy8l z@p962bFTT%Cj@JpU+_uX@`^U|04g?BIbex_XeMYT*t2y1P1^S;X9 z`_e}@>wGxFy+?|*_Oj9XsK)S37gR2Dud`c~HgjKMK)9~a-(&HwR)sEmzu!4L*XS?v z#Za$h^|u$TE}MDtw{&dji8G((mtNI0zV20WRn@rs-|}^rj6T123%_gh`4GGA%(b;H z{QRfh+^FY^{d)4vuNmuprGCpk|Kik%H~sS0L*1S|NsHw@5%XI6Kd-SyvAN9Es}s)L zy}f$%nlpc2q{co?sXO0aVyg2w8Q79@d3Jr@%GH50_dgAbwKV$QvUIhx(f`lN)6V?Q zuRV0ye)E%pugaXf=c6`#@L8{#clf!`y$|}F{yE-1zC9P7S6x51?(L=>`|E;>e$;n! z*5~;B_#9=F_u83rDUY4x8l79Wg}1%;T;W}|x7&KR@HZZ{H}d`&F&-I~GbilQUHEx5 z=UspGFH==heoR@o-z%b4;o-4l&bUt(#LWL`CcfUwDZX83U5(MhtN#-NV|lMQS-+6Z zv0ljie3uC5c5P6~J{;Tqb6Q7KVmqT&k+B{%%|V De2yM0 diff --git a/simscape-nano-hexapod.tex b/simscape-nano-hexapod.tex index eeab745..81bafe6 100644 --- a/simscape-nano-hexapod.tex +++ b/simscape-nano-hexapod.tex @@ -1,4 +1,4 @@ -% Created 2025-04-03 Thu 22:05 +% Created 2025-04-07 Mon 17:07 % Intended LaTeX compiler: pdflatex \documentclass[a4paper, 10pt, DIV=12, parskip=full, bibliography=totoc]{scrreprt} @@ -8,6 +8,13 @@ \author{Dehaeze Thomas} \date{\today} \title{Simscape Model - Nano Hexapod} +\hypersetup{ + pdfauthor={Dehaeze Thomas}, + pdftitle={Simscape Model - Nano Hexapod}, + pdfkeywords={}, + pdfsubject={}, + pdfcreator={Emacs 30.1 (Org mode 9.7.26)}, + pdflang={English}} \usepackage{biblatex} \begin{document} @@ -297,12 +304,12 @@ This equation links the pose\footnote{The \emph{pose} represents the position an \end{figure} \subsubsection{Inverse Kinematics} -The inverse kinematic problem involves determining the required strut lengths \(\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^T\) for a desired platform pose \(\bm{\mathcal{X}}\) (i.e. position \({}^A\bm{P}\) and orientation \({}^A\bm{R}_B\)). +The inverse kinematic problem involves determining the required strut lengths \(\bm{\mathcal{L}} = \left[ l_1, l_2, \ldots, l_6 \right]^{\intercal}\) for a desired platform pose \(\bm{\mathcal{X}}\) (i.e. position \({}^A\bm{P}\) and orientation \({}^A\bm{R}_B\)). This problem can be solved analytically using the loop closure equations \eqref{eq:nhexa_loop_closure}. The obtained strut lengths are given by \eqref{eq:nhexa_inverse_kinematics}. \begin{equation}\label{eq:nhexa_inverse_kinematics} - l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i} + l_i = \sqrt{{}^A\bm{P}^{\intercal} {}^A\bm{P} + {}^B\bm{b}_i^{\intercal} {}^B\bm{b}_i + {}^A\bm{a}_i^{\intercal} {}^A\bm{a}_i - 2 {}^A\bm{P}^{\intercal} {}^A\bm{a}_i + 2 {}^A\bm{P}^{\intercal} \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^{\intercal} {}^A\bm{a}_i} \end{equation} If the position and orientation of the platform lie in the feasible workspace, the solution is unique. @@ -341,7 +348,7 @@ By multiplying both sides by \({}^A\hat{\bm{s}}_i\), \eqref{eq:nhexa_loop_closur {}^A\hat{\bm{s}}_i {}^A\bm{v}_p + \underbrace{{}^A\hat{\bm{s}}_i ({}^A\bm{\omega} \times {}^A\bm{b}_i)}_{=({}^A\bm{b}_i \times {}^A\hat{\bm{s}}_i) {}^A\bm{\omega}} = \dot{l}_i + \underbrace{{}^A\hat{s}_i l_i \left( {}^A\bm{\omega}_i \times {}^A\hat{\bm{s}}_i \right)}_{=0} \end{equation} -Equation \eqref{eq:nhexa_loop_closure_velocity_bis} can be rearranged in matrix form to obtain \eqref{eq:nhexa_jacobian_velocities}, with \(\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^T\) the vector of strut velocities, and \(\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^T\) the vector of platform velocity and angular velocity. +Equation \eqref{eq:nhexa_loop_closure_velocity_bis} can be rearranged in matrix form to obtain \eqref{eq:nhexa_jacobian_velocities}, with \(\dot{\bm{\mathcal{L}}} = [ \dot{l}_1 \ \dots \ \dot{l}_6 ]^{\intercal}\) the vector of strut velocities, and \(\dot{\bm{\mathcal{X}}} = [{}^A\bm{v}_p ,\ {}^A\bm{\omega}]^{\intercal}\) the vector of platform velocity and angular velocity. \begin{equation}\label{eq:nhexa_jacobian_velocities} \boxed{\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}} @@ -351,12 +358,12 @@ The matrix \(\bm{J}\) is called the Jacobian matrix and is defined by \eqref{eq: \begin{equation}\label{eq:nhexa_jacobian} \bm{J} = \begin{bmatrix} - {{}^A\hat{\bm{s}}_1}^T & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^T \\ - {{}^A\hat{\bm{s}}_2}^T & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^T \\ - {{}^A\hat{\bm{s}}_3}^T & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^T \\ - {{}^A\hat{\bm{s}}_4}^T & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^T \\ - {{}^A\hat{\bm{s}}_5}^T & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^T \\ - {{}^A\hat{\bm{s}}_6}^T & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^T + {{}^A\hat{\bm{s}}_1}^{\intercal} & ({}^A\bm{b}_1 \times {}^A\hat{\bm{s}}_1)^{\intercal} \\ + {{}^A\hat{\bm{s}}_2}^{\intercal} & ({}^A\bm{b}_2 \times {}^A\hat{\bm{s}}_2)^{\intercal} \\ + {{}^A\hat{\bm{s}}_3}^{\intercal} & ({}^A\bm{b}_3 \times {}^A\hat{\bm{s}}_3)^{\intercal} \\ + {{}^A\hat{\bm{s}}_4}^{\intercal} & ({}^A\bm{b}_4 \times {}^A\hat{\bm{s}}_4)^{\intercal} \\ + {{}^A\hat{\bm{s}}_5}^{\intercal} & ({}^A\bm{b}_5 \times {}^A\hat{\bm{s}}_5)^{\intercal} \\ + {{}^A\hat{\bm{s}}_6}^{\intercal} & ({}^A\bm{b}_6 \times {}^A\hat{\bm{s}}_6)^{\intercal} \end{bmatrix} \end{equation} @@ -364,7 +371,7 @@ Therefore, the Jacobian matrix \(\bm{J}\) links the rate of change of the strut However, \(\bm{J}\) needs to be recomputed for every Stewart platform pose because it depends on the actual pose of the manipulator. \subsubsection{Approximate solution to the Forward and Inverse Kinematic problems} -For small displacements \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T\) around an operating point \(\bm{\mathcal{X}}_0\) (for which the Jacobian was computed), the associated joint displacement \(\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^T\) can be computed using the Jacobian \eqref{eq:nhexa_inverse_kinematics_approximate}. +For small displacements \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^{\intercal}\) around an operating point \(\bm{\mathcal{X}}_0\) (for which the Jacobian was computed), the associated joint displacement \(\delta\bm{\mathcal{L}} = [\delta l_1,\,\delta l_2,\,\delta l_3,\,\delta l_4,\,\delta l_5,\,\delta l_6]^{\intercal}\) can be computed using the Jacobian \eqref{eq:nhexa_inverse_kinematics_approximate}. \begin{equation}\label{eq:nhexa_inverse_kinematics_approximate} \boxed{\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}} @@ -400,27 +407,27 @@ It can be computed once at the rest position and used for both forward and inver The static force analysis of the Stewart platform can be performed using the principle of virtual work. This principle states that for a system in static equilibrium, the total virtual work of all forces acting on the system must be zero for any virtual displacement compatible with the system's constraints. -Let \(\bm{f} = [f_1, f_2, \cdots, f_6]^T\) represent the vector of actuator forces applied in each strut, and \(\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^T\) denote the external wrench (combined force \(\bm{F}\) and torque \(\bm{n}\)) acting on the mobile platform at point \(\bm{O}_B\). +Let \(\bm{f} = [f_1, f_2, \cdots, f_6]^{\intercal}\) represent the vector of actuator forces applied in each strut, and \(\bm{\mathcal{F}} = [\bm{F}, \bm{n}]^{\intercal}\) denote the external wrench (combined force \(\bm{F}\) and torque \(\bm{n}\)) acting on the mobile platform at point \(\bm{O}_B\). The virtual work \(\delta W\) consists of two contributions: \begin{itemize} -\item The work performed by the actuator forces through virtual strut displacements \(\delta \bm{\mathcal{L}}\): \(\bm{f}^T \delta \bm{\mathcal{L}}\) -\item The work performed by the external wrench through virtual platform displacements \(\delta \bm{\mathcal{X}}\): \(-\bm{\mathcal{F}}^T \delta \bm{\mathcal{X}}\) +\item The work performed by the actuator forces through virtual strut displacements \(\delta \bm{\mathcal{L}}\): \(\bm{f}^{\intercal} \delta \bm{\mathcal{L}}\) +\item The work performed by the external wrench through virtual platform displacements \(\delta \bm{\mathcal{X}}\): \(-\bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}}\) \end{itemize} Thus, the principle of virtual work can be expressed as: \begin{equation} -\delta W = \bm{f}^T \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^T \delta \bm{\mathcal{X}} = 0 +\delta W = \bm{f}^{\intercal} \delta \bm{\mathcal{L}} - \bm{\mathcal{F}}^{\intercal} \delta \bm{\mathcal{X}} = 0 \end{equation} Using the Jacobian relationship that links virtual displacements \eqref{eq:nhexa_inverse_kinematics_approximate}, this equation becomes: \begin{equation} -\left( \bm{f}^T \bm{J} - \bm{\mathcal{F}}^T \right) \delta \bm{\mathcal{X}} = 0 +\left( \bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} \right) \delta \bm{\mathcal{X}} = 0 \end{equation} Because this equation must hold for any virtual displacement \(\delta \bm{\mathcal{X}}\), the force mapping relationships \eqref{eq:nhexa_jacobian_forces} can be derived. \begin{equation}\label{eq:nhexa_jacobian_forces} -\bm{f}^T \bm{J} - \bm{\mathcal{F}}^T = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^T \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-T} \bm{\mathcal{F}}} +\bm{f}^{\intercal} \bm{J} - \bm{\mathcal{F}}^{\intercal} = 0 \quad \Rightarrow \quad \boxed{\bm{\mathcal{F}} = \bm{J}^{\intercal} \bm{f}} \quad \text{and} \quad \boxed{\bm{f} = \bm{J}^{-\intercal} \bm{\mathcal{F}}} \end{equation} These equations establish that the transpose of the Jacobian matrix maps actuator forces to platform forces and torques, while its inverse transpose maps platform forces and torques to required actuator forces. @@ -443,14 +450,14 @@ These individual relationships can be combined into a matrix form using the diag By applying the force mapping relationships \eqref{eq:nhexa_jacobian_forces} derived in the previous section and the Jacobian relationship for small displacements \eqref{eq:nhexa_forward_kinematics_approximate}, the relationship between applied wrench \(\bm{\mathcal{F}}\) and resulting platform displacement \(\delta \bm{\mathcal{X}}\) is obtained \eqref{eq:nhexa_stiffness_matrix}. \begin{equation}\label{eq:nhexa_stiffness_matrix} -\bm{\mathcal{F}} = \underbrace{\bm{J}^T \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}} +\bm{\mathcal{F}} = \underbrace{\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}}_{\bm{K}} \cdot \delta \bm{\mathcal{X}} \end{equation} -where \(\bm{K} = \bm{J}^T \bm{\mathcal{K}} \bm{J}\) is identified as the platform stiffness matrix. +where \(\bm{K} = \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J}\) is identified as the platform stiffness matrix. The inverse relationship is given by the compliance matrix \(\bm{C}\): \begin{equation} -\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^T \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}} +\delta \bm{\mathcal{X}} = \underbrace{(\bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J})^{-1}}_{\bm{C}} \bm{\mathcal{F}} \end{equation} These relationships reveal that the overall platform stiffness and compliance characteristics are determined by two factors: @@ -480,25 +487,25 @@ where \(\bm{M}\) represents the platform mass matrix, \(\bm{\mathcal{X}}\) the p The primary forces acting on the system are actuator forces \(\bm{f}\), elastic forces due to strut stiffness \(-\bm{\mathcal{K}} \bm{\mathcal{L}}\) and damping forces in the struts \(\bm{\mathcal{C}} \dot{\bm{\mathcal{L}}}\). \begin{equation} -\Sigma \bm{\mathcal{F}} = \bm{J}^T (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6) +\Sigma \bm{\mathcal{F}} = \bm{J}^{\intercal} (\bm{f} - \bm{\mathcal{K}} \bm{\mathcal{L}} - s \bm{\mathcal{C}} \bm{\mathcal{L}}), \quad \bm{\mathcal{K}} = \text{diag}(k_1\,\dots\,k_6),\ \bm{\mathcal{C}} = \text{diag}(c_1\,\dots\,c_6) \end{equation} Combining these forces and using \eqref{eq:nhexa_forward_kinematics_approximate} yields the complete dynamic equation \eqref{eq:nhexa_dynamical_equations}. \begin{equation}\label{eq:nhexa_dynamical_equations} - \bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^T \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^T \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}} + \bm{M} s^2 \bm{\mathcal{X}} = \bm{\mathcal{F}} - \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} \bm{\mathcal{X}} - \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s \bm{\mathcal{X}} \end{equation} The transfer function matrix in the Cartesian frame becomes \eqref{eq:nhexa_transfer_function_cart}. \begin{equation}\label{eq:nhexa_transfer_function_cart} - \frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{T} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{T} \bm{\mathcal{K}} \bm{J} )^{-1} + \frac{{\mathcal{X}}}{\bm{\mathcal{F}}}(s) = ( \bm{M} s^2 + \bm{J}^{\intercal} \bm{\mathcal{C}} \bm{J} s + \bm{J}^{\intercal} \bm{\mathcal{K}} \bm{J} )^{-1} \end{equation} Through coordinate transformation using the Jacobian matrix, the dynamics in the actuator space is obtained \eqref{eq:nhexa_transfer_function_struts}. \begin{equation}\label{eq:nhexa_transfer_function_struts} - \frac{\bm{\mathcal{L}}}{\bm{f}}(s) = ( \bm{J}^{-T} \bm{M} \bm{J}^{-1} s^2 + \bm{\mathcal{C}} + \bm{\mathcal{K}} )^{-1} + \frac{\bm{\mathcal{L}}}{\bm{f}}(s) = ( \bm{J}^{-\intercal} \bm{M} \bm{J}^{-1} s^2 + \bm{\mathcal{C}} + \bm{\mathcal{K}} )^{-1} \end{equation} Although this simplified model provides useful insights, real Stewart platforms exhibit more complex behaviors. @@ -688,7 +695,7 @@ This reduction from six to four observable modes is attributed to the system's s The system's behavior can be characterized in three frequency regions. At low frequencies, well below the first resonance, the plant demonstrates good decoupling between actuators, with the response dominated by the strut stiffness: \(\bm{G}(j\omega) \xrightarrow[\omega \to 0]{} \bm{\mathcal{K}}^{-1}\). In the mid-frequency range, the system exhibits coupled dynamics through its resonant modes, reflecting the complex interactions between the platform's degrees of freedom. -At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: \(\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-T} \bm{J}^T \frac{-1}{\omega^2}\) +At high frequencies, above the highest resonance, the response is governed by the payload's inertia mapped to the strut coordinates: \(\bm{G}(j\omega) \xrightarrow[\omega \to \infty]{} \bm{J} \bm{M}^{-\intercal} \bm{J}^{\intercal} \frac{-1}{\omega^2}\) The force sensor transfer functions, shown in Figure \ref{fig:nhexa_multi_body_plant_fm}, display characteristics typical of collocated actuator-sensor pairs. Each actuator's transfer function to its associated force sensor exhibits alternating complex conjugate poles and zeros. @@ -782,7 +789,7 @@ Furthermore, at low frequencies, the plant exhibits good decoupling between the \begin{center} \includegraphics[scale=1,scale=1]{figs/nhexa_control_cartesian.png} \end{center} -\subcaption{\label{fig:nhexa_control_cartesian}Control in the Cartesian frame. $\bm{J}^{-T}$ is used to project force and torques on each strut} +\subcaption{\label{fig:nhexa_control_cartesian}Control in the Cartesian frame. $\bm{J}^{-\intercal}$ is used to project force and torques on each strut} \end{subfigure} \caption{\label{fig:nhexa_control_frame}Two control strategies} \end{figure}