From b61a8d8fb5d47c89c97ec8081942ce33f673538c Mon Sep 17 00:00:00 2001 From: Jeff Irion Date: Tue, 24 Mar 2020 10:56:11 -0700 Subject: [PATCH] Add Graph SLAM formulation PDF and SE(2) solver + example --- SLAM/GraphBasedSLAM/LaTeX/.gitignore | 3 + SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib | 30 + .../LaTeX/graphSLAM_formulation.tex | 175 ++ SLAM/GraphBasedSLAM/data/README.rst | 6 + SLAM/GraphBasedSLAM/data/input_INTEL.g2o | 2711 +++++++++++++++++ .../graphSLAM_SE2_example.ipynb | 332 ++ SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf | Bin 0 -> 276368 bytes SLAM/GraphBasedSLAM/graphslam/__init__.py | 9 + .../GraphBasedSLAM/graphslam/edge/__init__.py | 5 + .../graphslam/edge/edge_odometry.py | 180 ++ SLAM/GraphBasedSLAM/graphslam/graph.py | 265 ++ SLAM/GraphBasedSLAM/graphslam/load.py | 66 + .../GraphBasedSLAM/graphslam/pose/__init__.py | 5 + SLAM/GraphBasedSLAM/graphslam/pose/se2.py | 171 ++ SLAM/GraphBasedSLAM/graphslam/util.py | 78 + SLAM/GraphBasedSLAM/graphslam/vertex.py | 67 + .../images/Graph_SLAM_optimization.gif | Bin 0 -> 114966 bytes 17 files changed, 4103 insertions(+) create mode 100644 SLAM/GraphBasedSLAM/LaTeX/.gitignore create mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib create mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex create mode 100644 SLAM/GraphBasedSLAM/data/README.rst create mode 100644 SLAM/GraphBasedSLAM/data/input_INTEL.g2o create mode 100644 SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb create mode 100644 SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf create mode 100644 SLAM/GraphBasedSLAM/graphslam/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/edge/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/edge/edge_odometry.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/graph.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/load.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/pose/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/pose/se2.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/util.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/vertex.py create mode 100644 SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif diff --git a/SLAM/GraphBasedSLAM/LaTeX/.gitignore b/SLAM/GraphBasedSLAM/LaTeX/.gitignore new file mode 100644 index 0000000000..b0b343402c --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/.gitignore @@ -0,0 +1,3 @@ +# Ignore LaTeX generated files +graphSLAM_formulation.* +!graphSLAM_formulation.tex diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib new file mode 100644 index 0000000000..4d3b71ae50 --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib @@ -0,0 +1,30 @@ +@article{blanco2010tutorial, + title={A tutorial on ${SE}(3)$ transformation parameterizations and on-manifold optimization}, + author={Blanco, Jose-Luis}, + journal={University of Malaga, Tech. Rep}, + volume={3}, + year={2010}, + publisher={Citeseer} +} + +@article{grisetti2010tutorial, + title={A tutorial on graph-based {SLAM}}, + author={Grisetti, Giorgio and Kummerle, Rainer and Stachniss, Cyrill and Burgard, Wolfram}, + journal={IEEE Intelligent Transportation Systems Magazine}, + volume={2}, + number={4}, + pages={31--43}, + year={2010}, + publisher={IEEE} +} + +@article{thrun2006graph, + title={The graph {SLAM} algorithm with applications to large-scale mapping of urban structures}, + author={Thrun, Sebastian and Montemerlo, Michael}, + journal={The International Journal of Robotics Research}, + volume={25}, + number={5-6}, + pages={403--429}, + year={2006}, + publisher={SAGE Publications} +} diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex new file mode 100644 index 0000000000..25f02cd3bd --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex @@ -0,0 +1,175 @@ +\documentclass{article} + +\usepackage{amsfonts} +\usepackage{amsmath,amssymb,amsfonts} +\usepackage{textcomp} +\usepackage{fullpage} +\usepackage{setspace} +\usepackage{float} +\usepackage{cite} +\usepackage{graphicx} +\usepackage{caption} +\usepackage{subcaption} +\usepackage[pdfborder={0 0 0}, pdfpagemode=UseNone, pdfstartview=FitH]{hyperref} + +\DeclareMathOperator*{\argmax}{arg\,max} +\DeclareMathOperator*{\argmin}{arg\,min} + +\def\keyterm{\textit} + +\newcommand{\transp}{{\scriptstyle{\mathsf{T}}}} + + + +\begin{document} + +\title{Graph SLAM Formulation} +\author{Jeff Irion} +\date{} + +\maketitle +\vspace{3em} + + +\section{Problem Formulation} + +Let a robot's trajectory through its environment be represented by a sequence of $N$ poses: $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$. Each pose lies on a manifold: $\mathbf{p}_i \in \mathcal{M}$. Simple examples of manifolds used in Graph SLAM include 1-D, 2-D, and 3-D space, i.e., $\mathbb{R}$, $\mathbb{R}^2$, and $\mathbb{R}^3$. These environments are \keyterm{rectilinear}, meaning that there is no concept of orientation. By contrast, in $SE(2)$ problem settings a robot's pose consists of its location in $\mathbb{R}^2$ and its orientation $\theta$. Similarly, in $SE(3)$ a robot's pose consists of its location in $\mathbb{R}^3$ and its orientation, which can be represented via Euler angles, quaternions, or $SO(3)$ rotation matrices. + +As the robot explores its environment, it collects a set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_j\}$. Examples of such measurements include odometry, GPS, and IMU data. Given a set of poses $\mathbf{p}_1, \ldots, \mathbf{p}_N$, we can compute the estimated measurement $\hat{\mathbf{z}}_j(\mathbf{p}_1, \ldots, \mathbf{p}_N)$. We can then compute the \keyterm{residual} $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)$ for measurement $j$. The formula for the residual depends on the type of measurement. As an example, let $\mathbf{z}_1$ be an odometry measurement that was collected when the robot traveled from $\mathbf{p}_1$ to $\mathbf{p}_2$. The expected measurement and the residual are computed as +% +\begin{align*} + \hat{\mathbf{z}}_1(\mathbf{p}_1, \mathbf{p}_2) &= \mathbf{p}_2 \ominus \mathbf{p}_1 \\ + \mathbf{e}_1(\mathbf{z}_1, \hat{\mathbf{z}}_1) &= \mathbf{z}_1 \ominus \hat{\mathbf{z}}_1 = \mathbf{z}_1 \ominus (\mathbf{p}_2 \ominus \mathbf{p}_1), +\end{align*} +% +where the $\ominus$ operator indicates inverse pose composition. We model measurement $\mathbf{z}_j$ as having independent Gaussian noise with zero mean and covariance matrix $\Omega_j^{-1}$; we refer to $\Omega_j$ as the \keyterm{information matrix} for measurement $j$. That is, +\begin{equation} + p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) = \eta_j \exp \left( (-\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right), \label{eq:observation_probability} +\end{equation} +where $\eta_j$ is the normalization constant. + +The objective of Graph SLAM is to find the maximum likelihood set of poses given the measurements $\mathcal{Z} = \{\mathbf{z}_j\}$; in other words, we want to find +% +\begin{equation*} + \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) +\end{equation*} +% +Using Bayes' rule, we can write this probability as +% +\begin{align} + p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \frac{p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) p(\mathbf{p}_1, \ldots, \mathbf{p}_N) }{ p(\mathcal{Z}) } \notag \\ + &\propto p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N), \label{eq:bayes} +\end{align} +% +since $p(\mathcal{Z})$ is a constant (albeit, an unknown constant) and we assume that $p(\mathbf{p}_1, \ldots, \mathbf{p}_N)$ is uniformly distributed \cite{thrun2006graph}. Therefore, we can use \eqref{eq:observation_probability} and \eqref{eq:bayes} to simplify the Graph SLAM optimization as follows: +% +\begin{align*} + \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M \exp \left( -(\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right) \\ + &= \argmin_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j). +\end{align*} +% +We define +% +\begin{equation*} + \chi^2 := \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j), +\end{equation*} +% +and this is what we seek to minimize. + + +\section{Dimensionality and Pose Representation} + +Before proceeding further, it is helpful to discuss the dimensionality of the problem. We have: +\begin{itemize} + \item A set of $N$ poses $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$, where each pose lies on the manifold $\mathcal{M}$ + \begin{itemize} + \item Each pose $\mathbf{p}_i$ is represented as a vector in (a subset of) $\mathbb{R}^d$. For example: + \begin{itemize} + \item[$\circ$] An $SE(2)$ pose is typically represented as $(x, y, \theta)$, and thus $d = 3$. + \item[$\circ$] An $SE(3)$ pose is typically represented as $(x, y, z, q_x, q_y, q_z, q_w)$, where $(x, y, z)$ is a point in $\mathbb{R}^3$ and $(q_x, q_y, q_z, q_w)$ is a \keyterm{quaternion}, and so $d = 7$. For more information about $SE(3)$ parameterizations and pose transformations, see \cite{blanco2010tutorial}. + \end{itemize} + \item We also need to be able to represent each pose compactly as a vector in (a subset of) $\mathbb{R}^c$. + \begin{itemize} + \item[$\circ$] Since an $SE(2)$ pose has three degrees of freedom, the $(x, y, \theta)$ representation is again sufficient and $c=3$. + \item[$\circ$] An $SE(3)$ pose only has six degrees of freedom, and we can represent it compactly as $(x, y, z, q_x, q_y, q_z)$, and thus $c=6$. + \end{itemize} + \item We use the $\boxplus$ operator to indicate pose composition when one or both of the poses are represented compactly. The output can be a pose in $\mathcal{M}$ or a vector in $\mathbb{R}^c$, as required by context. + \end{itemize} + \item A set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_1, \mathbf{z}_2, \ldots, \mathbf{z}_M\}$ + \begin{itemize} + \item Each measurement's dimensionality can be unique, and we will use $\bullet$ to denote a ``wildcard'' variable. + \item Measurement $\mathbf{z}_j \in \mathbb{R}^\bullet$ has an associated information matrix $\Omega_j \in \mathbb{R}^{\bullet \times \bullet}$ and residual function $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) = \mathbf{e}_j(\mathbf{z}_j, \mathbf{p}_1, \ldots, \mathbf{p}_N) \in \mathbb{R}^\bullet$. + \item A measurement could, in theory, constrain anywhere from 1 pose to all $N$ poses. In practice, each measurement usually constrains only 1 or 2 poses. + \end{itemize} +\end{itemize} + + +\section{Graph SLAM Algorithm} + +The ``Graph'' in Graph SLAM refers to the fact that we view the problem as a graph. The graph has a set $\mathcal{V}$ of $N$ vertices, where each vertex $v_i$ has an associated pose $\mathbf{p}_i$. Similarly, the graph has a set $\mathcal{E}$ of $M$ edges, where each edge $e_j$ has an associated measurement $\mathbf{z}_j$. In practice, the edges in this graph are either unary (i.e., a loop) or binary. (Note: $e_j$ refers to the edge in the graph associated with measurement $\mathbf{z}_j$, whereas $\mathbf{e}_j$ refers to the residual function associated with $\mathbf{z}_j$.) For more information about the Graph SLAM algorithm, see \cite{grisetti2010tutorial}. + +We want to optimize +% +\begin{equation*} + \chi^2 = \sum_{e_j \in \mathcal{E}} \mathbf{e}_j^\transp \Omega_j \mathbf{e}_j. +\end{equation*} +% +Let $\mathbf{x}_i \in \mathbb{R}^c$ be the compact representation of pose $\mathbf{p}_i \in \mathcal{M}$, and let +% +\begin{equation*} + \mathbf{x} := \begin{bmatrix} \mathbf{x}_1 \\ \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \end{bmatrix} \in \mathbb{R}^{cN} +\end{equation*} +% +We will solve this optimization problem iteratively. Let +% +\begin{equation} + \mathbf{x}^{k+1} := \mathbf{x}^k \boxplus \Delta \mathbf{x}^k = \begin{bmatrix} \mathbf{x}_1 \boxplus \Delta \mathbf{x}_1 \\ \mathbf{x}_2 \boxplus \Delta \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \boxplus \Delta \mathbf{x}_2 \end{bmatrix} \label{eq:update} +\end{equation} +% +The $\chi^2$ error at iteration $k+1$ is +\begin{equation} + \chi_{k+1}^2 = \sum_{e_j \in \mathcal{E}} \underbrace{\left[ \mathbf{e}_j(\mathbf{x}^{k+1}) \right]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^{k+1})}_{\bullet \times 1}. \label{eq:chisq_at_kplusone} +\end{equation} +% +We will linearize the residuals as: +% +\begin{align} + \mathbf{e}_j(\mathbf{x}^{k+1}) &= \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \notag \\ + &\approx \mathbf{e}_j(\mathbf{x}^{k}) + \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right] \Delta \mathbf{x}^k \notag \\ + &= \mathbf{e}_j(\mathbf{x}^{k}) + \left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right) \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \Delta \mathbf{x}^k. \label{eq:linearization} +\end{align} +% +Plugging \eqref{eq:linearization} into \eqref{eq:chisq_at_kplusone}, we get: +% +\small +\begin{align} + \chi_{k+1}^2 &\approx \ \ \ \ \ \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x}^k)]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^k)}_{\bullet \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{(\Delta \mathbf{x}^k)^\transp}_{1 \times cN} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &= \chi_k^2 + 2 \mathbf{b}^\transp \Delta \mathbf{x}^k + (\Delta \mathbf{x}^k)^\transp H \Delta \mathbf{x}^k, \notag +\end{align} +\normalsize +% +where +% +\begin{align*} + \mathbf{b}^\transp &= \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \\ + H &= \sum_{e_j \in \mathcal{E}} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN}. +\end{align*} +% +Using this notation, we obtain the optimal update as +% +\begin{equation} + \Delta \mathbf{x}^k = -H^{-1} \mathbf{b}. \label{eq:deltax} +\end{equation} +% +We apply this update to the poses via \eqref{eq:update} and repeat until convergence. + + + +\bibliographystyle{acm} +\bibliography{graphSLAM}{} + +\end{document} diff --git a/SLAM/GraphBasedSLAM/data/README.rst b/SLAM/GraphBasedSLAM/data/README.rst new file mode 100644 index 0000000000..c875cce73f --- /dev/null +++ b/SLAM/GraphBasedSLAM/data/README.rst @@ -0,0 +1,6 @@ +Acknowledgments and References +============================== + +Thanks to Luca Larlone for allowing inclusion of the `Intel dataset `_ in this repo. + +1. Carlone, L. and Censi, A., 2014. `From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimization `_. IEEE Transactions on Robotics, 30(2), pp.475-492. diff --git a/SLAM/GraphBasedSLAM/data/input_INTEL.g2o b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o new file mode 100644 index 0000000000..16f3a2600c --- /dev/null +++ b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o @@ -0,0 +1,2711 @@ +VERTEX_SE2 0 0.000000 0.000000 0.000000 +VERTEX_SE2 1 0.000000 0.000000 -0.000642 +VERTEX_SE2 2 0.000000 0.000000 -0.001180 +VERTEX_SE2 3 0.011002 -0.000975 -0.003562 +VERTEX_SE2 4 0.641008 -0.011200 -0.007444 +VERTEX_SE2 5 0.696016 -0.011716 -0.098726 +VERTEX_SE2 6 0.700269 -0.015435 -0.895998 +VERTEX_SE2 7 0.693956 0.004213 -1.511535 +VERTEX_SE2 8 0.699263 0.026693 -2.125069 +VERTEX_SE2 9 0.716114 0.041122 -2.763139 +VERTEX_SE2 10 0.728981 0.043219 2.905515 +VERTEX_SE2 11 0.733203 0.040537 2.231236 +VERTEX_SE2 12 0.733186 0.041545 1.581762 +VERTEX_SE2 13 0.738753 0.059070 0.922264 +VERTEX_SE2 14 0.759658 0.073750 0.314025 +VERTEX_SE2 15 0.768572 0.074357 -0.210903 +VERTEX_SE2 16 1.062493 0.014152 -0.229595 +VERTEX_SE2 17 1.663647 -0.133115 -0.260823 +VERTEX_SE2 18 2.287001 -0.296480 -0.271000 +VERTEX_SE2 19 2.914298 -0.494254 -0.319576 +VERTEX_SE2 20 3.527220 -0.693985 -0.308933 +VERTEX_SE2 21 4.152895 -0.850915 -0.191238 +VERTEX_SE2 22 4.779015 -0.992339 -0.168556 +VERTEX_SE2 23 5.423978 -1.030005 -0.054484 +VERTEX_SE2 24 6.064382 -1.090997 -0.105423 +VERTEX_SE2 25 6.707928 -1.144401 -0.096821 +VERTEX_SE2 26 7.315680 -1.224079 -0.137153 +VERTEX_SE2 27 7.929761 -1.294250 -0.121079 +VERTEX_SE2 28 8.510243 -1.372635 -0.125240 +VERTEX_SE2 29 8.886549 -1.416447 -0.094136 +VERTEX_SE2 30 8.893462 -1.418023 -0.625522 +VERTEX_SE2 31 9.005697 -1.557779 -0.893355 +VERTEX_SE2 32 9.398300 -2.067296 -0.911506 +VERTEX_SE2 33 9.800909 -2.566880 -0.858368 +VERTEX_SE2 34 10.230894 -3.045076 -0.834898 +VERTEX_SE2 35 10.670845 -3.512974 -0.797906 +VERTEX_SE2 36 11.118351 -3.980273 -0.803680 +VERTEX_SE2 37 11.413882 -4.282108 -0.793023 +VERTEX_SE2 38 11.416535 -4.285316 -1.109584 +VERTEX_SE2 39 11.425445 -4.316267 -1.276487 +VERTEX_SE2 40 11.612551 -4.916547 -1.255922 +VERTEX_SE2 41 11.808527 -5.541274 -1.284316 +VERTEX_SE2 42 11.976726 -6.133098 -1.303279 +VERTEX_SE2 43 12.132495 -6.760248 -1.339357 +VERTEX_SE2 44 12.273339 -7.389611 -1.372003 +VERTEX_SE2 45 12.381155 -8.023418 -1.427426 +VERTEX_SE2 46 12.464524 -8.661631 -1.446702 +VERTEX_SE2 47 12.536773 -9.300726 -1.488240 +VERTEX_SE2 48 12.585187 -9.946461 -1.494639 +VERTEX_SE2 49 12.629508 -10.588502 -1.545288 +VERTEX_SE2 50 12.623735 -11.202499 -1.589586 +VERTEX_SE2 51 12.613473 -11.816834 -1.619614 +VERTEX_SE2 52 12.558110 -12.427134 -1.697131 +VERTEX_SE2 53 12.497320 -13.013155 -1.685264 +VERTEX_SE2 54 12.418711 -13.557683 -1.747661 +VERTEX_SE2 55 12.419724 -13.549747 -1.742676 +VERTEX_SE2 56 12.414345 -13.580353 -1.732396 +VERTEX_SE2 57 12.310914 -14.233877 -1.743844 +VERTEX_SE2 58 12.203756 -14.876538 -1.697418 +VERTEX_SE2 59 12.115088 -15.515348 -1.720561 +VERTEX_SE2 60 12.025760 -16.150800 -1.698500 +VERTEX_SE2 61 11.930749 -16.787980 -1.748266 +VERTEX_SE2 62 11.833006 -17.390733 -1.709239 +VERTEX_SE2 63 11.733602 -17.998517 -1.746382 +VERTEX_SE2 64 11.649132 -18.607583 -1.685617 +VERTEX_SE2 65 11.563367 -19.214882 -1.740522 +VERTEX_SE2 66 11.460058 -19.848621 -1.752656 +VERTEX_SE2 67 11.343148 -20.481952 -1.756181 +VERTEX_SE2 68 11.257571 -20.955257 -1.774331 +VERTEX_SE2 69 11.255185 -20.964979 -1.932353 +VERTEX_SE2 70 11.251937 -20.972069 -2.613265 +VERTEX_SE2 71 11.258227 -20.971402 3.020985 +VERTEX_SE2 72 11.258227 -20.971402 3.009195 +VERTEX_SE2 73 11.254702 -20.970679 2.941681 +VERTEX_SE2 74 11.251643 -20.968771 2.313797 +VERTEX_SE2 75 11.250298 -20.968291 1.957266 +VERTEX_SE2 76 11.239515 -20.956998 2.644600 +VERTEX_SE2 77 11.227570 -20.952338 2.874132 +VERTEX_SE2 78 10.929861 -20.969392 -3.076000 +VERTEX_SE2 79 10.295660 -21.019100 -3.083625 +VERTEX_SE2 80 9.648073 -21.026221 3.122276 +VERTEX_SE2 81 9.008652 -21.005804 3.093707 +VERTEX_SE2 82 8.367330 -20.952196 3.043418 +VERTEX_SE2 83 7.730227 -20.888698 3.024388 +VERTEX_SE2 84 7.095779 -20.785072 2.952781 +VERTEX_SE2 85 6.465179 -20.660326 2.966718 +VERTEX_SE2 86 5.750805 -20.513125 2.886729 +VERTEX_SE2 87 5.163554 -20.341011 2.848617 +VERTEX_SE2 88 4.815868 -20.234565 2.823505 +VERTEX_SE2 89 4.792324 -20.235107 -3.054605 +VERTEX_SE2 90 4.149209 -20.288628 -3.081395 +VERTEX_SE2 91 3.497178 -20.337577 -3.028289 +VERTEX_SE2 92 2.861629 -20.387679 -3.140035 +VERTEX_SE2 93 2.221011 -20.339858 3.045531 +VERTEX_SE2 94 1.585959 -20.258625 3.005168 +VERTEX_SE2 95 0.940663 -20.228767 -3.139936 +VERTEX_SE2 96 0.302216 -20.232542 -3.119921 +VERTEX_SE2 97 -0.314018 -20.219530 3.087656 +VERTEX_SE2 98 -0.922581 -20.164719 3.024330 +VERTEX_SE2 99 -1.648795 -20.093526 3.065410 +VERTEX_SE2 100 -2.230833 -20.023281 3.007277 +VERTEX_SE2 101 -2.871354 -20.005103 3.102942 +VERTEX_SE2 102 -3.516483 -19.955697 3.008603 +VERTEX_SE2 103 -4.152223 -19.878149 3.115724 +VERTEX_SE2 104 -4.795838 -19.847155 3.090758 +VERTEX_SE2 105 -5.440965 -19.834033 -3.137000 +VERTEX_SE2 106 -6.074366 -19.819256 3.099547 +VERTEX_SE2 107 -6.721384 -19.784913 3.102775 +VERTEX_SE2 108 -7.140409 -19.781530 -3.121388 +VERTEX_SE2 109 -7.153321 -19.779550 2.708464 +VERTEX_SE2 110 -7.164494 -19.769929 2.111343 +VERTEX_SE2 111 -7.174123 -19.662635 1.600354 +VERTEX_SE2 112 -7.201482 -19.000514 1.652438 +VERTEX_SE2 113 -7.269988 -18.356059 1.697296 +VERTEX_SE2 114 -7.351668 -17.722124 1.732079 +VERTEX_SE2 115 -7.477063 -17.090635 1.787906 +VERTEX_SE2 116 -7.655600 -16.348269 1.827325 +VERTEX_SE2 117 -7.838440 -15.740356 1.917383 +VERTEX_SE2 118 -7.847180 -15.710500 1.574139 +VERTEX_SE2 119 -7.822729 -15.211952 1.515457 +VERTEX_SE2 120 -7.806541 -14.573234 1.599604 +VERTEX_SE2 121 -7.846755 -13.965257 1.661084 +VERTEX_SE2 122 -7.908309 -13.357352 1.710992 +VERTEX_SE2 123 -7.944931 -13.145472 1.692222 +VERTEX_SE2 124 -7.867047 -12.909702 1.255856 +VERTEX_SE2 125 -7.662551 -12.318719 1.238631 +VERTEX_SE2 126 -7.536130 -11.694942 1.435606 +VERTEX_SE2 127 -7.446823 -11.065323 1.432524 +VERTEX_SE2 128 -7.378220 -10.424022 1.466677 +VERTEX_SE2 129 -7.297629 -9.790420 1.431058 +VERTEX_SE2 130 -7.233612 -9.152396 1.479951 +VERTEX_SE2 131 -7.188908 -8.512333 1.563552 +VERTEX_SE2 132 -7.169731 -7.871150 1.508512 +VERTEX_SE2 133 -7.117635 -7.291335 1.466418 +VERTEX_SE2 134 -7.055851 -6.684237 1.442294 +VERTEX_SE2 135 -6.963757 -6.111663 1.409225 +VERTEX_SE2 136 -6.874804 -5.474955 1.421265 +VERTEX_SE2 137 -6.760504 -4.850881 1.369865 +VERTEX_SE2 138 -6.660597 -4.217332 1.438397 +VERTEX_SE2 139 -6.600415 -3.595492 1.503413 +VERTEX_SE2 140 -6.582744 -2.945853 1.533669 +VERTEX_SE2 141 -6.543894 -2.313106 1.484948 +VERTEX_SE2 142 -6.498552 -1.671107 1.480848 +VERTEX_SE2 143 -6.373361 -1.045821 1.369956 +VERTEX_SE2 144 -6.308206 -0.684059 1.387205 +VERTEX_SE2 145 -6.303725 -0.673188 0.888171 +VERTEX_SE2 146 -6.303130 -0.671010 0.294225 +VERTEX_SE2 147 -6.246280 -0.679152 -0.192923 +VERTEX_SE2 148 -5.818303 -0.770932 -0.228866 +VERTEX_SE2 149 -5.184464 -0.911850 -0.204032 +VERTEX_SE2 150 -4.555178 -1.023116 -0.190122 +VERTEX_SE2 151 -3.919217 -1.117808 -0.104723 +VERTEX_SE2 152 -3.282062 -1.199418 -0.172903 +VERTEX_SE2 153 -2.645312 -1.282994 -0.087181 +VERTEX_SE2 154 -2.011150 -1.359207 -0.164419 +VERTEX_SE2 155 -1.375820 -1.453297 -0.137992 +VERTEX_SE2 156 -0.735790 -1.532677 -0.114327 +VERTEX_SE2 157 -0.159947 -1.613323 -0.186690 +VERTEX_SE2 158 0.023851 -1.648467 -0.157600 +VERTEX_SE2 159 0.021228 -1.647288 0.835817 +VERTEX_SE2 160 0.027488 -1.639228 1.877886 +VERTEX_SE2 161 0.027486 -1.639234 2.859828 +VERTEX_SE2 162 0.045975 -1.631965 -2.381155 +VERTEX_SE2 163 0.045893 -1.634205 -1.377922 +VERTEX_SE2 164 0.057499 -1.646265 -0.447964 +VERTEX_SE2 165 0.193934 -1.655710 -0.045831 +VERTEX_SE2 166 0.853469 -1.682017 -0.046800 +VERTEX_SE2 167 1.490484 -1.716964 -0.075973 +VERTEX_SE2 168 2.098800 -1.751671 -0.063936 +VERTEX_SE2 169 2.712806 -1.808931 -0.100989 +VERTEX_SE2 170 3.318192 -1.863258 -0.121905 +VERTEX_SE2 171 3.896234 -1.949098 -0.160646 +VERTEX_SE2 172 4.538410 -2.042425 -0.147172 +VERTEX_SE2 173 5.172424 -2.149723 -0.165214 +VERTEX_SE2 174 5.803089 -2.247662 -0.120052 +VERTEX_SE2 175 6.424807 -2.318550 -0.139998 +VERTEX_SE2 176 7.030678 -2.417232 -0.125711 +VERTEX_SE2 177 7.660479 -2.494551 -0.148623 +VERTEX_SE2 178 8.290147 -2.612123 -0.182806 +VERTEX_SE2 179 8.639509 -2.668503 -0.129585 +VERTEX_SE2 180 8.642601 -2.669171 -0.571750 +VERTEX_SE2 181 9.107062 -2.977761 -0.623138 +VERTEX_SE2 182 9.551340 -3.341562 -0.796106 +VERTEX_SE2 183 9.953562 -3.792478 -0.852123 +VERTEX_SE2 184 10.330878 -4.306658 -1.002936 +VERTEX_SE2 185 10.652963 -4.854256 -1.099221 +VERTEX_SE2 186 10.909459 -5.445570 -1.168989 +VERTEX_SE2 187 11.138453 -6.018162 -1.194573 +VERTEX_SE2 188 11.372847 -6.610777 -1.202696 +VERTEX_SE2 189 11.598101 -7.209159 -1.232095 +VERTEX_SE2 190 11.795596 -7.819838 -1.258284 +VERTEX_SE2 191 11.984938 -8.432395 -1.279246 +VERTEX_SE2 192 12.158054 -9.043198 -1.303901 +VERTEX_SE2 193 12.302583 -9.611434 -1.355161 +VERTEX_SE2 194 12.426909 -10.210284 -1.377141 +VERTEX_SE2 195 12.534319 -10.811416 -1.400368 +VERTEX_SE2 196 12.632338 -11.445843 -1.442220 +VERTEX_SE2 197 12.700713 -12.082422 -1.470453 +VERTEX_SE2 198 12.755597 -12.719166 -1.529113 +VERTEX_SE2 199 12.754761 -13.356843 -1.590711 +VERTEX_SE2 200 12.733560 -13.993458 -1.612475 +VERTEX_SE2 201 12.687026 -14.631689 -1.668718 +VERTEX_SE2 202 12.639077 -15.202899 -1.651577 +VERTEX_SE2 203 12.556158 -16.006543 -1.707054 +VERTEX_SE2 204 12.455302 -16.598850 -1.804142 +VERTEX_SE2 205 12.305924 -17.187841 -1.809172 +VERTEX_SE2 206 12.174405 -17.760149 -1.802549 +VERTEX_SE2 207 12.040676 -18.353284 -1.781423 +VERTEX_SE2 208 11.897670 -18.981299 -1.785518 +VERTEX_SE2 209 11.769917 -19.609340 -1.741125 +VERTEX_SE2 210 11.647398 -20.238835 -1.754048 +VERTEX_SE2 211 11.537207 -20.870318 -1.755716 +VERTEX_SE2 212 11.394970 -21.493361 -1.812926 +VERTEX_SE2 213 11.230953 -22.120731 -1.837752 +VERTEX_SE2 214 11.058372 -22.734177 -1.845436 +VERTEX_SE2 215 10.953834 -23.088866 -1.885350 +VERTEX_SE2 216 10.950554 -23.095138 -2.393113 +VERTEX_SE2 217 10.952753 -23.094815 -2.944927 +VERTEX_SE2 218 10.951809 -23.094487 -3.005204 +VERTEX_SE2 219 10.365803 -23.067344 3.104107 +VERTEX_SE2 220 9.737327 -23.038247 3.059963 +VERTEX_SE2 221 9.095837 -22.994717 3.111718 +VERTEX_SE2 222 8.460944 -22.975047 3.086737 +VERTEX_SE2 223 7.821250 -22.969336 -3.100192 +VERTEX_SE2 224 7.183803 -22.994444 -3.126677 +VERTEX_SE2 225 6.544582 -23.012637 -3.078368 +VERTEX_SE2 226 5.906305 -23.029186 -3.129535 +VERTEX_SE2 227 5.264179 -23.084344 -2.972817 +VERTEX_SE2 228 4.660809 -23.049652 2.951621 +VERTEX_SE2 229 4.059169 -22.969281 3.076549 +VERTEX_SE2 230 3.689211 -22.947652 3.051106 +VERTEX_SE2 231 3.819912 -22.954624 3.124109 +VERTEX_SE2 232 3.476990 -22.813142 2.710350 +VERTEX_SE2 233 2.875321 -22.565879 2.819555 +VERTEX_SE2 234 2.261463 -22.358960 2.781360 +VERTEX_SE2 235 1.979653 -22.255530 2.781875 +VERTEX_SE2 236 1.616344 -22.278805 -3.083673 +VERTEX_SE2 237 0.964219 -22.341873 -3.006771 +VERTEX_SE2 238 0.323899 -22.443278 -3.033605 +VERTEX_SE2 239 -0.317791 -22.494927 -3.094849 +VERTEX_SE2 240 -0.925503 -22.426348 2.978831 +VERTEX_SE2 241 -1.504549 -22.345735 3.071089 +VERTEX_SE2 242 -2.117312 -22.325210 3.098446 +VERTEX_SE2 243 -2.764025 -22.279874 3.087887 +VERTEX_SE2 244 -3.406724 -22.271623 -3.133223 +VERTEX_SE2 245 -4.041131 -22.254659 3.087973 +VERTEX_SE2 246 -4.684337 -22.191483 3.008717 +VERTEX_SE2 247 -5.325218 -22.128855 3.108731 +VERTEX_SE2 248 -5.890123 -22.137360 3.133698 +VERTEX_SE2 249 -5.854210 -22.141017 -2.965499 +VERTEX_SE2 250 -5.862024 -22.141342 2.710834 +VERTEX_SE2 251 -6.210340 -21.788237 2.273028 +VERTEX_SE2 252 -6.584399 -21.351579 2.275461 +VERTEX_SE2 253 -6.971866 -20.886741 2.258217 +VERTEX_SE2 254 -7.349642 -20.406697 2.210371 +VERTEX_SE2 255 -7.376562 -20.371386 2.285362 +VERTEX_SE2 256 -7.376569 -20.370011 1.785796 +VERTEX_SE2 257 -7.435125 -19.813876 1.686629 +VERTEX_SE2 258 -7.526140 -19.190499 1.778261 +VERTEX_SE2 259 -7.676213 -18.571996 1.817167 +VERTEX_SE2 260 -7.815262 -17.997419 1.807084 +VERTEX_SE2 261 -7.812802 -17.957528 1.492756 +VERTEX_SE2 262 -7.748761 -17.305023 1.497634 +VERTEX_SE2 263 -7.704459 -16.684761 1.509160 +VERTEX_SE2 264 -7.686285 -16.075835 1.603801 +VERTEX_SE2 265 -7.713685 -15.464092 1.621756 +VERTEX_SE2 266 -7.659836 -14.884512 1.489698 +VERTEX_SE2 267 -7.590637 -14.130213 1.451229 +VERTEX_SE2 268 -7.434892 -13.512524 1.330524 +VERTEX_SE2 269 -7.285843 -12.888133 1.352351 +VERTEX_SE2 270 -7.181145 -12.258185 1.457078 +VERTEX_SE2 271 -7.046662 -11.629374 1.337392 +VERTEX_SE2 272 -6.916330 -10.998172 1.394889 +VERTEX_SE2 273 -6.887272 -10.359052 1.601643 +VERTEX_SE2 274 -6.914937 -9.718617 1.621477 +VERTEX_SE2 275 -6.859410 -9.108548 1.443918 +VERTEX_SE2 276 -6.805341 -8.498288 1.552614 +VERTEX_SE2 277 -6.805090 -7.914615 1.521694 +VERTEX_SE2 278 -6.706035 -7.282637 1.426405 +VERTEX_SE2 279 -6.600956 -6.648396 1.372248 +VERTEX_SE2 280 -6.468990 -6.023366 1.375327 +VERTEX_SE2 281 -6.315271 -5.399485 1.276051 +VERTEX_SE2 282 -6.134008 -4.785899 1.316907 +VERTEX_SE2 283 -5.985222 -4.161193 1.309959 +VERTEX_SE2 284 -5.813249 -3.550243 1.337990 +VERTEX_SE2 285 -5.683475 -2.918967 1.354789 +VERTEX_SE2 286 -5.554450 -2.315719 1.403911 +VERTEX_SE2 287 -5.547714 -2.274662 1.294491 +VERTEX_SE2 288 -5.541900 -2.266525 0.674528 +VERTEX_SE2 289 -5.522271 -2.259034 0.069939 +VERTEX_SE2 290 -5.061939 -2.331133 -0.161343 +VERTEX_SE2 291 -4.422087 -2.430958 -0.151620 +VERTEX_SE2 292 -3.797538 -2.541567 -0.206901 +VERTEX_SE2 293 -3.169915 -2.679421 -0.230678 +VERTEX_SE2 294 -2.547430 -2.824259 -0.230786 +VERTEX_SE2 295 -1.930374 -2.997710 -0.344395 +VERTEX_SE2 296 -1.332265 -3.234619 -0.390911 +VERTEX_SE2 297 -0.738078 -3.478649 -0.403774 +VERTEX_SE2 298 -0.140714 -3.729757 -0.400411 +VERTEX_SE2 299 0.420679 -3.975672 -0.334750 +VERTEX_SE2 300 1.008544 -4.149557 -0.288323 +VERTEX_SE2 301 1.570135 -4.331714 -0.343252 +VERTEX_SE2 302 1.877809 -4.442855 -0.360266 +VERTEX_SE2 303 1.877809 -4.442855 -0.352308 +VERTEX_SE2 304 2.376686 -4.626875 -0.338959 +VERTEX_SE2 305 3.003258 -4.750507 -0.149877 +VERTEX_SE2 306 3.635522 -4.836601 -0.164412 +VERTEX_SE2 307 4.273138 -4.958970 -0.197471 +VERTEX_SE2 308 4.897872 -5.092864 -0.249303 +VERTEX_SE2 309 5.530724 -5.222563 -0.152307 +VERTEX_SE2 310 6.160264 -5.318301 -0.184629 +VERTEX_SE2 311 6.445365 -5.373694 -0.004883 +VERTEX_SE2 312 6.452735 -5.370466 0.998034 +VERTEX_SE2 313 6.475194 -5.146827 1.501717 +VERTEX_SE2 314 6.500598 -4.513221 1.545236 +VERTEX_SE2 315 6.514519 -3.879666 1.544361 +VERTEX_SE2 316 6.515603 -3.240166 1.596992 +VERTEX_SE2 317 6.494598 -2.602753 1.608134 +VERTEX_SE2 318 6.435460 -1.967773 1.704091 +VERTEX_SE2 319 6.377663 -1.623559 1.776803 +VERTEX_SE2 320 6.378012 -1.622652 2.750031 +VERTEX_SE2 321 6.369361 -1.625849 -2.488361 +VERTEX_SE2 322 6.365946 -1.632038 -1.487277 +VERTEX_SE2 323 6.380435 -1.647235 -0.490000 +VERTEX_SE2 324 6.388880 -1.650346 0.173199 +VERTEX_SE2 325 6.392046 -1.650203 -0.351692 +VERTEX_SE2 326 6.411655 -1.665878 -0.943866 +VERTEX_SE2 327 6.415870 -1.688728 -1.564092 +VERTEX_SE2 328 6.385292 -2.332605 -1.609333 +VERTEX_SE2 329 6.349431 -2.981039 -1.664005 +VERTEX_SE2 330 6.281461 -3.617106 -1.682877 +VERTEX_SE2 331 6.213453 -4.254537 -1.697056 +VERTEX_SE2 332 6.121245 -4.888223 -1.715483 +VERTEX_SE2 333 6.093922 -5.063750 -1.650313 +VERTEX_SE2 334 6.091827 -5.064491 -0.592795 +VERTEX_SE2 335 6.120861 -5.065606 0.404271 +VERTEX_SE2 336 6.129696 -5.059618 1.351179 +VERTEX_SE2 337 6.128718 -5.050440 2.336187 +VERTEX_SE2 338 6.132587 -5.051833 -2.965274 +VERTEX_SE2 339 6.136968 -5.047185 -1.923597 +VERTEX_SE2 340 6.142971 -5.060659 -0.911817 +VERTEX_SE2 341 6.275970 -5.101488 -0.283246 +VERTEX_SE2 342 6.910811 -5.263299 -0.183431 +VERTEX_SE2 343 7.538989 -5.324161 -0.052630 +VERTEX_SE2 344 8.173624 -5.364758 -0.062705 +VERTEX_SE2 345 8.440897 -5.378047 -0.090243 +VERTEX_SE2 346 8.445372 -5.378415 -0.737666 +VERTEX_SE2 347 8.467770 -5.462068 -1.296495 +VERTEX_SE2 348 8.621467 -6.030776 -1.313338 +VERTEX_SE2 349 8.761762 -6.631679 -1.353796 +VERTEX_SE2 350 8.929986 -7.398958 -1.373714 +VERTEX_SE2 351 8.978041 -7.665351 -1.403006 +VERTEX_SE2 352 8.978090 -7.667619 -1.691302 +VERTEX_SE2 353 8.976498 -7.670853 -2.356727 +VERTEX_SE2 354 8.981756 -7.667962 -2.960124 +VERTEX_SE2 355 8.981756 -7.667962 2.602071 +VERTEX_SE2 356 8.978992 -7.664902 2.026818 +VERTEX_SE2 357 8.977837 -7.643021 1.373746 +VERTEX_SE2 358 8.983884 -7.628618 0.758292 +VERTEX_SE2 359 8.989631 -7.624545 0.144263 +VERTEX_SE2 360 8.994126 -7.624478 -0.032038 +VERTEX_SE2 361 9.004896 -7.619118 0.887338 +VERTEX_SE2 362 9.042246 -7.366063 1.421081 +VERTEX_SE2 363 9.090049 -7.072841 1.414605 +VERTEX_SE2 364 8.954880 -6.758641 2.029221 +VERTEX_SE2 365 8.843129 -6.487231 1.532139 +VERTEX_SE2 366 8.933049 -6.331605 0.978068 +VERTEX_SE2 367 9.294391 -5.803956 0.980155 +VERTEX_SE2 368 9.641307 -5.309201 0.927211 +VERTEX_SE2 369 9.642383 -5.307246 0.668025 +VERTEX_SE2 370 9.648356 -5.305144 0.068704 +VERTEX_SE2 371 9.655229 -5.307316 -0.488502 +VERTEX_SE2 372 10.139103 -5.587085 -0.520850 +VERTEX_SE2 373 10.666751 -5.878088 -0.523177 +VERTEX_SE2 374 11.206068 -6.209159 -0.589126 +VERTEX_SE2 375 11.598593 -6.466633 -0.617897 +VERTEX_SE2 376 11.600632 -6.467490 0.080627 +VERTEX_SE2 377 11.643620 -6.425565 0.779646 +VERTEX_SE2 378 12.107190 -5.948151 0.834726 +VERTEX_SE2 379 12.510240 -5.446009 0.920455 +VERTEX_SE2 380 12.867606 -4.912917 1.040753 +VERTEX_SE2 381 12.982544 -4.709680 1.191659 +VERTEX_SE2 382 12.984649 -4.703709 2.244782 +VERTEX_SE2 383 12.988448 -4.705226 -3.058347 +VERTEX_SE2 384 12.986650 -4.707628 -2.101256 +VERTEX_SE2 385 12.982495 -4.718256 -1.078274 +VERTEX_SE2 386 13.111397 -4.840399 -0.855882 +VERTEX_SE2 387 13.631915 -5.191372 -0.527133 +VERTEX_SE2 388 14.188298 -5.499440 -0.516375 +VERTEX_SE2 389 14.722428 -5.830510 -0.596695 +VERTEX_SE2 390 14.780394 -5.868314 -0.117993 +VERTEX_SE2 391 14.643686 -5.885580 0.265004 +VERTEX_SE2 392 14.640989 -5.886114 1.312766 +VERTEX_SE2 393 14.635188 -5.855400 2.572219 +VERTEX_SE2 394 14.626068 -5.853862 -2.712409 +VERTEX_SE2 395 14.810464 -5.693039 -2.372812 +VERTEX_SE2 396 14.810464 -5.693039 -2.371562 +VERTEX_SE2 397 14.809202 -5.693678 -2.381203 +VERTEX_SE2 398 14.806796 -5.697007 -2.182098 +VERTEX_SE2 399 14.762364 -5.814932 -1.881357 +VERTEX_SE2 400 14.564819 -6.441727 -1.829942 +VERTEX_SE2 401 14.377600 -7.049960 -1.921842 +VERTEX_SE2 402 14.049396 -7.600148 -2.188305 +VERTEX_SE2 403 13.678588 -8.113304 -2.221999 +VERTEX_SE2 404 13.306297 -8.574268 -2.300702 +VERTEX_SE2 405 13.304585 -8.576945 -1.766179 +VERTEX_SE2 406 13.302371 -8.571544 -0.786819 +VERTEX_SE2 407 13.585994 -8.797369 -0.658504 +VERTEX_SE2 408 14.069560 -9.180165 -0.696311 +VERTEX_SE2 409 14.292699 -9.377696 -0.795739 +VERTEX_SE2 410 14.294947 -9.381536 -1.423249 +VERTEX_SE2 411 14.294896 -9.380539 -2.012202 +VERTEX_SE2 412 13.969601 -9.830799 -2.215053 +VERTEX_SE2 413 13.573781 -10.323212 -2.294584 +VERTEX_SE2 414 13.168212 -10.809845 -2.190851 +VERTEX_SE2 415 12.788348 -11.328437 -2.184168 +VERTEX_SE2 416 12.618672 -11.583273 -2.239720 +VERTEX_SE2 417 12.365589 -11.724804 -2.664770 +VERTEX_SE2 418 11.973570 -11.921372 -2.710238 +VERTEX_SE2 419 11.979618 -11.915306 -2.279799 +VERTEX_SE2 420 12.016291 -11.860711 -2.064037 +VERTEX_SE2 421 12.016287 -11.845604 -1.097383 +VERTEX_SE2 422 12.016575 -11.841230 0.140539 +VERTEX_SE2 423 12.021144 -11.838978 0.485675 +VERTEX_SE2 424 12.021144 -11.838978 0.485954 +VERTEX_SE2 425 12.020459 -11.840215 0.497589 +VERTEX_SE2 426 12.020459 -11.840215 0.488372 +VERTEX_SE2 427 12.049082 -11.824671 0.491399 +VERTEX_SE2 428 12.625045 -11.496891 0.485740 +VERTEX_SE2 429 13.200413 -11.202813 0.444713 +VERTEX_SE2 430 13.512701 -11.059854 0.398340 +VERTEX_SE2 431 13.491669 -11.069431 0.449977 +VERTEX_SE2 432 13.501654 -11.067336 -0.182740 +VERTEX_SE2 433 13.502954 -11.067884 -0.861102 +VERTEX_SE2 434 13.743529 -11.537644 -1.089862 +VERTEX_SE2 435 14.040604 -12.094609 -1.118566 +VERTEX_SE2 436 14.297216 -12.672347 -1.127731 +VERTEX_SE2 437 14.580075 -13.245886 -1.120167 +VERTEX_SE2 438 14.774602 -13.672697 -1.152842 +VERTEX_SE2 439 14.775466 -13.675785 -1.592980 +VERTEX_SE2 440 14.781226 -13.661057 -2.241615 +VERTEX_SE2 441 14.801541 -13.646476 -2.868987 +VERTEX_SE2 442 14.816809 -13.646193 2.779417 +VERTEX_SE2 443 14.817345 -13.647038 2.207553 +VERTEX_SE2 444 14.811569 -13.629249 1.610879 +VERTEX_SE2 445 14.815891 -13.615770 0.947107 +VERTEX_SE2 446 14.818888 -13.610711 1.145697 +VERTEX_SE2 447 14.818661 -13.580487 1.771810 +VERTEX_SE2 448 14.666760 -12.956104 1.786852 +VERTEX_SE2 449 14.494693 -12.326428 1.885308 +VERTEX_SE2 450 14.289690 -11.713731 1.896557 +VERTEX_SE2 451 14.124257 -11.267884 1.936509 +VERTEX_SE2 452 14.123115 -11.264972 1.553661 +VERTEX_SE2 453 14.123047 -11.266384 0.924731 +VERTEX_SE2 454 14.355665 -11.130372 0.497531 +VERTEX_SE2 455 14.885259 -10.850245 0.477764 +VERTEX_SE2 456 15.454443 -10.572873 0.414138 +VERTEX_SE2 457 15.786015 -10.438633 0.327481 +VERTEX_SE2 458 15.795226 -10.438701 -0.315965 +VERTEX_SE2 459 15.791330 -10.434037 -0.921822 +VERTEX_SE2 460 15.959734 -10.828507 -1.177398 +VERTEX_SE2 461 16.180144 -11.439953 -1.264281 +VERTEX_SE2 462 16.335308 -11.963645 -1.303337 +VERTEX_SE2 463 16.335291 -11.965068 -0.460067 +VERTEX_SE2 464 16.605696 -11.914838 0.220623 +VERTEX_SE2 465 17.195283 -11.771695 0.229379 +VERTEX_SE2 466 17.767104 -11.657874 0.174926 +VERTEX_SE2 467 18.369280 -11.563197 0.132707 +VERTEX_SE2 468 19.009735 -11.482106 0.096378 +VERTEX_SE2 469 19.650896 -11.453733 0.012587 +VERTEX_SE2 470 20.146853 -11.442829 0.030741 +VERTEX_SE2 471 20.150029 -11.442932 -0.170062 +VERTEX_SE2 472 20.172311 -11.454699 -0.804400 +VERTEX_SE2 473 20.175889 -11.459298 -1.446679 +VERTEX_SE2 474 20.174399 -11.466191 -2.079685 +VERTEX_SE2 475 20.170246 -11.468957 -2.655668 +VERTEX_SE2 476 20.165497 -11.470500 2.973880 +VERTEX_SE2 477 20.170525 -11.474309 2.412190 +VERTEX_SE2 478 20.175145 -11.482300 1.782778 +VERTEX_SE2 479 20.175335 -11.487697 1.326596 +VERTEX_SE2 480 20.175383 -11.489918 1.886460 +VERTEX_SE2 481 20.164295 -11.475887 2.884919 +VERTEX_SE2 482 20.162062 -11.476008 -3.063751 +VERTEX_SE2 483 20.162062 -11.476008 -3.070064 +VERTEX_SE2 484 19.701970 -11.512371 -3.035533 +VERTEX_SE2 485 19.076677 -11.593317 -3.038332 +VERTEX_SE2 486 18.439371 -11.653164 -3.029341 +VERTEX_SE2 487 17.807280 -11.746714 -3.001669 +VERTEX_SE2 488 17.172291 -11.839127 -2.966212 +VERTEX_SE2 489 16.696147 -11.938931 -2.936476 +VERTEX_SE2 490 16.692490 -11.941051 -2.452793 +VERTEX_SE2 491 16.691616 -11.944932 -1.519098 +VERTEX_SE2 492 16.776617 -12.175290 -1.217149 +VERTEX_SE2 493 16.974062 -12.765556 -1.272900 +VERTEX_SE2 494 17.150447 -13.373462 -1.334510 +VERTEX_SE2 495 17.352115 -13.978346 -1.223707 +VERTEX_SE2 496 17.581624 -14.577196 -1.102707 +VERTEX_SE2 497 17.847299 -15.159575 -1.186084 +VERTEX_SE2 498 18.054425 -15.760767 -1.285551 +VERTEX_SE2 499 18.205483 -16.382164 -1.300921 +VERTEX_SE2 500 18.520086 -16.898620 -0.969638 +VERTEX_SE2 501 18.848430 -17.411482 -1.035455 +VERTEX_SE2 502 19.181866 -18.047877 -1.113614 +VERTEX_SE2 503 19.382829 -18.470616 -1.125142 +VERTEX_SE2 504 19.382968 -18.471669 -0.242877 +VERTEX_SE2 505 19.636847 -18.373822 0.396037 +VERTEX_SE2 506 20.222463 -18.152233 0.250781 +VERTEX_SE2 507 20.842906 -18.012083 0.178603 +VERTEX_SE2 508 21.473389 -17.912172 0.170945 +VERTEX_SE2 509 22.107555 -17.811551 0.119274 +VERTEX_SE2 510 22.477732 -17.773275 0.109324 +VERTEX_SE2 511 22.480191 -17.776579 1.000327 +VERTEX_SE2 512 22.479151 -17.767197 2.221724 +VERTEX_SE2 513 22.480923 -17.768589 -3.088724 +VERTEX_SE2 514 22.392210 -17.797083 -2.856452 +VERTEX_SE2 515 21.763760 -17.994866 -2.851524 +VERTEX_SE2 516 21.150540 -18.168893 -2.831780 +VERTEX_SE2 517 20.555780 -18.389856 -2.799728 +VERTEX_SE2 518 19.960512 -18.610158 -2.771638 +VERTEX_SE2 519 19.439217 -18.815169 -2.783788 +VERTEX_SE2 520 19.254408 -18.883689 -2.378354 +VERTEX_SE2 521 19.253544 -18.891468 -1.358862 +VERTEX_SE2 522 19.446557 -19.274210 -1.088837 +VERTEX_SE2 523 19.743533 -19.846628 -1.102099 +VERTEX_SE2 524 20.002482 -20.395419 -1.149751 +VERTEX_SE2 525 20.240546 -20.920829 -1.130979 +VERTEX_SE2 526 20.481533 -21.478440 -1.194565 +VERTEX_SE2 527 20.701007 -22.071838 -1.233424 +VERTEX_SE2 528 20.883349 -22.686071 -1.313266 +VERTEX_SE2 529 21.048790 -23.294125 -1.338785 +VERTEX_SE2 530 21.186548 -23.922294 -1.365903 +VERTEX_SE2 531 21.294513 -24.545568 -1.442267 +VERTEX_SE2 532 21.321981 -24.753969 -1.388289 +VERTEX_SE2 533 21.331696 -24.762834 -0.381514 +VERTEX_SE2 534 21.336665 -24.762597 0.290307 +VERTEX_SE2 535 21.336665 -24.762597 0.291645 +VERTEX_SE2 536 21.667408 -24.621679 0.424610 +VERTEX_SE2 537 22.237616 -24.383793 0.368660 +VERTEX_SE2 538 22.783578 -24.188298 0.343558 +VERTEX_SE2 539 23.392496 -23.994630 0.281055 +VERTEX_SE2 540 24.012651 -23.846863 0.190656 +VERTEX_SE2 541 24.616500 -23.677520 0.355935 +VERTEX_SE2 542 25.198874 -23.413487 0.414186 +VERTEX_SE2 543 25.308230 -23.366534 0.386937 +VERTEX_SE2 544 25.311458 -23.363477 1.030295 +VERTEX_SE2 545 25.308953 -23.348021 2.106974 +VERTEX_SE2 546 25.370099 -23.384281 2.942044 +VERTEX_SE2 547 25.364196 -23.389842 -2.309543 +VERTEX_SE2 548 25.360603 -23.401304 -1.377667 +VERTEX_SE2 549 25.371198 -23.418104 -0.563163 +VERTEX_SE2 550 25.376228 -23.423323 -1.037842 +VERTEX_SE2 551 25.379648 -23.436304 -1.657979 +VERTEX_SE2 552 25.377719 -23.441024 -2.284180 +VERTEX_SE2 553 25.238021 -23.493388 -2.855731 +VERTEX_SE2 554 24.607784 -23.677279 -2.888859 +VERTEX_SE2 555 23.993431 -23.860841 -2.797492 +VERTEX_SE2 556 23.396241 -24.105763 -2.659796 +VERTEX_SE2 557 22.822728 -24.393516 -2.702744 +VERTEX_SE2 558 22.275040 -24.674698 -2.623823 +VERTEX_SE2 559 22.270077 -24.676821 -3.034381 +VERTEX_SE2 560 22.270077 -24.676821 2.743761 +VERTEX_SE2 561 22.260080 -24.676351 -3.038320 +VERTEX_SE2 562 22.096754 -24.820650 -2.399936 +VERTEX_SE2 563 21.592502 -25.154311 -2.594747 +VERTEX_SE2 564 21.053412 -25.498706 -2.548499 +VERTEX_SE2 565 20.537425 -25.832798 -2.600465 +VERTEX_SE2 566 20.532490 -25.835035 -1.796294 +VERTEX_SE2 567 20.533426 -25.833987 -0.940208 +VERTEX_SE2 568 20.891388 -26.294540 -0.894012 +VERTEX_SE2 569 21.276856 -26.790552 -0.946159 +VERTEX_SE2 570 21.649420 -27.310717 -0.950967 +VERTEX_SE2 571 21.849361 -27.596250 -0.994364 +VERTEX_SE2 572 21.840333 -27.646492 -1.231717 +VERTEX_SE2 573 21.868880 -27.724009 -0.949072 +VERTEX_SE2 574 21.877216 -27.725452 0.006744 +VERTEX_SE2 575 21.894503 -27.715687 1.016050 +VERTEX_SE2 576 21.893519 -27.715892 2.040189 +VERTEX_SE2 577 21.885895 -27.713246 3.008947 +VERTEX_SE2 578 21.866274 -27.704702 2.643177 +VERTEX_SE2 579 21.298924 -27.387881 2.657278 +VERTEX_SE2 580 20.716909 -27.105551 2.731333 +VERTEX_SE2 581 20.125767 -26.856860 2.772637 +VERTEX_SE2 582 19.523535 -26.633599 2.814640 +VERTEX_SE2 583 19.213810 -26.536403 2.892766 +VERTEX_SE2 584 19.210319 -26.535584 -2.550218 +VERTEX_SE2 585 18.716874 -26.893765 -2.433208 +VERTEX_SE2 586 18.264978 -27.304159 -2.336932 +VERTEX_SE2 587 17.844050 -27.776684 -2.312675 +VERTEX_SE2 588 17.404102 -28.246717 -2.309353 +VERTEX_SE2 589 17.007668 -28.742973 -2.229083 +VERTEX_SE2 590 16.625023 -29.262060 -2.155304 +VERTEX_SE2 591 16.286319 -29.796280 -2.152683 +VERTEX_SE2 592 15.939159 -30.336565 -2.150686 +VERTEX_SE2 593 15.791190 -30.564791 -1.938181 +VERTEX_SE2 594 15.794250 -30.581455 -0.945084 +VERTEX_SE2 595 16.194292 -30.997078 -0.704760 +VERTEX_SE2 596 16.636104 -31.366417 -0.722635 +VERTEX_SE2 597 17.103989 -31.796447 -0.756770 +VERTEX_SE2 598 17.538795 -32.215917 -0.796372 +VERTEX_SE2 599 17.800839 -32.499098 -0.859831 +VERTEX_SE2 600 17.808423 -32.504032 -0.045074 +VERTEX_SE2 601 17.830600 -32.493623 0.983541 +VERTEX_SE2 602 17.834247 -32.474305 2.007952 +VERTEX_SE2 603 17.607884 -32.374428 2.788384 +VERTEX_SE2 604 17.046943 -32.100473 2.547892 +VERTEX_SE2 605 16.511286 -31.761753 2.630512 +VERTEX_SE2 606 15.949994 -31.464096 2.672598 +VERTEX_SE2 607 15.464785 -31.153778 2.591564 +VERTEX_SE2 608 15.140800 -30.969820 2.636022 +VERTEX_SE2 609 15.131468 -30.966068 2.972317 +VERTEX_SE2 610 15.122044 -30.973580 -2.378251 +VERTEX_SE2 611 14.678938 -31.406105 -2.375287 +VERTEX_SE2 612 14.313602 -31.741587 -2.372510 +VERTEX_SE2 613 14.338061 -31.720011 -1.908805 +VERTEX_SE2 614 14.338698 -31.726674 -0.870968 +VERTEX_SE2 615 14.768768 -31.977559 -0.566453 +VERTEX_SE2 616 15.311642 -32.305648 -0.617609 +VERTEX_SE2 617 15.760313 -32.746217 -0.834639 +VERTEX_SE2 618 16.193436 -33.214065 -0.824521 +VERTEX_SE2 619 16.601337 -33.656810 -0.825989 +VERTEX_SE2 620 17.000072 -34.120401 -0.922318 +VERTEX_SE2 621 16.788426 -33.839458 -0.973924 +VERTEX_SE2 622 16.630958 -33.597689 -1.048966 +VERTEX_SE2 623 16.629619 -33.594321 -1.586115 +VERTEX_SE2 624 16.631309 -33.591662 -2.228805 +VERTEX_SE2 625 16.624999 -33.596266 -2.887438 +VERTEX_SE2 626 16.617480 -33.597475 2.777619 +VERTEX_SE2 627 16.349285 -33.346497 2.366813 +VERTEX_SE2 628 15.919513 -32.868045 2.265896 +VERTEX_SE2 629 15.485805 -32.395397 2.336946 +VERTEX_SE2 630 15.046318 -31.973583 2.422035 +VERTEX_SE2 631 14.646636 -31.639639 2.442255 +VERTEX_SE2 632 14.643929 -31.637238 3.118464 +VERTEX_SE2 633 14.589597 -31.712326 -2.089116 +VERTEX_SE2 634 14.266192 -32.277649 -2.063889 +VERTEX_SE2 635 13.925936 -32.819825 -2.201180 +VERTEX_SE2 636 13.554818 -33.335756 -2.220264 +VERTEX_SE2 637 13.147645 -33.820778 -2.320948 +VERTEX_SE2 638 12.855265 -34.121161 -2.351695 +VERTEX_SE2 639 12.424371 -34.596136 -2.272930 +VERTEX_SE2 640 11.985578 -35.070016 -2.342632 +VERTEX_SE2 641 11.552638 -35.529379 -2.352802 +VERTEX_SE2 642 11.112191 -35.949492 -2.400353 +VERTEX_SE2 643 10.731895 -36.277399 -2.465381 +VERTEX_SE2 644 10.729340 -36.284109 -1.701776 +VERTEX_SE2 645 10.869715 -36.451460 -0.744873 +VERTEX_SE2 646 11.382066 -36.817597 -0.447477 +VERTEX_SE2 647 11.978978 -37.021611 -0.156322 +VERTEX_SE2 648 12.612056 -37.054234 0.012089 +VERTEX_SE2 649 13.205551 -37.119561 -0.322437 +VERTEX_SE2 650 13.749716 -37.452144 -0.576811 +VERTEX_SE2 651 13.876986 -37.522144 0.229018 +VERTEX_SE2 652 13.879256 -37.519914 1.262617 +VERTEX_SE2 653 13.872372 -37.502026 2.301465 +VERTEX_SE2 654 13.581181 -37.403460 2.818912 +VERTEX_SE2 655 13.048482 -37.219840 2.815600 +VERTEX_SE2 656 12.474722 -37.010334 2.804516 +VERTEX_SE2 657 11.844104 -36.899464 3.083365 +VERTEX_SE2 658 11.204549 -36.869297 3.076381 +VERTEX_SE2 659 10.709556 -36.810477 3.005332 +VERTEX_SE2 660 10.703219 -36.809512 -2.677502 +VERTEX_SE2 661 10.609221 -37.000250 -2.023854 +VERTEX_SE2 662 10.337163 -37.568215 -1.954223 +VERTEX_SE2 663 10.139552 -38.159090 -1.853215 +VERTEX_SE2 664 10.135226 -38.165415 -1.314901 +VERTEX_SE2 665 10.170577 -38.183639 -0.436050 +VERTEX_SE2 666 10.743964 -38.430041 -0.401598 +VERTEX_SE2 667 11.280508 -38.651643 -0.399484 +VERTEX_SE2 668 11.840921 -38.888748 -0.376305 +VERTEX_SE2 669 12.435464 -39.121854 -0.404047 +VERTEX_SE2 670 13.006910 -39.403898 -0.466305 +VERTEX_SE2 671 13.282608 -39.541377 -0.414044 +VERTEX_SE2 672 12.769426 -39.275957 -0.506105 +VERTEX_SE2 673 12.545541 -39.138628 -0.639846 +VERTEX_SE2 674 12.542473 -39.133012 -1.294945 +VERTEX_SE2 675 12.544204 -39.117309 -1.910166 +VERTEX_SE2 676 12.549939 -39.112303 -2.540226 +VERTEX_SE2 677 12.562810 -39.108340 3.120460 +VERTEX_SE2 678 12.373080 -39.013683 2.669222 +VERTEX_SE2 679 11.859571 -38.764102 2.729006 +VERTEX_SE2 680 11.438738 -38.641448 3.069344 +VERTEX_SE2 681 10.825052 -38.579071 3.043558 +VERTEX_SE2 682 10.191857 -38.531816 3.093190 +VERTEX_SE2 683 9.891918 -38.522270 -3.028351 +VERTEX_SE2 684 9.884198 -38.525775 -1.959011 +VERTEX_SE2 685 9.893810 -38.971112 -1.519535 +VERTEX_SE2 686 9.862204 -39.454619 -1.666211 +VERTEX_SE2 687 9.788467 -40.084236 -1.702984 +VERTEX_SE2 688 9.681861 -40.709183 -1.716237 +VERTEX_SE2 689 9.605655 -41.306367 -1.689887 +VERTEX_SE2 690 9.568647 -41.883115 -1.616935 +VERTEX_SE2 691 9.547797 -42.313693 -1.645939 +VERTEX_SE2 692 9.547338 -42.304642 -1.113930 +VERTEX_SE2 693 9.542348 -42.304320 -0.077783 +VERTEX_SE2 694 9.537355 -42.304058 0.754255 +VERTEX_SE2 695 9.537558 -42.302067 1.551174 +VERTEX_SE2 696 9.534841 -42.288755 2.572731 +VERTEX_SE2 697 9.523163 -42.279299 2.318206 +VERTEX_SE2 698 9.451431 -41.889589 1.660453 +VERTEX_SE2 699 9.371393 -41.248546 1.772879 +VERTEX_SE2 700 9.226326 -40.627573 1.824729 +VERTEX_SE2 701 9.049173 -40.073867 1.881983 +VERTEX_SE2 702 8.937709 -39.503989 1.764440 +VERTEX_SE2 703 8.820349 -38.895181 1.796436 +VERTEX_SE2 704 8.652821 -38.280287 1.812200 +VERTEX_SE2 705 8.469818 -37.662927 1.876685 +VERTEX_SE2 706 8.352303 -37.160636 1.599049 +VERTEX_SE2 707 8.353815 -37.156710 1.065513 +VERTEX_SE2 708 8.350433 -37.159057 0.410972 +VERTEX_SE2 709 8.285591 -37.179408 0.069240 +VERTEX_SE2 710 8.271325 -37.178203 -0.506017 +VERTEX_SE2 711 8.272256 -37.177853 -1.117758 +VERTEX_SE2 712 8.271421 -37.172816 -1.692402 +VERTEX_SE2 713 8.082147 -37.631033 -1.986694 +VERTEX_SE2 714 7.781665 -38.118818 -2.191858 +VERTEX_SE2 715 7.436278 -38.650634 -2.086627 +VERTEX_SE2 716 7.101560 -39.196310 -2.222833 +VERTEX_SE2 717 6.732648 -39.710336 -2.136309 +VERTEX_SE2 718 6.249991 -40.323558 -2.309481 +VERTEX_SE2 719 5.841996 -40.813346 -2.233064 +VERTEX_SE2 720 5.439595 -41.301667 -2.290296 +VERTEX_SE2 721 5.032639 -41.793490 -2.219961 +VERTEX_SE2 722 5.017459 -41.813716 -2.151150 +VERTEX_SE2 723 5.020505 -41.823419 -1.052793 +VERTEX_SE2 724 5.031411 -41.829247 0.024382 +VERTEX_SE2 725 5.041952 -41.823519 0.663795 +VERTEX_SE2 726 5.186097 -41.536150 1.121855 +VERTEX_SE2 727 5.441157 -40.953385 1.154429 +VERTEX_SE2 728 5.708786 -40.374749 1.157456 +VERTEX_SE2 729 5.942746 -39.779976 1.216830 +VERTEX_SE2 730 6.141286 -39.181998 1.255908 +VERTEX_SE2 731 6.337960 -38.578088 1.269244 +VERTEX_SE2 732 6.370731 -38.458677 1.718146 +VERTEX_SE2 733 6.369310 -38.458803 2.719136 +VERTEX_SE2 734 5.849568 -38.267284 2.798462 +VERTEX_SE2 735 5.287090 -38.058027 2.767482 +VERTEX_SE2 736 5.282360 -38.056088 -2.913613 +VERTEX_SE2 737 5.275781 -38.066121 -2.109607 +VERTEX_SE2 738 4.978024 -38.585828 -2.089531 +VERTEX_SE2 739 4.620518 -39.102322 -2.146106 +VERTEX_SE2 740 4.357016 -39.553955 -2.081799 +VERTEX_SE2 741 4.357431 -39.553064 -2.448926 +VERTEX_SE2 742 4.347527 -39.558696 -3.099199 +VERTEX_SE2 743 4.342558 -39.557580 2.569578 +VERTEX_SE2 744 4.336078 -39.550170 2.032393 +VERTEX_SE2 745 4.335980 -39.547933 1.441244 +VERTEX_SE2 746 4.573919 -39.080308 0.968419 +VERTEX_SE2 747 4.940154 -38.557294 0.934212 +VERTEX_SE2 748 5.302092 -38.106400 0.867038 +VERTEX_SE2 749 5.345738 -38.052022 1.298344 +VERTEX_SE2 750 5.342230 -38.047361 2.229268 +VERTEX_SE2 751 5.083575 -37.967511 2.872246 +VERTEX_SE2 752 4.493353 -37.766114 2.770046 +VERTEX_SE2 753 3.897446 -37.540993 2.834236 +VERTEX_SE2 754 3.312644 -37.288841 2.673214 +VERTEX_SE2 755 2.737782 -37.020556 2.749498 +VERTEX_SE2 756 2.174638 -36.731322 2.558054 +VERTEX_SE2 757 1.632084 -36.401074 2.656949 +VERTEX_SE2 758 1.085717 -36.165115 2.783429 +VERTEX_SE2 759 0.594312 -35.911010 2.644238 +VERTEX_SE2 760 0.049628 -35.662561 2.758388 +VERTEX_SE2 761 0.027544 -35.652794 2.941901 +VERTEX_SE2 762 0.026506 -35.653762 -2.331733 +VERTEX_SE2 763 -0.256374 -36.186295 -2.039623 +VERTEX_SE2 764 -0.462375 -36.581571 -2.067616 +VERTEX_SE2 765 -0.464849 -36.589741 -1.429340 +VERTEX_SE2 766 -0.458452 -36.594227 -0.430727 +VERTEX_SE2 767 -0.455458 -36.594045 0.498539 +VERTEX_SE2 768 -0.452643 -36.586959 1.219631 +VERTEX_SE2 769 -0.342345 -35.973305 1.375930 +VERTEX_SE2 770 -0.198947 -35.353053 1.308266 +VERTEX_SE2 771 -0.182607 -35.284960 1.867596 +VERTEX_SE2 772 -0.189467 -35.280006 2.733492 +VERTEX_SE2 773 -0.733580 -35.074067 2.818690 +VERTEX_SE2 774 -1.260348 -34.911848 2.840206 +VERTEX_SE2 775 -1.264437 -34.911446 -2.599985 +VERTEX_SE2 776 -1.363996 -35.119485 -1.984041 +VERTEX_SE2 777 -1.608279 -35.704951 -1.925618 +VERTEX_SE2 778 -1.822302 -36.299953 -1.947124 +VERTEX_SE2 779 -2.047440 -36.894571 -1.929730 +VERTEX_SE2 780 -2.139238 -37.102862 -2.060860 +VERTEX_SE2 781 -2.145402 -37.110533 -2.636030 +VERTEX_SE2 782 -2.437259 -37.141405 -3.067105 +VERTEX_SE2 783 -3.047824 -37.175458 -3.068514 +VERTEX_SE2 784 -3.287219 -37.194026 -3.090710 +VERTEX_SE2 785 -3.295317 -37.191509 2.638474 +VERTEX_SE2 786 -3.298918 -37.188857 2.048008 +VERTEX_SE2 787 -3.298039 -37.190654 1.555448 +VERTEX_SE2 788 -3.294912 -37.183493 0.924060 +VERTEX_SE2 789 -3.288075 -37.179210 0.370053 +VERTEX_SE2 790 -2.810788 -37.026036 0.301996 +VERTEX_SE2 791 -2.219090 -36.811172 0.399811 +VERTEX_SE2 792 -1.939736 -36.661187 1.102401 +VERTEX_SE2 793 -1.678873 -36.103497 1.143891 +VERTEX_SE2 794 -1.429675 -35.516238 1.211715 +VERTEX_SE2 795 -1.418449 -35.555793 1.634956 +VERTEX_SE2 796 -1.418085 -35.571576 2.285912 +VERTEX_SE2 797 -1.667269 -35.397655 2.541335 +VERTEX_SE2 798 -2.187789 -35.048694 2.588216 +VERTEX_SE2 799 -2.741194 -34.735022 2.650579 +VERTEX_SE2 800 -3.307545 -34.448654 2.720068 +VERTEX_SE2 801 -3.902341 -34.216184 2.802965 +VERTEX_SE2 802 -4.505679 -34.024853 2.857856 +VERTEX_SE2 803 -5.085804 -33.763383 2.689794 +VERTEX_SE2 804 -5.662771 -33.497682 2.743005 +VERTEX_SE2 805 -6.261534 -33.279468 2.816554 +VERTEX_SE2 806 -6.840015 -33.097367 2.855463 +VERTEX_SE2 807 -7.023476 -33.048729 -3.135502 +VERTEX_SE2 808 -7.026802 -33.056076 -2.177404 +VERTEX_SE2 809 -7.281242 -33.594521 -2.029487 +VERTEX_SE2 810 -7.631595 -34.121859 -2.166451 +VERTEX_SE2 811 -7.962424 -34.637653 -2.167266 +VERTEX_SE2 812 -7.965744 -34.642706 -1.427803 +VERTEX_SE2 813 -7.950068 -34.658744 -0.442321 +VERTEX_SE2 814 -7.946972 -34.656894 0.560269 +VERTEX_SE2 815 -7.933401 -34.640091 1.489098 +VERTEX_SE2 816 -7.934735 -34.631584 2.177465 +VERTEX_SE2 817 -7.937452 -34.619639 1.515677 +VERTEX_SE2 818 -7.834770 -34.423652 1.032291 +VERTEX_SE2 819 -7.526530 -33.907724 1.048948 +VERTEX_SE2 820 -7.214976 -33.390015 1.010358 +VERTEX_SE2 821 -6.920703 -32.916256 1.028688 +VERTEX_SE2 822 -6.919798 -32.914444 1.802164 +VERTEX_SE2 823 -6.939217 -32.906160 2.735576 +VERTEX_SE2 824 -7.523314 -32.665202 2.656921 +VERTEX_SE2 825 -8.081019 -32.349406 2.627743 +VERTEX_SE2 826 -8.677362 -32.112604 2.791147 +VERTEX_SE2 827 -9.263427 -31.871967 2.742741 +VERTEX_SE2 828 -9.860125 -31.638542 2.778381 +VERTEX_SE2 829 -10.419194 -31.408540 2.739767 +VERTEX_SE2 830 -10.979677 -31.164322 2.732511 +VERTEX_SE2 831 -11.504644 -30.911305 2.686863 +VERTEX_SE2 832 -12.017274 -30.666706 2.684351 +VERTEX_SE2 833 -12.247951 -30.553587 2.823368 +VERTEX_SE2 834 -12.252957 -30.553546 -2.400674 +VERTEX_SE2 835 -12.257933 -30.565509 -1.619664 +VERTEX_SE2 836 -12.250730 -30.581427 -0.672599 +VERTEX_SE2 837 -12.229702 -30.583353 0.368164 +VERTEX_SE2 838 -12.218778 -30.573267 1.234031 +VERTEX_SE2 839 -12.217846 -30.572182 1.017315 +VERTEX_SE2 840 -12.205638 -30.563033 0.457221 +VERTEX_SE2 841 -12.186893 -30.559209 -0.157128 +VERTEX_SE2 842 -11.953603 -30.647983 -0.386378 +VERTEX_SE2 843 -11.425785 -30.867365 -0.387868 +VERTEX_SE2 844 -10.836985 -31.098902 -0.394843 +VERTEX_SE2 845 -10.253132 -31.347696 -0.408511 +VERTEX_SE2 846 -9.662939 -31.589256 -0.405754 +VERTEX_SE2 847 -9.086083 -31.851482 -0.431429 +VERTEX_SE2 848 -8.940268 -31.914214 0.052760 +VERTEX_SE2 849 -8.937884 -31.910733 0.981233 +VERTEX_SE2 850 -8.846299 -31.550192 1.337597 +VERTEX_SE2 851 -8.670841 -30.931185 1.246884 +VERTEX_SE2 852 -8.462808 -30.325041 1.262739 +VERTEX_SE2 853 -8.280607 -29.742061 1.236186 +VERTEX_SE2 854 -8.076287 -29.173781 1.239399 +VERTEX_SE2 855 -7.887388 -28.592768 1.238706 +VERTEX_SE2 856 -7.661883 -27.996043 1.201622 +VERTEX_SE2 857 -7.435282 -27.400366 1.195491 +VERTEX_SE2 858 -7.181293 -26.816604 1.144746 +VERTEX_SE2 859 -6.975384 -26.352422 1.141340 +VERTEX_SE2 860 -6.975931 -26.349425 2.005134 +VERTEX_SE2 861 -7.070368 -26.315710 2.933845 +VERTEX_SE2 862 -7.703743 -26.156922 2.877954 +VERTEX_SE2 863 -8.318477 -25.984947 2.848940 +VERTEX_SE2 864 -8.894038 -25.792766 2.850044 +VERTEX_SE2 865 -9.480815 -25.646186 2.911227 +VERTEX_SE2 866 -10.042232 -25.502772 2.913209 +VERTEX_SE2 867 -10.195104 -25.469004 3.098784 +VERTEX_SE2 868 -10.213426 -25.478919 -2.146684 +VERTEX_SE2 869 -10.215119 -25.492408 -1.155028 +VERTEX_SE2 870 -10.214332 -25.494499 -0.141931 +VERTEX_SE2 871 -10.213017 -25.492991 0.844964 +VERTEX_SE2 872 -10.207635 -25.487052 1.539524 +VERTEX_SE2 873 -10.203844 -25.478644 0.974807 +VERTEX_SE2 874 -10.191816 -25.467641 0.422903 +VERTEX_SE2 875 -10.178876 -25.463448 -0.155631 +VERTEX_SE2 876 -9.623904 -25.632105 -0.308985 +VERTEX_SE2 877 -9.083899 -25.830525 -0.389894 +VERTEX_SE2 878 -8.876969 -25.899540 -0.000578 +VERTEX_SE2 879 -8.229916 -25.842173 0.054103 +VERTEX_SE2 880 -7.774580 -25.835590 -0.054479 +VERTEX_SE2 881 -7.817933 -25.833359 -0.045761 +VERTEX_SE2 882 -7.174094 -25.927843 -0.286988 +VERTEX_SE2 883 -6.578127 -26.179696 -0.472812 +VERTEX_SE2 884 -6.240032 -26.360890 -0.535840 +VERTEX_SE2 885 -6.234259 -26.360820 0.054937 +VERTEX_SE2 886 -6.226914 -26.353411 1.089009 +VERTEX_SE2 887 -6.223165 -26.344082 2.116331 +VERTEX_SE2 888 -6.228613 -26.341527 3.115899 +VERTEX_SE2 889 -6.233959 -26.343474 -2.255359 +VERTEX_SE2 890 -6.384262 -26.679298 -1.975677 +VERTEX_SE2 891 -6.638596 -27.241278 -2.042104 +VERTEX_SE2 892 -6.943864 -27.800951 -2.074085 +VERTEX_SE2 893 -7.222566 -28.381189 -1.832614 +VERTEX_SE2 894 -7.306963 -29.019629 -1.606544 +VERTEX_SE2 895 -7.223579 -29.638727 -1.302591 +VERTEX_SE2 896 -7.217764 -29.658031 -0.821107 +VERTEX_SE2 897 -6.741710 -29.937142 -0.546756 +VERTEX_SE2 898 -6.211746 -30.256253 -0.528856 +VERTEX_SE2 899 -5.784445 -30.515658 -0.593948 +VERTEX_SE2 900 -5.213641 -30.892109 -0.593973 +VERTEX_SE2 901 -4.743942 -31.232862 -0.655646 +VERTEX_SE2 902 -4.223039 -31.613559 -0.627847 +VERTEX_SE2 903 -3.820846 -31.901295 -0.669947 +VERTEX_SE2 904 -3.815849 -31.904352 0.045079 +VERTEX_SE2 905 -3.263955 -31.843907 0.103405 +VERTEX_SE2 906 -2.639473 -31.754495 0.172374 +VERTEX_SE2 907 -2.019027 -31.639234 0.167356 +VERTEX_SE2 908 -1.390615 -31.531155 0.192144 +VERTEX_SE2 909 -0.774159 -31.409648 0.174319 +VERTEX_SE2 910 -0.621113 -31.427046 -0.195369 +VERTEX_SE2 911 -0.014492 -31.535247 -0.134304 +VERTEX_SE2 912 0.586470 -31.609953 -0.123402 +VERTEX_SE2 913 1.163336 -31.678045 -0.116774 +VERTEX_SE2 914 1.788505 -31.757735 -0.141346 +VERTEX_SE2 915 2.338537 -31.842759 -0.178606 +VERTEX_SE2 916 2.533087 -31.771891 0.368065 +VERTEX_SE2 917 3.132539 -31.589985 0.113800 +VERTEX_SE2 918 3.652121 -31.566106 0.038805 +VERTEX_SE2 919 4.280972 -31.547492 -0.003530 +VERTEX_SE2 920 4.910829 -31.560372 -0.019732 +VERTEX_SE2 921 5.544993 -31.581438 -0.071106 +VERTEX_SE2 922 6.178198 -31.632867 -0.095979 +VERTEX_SE2 923 6.782469 -31.705277 -0.156454 +VERTEX_SE2 924 7.306767 -31.788672 -0.137071 +VERTEX_SE2 925 7.316981 -31.785338 0.373816 +VERTEX_SE2 926 7.870711 -31.558218 0.392795 +VERTEX_SE2 927 8.451492 -31.319547 0.372320 +VERTEX_SE2 928 9.048413 -31.086577 0.366185 +VERTEX_SE2 929 9.642832 -30.858817 0.368104 +VERTEX_SE2 930 10.245448 -30.641674 0.289261 +VERTEX_SE2 931 10.860347 -30.480136 0.213162 +VERTEX_SE2 932 11.487766 -30.354631 0.158095 +VERTEX_SE2 933 12.113942 -30.270301 0.098329 +VERTEX_SE2 934 12.615349 -30.217794 0.093110 +VERTEX_SE2 935 12.620802 -30.215724 0.789990 +VERTEX_SE2 936 12.621200 -30.213495 1.735352 +VERTEX_SE2 937 12.506666 -29.673239 1.798228 +VERTEX_SE2 938 12.424893 -29.074588 1.624736 +VERTEX_SE2 939 12.382460 -28.442898 1.652316 +VERTEX_SE2 940 12.358048 -27.806499 1.569594 +VERTEX_SE2 941 12.373922 -27.170573 1.518896 +VERTEX_SE2 942 12.403040 -26.619551 1.526103 +VERTEX_SE2 943 12.433212 -25.976160 1.617626 +VERTEX_SE2 944 12.409024 -25.337583 1.563948 +VERTEX_SE2 945 12.425512 -24.701834 1.511054 +VERTEX_SE2 946 12.438281 -24.522578 1.577626 +VERTEX_SE2 947 12.297194 -24.116617 1.909253 +VERTEX_SE2 948 12.106012 -23.569193 1.887290 +VERTEX_SE2 949 11.964410 -22.979201 1.728071 +VERTEX_SE2 950 11.889816 -22.346608 1.484552 +VERTEX_SE2 951 11.958985 -21.712798 1.409506 +VERTEX_SE2 952 12.033066 -21.078819 1.656468 +VERTEX_SE2 953 11.960841 -20.446967 1.733995 +VERTEX_SE2 954 11.870328 -19.821157 1.720988 +VERTEX_SE2 955 11.840813 -19.182342 1.553709 +VERTEX_SE2 956 11.856933 -18.549356 1.547775 +VERTEX_SE2 957 11.900583 -17.914412 1.456986 +VERTEX_SE2 958 11.980717 -17.309521 1.428422 +VERTEX_SE2 959 12.082916 -16.713544 1.360362 +VERTEX_SE2 960 12.156646 -16.109750 1.448732 +VERTEX_SE2 961 12.237458 -15.513097 1.428643 +VERTEX_SE2 962 12.263723 -14.879685 1.501648 +VERTEX_SE2 963 12.237575 -14.246674 1.697303 +VERTEX_SE2 964 12.165060 -13.610953 1.639856 +VERTEX_SE2 965 12.127557 -12.978752 1.638378 +VERTEX_SE2 966 12.104648 -12.566160 1.581231 +VERTEX_SE2 967 12.101573 -12.558682 2.440323 +VERTEX_SE2 968 12.096363 -12.554972 -2.940213 +VERTEX_SE2 969 12.095404 -12.555254 -2.878924 +VERTEX_SE2 970 12.095404 -12.555254 -2.879037 +VERTEX_SE2 971 11.746171 -12.650445 -2.877325 +VERTEX_SE2 972 11.152947 -12.816606 -2.870194 +VERTEX_SE2 973 10.545291 -12.861291 3.130276 +VERTEX_SE2 974 9.909280 -12.851322 -3.119743 +VERTEX_SE2 975 9.273543 -12.871196 -3.113968 +VERTEX_SE2 976 8.636290 -12.899229 -3.099985 +VERTEX_SE2 977 7.998434 -12.914064 -3.126289 +VERTEX_SE2 978 7.362084 -12.942484 -3.081464 +VERTEX_SE2 979 6.727323 -12.975809 -3.095884 +VERTEX_SE2 980 6.088538 -13.025797 -3.052420 +VERTEX_SE2 981 5.456362 -13.081213 -3.049818 +VERTEX_SE2 982 4.878233 -13.153816 -3.010682 +VERTEX_SE2 983 4.276746 -13.227843 -3.016388 +VERTEX_SE2 984 3.677713 -13.322859 -2.961936 +VERTEX_SE2 985 3.077590 -13.433257 -2.944700 +VERTEX_SE2 986 2.454219 -13.573733 -2.911877 +VERTEX_SE2 987 1.831643 -13.709396 -2.952510 +VERTEX_SE2 988 1.208691 -13.826413 -2.942854 +VERTEX_SE2 989 0.584787 -13.958913 -2.938610 +VERTEX_SE2 990 -0.036556 -14.080445 -2.953180 +VERTEX_SE2 991 -0.661927 -14.209275 -2.932525 +VERTEX_SE2 992 -1.260572 -14.319726 -2.969755 +VERTEX_SE2 993 -1.888936 -14.441757 -2.941917 +VERTEX_SE2 994 -2.487885 -14.558335 -2.956980 +VERTEX_SE2 995 -3.058043 -14.679439 -2.909164 +VERTEX_SE2 996 -3.642056 -14.831099 -2.881732 +VERTEX_SE2 997 -4.264284 -14.974196 -2.946069 +VERTEX_SE2 998 -4.649607 -15.053751 -2.924278 +VERTEX_SE2 999 -4.656689 -15.065859 -2.206631 +VERTEX_SE2 1000 -4.965388 -15.623496 -2.058280 +VERTEX_SE2 1001 -5.318062 -16.158055 -2.379913 +VERTEX_SE2 1002 -5.750626 -16.618291 -2.287924 +VERTEX_SE2 1003 -6.211655 -17.061941 -2.468589 +VERTEX_SE2 1004 -6.694526 -17.473495 -2.405819 +VERTEX_SE2 1005 -7.127979 -17.892536 -2.338545 +VERTEX_SE2 1006 -7.533434 -18.348428 -2.255884 +VERTEX_SE2 1007 -7.879092 -18.809574 -2.158490 +VERTEX_SE2 1008 -8.039907 -19.059004 -1.992248 +VERTEX_SE2 1009 -8.036682 -19.246221 -1.535293 +VERTEX_SE2 1010 -8.014039 -19.881169 -1.488904 +VERTEX_SE2 1011 -7.963340 -20.508886 -1.536571 +VERTEX_SE2 1012 -7.940438 -21.138959 -1.498741 +VERTEX_SE2 1013 -7.851368 -21.773013 -1.387987 +VERTEX_SE2 1014 -7.817932 -22.401411 -1.567544 +VERTEX_SE2 1015 -7.777031 -23.038795 -1.486212 +VERTEX_SE2 1016 -7.720006 -23.818187 -1.481750 +VERTEX_SE2 1017 -7.654678 -24.418258 -1.539186 +VERTEX_SE2 1018 -7.642739 -24.996103 -1.532186 +VERTEX_SE2 1019 -7.587869 -25.606880 -1.473009 +VERTEX_SE2 1020 -7.542280 -26.239004 -1.487341 +VERTEX_SE2 1021 -7.489141 -26.876264 -1.528391 +VERTEX_SE2 1022 -7.485868 -26.947021 -1.536042 +VERTEX_SE2 1023 -7.484661 -26.958141 -1.449942 +VERTEX_SE2 1024 -7.409816 -27.598995 -1.424093 +VERTEX_SE2 1025 -7.295845 -28.237813 -1.407035 +VERTEX_SE2 1026 -7.266936 -28.415848 -1.400374 +VERTEX_SE2 1027 -7.264213 -28.420001 -0.485709 +VERTEX_SE2 1028 -7.082225 -28.411802 0.076550 +VERTEX_SE2 1029 -6.501990 -28.370465 0.054524 +VERTEX_SE2 1030 -5.899285 -28.359129 -0.023135 +VERTEX_SE2 1031 -5.264812 -28.390632 -0.074570 +VERTEX_SE2 1032 -4.627186 -28.437737 -0.067955 +VERTEX_SE2 1033 -3.988448 -28.495960 -0.110249 +VERTEX_SE2 1034 -3.830826 -28.515420 -0.320119 +VERTEX_SE2 1035 -3.824146 -28.521449 -0.932344 +VERTEX_SE2 1036 -3.823513 -28.519287 -1.496421 +VERTEX_SE2 1037 -3.907010 -28.904450 -1.730668 +VERTEX_SE2 1038 -3.935283 -29.554657 -1.636155 +VERTEX_SE2 1039 -4.005708 -30.240003 -1.664719 +VERTEX_SE2 1040 -4.005908 -30.238599 -1.026894 +VERTEX_SE2 1041 -4.005975 -30.237093 0.002348 +VERTEX_SE2 1042 -3.997565 -30.235981 1.002167 +VERTEX_SE2 1043 -3.992361 -30.227413 1.983494 +VERTEX_SE2 1044 -3.977187 -30.235628 2.989203 +VERTEX_SE2 1045 -3.975026 -30.236085 2.875365 +VERTEX_SE2 1046 -3.962563 -30.241673 2.490123 +VERTEX_SE2 1047 -3.950447 -30.258328 1.934722 +VERTEX_SE2 1048 -3.961452 -29.893794 1.621975 +VERTEX_SE2 1049 -4.005576 -29.246490 1.639262 +VERTEX_SE2 1050 -4.077126 -28.603234 1.715064 +VERTEX_SE2 1051 -4.144972 -27.965909 1.641633 +VERTEX_SE2 1052 -4.202505 -27.357765 1.700204 +VERTEX_SE2 1053 -4.242648 -26.957178 1.653111 +VERTEX_SE2 1054 -4.243150 -26.953596 2.434770 +VERTEX_SE2 1055 -4.236475 -26.953142 -2.756219 +VERTEX_SE2 1056 -4.223234 -26.936933 -1.722386 +VERTEX_SE2 1057 -4.227338 -26.917941 -0.719127 +VERTEX_SE2 1058 -4.226406 -26.918299 0.214528 +VERTEX_SE2 1059 -3.650549 -26.814433 0.137155 +VERTEX_SE2 1060 -3.017058 -26.728657 0.145123 +VERTEX_SE2 1061 -2.566458 -26.676490 0.026280 +VERTEX_SE2 1062 -2.547934 -26.680711 -0.534242 +VERTEX_SE2 1063 -2.549662 -26.679283 -1.128091 +VERTEX_SE2 1064 -2.494849 -26.986675 -1.390919 +VERTEX_SE2 1065 -2.341227 -27.585706 -1.267035 +VERTEX_SE2 1066 -2.181042 -28.156133 -1.321458 +VERTEX_SE2 1067 -2.176008 -28.167308 -0.885641 +VERTEX_SE2 1068 -2.171515 -28.170280 -0.208552 +VERTEX_SE2 1069 -2.166440 -28.170156 -0.036102 +VERTEX_SE2 1070 -2.158515 -28.171216 -0.571481 +VERTEX_SE2 1071 -1.728296 -28.528563 -0.696733 +VERTEX_SE2 1072 -1.327331 -28.874102 -0.763594 +VERTEX_SE2 1073 -1.328212 -28.872089 -1.271112 +VERTEX_SE2 1074 -1.186974 -29.415680 -1.303788 +VERTEX_SE2 1075 -1.030631 -30.004733 -1.285588 +VERTEX_SE2 1076 -1.010783 -30.067165 -0.872464 +VERTEX_SE2 1077 -0.990761 -30.068841 -0.051064 +VERTEX_SE2 1078 -0.349127 -30.042537 -0.001133 +VERTEX_SE2 1079 0.251517 -30.025133 0.066104 +VERTEX_SE2 1080 0.250521 -30.025208 -0.411064 +VERTEX_SE2 1081 0.710773 -30.299114 -0.528492 +VERTEX_SE2 1082 0.906064 -30.410866 -0.239852 +VERTEX_SE2 1083 0.893124 -30.419745 0.817776 +VERTEX_SE2 1084 0.892987 -30.410710 1.808848 +VERTEX_SE2 1085 0.877326 -30.393872 2.785923 +VERTEX_SE2 1086 0.299041 -30.311718 3.014416 +VERTEX_SE2 1087 -0.304600 -30.219651 3.001192 +VERTEX_SE2 1088 -0.901080 -30.145015 2.983479 +VERTEX_SE2 1089 -0.971780 -30.133164 2.884958 +VERTEX_SE2 1090 -0.973114 -30.132686 2.263087 +VERTEX_SE2 1091 -1.258802 -29.655877 2.082828 +VERTEX_SE2 1092 -1.565146 -29.096531 2.065302 +VERTEX_SE2 1093 -1.831232 -28.571344 1.997715 +VERTEX_SE2 1094 -1.829673 -28.566075 1.590728 +VERTEX_SE2 1095 -1.822889 -28.540013 0.997280 +VERTEX_SE2 1096 -1.811806 -28.530957 0.422426 +VERTEX_SE2 1097 -1.452357 -28.453682 0.204872 +VERTEX_SE2 1098 -0.806231 -28.342284 0.146524 +VERTEX_SE2 1099 -0.207476 -28.279115 0.048016 +VERTEX_SE2 1100 -0.187763 -28.277509 0.407350 +VERTEX_SE2 1101 0.022408 -28.110407 0.670039 +VERTEX_SE2 1102 0.031962 -28.106738 0.272412 +VERTEX_SE2 1103 0.639388 -27.958876 0.236513 +VERTEX_SE2 1104 1.275605 -27.810841 0.206756 +VERTEX_SE2 1105 1.907140 -27.685723 0.186870 +VERTEX_SE2 1106 2.395193 -27.596899 0.159641 +VERTEX_SE2 1107 2.402168 -27.592873 0.412775 +VERTEX_SE2 1108 2.958139 -27.302229 0.418732 +VERTEX_SE2 1109 3.567153 -27.081855 0.312557 +VERTEX_SE2 1110 4.153225 -26.897988 0.261047 +VERTEX_SE2 1111 4.708902 -26.834648 0.157605 +VERTEX_SE2 1112 5.252614 -26.628115 0.500855 +VERTEX_SE2 1113 5.822286 -26.335525 0.403408 +VERTEX_SE2 1114 6.390291 -26.092686 0.418701 +VERTEX_SE2 1115 6.922867 -25.852780 0.400788 +VERTEX_SE2 1116 7.511667 -25.579208 0.435293 +VERTEX_SE2 1117 7.600383 -25.536976 0.305438 +VERTEX_SE2 1118 7.602610 -25.537159 -0.306056 +VERTEX_SE2 1119 7.600066 -25.535572 -0.741091 +VERTEX_SE2 1120 8.016891 -25.978082 -0.806559 +VERTEX_SE2 1121 8.158671 -26.132496 -0.927181 +VERTEX_SE2 1122 8.158918 -26.136107 -1.481463 +VERTEX_SE2 1123 8.202585 -26.722199 -1.466214 +VERTEX_SE2 1124 8.300951 -27.294198 -1.369439 +VERTEX_SE2 1125 8.427601 -27.927776 -1.357617 +VERTEX_SE2 1126 8.448389 -28.015008 -1.020843 +VERTEX_SE2 1127 8.448797 -28.014120 0.029251 +VERTEX_SE2 1128 8.446703 -28.014495 1.009931 +VERTEX_SE2 1129 8.448367 -28.002253 2.018659 +VERTEX_SE2 1130 8.179683 -27.484075 2.030704 +VERTEX_SE2 1131 8.020715 -26.725314 1.595581 +VERTEX_SE2 1132 8.007311 -26.085207 1.574275 +VERTEX_SE2 1133 8.027146 -25.500857 1.533912 +VERTEX_SE2 1134 8.037276 -25.234473 1.435052 +VERTEX_SE2 1135 8.041135 -25.225813 0.875236 +VERTEX_SE2 1136 8.045119 -25.226197 0.309468 +VERTEX_SE2 1137 8.350426 -25.173106 0.123314 +VERTEX_SE2 1138 9.001574 -25.103517 0.105516 +VERTEX_SE2 1139 9.526482 -25.047001 0.028463 +VERTEX_SE2 1140 9.524465 -25.046883 -0.458084 +VERTEX_SE2 1141 9.526460 -25.047900 -1.013894 +VERTEX_SE2 1142 9.607360 -25.436185 -1.384688 +VERTEX_SE2 1143 9.757086 -26.048918 -1.299305 +VERTEX_SE2 1144 9.911339 -26.642229 -1.333595 +VERTEX_SE2 1145 10.051242 -27.237116 -1.362737 +VERTEX_SE2 1146 10.176396 -27.833614 -1.346612 +VERTEX_SE2 1147 10.348017 -28.420420 -1.277963 +VERTEX_SE2 1148 10.522608 -29.006300 -1.265737 +VERTEX_SE2 1149 10.546607 -29.077059 -0.762568 +VERTEX_SE2 1150 10.540261 -29.074848 0.225763 +VERTEX_SE2 1151 10.553029 -29.065002 1.213625 +VERTEX_SE2 1152 10.547143 -29.052737 2.249842 +VERTEX_SE2 1153 10.539006 -29.045893 -3.036684 +VERTEX_SE2 1154 10.279724 -29.230068 -2.499597 +VERTEX_SE2 1155 9.768765 -29.605741 -2.552981 +VERTEX_SE2 1156 9.258910 -29.939074 -2.546643 +VERTEX_SE2 1157 8.791360 -30.283703 -2.440027 +VERTEX_SE2 1158 8.293580 -30.637927 -2.573320 +VERTEX_SE2 1159 7.766648 -30.929430 -2.672819 +VERTEX_SE2 1160 7.188507 -31.197997 -2.815407 +VERTEX_SE2 1161 6.565573 -31.348475 -2.910356 +VERTEX_SE2 1162 5.944969 -31.503360 -2.857013 +VERTEX_SE2 1163 5.325232 -31.686006 -2.866763 +VERTEX_SE2 1164 4.712273 -31.878415 -2.786199 +VERTEX_SE2 1165 4.215997 -32.064635 -2.806894 +VERTEX_SE2 1166 4.211816 -32.067381 -2.313330 +VERTEX_SE2 1167 4.212397 -32.068184 -1.368491 +VERTEX_SE2 1168 4.215987 -32.071852 -0.457146 +VERTEX_SE2 1169 4.277451 -32.051395 0.371897 +VERTEX_SE2 1170 4.829613 -31.826964 0.380849 +VERTEX_SE2 1171 5.421192 -31.572841 0.415111 +VERTEX_SE2 1172 5.981253 -31.335402 0.355461 +VERTEX_SE2 1173 6.575628 -31.109741 0.367274 +VERTEX_SE2 1174 7.180922 -30.893036 0.301697 +VERTEX_SE2 1175 7.792370 -30.719051 0.271366 +VERTEX_SE2 1176 8.409541 -30.550025 0.230936 +VERTEX_SE2 1177 9.024476 -30.404549 0.236005 +VERTEX_SE2 1178 9.647424 -30.266268 0.192062 +VERTEX_SE2 1179 10.265276 -30.135370 0.224605 +VERTEX_SE2 1180 10.529482 -30.074919 0.220636 +VERTEX_SE2 1181 10.535574 -30.072977 1.058820 +VERTEX_SE2 1182 10.524149 -30.016817 1.779823 +VERTEX_SE2 1183 10.386448 -29.400748 1.808327 +VERTEX_SE2 1184 10.207851 -28.783707 1.881370 +VERTEX_SE2 1185 10.025332 -28.173735 1.852352 +VERTEX_SE2 1186 9.825515 -27.568409 1.922073 +VERTEX_SE2 1187 9.605142 -26.948356 1.888299 +VERTEX_SE2 1188 9.398682 -26.350552 1.909670 +VERTEX_SE2 1189 9.199117 -25.746642 1.931343 +VERTEX_SE2 1190 9.094298 -25.467233 1.939338 +VERTEX_SE2 1191 9.094967 -25.468452 2.859515 +VERTEX_SE2 1192 9.008026 -25.506399 -2.626152 +VERTEX_SE2 1193 8.461781 -25.785098 -2.758330 +VERTEX_SE2 1194 7.923840 -26.019541 -2.716510 +VERTEX_SE2 1195 7.347445 -26.288871 -2.664510 +VERTEX_SE2 1196 6.780364 -26.579172 -2.837709 +VERTEX_SE2 1197 6.180419 -26.774947 -2.826952 +VERTEX_SE2 1198 5.583380 -27.006326 -2.569041 +VERTEX_SE2 1199 5.035569 -27.311853 -2.784743 +VERTEX_SE2 1200 4.440692 -27.555930 -2.716631 +VERTEX_SE2 1201 3.868153 -27.824566 -2.661795 +VERTEX_SE2 1202 3.307623 -28.126760 -2.639885 +VERTEX_SE2 1203 2.784459 -28.432197 -2.731103 +VERTEX_SE2 1204 2.199445 -28.603325 -2.879452 +VERTEX_SE2 1205 1.642686 -28.765416 -2.851240 +VERTEX_SE2 1206 1.070524 -28.960362 -2.791568 +VERTEX_SE2 1207 0.458097 -29.116494 -2.879433 +VERTEX_SE2 1208 -0.157073 -29.300653 -2.816562 +VERTEX_SE2 1209 -0.759388 -29.505640 -2.820223 +VERTEX_SE2 1210 -1.349503 -29.728180 -2.801535 +VERTEX_SE2 1211 -1.962101 -29.894344 -2.871965 +VERTEX_SE2 1212 -2.570554 -30.072460 -2.819915 +VERTEX_SE2 1213 -3.165262 -30.298664 -2.744821 +VERTEX_SE2 1214 -3.865282 -30.564861 -2.965631 +VERTEX_SE2 1215 -4.462533 -30.687173 -2.905497 +VERTEX_SE2 1216 -4.996128 -30.904402 -2.687065 +VERTEX_SE2 1217 -5.548071 -31.150837 -2.705863 +VERTEX_SE2 1218 -6.079683 -31.407444 -2.756532 +VERTEX_SE2 1219 -6.680544 -31.658044 -2.725934 +VERTEX_SE2 1220 -7.206328 -31.919274 -2.635196 +VERTEX_SE2 1221 -7.204948 -31.917957 -3.087949 +VERTEX_SE2 1222 -7.218143 -31.913501 2.597929 +VERTEX_SE2 1223 -7.226028 -31.904243 2.038302 +VERTEX_SE2 1224 -7.405412 -31.351278 1.855394 +VERTEX_SE2 1225 -7.584838 -30.751843 1.869158 +VERTEX_SE2 1226 -7.616041 -30.650012 1.852427 +VERTEX_SE2 1227 -7.616041 -30.650012 1.851765 +EDGE_SE2 0 1 0.000000 0.000000 -0.000642 11.111271 -0.249667 0.000000 399.999840 0.000000 2496.793089 +EDGE_SE2 1 2 0.000000 0.000000 -0.000538 11.111224 -0.209222 0.000000 399.999887 0.000000 2497.312169 +EDGE_SE2 2 3 0.011003 -0.000962 -0.002382 5898.288051 69216.359995 0.000000 813797.504789 0.000000 2488.132420 +EDGE_SE2 3 4 0.630039 -0.007981 -0.003882 11.129692 2.115033 0.000000 251.862638 0.000000 2480.702442 +EDGE_SE2 4 5 0.055010 -0.000106 -0.091282 274.195567 -2936.281177 0.000000 32782.895793 0.000000 2099.259006 +EDGE_SE2 5 6 0.004599 -0.003282 -0.797272 97512.798743 -544001.571431 0.000000 3035217.135802 0.000000 773.949086 +EDGE_SE2 6 7 -0.019286 0.007346 -0.615537 14562.788488 -56611.041711 0.000000 220247.580117 0.000000 957.869160 +EDGE_SE2 7 8 -0.022127 0.006629 -0.613534 18833.046432 -56332.014355 0.000000 168606.730383 0.000000 960.248785 +EDGE_SE2 8 9 -0.021138 0.006734 -0.638070 21300.350989 -62226.140556 0.000000 181891.375069 0.000000 931.697855 +EDGE_SE2 9 10 -0.012731 0.002805 -0.614531 88261.230144 -210099.692864 0.000000 500201.721901 0.000000 959.062847 +EDGE_SE2 10 11 -0.004733 0.001621 -0.674279 455441.532335 -1269769.465818 0.000000 3540210.494348 0.000000 891.834664 +EDGE_SE2 11 12 0.000807 -0.000605 -0.649474 3209.969094 -560838.218926 0.000000 98328698.890567 0.000000 918.859395 +EDGE_SE2 12 13 0.017463 -0.005758 -0.659498 33087.416467 -93212.317327 0.000000 262692.689594 0.000000 907.792399 +EDGE_SE2 13 14 0.024327 -0.007794 -0.608239 13237.887356 -43033.186144 0.000000 140019.158071 0.000000 966.582281 +EDGE_SE2 14 15 0.008665 -0.002176 -0.524928 94975.828833 -331589.466697 0.000000 1157826.108740 0.000000 1075.081358 +EDGE_SE2 15 16 0.300013 0.002659 -0.018692 11.945981 -30.290393 0.000000 1110.094393 0.000000 2409.096616 +EDGE_SE2 16 17 0.618894 -0.006590 -0.031228 11.216951 -5.142163 0.000000 260.940781 0.000000 2350.880836 +EDGE_SE2 17 18 0.644399 0.002908 -0.010177 11.160679 -3.373944 0.000000 240.764207 0.000000 2449.881377 +EDGE_SE2 18 19 0.657345 -0.022632 -0.048576 11.155234 -3.115574 0.000000 231.108306 0.000000 2273.736754 +EDGE_SE2 19 20 0.644638 0.002939 0.010643 11.119605 1.396220 0.000000 240.626947 0.000000 2447.622654 +EDGE_SE2 20 21 0.643768 0.040732 0.117695 11.791489 12.469629 0.000000 239.648403 0.000000 2001.213355 +EDGE_SE2 21 22 0.641586 -0.019837 0.022682 11.775592 12.387374 0.000000 242.038634 0.000000 2390.335076 +EDGE_SE2 22 23 0.642142 0.071066 0.114072 11.114499 0.879730 0.000000 239.576730 0.000000 2014.250547 +EDGE_SE2 23 24 0.642775 -0.026027 -0.050939 11.136380 -2.413434 0.000000 241.616002 0.000000 2263.523413 +EDGE_SE2 24 25 0.645593 0.014612 0.008602 11.156105 -3.207460 0.000000 239.760661 0.000000 2457.538661 +EDGE_SE2 25 26 0.612608 -0.020554 -0.040332 11.122880 -1.732513 0.000000 266.150269 0.000000 2309.915505 +EDGE_SE2 26 27 0.617908 0.014448 0.016074 11.124480 -1.830524 0.000000 261.753630 0.000000 2421.527089 +EDGE_SE2 27 28 0.585700 -0.007698 -0.004161 11.133727 2.517886 0.000000 291.434633 0.000000 2479.324138 +EDGE_SE2 28 29 0.378831 0.003536 0.031104 11.435983 14.920983 0.000000 696.414325 0.000000 2351.446301 +EDGE_SE2 29 30 0.007031 -0.000919 -0.531386 303620.480641 -715329.968352 0.000000 1685390.466875 0.000000 1066.033037 +EDGE_SE2 30 31 0.172814 -0.047579 -0.267833 11.113242 2.570601 0.000000 3112.523002 0.000000 1555.306207 +EDGE_SE2 31 32 0.643089 -0.013458 -0.018151 11.112884 0.639397 0.000000 241.693017 0.000000 2411.657469 +EDGE_SE2 32 33 0.641505 0.012210 0.053138 11.380647 7.899680 0.000000 242.638725 0.000000 2254.080602 +EDGE_SE2 33 34 0.642958 0.012818 0.023470 11.113996 0.815809 0.000000 241.800271 0.000000 2386.655713 +EDGE_SE2 34 35 0.642138 0.012026 0.036992 11.188281 4.224347 0.000000 242.355561 0.000000 2324.819270 +EDGE_SE2 35 36 0.646989 -0.005904 -0.005774 11.113668 0.763126 0.000000 238.872355 0.000000 2471.378132 +EDGE_SE2 36 37 0.422413 0.003265 0.010657 11.115820 1.608217 0.000000 560.397185 0.000000 2447.554843 +EDGE_SE2 37 38 0.004147 -0.000362 -0.316561 298816.394178 -1278713.788579 0.000000 5472166.543975 0.000000 1442.308081 +EDGE_SE2 38 39 0.031682 -0.005795 -0.166903 29.991712 1348.903464 0.000000 96382.012864 0.000000 1835.990780 +EDGE_SE2 39 40 0.628745 0.004932 0.020565 11.150244 3.076040 0.000000 252.904983 0.000000 2400.262103 +EDGE_SE2 40 41 0.654706 -0.007135 -0.028394 11.179108 -3.886059 0.000000 233.200483 0.000000 2363.855583 +EDGE_SE2 41 42 0.615233 -0.005892 -0.018963 11.133406 -2.375163 0.000000 264.145862 0.000000 2407.815356 +EDGE_SE2 42 43 0.646018 -0.015551 -0.036078 11.144050 -2.742429 0.000000 239.441473 0.000000 2328.922864 +EDGE_SE2 43 44 0.644889 -0.007273 -0.032646 11.215795 -4.898393 0.000000 240.317651 0.000000 2344.428944 +EDGE_SE2 44 45 0.642617 -0.019475 -0.055423 11.256800 -5.797160 0.000000 241.788650 0.000000 2244.330959 +EDGE_SE2 45 46 0.643577 -0.008674 -0.019276 11.118853 -1.335200 0.000000 241.382966 0.000000 2406.336795 +EDGE_SE2 46 47 0.643124 -0.007411 -0.041538 11.318826 -6.918261 0.000000 241.534792 0.000000 2304.569286 +EDGE_SE2 47 48 0.647528 -0.005000 -0.006399 11.111509 0.300792 0.000000 238.482697 0.000000 2468.309505 +EDGE_SE2 48 49 0.643552 -0.004657 -0.050649 11.544947 -9.986829 0.000000 241.006497 0.000000 2264.773140 +EDGE_SE2 49 50 0.613650 -0.021431 -0.044298 11.133509 -2.385631 0.000000 265.211665 0.000000 2292.403781 +EDGE_SE2 50 51 0.614419 0.001282 -0.030028 11.372766 -8.144597 0.000000 264.630129 0.000000 2356.361658 +EDGE_SE2 51 52 0.612275 -0.025515 -0.077517 11.439261 -9.144885 0.000000 265.960759 0.000000 2153.236570 +EDGE_SE2 52 53 0.589010 0.013532 0.011867 11.145260 -3.075254 0.000000 288.053971 0.000000 2441.704725 +EDGE_SE2 53 54 0.549942 -0.015900 -0.062397 11.469128 -10.685144 0.000000 330.013480 0.000000 2214.962293 +EDGE_SE2 54 55 -0.007990 -0.000400 0.004985 3173.514815 -70220.700546 0.000000 1559251.248529 0.000000 2475.260146 +EDGE_SE2 55 56 0.031075 -0.000065 0.010280 26.926592 1279.597558 0.000000 103540.680562 0.000000 2449.381862 +EDGE_SE2 56 57 0.661651 0.003067 -0.011448 11.167314 -3.494319 0.000000 228.362912 0.000000 2443.728134 +EDGE_SE2 57 58 0.651514 0.005099 0.046426 11.445370 8.655456 0.000000 235.239298 0.000000 2283.089649 +EDGE_SE2 58 59 0.644894 -0.007287 -0.023143 11.143280 -2.715787 0.000000 240.386652 0.000000 2388.181524 +EDGE_SE2 59 60 0.641666 0.006484 0.022061 11.144235 2.770355 0.000000 242.816230 0.000000 2393.240674 +EDGE_SE2 60 61 0.644092 -0.013088 -0.049766 11.310377 -6.764558 0.000000 240.749901 0.000000 2268.584724 +EDGE_SE2 61 62 0.610542 0.010202 0.039027 11.239154 5.735944 0.000000 268.065336 0.000000 2315.721577 +EDGE_SE2 62 63 0.615687 -0.014578 -0.037143 11.156928 -3.401279 0.000000 263.609811 0.000000 2324.142368 +EDGE_SE2 63 64 0.614457 0.023223 0.060765 11.244984 5.822514 0.000000 264.348682 0.000000 2221.783030 +EDGE_SE2 64 65 0.613126 -0.015622 -0.054905 11.331684 -7.492495 0.000000 265.618387 0.000000 2246.535610 +EDGE_SE2 65 66 0.642083 0.005221 -0.012134 11.206140 -4.688688 0.000000 242.448428 0.000000 2440.416656 +EDGE_SE2 66 67 0.644032 -0.000439 -0.003525 11.112971 -0.654045 0.000000 241.091541 0.000000 2482.467756 +EDGE_SE2 67 68 0.480969 0.003132 -0.018150 11.367193 -10.381901 0.000000 432.006963 0.000000 2411.662206 +EDGE_SE2 68 69 0.010004 -0.000372 -0.158022 14522.704416 -119457.061100 0.000000 983362.087562 0.000000 1864.259601 +EDGE_SE2 69 70 0.007781 -0.000530 -0.680912 544035.164858 -773651.719241 0.000000 1100214.270443 0.000000 884.810063 +EDGE_SE2 70 71 -0.005768 0.002595 -0.648935 125743.539339 -546312.647396 0.000000 2373762.361377 0.000000 919.460202 +EDGE_SE2 71 72 0.000000 0.000000 -0.011790 11.165166 -4.584575 0.000000 399.945945 0.000000 2442.076380 +EDGE_SE2 72 73 0.003590 -0.000252 -0.067514 59.238767 19279.280557 0.000000 7723027.108236 0.000000 2193.777612 +EDGE_SE2 73 74 0.003377 -0.001263 -0.627884 547328.125180 -1977782.419372 0.000000 7146917.196299 0.000000 943.393977 +EDGE_SE2 74 75 0.001263 0.000666 -0.356531 27289611.550657 -24363663.505902 0.000000 21751450.848890 0.000000 1358.565441 +EDGE_SE2 75 76 0.014525 0.005731 0.687334 38537.927166 119650.043523 0.000000 371599.899935 0.000000 878.087699 +EDGE_SE2 76 77 0.012722 0.001600 0.229532 6624.040036 63075.527086 0.000000 601638.946912 0.000000 1653.713745 +EDGE_SE2 77 78 0.282617 0.095127 0.333053 11.189119 9.319517 0.000000 1124.510027 0.000000 1406.840866 +EDGE_SE2 78 79 0.636095 0.008032 -0.007625 11.207888 -4.778031 0.000000 247.011069 0.000000 2462.306663 +EDGE_SE2 79 80 0.646911 -0.030410 -0.077284 11.319895 -6.885926 0.000000 238.216160 0.000000 2154.168095 +EDGE_SE2 80 81 0.639697 -0.008063 -0.028569 11.170556 -3.722959 0.000000 244.273973 0.000000 2363.051282 +EDGE_SE2 81 82 0.643152 -0.022848 -0.050289 11.161415 -3.403565 0.000000 241.398318 0.000000 2266.325966 +EDGE_SE2 82 83 0.640259 -0.000745 -0.019030 11.185422 -4.158907 0.000000 243.868413 0.000000 2407.498744 +EDGE_SE2 83 84 0.642213 -0.028725 -0.071607 11.278239 -6.209353 0.000000 241.809620 0.000000 2177.051366 +EDGE_SE2 84 85 0.642807 -0.004171 0.013937 11.207431 4.714878 0.000000 241.906303 0.000000 2431.743719 +EDGE_SE2 85 86 0.729089 -0.020666 -0.079989 11.582543 -9.118938 0.000000 187.499441 0.000000 2143.389493 +EDGE_SE2 86 87 0.611674 -0.018501 -0.038112 11.126983 -2.015351 0.000000 267.015944 0.000000 2319.805566 +EDGE_SE2 87 88 0.363613 -0.001497 -0.025112 11.439512 -15.640496 0.000000 756.007915 0.000000 2379.016060 +EDGE_SE2 88 89 0.022194 0.007878 0.405075 748.400424 11505.714792 0.000000 179562.707200 0.000000 1266.312242 +EDGE_SE2 89 90 0.645333 -0.002553 -0.026790 11.230485 -5.227171 0.000000 239.999401 0.000000 2371.246746 +EDGE_SE2 90 91 0.653796 0.009633 0.053106 11.438992 8.540445 0.000000 233.567599 0.000000 2254.217590 +EDGE_SE2 91 92 0.637138 -0.022076 -0.111746 12.505303 -18.044302 0.000000 244.649107 0.000000 2022.687812 +EDGE_SE2 92 93 0.640542 -0.048819 -0.097619 11.218480 -4.981269 0.000000 242.212560 0.000000 2075.089230 +EDGE_SE2 93 94 0.639915 -0.019948 -0.040363 11.130823 -2.142336 0.000000 243.948392 0.000000 2309.777849 +EDGE_SE2 94 95 0.643361 0.058181 0.138081 11.634914 10.928304 0.000000 239.112551 0.000000 1930.161562 +EDGE_SE2 95 96 0.638452 0.002717 0.020015 11.169275 3.690420 0.000000 245.262988 0.000000 2402.851280 +EDGE_SE2 96 97 0.615807 -0.026362 -0.075608 11.382661 -8.269572 0.000000 262.946629 0.000000 2160.886525 +EDGE_SE2 97 98 0.610633 -0.021924 -0.063326 11.304343 -7.040699 0.000000 267.649507 0.000000 2211.093675 +EDGE_SE2 98 99 0.729556 0.014258 0.041080 11.193076 3.804772 0.000000 187.727053 0.000000 2306.597420 +EDGE_SE2 99 100 0.585696 -0.025742 -0.058133 11.167610 -3.975845 0.000000 290.892636 0.000000 2232.849702 +EDGE_SE2 100 101 0.637186 0.067759 0.095665 11.135663 -2.388768 0.000000 243.522972 0.000000 2082.497224 +EDGE_SE2 101 102 0.646556 -0.024441 -0.094339 11.838827 -12.853666 0.000000 238.145742 0.000000 2087.546965 +EDGE_SE2 102 103 0.640410 0.007435 0.107121 13.227361 22.089363 0.000000 241.679335 0.000000 2039.622675 +EDGE_SE2 103 104 0.644201 -0.014336 -0.024966 11.112805 -0.623830 0.000000 240.845479 0.000000 2379.693860 +EDGE_SE2 104 105 0.644960 0.019675 0.055427 11.253454 5.708380 0.000000 240.033921 0.000000 2244.313947 +EDGE_SE2 105 106 0.633327 -0.017685 -0.046638 11.194517 -4.454694 0.000000 249.035067 0.000000 2282.164848 +EDGE_SE2 106 107 0.647889 -0.007117 0.003228 11.156976 3.226972 0.000000 238.156676 0.000000 2483.937815 +EDGE_SE2 107 108 0.418841 0.012880 0.059022 11.557560 15.782621 0.000000 569.050200 0.000000 2229.102528 +EDGE_SE2 108 109 0.012870 -0.002240 -0.453333 45067.256701 -156114.787673 0.000000 540932.368601 0.000000 1183.612533 +EDGE_SE2 109 110 0.014179 -0.004043 -0.597121 45347.441263 -137112.106751 0.000000 414683.621097 0.000000 980.086413 +EDGE_SE2 110 111 0.096952 -0.046958 -0.510989 42.005133 -514.703903 0.000000 8586.236292 0.000000 1095.008280 +EDGE_SE2 111 112 0.662640 0.007778 0.052084 11.463505 8.729519 0.000000 227.358980 0.000000 2258.599235 +EDGE_SE2 112 113 0.647895 0.015723 0.044858 11.207376 4.673389 0.000000 237.990065 0.000000 2289.947176 +EDGE_SE2 113 114 0.639175 0.001049 0.034783 11.367673 7.738365 0.000000 244.514402 0.000000 2334.755667 +EDGE_SE2 114 115 0.643430 0.022360 0.055827 11.213458 4.852193 0.000000 241.150882 0.000000 2242.613753 +EDGE_SE2 115 116 0.763396 0.014434 0.039419 11.178609 3.289916 0.000000 171.464543 0.000000 2313.975233 +EDGE_SE2 116 117 0.634411 0.022615 0.090058 11.812568 12.875464 0.000000 247.444399 0.000000 2103.976068 +EDGE_SE2 117 118 0.031050 -0.001921 -0.343244 7981.193322 -27566.715976 0.000000 95358.161435 0.000000 1385.575483 +EDGE_SE2 118 119 0.498463 -0.026118 -0.058682 11.126767 -2.471741 0.000000 401.352854 0.000000 2230.534528 +EDGE_SE2 119 120 0.638636 0.019165 0.084147 11.796072 12.637674 0.000000 244.278828 0.000000 2126.981262 +EDGE_SE2 120 121 0.608883 0.022686 0.061480 11.262812 6.257264 0.000000 269.206349 0.000000 2218.790906 +EDGE_SE2 121 122 0.610979 0.006491 0.049908 11.507132 10.075663 0.000000 267.458443 0.000000 2267.971114 +EDGE_SE2 122 123 0.214919 0.006655 -0.018770 16.427458 -106.823784 0.000000 2157.570163 0.000000 2408.727735 +EDGE_SE2 123 124 0.224600 -0.105868 -0.436366 11.138335 6.622207 0.000000 1621.948711 0.000000 1211.740925 +EDGE_SE2 124 125 0.625260 -0.011376 -0.017225 11.111340 0.236437 0.000000 255.702505 0.000000 2416.050226 +EDGE_SE2 125 126 0.630905 0.083897 0.196975 12.098786 15.227356 0.000000 245.877115 0.000000 1744.897213 +EDGE_SE2 126 127 0.635911 -0.003633 -0.003082 11.112746 0.621349 0.000000 247.280806 0.000000 2484.660949 +EDGE_SE2 127 128 0.644637 0.020444 0.034153 11.112488 0.561814 0.000000 240.398060 0.000000 2337.601172 +EDGE_SE2 128 129 0.638546 -0.014303 -0.035619 11.152032 -3.094288 0.000000 245.089747 0.000000 2330.987741 +EDGE_SE2 129 130 0.640721 0.025473 0.048893 11.130575 2.125338 0.000000 243.187509 0.000000 2272.362609 +EDGE_SE2 130 131 0.641480 0.013548 0.083601 12.014929 14.445918 0.000000 242.003477 0.000000 2129.125269 +EDGE_SE2 131 132 0.641305 -0.014532 -0.055040 11.354232 -7.504896 0.000000 242.779959 0.000000 2245.960726 +EDGE_SE2 132 133 0.581934 -0.015905 -0.042094 11.173057 -4.193601 0.000000 295.010721 0.000000 2302.110777 +EDGE_SE2 133 134 0.610231 0.001805 -0.024124 11.299860 -6.968043 0.000000 268.350792 0.000000 2383.608476 +EDGE_SE2 134 135 0.579655 -0.017960 -0.033069 11.112368 -0.599782 0.000000 297.332685 0.000000 2342.509439 +EDGE_SE2 135 136 0.642725 0.014632 0.012040 11.137646 -2.474784 0.000000 241.922944 0.000000 2440.870018 +EDGE_SE2 136 137 0.634138 -0.020053 -0.051400 11.204026 -4.694831 0.000000 248.333522 0.000000 2261.538905 +EDGE_SE2 137 138 0.640742 0.028547 0.068532 11.244796 5.567274 0.000000 242.959321 0.000000 2189.600800 +EDGE_SE2 138 139 0.624343 0.022436 0.065016 11.318542 7.127247 0.000000 256.001043 0.000000 2204.081980 +EDGE_SE2 139 140 0.649355 0.026111 0.030256 11.133375 -2.241330 0.000000 236.751877 0.000000 2355.318828 +EDGE_SE2 140 141 0.633752 -0.015337 -0.048721 11.254069 -5.827843 0.000000 248.689278 0.000000 2273.108048 +EDGE_SE2 141 142 0.643523 0.009872 -0.004100 11.198132 -4.475923 0.000000 241.330701 0.000000 2479.625389 +EDGE_SE2 142 143 0.634003 -0.068517 -0.110892 11.113575 -0.760641 0.000000 245.906731 0.000000 2025.798896 +EDGE_SE2 143 144 0.367489 0.008323 0.017249 11.132342 -3.934021 0.000000 740.076637 0.000000 2415.936223 +EDGE_SE2 144 145 0.011506 -0.002421 -0.499034 59809.374609 -199183.039696 0.000000 663473.241646 0.000000 1112.543606 +EDGE_SE2 145 146 0.002065 0.000912 -0.593946 14068785.759218 -8838843.642003 0.000000 5553100.053245 0.000000 983.994793 +EDGE_SE2 146 147 0.052046 -0.024279 -0.487148 88.850566 -1532.993200 0.000000 30241.168070 0.000000 1130.398639 +EDGE_SE2 147 148 0.437634 -0.008022 -0.035943 11.269607 -8.996749 0.000000 521.795770 0.000000 2329.529896 +EDGE_SE2 148 149 0.649282 0.006558 0.024834 11.160187 3.330542 0.000000 237.137078 0.000000 2380.306915 +EDGE_SE2 149 150 0.638778 0.018547 0.013910 11.164529 -3.533262 0.000000 244.815913 0.000000 2431.874707 +EDGE_SE2 150 151 0.642396 0.027197 0.085399 11.539278 9.931167 0.000000 241.460866 0.000000 2122.077176 +EDGE_SE2 151 152 0.642196 -0.014560 -0.068180 11.589745 -10.509493 0.000000 241.870955 0.000000 2191.044127 +EDGE_SE2 152 153 0.641634 0.027219 0.085722 11.545124 10.011045 0.000000 242.028095 0.000000 2120.814737 +EDGE_SE2 153 154 0.638389 -0.020707 -0.077238 11.580742 -10.472604 0.000000 244.646718 0.000000 2154.352072 +EDGE_SE2 154 155 0.642162 0.011168 0.026427 11.130001 2.090263 0.000000 242.407116 0.000000 2372.924244 +EDGE_SE2 155 156 0.644865 0.009414 0.023665 11.129963 2.079071 0.000000 240.400517 0.000000 2385.746522 +EDGE_SE2 156 157 0.581283 -0.014428 -0.072363 11.754151 -13.514232 0.000000 295.128631 0.000000 2173.984116 +EDGE_SE2 157 158 0.187127 -0.000419 0.029090 13.902620 89.068131 0.000000 2852.990445 0.000000 2360.659192 +EDGE_SE2 158 159 -0.002775 0.000752 0.993417 10949150.533757 3540503.247990 0.000000 1144864.853964 0.000000 629.134778 +EDGE_SE2 159 160 0.010178 0.000761 1.042069 650920.894971 448555.873968 0.000000 309120.571532 0.000000 599.513799 +EDGE_SE2 160 161 -0.000005 0.000004 0.981942 2693538350855.096191 -157146640359.091309 0.000000 9168262482.076782 0.000000 636.440966 +EDGE_SE2 161 162 -0.015739 -0.012123 1.042202 35897.561333 88343.035344 0.000000 217488.511233 0.000000 599.435534 +EDGE_SE2 162 163 0.001603 0.001566 1.003233 1029828.017450 4408843.295789 0.000000 18875113.167768 0.000000 622.984264 +EDGE_SE2 163 164 0.014062 0.009080 0.929958 43510.337182 116762.574144 0.000000 313430.450998 0.000000 671.188169 +EDGE_SE2 164 165 0.127064 0.050581 0.402133 14.003612 124.194925 0.000000 5343.652150 0.000000 1271.632407 +EDGE_SE2 165 166 0.660048 0.003938 -0.000969 11.121614 -1.514549 0.000000 229.516161 0.000000 2495.162033 +EDGE_SE2 166 167 0.637952 -0.005107 -0.029173 11.216206 -4.964111 0.000000 245.589760 0.000000 2360.278446 +EDGE_SE2 167 168 0.609195 0.011564 0.012037 11.123559 -1.792903 0.000000 269.346120 0.000000 2440.884489 +EDGE_SE2 168 169 0.616410 -0.017912 -0.037053 11.127238 -2.015259 0.000000 262.946448 0.000000 2324.545784 +EDGE_SE2 169 170 0.607779 0.006983 -0.020916 11.383588 -8.405441 0.000000 270.404841 0.000000 2398.611924 +EDGE_SE2 170 171 0.584191 -0.014911 -0.038741 11.160361 -3.724488 0.000000 292.775082 0.000000 2316.996943 +EDGE_SE2 171 172 0.648836 0.010594 0.013474 11.112953 -0.645665 0.000000 237.471401 0.000000 2433.967559 +EDGE_SE2 172 173 0.642894 -0.013166 -0.018042 11.112478 0.561628 0.000000 241.844714 0.000000 2412.173920 +EDGE_SE2 173 174 0.638185 0.007116 0.045162 11.382152 7.965912 0.000000 245.229896 0.000000 2288.615243 +EDGE_SE2 174 175 0.625733 0.004082 -0.019946 11.282223 -6.462935 0.000000 255.218243 0.000000 2403.176400 +EDGE_SE2 175 176 0.613713 -0.013173 0.014287 11.435899 9.081745 0.000000 265.055874 0.000000 2430.067237 +EDGE_SE2 176 177 0.634525 0.002256 -0.022912 11.277271 -6.276557 0.000000 248.202540 0.000000 2389.260272 +EDGE_SE2 177 178 0.640137 -0.023037 -0.034183 11.111855 0.416076 0.000000 243.719928 0.000000 2337.465554 +EDGE_SE2 178 179 0.353790 0.008069 0.053221 11.839402 23.935910 0.000000 797.785636 0.000000 2253.725346 +EDGE_SE2 179 180 0.003152 -0.000263 -0.442165 1233046.693540 -3286666.439106 0.000000 8760647.410566 0.000000 1202.015605 +EDGE_SE2 180 181 0.557570 -0.008188 -0.051388 11.529199 -11.385701 0.000000 321.175409 0.000000 2261.590530 +EDGE_SE2 181 182 0.573085 -0.036151 -0.172968 14.630195 -31.871096 0.000000 299.756322 0.000000 1817.053357 +EDGE_SE2 182 183 0.603594 -0.027970 -0.056017 11.135892 -2.551709 0.000000 273.866587 0.000000 2241.806837 +EDGE_SE2 183 184 0.635433 -0.054532 -0.150813 12.107735 -15.262873 0.000000 244.855650 0.000000 1887.689196 +EDGE_SE2 184 185 0.634881 -0.022979 -0.096285 11.965079 -14.190439 0.000000 246.914669 0.000000 2080.142393 +EDGE_SE2 185 186 0.643298 -0.040128 -0.069768 11.123925 -1.715150 0.000000 240.694352 0.000000 2184.544034 +EDGE_SE2 186 187 0.616544 -0.013175 -0.025584 11.115593 -1.062453 0.000000 262.945790 0.000000 2376.826796 +EDGE_SE2 187 188 0.637286 0.000267 -0.008123 11.128264 -2.008140 0.000000 246.207666 0.000000 2459.874568 +EDGE_SE2 188 189 0.639354 -0.005159 -0.029399 11.217330 -4.979110 0.000000 244.512278 0.000000 2359.242182 +EDGE_SE2 189 190 0.641605 -0.016631 -0.026189 11.111129 -0.063557 0.000000 242.757543 0.000000 2374.025058 +EDGE_SE2 190 191 0.641101 -0.008160 -0.020962 11.126855 -1.911760 0.000000 243.247747 0.000000 2398.395787 +EDGE_SE2 191 192 0.634787 -0.009757 -0.024655 11.131543 -2.200448 0.000000 248.088013 0.000000 2381.138634 +EDGE_SE2 192 193 0.586234 -0.010454 -0.051260 11.423659 -9.345831 0.000000 290.571036 0.000000 2262.141300 +EDGE_SE2 193 194 0.611583 -0.006689 -0.021980 11.142360 -2.829372 0.000000 267.292453 0.000000 2393.620056 +EDGE_SE2 194 195 0.610567 -0.010284 -0.023227 11.121593 -1.641455 0.000000 268.159748 0.000000 2387.789433 +EDGE_SE2 195 196 0.641859 -0.011003 -0.041852 11.252480 -5.719563 0.000000 242.515471 0.000000 2303.180363 +EDGE_SE2 196 197 0.640092 -0.013813 -0.028233 11.121429 -1.549936 0.000000 243.946727 0.000000 2364.595903 +EDGE_SE2 197 198 0.639039 -0.009178 -0.058660 11.569437 -10.339579 0.000000 244.366482 0.000000 2230.627234 +EDGE_SE2 198 199 0.637088 -0.027408 -0.061598 11.192373 -4.367444 0.000000 245.840841 0.000000 2218.297682 +EDGE_SE2 199 200 0.636910 -0.008520 -0.021764 11.127669 -1.974000 0.000000 246.454469 0.000000 2394.632181 +EDGE_SE2 200 201 0.639616 -0.019900 -0.056243 11.258405 -5.857515 0.000000 244.050370 0.000000 2240.847600 +EDGE_SE2 201 202 0.573162 0.008125 0.017141 11.113691 0.869688 0.000000 304.336907 0.000000 2416.449299 +EDGE_SE2 202 203 0.807715 -0.017801 -0.055477 11.269967 -4.748397 0.000000 153.046283 0.000000 2244.101317 +EDGE_SE2 203 204 0.600516 -0.019464 -0.097088 12.222178 -17.152147 0.000000 275.898243 0.000000 2077.098438 +EDGE_SE2 204 205 0.607570 -0.009135 -0.005030 11.137105 2.598215 0.000000 270.811426 0.000000 2475.038492 +EDGE_SE2 205 206 0.587179 0.007336 0.006623 11.120721 -1.637028 0.000000 289.985432 0.000000 2467.211100 +EDGE_SE2 206 207 0.607993 0.006080 0.021126 11.143219 2.885684 0.000000 270.462940 0.000000 2397.625450 +EDGE_SE2 207 208 0.644034 -0.008545 -0.004095 11.130455 2.108903 0.000000 241.029670 0.000000 2479.650084 +EDGE_SE2 208 209 0.640840 0.009001 0.044393 11.325040 7.046915 0.000000 243.239179 0.000000 2291.986757 +EDGE_SE2 209 210 0.641153 -0.014043 -0.012923 11.129806 2.082671 0.000000 243.128297 0.000000 2436.616291 +EDGE_SE2 210 211 0.640990 0.006728 -0.001668 11.145470 -2.824640 0.000000 243.325777 0.000000 2491.680820 +EDGE_SE2 211 212 0.638573 -0.025254 -0.057210 11.184192 -4.132365 0.000000 244.776704 0.000000 2236.750195 +EDGE_SE2 212 213 0.648396 -0.008808 -0.024826 11.139763 -2.548475 0.000000 237.786398 0.000000 2380.344078 +EDGE_SE2 213 214 0.637242 -0.004643 -0.007684 11.111148 -0.093735 0.000000 246.245036 0.000000 2462.018335 +EDGE_SE2 214 215 0.369747 -0.004429 -0.039914 11.673090 -20.110851 0.000000 730.793592 0.000000 2311.772848 +EDGE_SE2 215 216 0.006980 -0.001179 -0.507763 222524.090867 -628114.036197 0.000000 1773063.824260 0.000000 1099.699039 +EDGE_SE2 216 217 -0.001832 0.001260 -0.551814 52174.391125 1025898.356469 0.000000 20176415.615022 0.000000 1038.151360 +EDGE_SE2 217 218 0.000862 -0.000506 -0.060277 20602967.870958 40459206.697150 0.000000 79452073.533188 0.000000 2223.828683 +EDGE_SE2 218 219 0.576874 -0.106568 -0.173874 11.132755 2.459345 0.000000 290.557594 0.000000 1814.249623 +EDGE_SE2 219 220 0.629125 -0.005523 -0.044144 11.413053 -8.534327 0.000000 252.332357 0.000000 2293.080041 +EDGE_SE2 220 221 0.642903 0.008921 0.051755 11.442103 8.733716 0.000000 241.563444 0.000000 2260.012484 +EDGE_SE2 221 222 0.635198 -0.000697 -0.024981 11.246132 -5.652071 0.000000 247.710771 0.000000 2379.624210 +EDGE_SE2 222 223 0.639045 0.029371 0.096256 11.701399 11.718901 0.000000 243.764798 0.000000 2080.252449 +EDGE_SE2 223 224 0.637940 -0.001297 -0.026485 11.251362 -5.734476 0.000000 245.578734 0.000000 2372.656095 +EDGE_SE2 224 225 0.639421 0.008657 0.048309 11.393218 8.109986 0.000000 244.256072 0.000000 2274.895125 +EDGE_SE2 225 226 0.638048 -0.023812 -0.051167 11.156122 -3.246372 0.000000 245.250378 0.000000 2262.541595 +EDGE_SE2 226 227 0.642744 0.047412 0.156718 12.692747 18.992206 0.000000 239.168545 0.000000 1868.465232 +EDGE_SE2 227 228 0.588969 -0.135551 -0.358747 15.698176 -34.406864 0.000000 269.191657 0.000000 1354.137035 +EDGE_SE2 228 229 0.605993 0.034684 0.124928 12.304340 17.583695 0.000000 270.228487 0.000000 1975.560427 +EDGE_SE2 229 230 0.370582 0.002463 -0.025443 11.849164 -22.992568 0.000000 727.398994 0.000000 2377.480475 +EDGE_SE2 230 231 -0.130796 -0.004868 0.073003 18.577316 208.431226 0.000000 5829.807352 0.000000 2171.391514 +EDGE_SE2 231 232 0.345343 -0.135465 -0.413759 12.252120 -28.551107 0.000000 725.536788 0.000000 1250.803404 +EDGE_SE2 232 233 0.649941 0.026872 0.109205 12.147339 15.241388 0.000000 235.289518 0.000000 2031.965694 +EDGE_SE2 233 234 0.647791 -0.001996 -0.038195 11.391127 -7.971100 0.000000 238.021188 0.000000 2319.434660 +EDGE_SE2 234 235 0.300180 0.002544 0.000515 11.180724 -8.744740 0.000000 1109.628316 0.000000 2497.426988 +EDGE_SE2 235 236 0.331863 0.149674 0.417637 11.138398 -4.503817 0.000000 754.488686 0.000000 1243.969525 +EDGE_SE2 236 237 0.654682 0.025212 0.076902 11.438281 8.513385 0.000000 232.640473 0.000000 2155.696624 +EDGE_SE2 237 238 0.648140 0.014417 -0.026834 11.656908 -11.112994 0.000000 237.383264 0.000000 2371.043534 +EDGE_SE2 238 239 0.643519 -0.017811 -0.061244 11.370468 -7.722173 0.000000 241.033805 0.000000 2219.777847 +EDGE_SE2 239 240 0.603843 -0.096900 -0.209505 11.761203 -12.890609 0.000000 266.717846 0.000000 1708.931569 +EDGE_SE2 240 241 0.584456 0.014283 0.092258 12.403890 19.031519 0.000000 291.281847 0.000000 2095.509047 +EDGE_SE2 241 242 0.612687 0.022692 0.027357 11.134913 -2.463133 0.000000 266.004463 0.000000 2368.630078 +EDGE_SE2 242 243 0.648066 -0.017400 -0.010559 11.171248 3.692755 0.000000 237.869261 0.000000 2448.029575 +EDGE_SE2 243 244 0.642215 0.026261 0.062075 11.214953 4.895996 0.000000 241.951020 0.000000 2216.305562 +EDGE_SE2 244 245 0.634243 -0.022273 -0.061989 11.282517 -6.373688 0.000000 248.115451 0.000000 2216.664530 +EDGE_SE2 245 246 0.645668 -0.028614 -0.079256 11.390140 -7.976362 0.000000 239.124210 0.000000 2146.303161 +EDGE_SE2 246 247 0.643529 0.022831 0.100014 12.068378 14.809059 0.000000 240.209522 0.000000 2066.063111 +EDGE_SE2 247 248 0.564321 0.027061 0.024967 11.270232 -6.932385 0.000000 313.133504 0.000000 2379.689217 +EDGE_SE2 248 249 -0.035940 0.003373 0.183988 5772.276933 20220.354842 0.000000 70979.863375 0.000000 1783.386223 +EDGE_SE2 249 250 0.007750 -0.001049 -0.606852 338497.920927 -662461.020100 0.000000 1296530.178991 0.000000 968.251297 +EDGE_SE2 250 251 0.463939 -0.175406 -0.437806 13.410741 -30.065645 0.000000 404.193089 0.000000 1209.314960 +EDGE_SE2 251 252 0.574959 0.003510 0.002433 11.115040 -1.069896 0.000000 302.485346 0.000000 2487.879253 +EDGE_SE2 252 253 0.605120 -0.005928 -0.017244 11.125640 -1.950811 0.000000 273.056569 0.000000 2415.959973 +EDGE_SE2 253 254 0.610735 -0.012632 -0.047846 11.300633 -6.974744 0.000000 267.794244 0.000000 2276.905934 +EDGE_SE2 254 255 0.044400 0.000523 0.074991 213.390433 3196.298492 0.000000 50517.134043 0.000000 2163.367754 +EDGE_SE2 255 256 0.001043 -0.000895 -0.499566 2299182.592246 10791888.202847 0.000000 50655150.120270 0.000000 1111.754353 +EDGE_SE2 256 257 0.555824 -0.061442 -0.099167 11.147977 3.373126 0.000000 319.742706 0.000000 2069.248487 +EDGE_SE2 257 258 0.629719 0.018359 0.091632 12.050310 15.010875 0.000000 251.024412 0.000000 2097.913089 +EDGE_SE2 258 259 0.636152 0.019457 0.038906 11.127473 1.964002 0.000000 246.855618 0.000000 2316.261026 +EDGE_SE2 259 260 0.591139 -0.005281 -0.010083 11.111475 -0.316152 0.000000 286.144813 0.000000 2450.337378 +EDGE_SE2 260 261 0.038207 -0.011731 -0.314328 28.012479 -1028.395525 0.000000 62585.773083 0.000000 1447.213112 +EDGE_SE2 261 262 0.655511 -0.012976 0.004878 11.245910 5.462837 0.000000 232.497259 0.000000 2475.787308 +EDGE_SE2 262 263 0.621841 0.001156 0.011526 11.134237 2.392264 0.000000 258.583295 0.000000 2443.351271 +EDGE_SE2 263 264 0.608889 0.019368 0.094641 12.130010 16.192201 0.000000 268.435238 0.000000 2086.395259 +EDGE_SE2 264 265 0.612314 0.007199 0.017955 11.120930 1.584091 0.000000 266.671128 0.000000 2412.586253 +EDGE_SE2 265 266 0.576085 -0.083302 -0.132058 11.148980 3.279437 0.000000 295.110014 0.000000 1950.754657 +EDGE_SE2 266 267 0.757425 -0.007866 -0.038469 11.239778 -4.580310 0.000000 174.161685 0.000000 2318.210856 +EDGE_SE2 267 268 0.631857 -0.080953 -0.120705 11.121739 1.581391 0.000000 246.417934 0.000000 1990.478036 +EDGE_SE2 268 269 0.641922 0.003817 0.021827 11.169502 3.676650 0.000000 242.613796 0.000000 2394.336911 +EDGE_SE2 269 270 0.637667 0.034307 0.104727 11.718968 11.913668 0.000000 244.612698 0.000000 2048.472187 +EDGE_SE2 270 271 0.640010 -0.062261 -0.119686 11.230091 -5.238185 0.000000 241.725444 0.000000 1994.102659 +EDGE_SE2 271 272 0.644232 0.019193 0.057497 11.287428 6.360389 0.000000 240.553533 0.000000 2235.536271 +EDGE_SE2 272 273 0.634342 0.083237 0.206754 12.465423 17.719715 0.000000 242.954542 0.000000 1716.732048 +EDGE_SE2 273 274 0.640984 0.007900 0.019834 11.124210 1.744119 0.000000 243.341574 0.000000 2403.704272 +EDGE_SE2 274 275 0.606472 -0.086361 -0.177559 11.443959 -9.213419 0.000000 266.144138 0.000000 1802.912528 +EDGE_SE2 275 276 0.612197 0.023588 0.108696 12.366721 17.860495 0.000000 265.168738 0.000000 2033.831865 +EDGE_SE2 276 277 0.583581 0.010361 -0.030920 11.779645 -13.724550 0.000000 292.866956 0.000000 2352.285755 +EDGE_SE2 277 278 0.636078 -0.067917 -0.095289 11.139759 2.584894 0.000000 244.345909 0.000000 2083.927264 +EDGE_SE2 278 279 0.642761 -0.012725 -0.054157 11.383584 -7.926158 0.000000 241.680475 0.000000 2249.724898 +EDGE_SE2 279 280 0.638781 -0.006089 0.003079 11.148313 2.949856 0.000000 245.014031 0.000000 2484.675811 +EDGE_SE2 280 281 0.641856 -0.029617 -0.099276 11.763757 -12.263888 0.000000 241.562200 0.000000 2068.838150 +EDGE_SE2 281 282 0.639782 0.004798 0.040856 11.370470 7.772433 0.000000 244.033931 0.000000 2307.590321 +EDGE_SE2 282 283 0.642050 0.012891 -0.006948 11.280026 -6.249342 0.000000 242.317369 0.000000 2465.618735 +EDGE_SE2 283 284 0.634635 -0.008598 0.028031 11.520810 9.848040 0.000000 247.830973 0.000000 2365.525243 +EDGE_SE2 284 285 0.644186 0.019368 0.016799 11.151476 -3.044364 0.000000 240.720053 0.000000 2418.075116 +EDGE_SE2 285 286 0.616883 0.003268 0.049122 11.594142 11.014881 0.000000 262.290847 0.000000 2271.370705 +EDGE_SE2 286 287 0.041606 0.000178 -0.109420 754.499701 -6510.220695 0.000000 57024.326077 0.000000 2031.178201 +EDGE_SE2 287 288 0.009415 -0.003373 -0.619963 74221.251106 -262085.361102 0.000000 925608.832783 0.000000 952.642204 +EDGE_SE2 288 289 0.020008 -0.006408 -0.604589 19113.152514 -62948.109898 0.000000 207447.816761 0.000000 970.984702 +EDGE_SE2 289 290 0.454169 -0.104092 -0.231282 11.127187 -2.688060 0.000000 460.591382 0.000000 1649.016296 +EDGE_SE2 290 291 0.647578 0.004260 0.009723 11.113360 0.715048 0.000000 238.447481 0.000000 2452.084944 +EDGE_SE2 291 292 0.634089 -0.015008 -0.055281 11.348399 -7.502724 0.000000 248.336711 0.000000 2244.935000 +EDGE_SE2 292 293 0.642557 -0.005982 -0.023777 11.159473 -3.342559 0.000000 242.132375 0.000000 2385.224555 +EDGE_SE2 293 294 0.639112 0.001322 -0.000108 11.112218 -0.508677 0.000000 244.817748 0.000000 2499.460087 +EDGE_SE2 294 295 0.640372 -0.027705 -0.113609 12.259570 -16.292856 0.000000 242.253178 0.000000 2015.925806 +EDGE_SE2 295 296 0.642975 -0.021060 -0.046516 11.154844 -3.174767 0.000000 241.583458 0.000000 2282.696976 +EDGE_SE2 296 297 0.642345 0.000782 -0.012863 11.156958 -3.255777 0.000000 242.314814 0.000000 2436.904980 +EDGE_SE2 297 298 0.647985 0.003784 0.003363 11.112504 -0.562400 0.000000 238.150885 0.000000 2483.269445 +EDGE_SE2 298 299 0.612845 -0.007635 0.065661 12.664708 19.847274 0.000000 264.661036 0.000000 2201.414711 +EDGE_SE2 299 300 0.612360 0.028900 0.046427 11.111248 -0.186667 0.000000 266.084327 0.000000 2283.085285 +EDGE_SE2 300 301 0.590205 -0.014952 -0.054929 11.352681 -8.158527 0.000000 286.648280 0.000000 2246.433393 +EDGE_SE2 301 302 0.327130 -0.001110 -0.017014 11.282416 -12.575459 0.000000 934.273069 0.000000 2417.052846 +EDGE_SE2 302 303 0.000000 0.000000 0.007958 11.135739 3.094647 0.000000 399.975372 0.000000 2460.679983 +EDGE_SE2 303 304 0.531735 -0.000572 0.013349 11.182383 4.940694 0.000000 353.608097 0.000000 2434.568072 +EDGE_SE2 304 305 0.632029 0.091742 0.189082 11.583394 10.503320 0.000000 244.699503 0.000000 1768.138981 +EDGE_SE2 305 306 0.638032 0.009278 -0.014535 11.309292 -6.814055 0.000000 245.399171 0.000000 2428.879337 +EDGE_SE2 306 307 0.649045 -0.016359 -0.033059 11.125080 -1.777236 0.000000 237.218596 0.000000 2342.554790 +EDGE_SE2 307 308 0.638862 -0.008726 -0.051832 11.451746 -8.918684 0.000000 244.624962 0.000000 2259.681604 +EDGE_SE2 308 309 0.645288 0.030453 0.096996 11.678208 11.369540 0.000000 239.055109 0.000000 2077.446846 +EDGE_SE2 309 310 0.636777 0.000884 -0.032322 11.378630 -7.932902 0.000000 246.350008 0.000000 2345.900799 +EDGE_SE2 310 311 0.290424 -0.002112 0.179746 51.710880 214.552149 0.000000 1144.926065 0.000000 1796.234285 +EDGE_SE2 311 312 0.007354 0.003264 1.002917 471360.416969 711283.404228 0.000000 1073363.876974 0.000000 623.180856 +EDGE_SE2 312 313 0.200119 0.102327 0.503683 13.003444 61.001684 0.000000 1977.575148 0.000000 1105.674845 +EDGE_SE2 313 314 0.633848 0.018391 0.043519 11.161147 3.447475 0.000000 248.643057 0.000000 2295.827675 +EDGE_SE2 314 315 0.633704 0.002276 -0.000875 11.115856 -1.062415 0.000000 249.007791 0.000000 2495.630735 +EDGE_SE2 315 316 0.639305 0.015820 0.052631 11.292626 6.506496 0.000000 244.340479 0.000000 2256.252482 +EDGE_SE2 316 317 0.637745 0.004302 0.011142 11.115650 1.032197 0.000000 245.854624 0.000000 2445.207439 +EDGE_SE2 317 318 0.636745 0.035394 0.095957 11.494620 9.481044 0.000000 245.500106 0.000000 2081.387677 +EDGE_SE2 318 319 0.348842 0.011538 0.072712 12.383431 32.072340 0.000000 819.582938 0.000000 2172.569763 +EDGE_SE2 319 320 0.000816 -0.000527 0.973228 106005797.819726 2536098.274165 0.000000 60685.105012 0.000000 642.074570 +EDGE_SE2 320 321 0.006777 0.006256 1.044793 102222.634261 331234.073682 0.000000 1073432.269379 0.000000 597.917382 +EDGE_SE2 321 322 0.006473 0.002839 1.001084 615262.184536 923437.444301 0.000000 1386009.040037 0.000000 624.323050 +EDGE_SE2 322 323 0.016353 0.013170 0.997277 22353.154021 67589.307695 0.000000 204482.767224 0.000000 626.705357 +EDGE_SE2 323 324 0.008916 0.001230 0.663199 311347.556233 536104.854899 0.000000 923155.252921 0.000000 903.756801 +EDGE_SE2 324 325 0.003144 -0.000405 -0.524891 1487579.272379 -3549001.141685 0.000000 8467125.043520 0.000000 1075.133530 +EDGE_SE2 325 326 0.023808 -0.007961 -0.592174 11258.329132 -40719.337055 0.000000 147431.069280 0.000000 986.186273 +EDGE_SE2 326 327 0.020978 -0.009992 -0.620226 5671.563195 -31879.996101 0.000000 179561.107529 0.000000 952.332958 +EDGE_SE2 327 328 0.643658 -0.034894 -0.045241 11.129369 2.047184 0.000000 240.647976 0.000000 2288.269306 +EDGE_SE2 328 329 0.649334 -0.010852 -0.054672 11.436629 -8.570843 0.000000 236.780423 0.000000 2247.528337 +EDGE_SE2 329 330 0.639632 -0.008474 -0.018872 11.118489 -1.311825 0.000000 244.371181 0.000000 2408.245480 +EDGE_SE2 330 331 0.641038 0.003713 -0.014179 11.203728 -4.636800 0.000000 243.249680 0.000000 2430.584821 +EDGE_SE2 331 332 0.640252 -0.011677 -0.018427 11.111120 -0.044254 0.000000 243.867115 0.000000 2410.350498 +EDGE_SE2 332 333 0.177633 -0.001729 0.065170 28.796073 235.654693 0.000000 3151.244188 0.000000 2203.444704 +EDGE_SE2 333 334 0.000905 -0.002029 1.057518 13067665.297415 -9690930.296947 0.000000 7186773.836950 0.000000 590.544626 +EDGE_SE2 334 335 0.024703 0.015296 0.997066 21742.343151 45843.877395 0.000000 96722.659299 0.000000 626.837793 +EDGE_SE2 335 336 0.010478 0.002030 0.946908 412732.144616 438156.323325 0.000000 465170.257567 0.000000 659.552164 +EDGE_SE2 336 337 0.008745 0.002954 0.985008 440385.721295 568301.950425 0.000000 733402.863015 0.000000 634.476419 +EDGE_SE2 337 338 -0.003685 -0.001824 0.981724 1470665.482891 2556461.697178 0.000000 4443948.812959 0.000000 636.580801 +EDGE_SE2 338 339 -0.005129 -0.003808 1.041677 377018.548764 884152.776785 0.000000 2073514.322517 0.000000 599.744033 +EDGE_SE2 339 340 0.010570 0.010289 1.011780 25946.779143 106050.417947 0.000000 433649.108522 0.000000 617.702041 +EDGE_SE2 340 341 0.113717 0.080150 0.628571 12.212286 75.337385 0.000000 5165.350612 0.000000 942.598218 +EDGE_SE2 341 342 0.654766 0.022058 0.099815 12.080273 14.632015 0.000000 232.019342 0.000000 2066.810844 +EDGE_SE2 342 343 0.628741 0.054742 0.130801 11.574390 10.533194 0.000000 250.595866 0.000000 1955.093991 +EDGE_SE2 343 344 0.635892 -0.007155 -0.010075 11.111438 0.277943 0.000000 247.273507 0.000000 2450.376193 +EDGE_SE2 344 345 0.267580 0.003485 -0.027538 13.388942 -56.127772 0.000000 1394.149289 0.000000 2367.795687 +EDGE_SE2 345 346 0.004489 0.000038 -0.647423 1844936.688291 -2397918.213433 0.000000 3116674.368121 0.000000 921.148732 +EDGE_SE2 346 347 0.072838 -0.046842 -0.558829 13.253512 168.933111 0.000000 13331.862665 0.000000 1028.828663 +EDGE_SE2 347 348 0.589079 -0.006098 -0.016843 11.122785 -1.798313 0.000000 288.130205 0.000000 2417.865855 +EDGE_SE2 348 349 0.616820 -0.017333 -0.040458 11.149561 -3.109556 0.000000 262.589175 0.000000 2309.356075 +EDGE_SE2 349 350 0.785503 -0.000917 -0.019918 11.164179 -2.829897 0.000000 162.017193 0.000000 2403.308352 +EDGE_SE2 350 351 0.270645 -0.005037 -0.029292 11.265595 -14.459903 0.000000 1364.581559 0.000000 2359.732718 +EDGE_SE2 351 352 0.002244 -0.000330 -0.288296 389945.087215 -2724716.373664 0.000000 19039335.129753 0.000000 1506.290344 +EDGE_SE2 352 353 0.003402 -0.001192 -0.665425 800995.211276 -2349889.351851 0.000000 6894005.592158 0.000000 901.342500 +EDGE_SE2 353 354 -0.005763 0.001670 -0.603397 277124.929036 -832459.339385 0.000000 2500747.295676 0.000000 972.428940 +EDGE_SE2 354 355 0.000000 0.000000 -0.720990 180.577269 -192.833418 0.000000 230.533842 0.000000 844.079125 +EDGE_SE2 355 356 0.003943 -0.001205 -0.575253 444990.541595 -1555501.608157 0.000000 5437532.684522 0.000000 1007.486830 +EDGE_SE2 356 357 0.020153 -0.008599 -0.653072 12735.537924 -49883.324785 0.000000 195567.746252 0.000000 914.863854 +EDGE_SE2 357 358 0.015309 -0.003110 -0.615454 66643.110857 -151211.449053 0.000000 343163.086320 0.000000 957.967591 +EDGE_SE2 358 359 0.006974 -0.000995 -0.614029 417035.012297 -816381.545249 0.000000 1598190.077659 0.000000 959.659886 +EDGE_SE2 359 360 0.004457 -0.000580 -0.176301 10913.841058 -232052.237339 0.000000 4938979.710352 0.000000 1806.770854 +EDGE_SE2 360 361 0.010594 0.005702 0.919376 117786.647020 259806.659966 0.000000 573130.987341 0.000000 678.609427 +EDGE_SE2 361 362 0.219803 0.130838 0.533743 11.126432 -4.821230 0.000000 1528.288566 0.000000 1062.759073 +EDGE_SE2 362 363 0.297072 -0.003532 -0.006476 11.143964 6.070793 0.000000 1132.926894 0.000000 2467.931845 +EDGE_SE2 363 364 0.289348 0.182399 0.614616 13.404127 43.923133 0.000000 852.466620 0.000000 958.962236 +EDGE_SE2 364 365 0.292841 -0.019896 -0.497082 210.238012 -435.053006 0.000000 961.616130 0.000000 1115.446721 +EDGE_SE2 365 366 0.158985 -0.083838 -0.554071 25.686079 -211.524041 0.000000 3080.923734 0.000000 1035.138105 +EDGE_SE2 366 367 0.639497 -0.004946 0.002087 11.133620 2.291973 0.000000 244.487349 0.000000 2489.597576 +EDGE_SE2 367 368 0.604131 -0.012617 -0.052944 11.381139 -8.419024 0.000000 273.602223 0.000000 2254.911286 +EDGE_SE2 368 369 0.002209 0.000313 -0.259186 3043052.869717 -7202482.111400 0.000000 17047344.890980 0.000000 1576.740546 +EDGE_SE2 369 370 0.005991 -0.002050 -0.599321 177021.973379 -640449.340665 0.000000 2317243.809168 0.000000 977.391885 +EDGE_SE2 370 371 0.006708 -0.002639 -0.557206 63344.214539 -343349.901593 0.000000 1861425.577547 0.000000 1030.974377 +EDGE_SE2 371 372 0.558575 -0.019962 -0.032348 11.114630 1.042696 0.000000 320.094134 0.000000 2345.782636 +EDGE_SE2 372 373 0.602488 0.010152 -0.002327 11.208284 -5.066873 0.000000 275.312725 0.000000 2488.405486 +EDGE_SE2 373 374 0.632591 -0.017325 -0.065949 11.465862 -9.193251 0.000000 249.351067 0.000000 2200.225307 +EDGE_SE2 374 375 0.469417 0.004030 -0.028771 11.728554 -16.521047 0.000000 453.167816 0.000000 2362.123399 +EDGE_SE2 375 376 0.002158 0.000483 0.698524 4333313.980583 8354996.990813 0.000000 16109195.449061 0.000000 866.555999 +EDGE_SE2 376 377 0.046225 0.038326 0.699019 12.380728 187.607270 0.000000 27733.237753 0.000000 866.051140 +EDGE_SE2 377 378 0.665310 0.013616 0.055080 11.368301 7.426696 0.000000 225.566926 0.000000 2245.790433 +EDGE_SE2 378 379 0.642743 0.038423 0.085729 11.266862 5.984327 0.000000 241.043246 0.000000 2120.787390 +EDGE_SE2 379 380 0.640645 0.038346 0.120298 11.958441 13.985039 0.000000 241.931786 0.000000 1991.924564 +EDGE_SE2 380 381 0.233459 0.003584 0.150906 44.408710 244.130938 0.000000 1801.027395 0.000000 1887.384136 +EDGE_SE2 381 382 0.006327 0.000255 1.053123 1795131.477569 1120171.329981 0.000000 699008.143264 0.000000 593.075621 +EDGE_SE2 382 383 -0.003556 -0.002021 0.980056 1193066.389244 2388759.272445 0.000000 4782832.968807 0.000000 637.653764 +EDGE_SE2 383 384 0.001991 0.002244 0.957091 138704.428768 1233640.966374 0.000000 10972926.458664 0.000000 652.706547 +EDGE_SE2 384 385 0.011270 0.001792 1.022982 445019.439592 379059.233315 0.000000 322894.736351 0.000000 610.880091 +EDGE_SE2 385 386 0.168577 0.055826 0.222392 40.994230 -305.838725 0.000000 3141.216954 0.000000 1673.088872 +EDGE_SE2 386 387 0.606264 0.162988 0.328749 12.170230 15.994975 0.000000 252.669738 0.000000 1415.970180 +EDGE_SE2 387 388 0.635832 0.013644 0.010758 11.138130 -2.525694 0.000000 247.211302 0.000000 2447.065724 +EDGE_SE2 388 389 0.627947 -0.024187 -0.080320 11.534345 -10.113978 0.000000 252.803888 0.000000 2142.077483 +EDGE_SE2 389 390 0.069191 0.001300 0.478702 4122.849667 8300.847325 0.000000 16769.002054 0.000000 1143.348663 +EDGE_SE2 390 391 -0.133725 -0.033239 0.382997 112.537800 723.030020 0.000000 5165.300931 0.000000 1307.066045 +EDGE_SE2 391 392 -0.002743 0.000191 1.047762 10690557.469801 5209631.734700 0.000000 2538727.272155 0.000000 596.185006 +EDGE_SE2 392 393 0.028217 0.013447 1.259453 54184.105027 51083.362632 0.000000 48181.052425 0.000000 489.703700 +EDGE_SE2 393 394 0.008510 0.003621 0.998557 368727.424224 543264.764209 0.000000 800454.686659 0.000000 625.902660 +EDGE_SE2 394 395 -0.234595 -0.069505 0.339597 15.518106 85.399492 0.000000 1665.996927 0.000000 1393.130101 +EDGE_SE2 395 396 0.000000 0.000000 0.001250 11.111719 0.486111 0.000000 399.999392 0.000000 2493.761699 +EDGE_SE2 396 397 0.001351 -0.000419 -0.009641 4125762.827775 13757530.022207 0.000000 45875198.303653 0.000000 2452.483262 +EDGE_SE2 397 398 0.004038 0.000754 0.199105 1257.017158 85923.998064 0.000000 5925765.672764 0.000000 1738.703710 +EDGE_SE2 398 399 0.122070 0.031296 0.300741 26.669772 312.344207 0.000000 6281.503348 0.000000 1477.604991 +EDGE_SE2 399 400 0.657179 0.003449 0.051415 11.580586 10.161892 0.000000 231.067499 0.000000 2261.474377 +EDGE_SE2 400 401 0.635899 -0.025106 -0.091900 11.758968 -12.342900 0.000000 246.266720 0.000000 2096.883376 +EDGE_SE2 401 402 0.629497 -0.118990 -0.266463 12.583010 -18.442000 0.000000 242.178169 0.000000 1558.672941 +EDGE_SE2 402 403 0.633089 -0.005208 -0.033694 11.265698 -6.068382 0.000000 249.328787 0.000000 2339.677603 +EDGE_SE2 403 404 0.592291 -0.016693 -0.078703 11.809289 -13.806384 0.000000 284.130876 0.000000 2148.504341 +EDGE_SE2 404 405 0.003136 0.000509 0.534523 1319098.360620 3365183.519520 0.000000 8585083.951642 0.000000 1061.678944 +EDGE_SE2 405 406 -0.004868 -0.003220 0.979360 434468.323030 1042340.456046 0.000000 2500772.052588 0.000000 638.102476 +EDGE_SE2 406 407 0.360175 0.041381 0.128315 11.256473 10.438221 0.000000 760.666018 0.000000 1963.718742 +EDGE_SE2 407 408 0.616703 -0.006846 -0.037807 11.290664 -6.721434 0.000000 262.722906 0.000000 2321.169297 +EDGE_SE2 408 409 0.297889 -0.008429 -0.099428 16.743853 -79.045672 0.000000 1120.378773 0.000000 2068.266140 +EDGE_SE2 409 410 0.004317 -0.001082 -0.627510 701653.157370 -1746561.647658 0.000000 4347637.661335 0.000000 943.827609 +EDGE_SE2 410 411 -0.000994 0.000097 -0.588953 22378715.073239 -41773418.211876 0.000000 77976755.075261 0.000000 990.188564 +EDGE_SE2 411 412 0.546073 -0.101761 -0.202851 11.219546 -5.824669 0.000000 323.987402 0.000000 1727.890996 +EDGE_SE2 412 413 0.631438 -0.020731 -0.079531 11.633150 -11.167657 0.000000 250.014003 0.000000 2145.209801 +EDGE_SE2 413 414 0.633214 0.018368 0.103733 12.438356 17.726525 0.000000 247.864474 0.000000 2052.163475 +EDGE_SE2 414 415 0.642786 -0.007808 0.006683 11.192966 4.346517 0.000000 241.911433 0.000000 2466.917009 +EDGE_SE2 415 416 0.306053 0.007945 -0.055552 18.109521 -85.672115 0.000000 1059.879484 0.000000 2243.782429 +EDGE_SE2 416 417 0.267976 -0.110772 -0.425050 12.399497 -38.940001 0.000000 1188.028820 0.000000 1231.061654 +EDGE_SE2 417 418 0.438509 -0.005278 -0.045468 11.679675 -16.999880 0.000000 519.402521 0.000000 2287.275721 +EDGE_SE2 418 419 -0.008030 -0.002982 0.430439 7637.313369 101662.498186 0.000000 1355241.825942 0.000000 1221.803385 +EDGE_SE2 419 420 -0.065315 -0.007710 0.215762 233.503005 2255.992653 0.000000 22896.400499 0.000000 1691.386574 +EDGE_SE2 420 421 -0.013305 -0.007156 0.966654 91010.544219 177739.023434 0.000000 347168.883115 0.000000 646.374313 +EDGE_SE2 421 422 -0.003762 0.002250 1.237922 4986989.532826 -1042930.375544 0.000000 218119.888862 0.000000 499.171886 +EDGE_SE2 422 423 0.004840 0.001590 0.345136 2976.169439 106843.491501 0.000000 3850030.373965 0.000000 1381.680463 +EDGE_SE2 423 424 0.000000 0.000000 0.000279 11.111141 0.108500 0.000000 399.999970 0.000000 2498.605584 +EDGE_SE2 424 425 -0.001184 -0.000773 0.011635 14427656.748816 -22661090.484365 0.000000 35593138.003454 0.000000 2442.824774 +EDGE_SE2 425 426 0.000000 0.000000 -0.009217 11.144147 -3.584186 0.000000 399.966964 0.000000 2454.544407 +EDGE_SE2 426 427 0.032570 0.000297 0.003027 14.602102 -573.593983 0.000000 94256.571445 0.000000 2484.933444 +EDGE_SE2 427 428 0.662478 0.017221 -0.005659 11.327981 -6.850147 0.000000 227.483295 0.000000 2471.943383 +EDGE_SE2 428 429 0.646109 -0.008556 -0.041027 11.287389 -6.342667 0.000000 239.327268 0.000000 2306.832289 +EDGE_SE2 429 430 0.343414 -0.005292 -0.046373 11.913023 -25.889333 0.000000 846.935174 0.000000 2283.320937 +EDGE_SE2 430 431 -0.023101 -0.000669 0.051637 107.302578 4242.658469 0.000000 187139.464787 0.000000 2260.519686 +EDGE_SE2 431 432 0.009902 -0.002457 -0.632717 138557.863737 -337512.999974 0.000000 822224.717657 0.000000 937.817169 +EDGE_SE2 432 433 0.001378 -0.000302 -0.678362 9999210.149914 -20053649.036543 0.000000 40218116.393371 0.000000 887.500758 +EDGE_SE2 433 434 0.513100 -0.123605 -0.228760 11.131390 2.656033 0.000000 358.981365 0.000000 1655.792374 +EDGE_SE2 434 435 0.631214 0.005719 -0.028704 11.453001 -9.049106 0.000000 250.621585 0.000000 2362.431102 +EDGE_SE2 435 436 0.631793 -0.021639 -0.009165 11.261393 5.992726 0.000000 250.081133 0.000000 2454.797368 +EDGE_SE2 436 437 0.639424 0.009664 0.007564 11.124412 -1.761949 0.000000 244.511544 0.000000 2462.604819 +EDGE_SE2 437 438 0.468926 -0.010782 -0.032675 11.152708 -4.294523 0.000000 454.487167 0.000000 2344.297271 +EDGE_SE2 438 439 0.003173 -0.000464 -0.440138 821397.131579 -2704073.669587 0.000000 8902055.008072 0.000000 1205.401670 +EDGE_SE2 439 440 -0.014852 0.005433 -0.648635 34474.470288 -112210.861458 0.000000 365363.698028 0.000000 919.794858 +EDGE_SE2 440 441 -0.024049 0.006849 -0.627372 18805.328328 -51499.965243 0.000000 141131.456239 0.000000 943.987688 +EDGE_SE2 441 442 -0.014780 0.003839 -0.634781 59210.969468 -147922.954315 0.000000 369626.867304 0.000000 935.450222 +EDGE_SE2 442 443 -0.000800 0.000601 -0.571864 520464.172419 7194009.672200 0.000000 99439862.677541 0.000000 1011.835875 +EDGE_SE2 443 444 0.017737 -0.005934 -0.596674 20918.075426 -74425.493858 0.000000 264954.124953 0.000000 980.635254 +EDGE_SE2 444 445 0.013295 -0.004859 -0.663772 47441.842994 -146367.463524 0.000000 451689.453992 0.000000 903.134403 +EDGE_SE2 445 446 0.005858 0.000522 0.198590 34655.344042 314604.971132 0.000000 2856945.136973 0.000000 1740.198174 +EDGE_SE2 446 447 0.027440 0.012672 0.626113 4057.920343 20653.549968 0.000000 105419.866954 0.000000 945.449998 +EDGE_SE2 447 448 0.642139 0.024176 0.015042 11.228997 -5.217769 0.000000 242.055366 0.000000 2426.453558 +EDGE_SE2 448 449 0.651924 0.033077 0.098456 11.620735 10.662081 0.000000 234.177343 0.000000 2071.928088 +EDGE_SE2 449 450 0.646061 0.005408 0.011249 11.113005 0.657701 0.000000 239.562562 0.000000 2444.690013 +EDGE_SE2 450 451 0.475342 0.014049 0.039952 11.157786 4.485326 0.000000 442.142124 0.000000 2311.603906 +EDGE_SE2 451 452 0.003128 0.000025 -0.382848 1482988.188246 -3599772.040321 0.000000 8738081.943140 0.000000 1307.347729 +EDGE_SE2 452 453 -0.001414 0.000044 -0.628930 15847694.024322 -23260624.874036 0.000000 34141069.617498 0.000000 942.182786 +EDGE_SE2 453 454 0.248647 -0.103850 -0.427200 12.471635 -43.090213 0.000000 1375.854801 0.000000 1227.355391 +EDGE_SE2 454 455 0.599080 -0.006587 -0.019767 11.131695 -2.346400 0.000000 278.577271 0.000000 2404.020135 +EDGE_SE2 455 456 0.632985 -0.015395 -0.063626 11.479192 -9.358780 0.000000 249.066485 0.000000 2209.846555 +EDGE_SE2 456 457 0.357560 -0.010532 -0.086657 13.629849 -43.977817 0.000000 778.975316 0.000000 2117.166652 +EDGE_SE2 457 458 0.008700 -0.003028 -0.643446 108644.728053 -340906.127357 0.000000 1069817.962261 0.000000 925.612330 +EDGE_SE2 458 459 -0.005152 0.003223 -0.605857 5968.917352 -126872.556203 0.000000 2701785.030428 0.000000 969.451909 +EDGE_SE2 459 460 0.416054 -0.104238 -0.255576 11.165314 -5.371986 0.000000 543.523585 0.000000 1585.820389 +EDGE_SE2 460 461 0.649228 -0.030811 -0.086883 11.462229 -8.893307 0.000000 236.365424 0.000000 2116.286282 +EDGE_SE2 461 462 0.546102 -0.010087 -0.039056 11.248462 -6.670465 0.000000 335.062438 0.000000 2315.592315 +EDGE_SE2 462 463 0.001368 -0.000392 0.843270 40115968.021050 19291406.563907 0.000000 9277076.794710 0.000000 735.803923 +EDGE_SE2 463 464 0.219986 0.165070 0.680690 12.900768 48.403186 0.000000 1320.227268 0.000000 885.043825 +EDGE_SE2 464 465 0.606621 0.010649 0.008756 11.131273 -2.291927 0.000000 271.643258 0.000000 2456.788366 +EDGE_SE2 465 466 0.582724 -0.019176 -0.054453 11.242627 -6.100006 0.000000 294.042673 0.000000 2248.462015 +EDGE_SE2 466 467 0.609463 -0.011568 -0.042219 11.250443 -5.994134 0.000000 268.982117 0.000000 2301.558596 +EDGE_SE2 467 468 0.645554 -0.004365 -0.036329 11.311111 -6.762186 0.000000 239.747111 0.000000 2327.794866 +EDGE_SE2 468 469 0.640915 -0.033457 -0.083791 11.342903 -7.324322 0.000000 242.550344 0.000000 2128.378819 +EDGE_SE2 469 470 0.496055 0.004661 0.018154 11.141432 3.461691 0.000000 406.321439 0.000000 2411.643257 +EDGE_SE2 470 471 0.003172 -0.000201 -0.200803 186163.578620 -1344733.466553 0.000000 9714134.809108 0.000000 1733.789946 +EDGE_SE2 471 472 0.023951 -0.007826 -0.634338 15457.850073 -46841.273730 0.000000 142054.355974 0.000000 935.957765 +EDGE_SE2 472 473 0.005795 -0.000612 -0.642279 770586.651464 -1294281.400636 0.000000 2173924.317941 0.000000 926.928274 +EDGE_SE2 473 474 0.006655 -0.002332 -0.633006 171083.550792 -560999.777087 0.000000 1839703.994891 0.000000 937.485259 +EDGE_SE2 474 475 0.004438 -0.002279 -0.575983 41353.024051 -405427.745271 0.000000 3975919.455633 0.000000 1006.553705 +EDGE_SE2 475 476 0.004920 -0.000853 -0.653637 861490.486597 -1647075.461555 0.000000 3149079.624245 0.000000 914.238796 +EDGE_SE2 476 477 -0.005593 0.002916 -0.561690 16496.747941 -202882.586381 0.000000 2496811.464145 0.000000 1025.062106 +EDGE_SE2 477 478 -0.008770 0.002879 -0.629412 110767.500374 -343119.326612 0.000000 1062982.494329 0.000000 941.625450 +EDGE_SE2 478 479 -0.005316 0.000950 -0.456182 260653.569609 -908664.641767 0.000000 3167842.768150 0.000000 1178.986119 +EDGE_SE2 479 480 -0.002143 -0.000584 0.559864 1701134.587605 5621159.573829 0.000000 18574462.284739 0.000000 1027.463821 +EDGE_SE2 480 481 0.016780 0.006185 0.998459 113112.243905 150237.129574 0.000000 199577.592411 0.000000 625.964239 +EDGE_SE2 481 482 0.002129 0.000684 0.334515 11133.789831 471436.097728 0.000000 19981887.764379 0.000000 1403.760085 +EDGE_SE2 482 483 0.000000 0.000000 -0.006313 11.126610 -2.454990 0.000000 399.984501 0.000000 2468.731408 +EDGE_SE2 483 484 0.461514 0.003388 0.034531 11.449878 12.456397 0.000000 469.130063 0.000000 2335.893245 +EDGE_SE2 484 485 0.630348 0.014297 -0.002799 11.267128 -6.122690 0.000000 251.389266 0.000000 2486.063539 +EDGE_SE2 485 486 0.640080 -0.006164 0.008991 11.191872 4.336635 0.000000 243.975902 0.000000 2455.644098 +EDGE_SE2 486 487 0.638592 0.022157 0.027672 11.122603 -1.639115 0.000000 244.911905 0.000000 2367.178245 +EDGE_SE2 487 488 0.641671 0.002950 0.035457 11.331743 7.147283 0.000000 242.644669 0.000000 2331.717176 +EDGE_SE2 488 489 0.486254 0.015193 0.029736 11.112036 -0.616989 0.000000 422.520775 0.000000 2357.698224 +EDGE_SE2 489 490 0.004012 0.001331 0.483683 148092.465768 898284.334868 0.000000 5449142.422335 0.000000 1135.684680 +EDGE_SE2 490 491 0.003142 0.002440 0.933695 460500.560493 1642380.154927 0.000000 5857718.767430 0.000000 668.596440 +EDGE_SE2 491 492 0.234443 0.072984 0.301949 11.111148 0.245247 0.000000 1658.639702 0.000000 1474.864302 +EDGE_SE2 492 493 0.622117 -0.019196 -0.055751 11.264294 -6.149470 0.000000 257.979045 0.000000 2242.936641 +EDGE_SE2 493 494 0.632902 -0.009810 -0.061610 11.617811 -10.980862 0.000000 249.080844 0.000000 2218.247533 +EDGE_SE2 494 495 0.635286 0.054465 0.110803 11.261154 5.934337 0.000000 245.819252 0.000000 2026.123532 +EDGE_SE2 495 496 0.641209 0.012116 0.121000 13.521763 23.526915 0.000000 240.723619 0.000000 1989.430553 +EDGE_SE2 496 497 0.639602 -0.025661 -0.083377 11.547127 -10.068553 0.000000 243.615831 0.000000 2130.005800 +EDGE_SE2 497 498 0.634982 -0.033636 -0.099467 11.622457 -10.978306 0.000000 246.809304 0.000000 2068.119413 +EDGE_SE2 498 499 0.638794 -0.029903 -0.015370 11.341287 7.326250 0.000000 244.297416 0.000000 2424.886152 +EDGE_SE2 499 500 0.581639 0.165523 0.331283 11.876261 14.147113 0.000000 272.681816 0.000000 1410.584918 +EDGE_SE2 500 501 0.608658 -0.019295 -0.065817 11.412115 -8.816677 0.000000 269.359185 0.000000 2200.770331 +EDGE_SE2 501 502 0.717458 -0.037860 -0.078159 11.229253 -4.643405 0.000000 193.613030 0.000000 2150.673003 +EDGE_SE2 502 503 0.468033 -0.006282 -0.011528 11.112706 0.842757 0.000000 456.422908 0.000000 2443.341609 +EDGE_SE2 503 504 0.001010 -0.000329 0.882265 76783402.732445 30131648.184749 0.000000 11824394.003794 0.000000 705.632337 +EDGE_SE2 504 505 0.222895 0.156032 0.638914 12.174041 37.721370 0.000000 1349.770700 0.000000 930.738499 +EDGE_SE2 505 506 0.625769 -0.021473 -0.145256 14.102191 -26.846905 0.000000 252.079673 0.000000 1906.052494 +EDGE_SE2 506 507 0.635814 -0.018204 -0.072178 11.558631 -10.268279 0.000000 246.715411 0.000000 2174.734405 +EDGE_SE2 507 508 0.638204 -0.013687 -0.007658 11.155629 3.229265 0.000000 245.359315 0.000000 2462.145389 +EDGE_SE2 508 509 0.642039 -0.008726 -0.051671 11.446573 -8.804866 0.000000 242.212186 0.000000 2260.373525 +EDGE_SE2 509 510 0.372102 -0.006043 -0.009950 11.139237 4.471542 0.000000 722.013535 0.000000 2450.982789 +EDGE_SE2 510 511 0.002084 -0.003553 0.891003 5160201.305808 -1945038.253710 0.000000 733157.306436 0.000000 699.126192 +EDGE_SE2 511 512 0.007335 0.005942 1.221397 297144.725264 495141.758266 0.000000 825112.510283 0.000000 506.626201 +EDGE_SE2 512 513 -0.002181 -0.000566 0.972737 8538321.615481 9762487.124922 0.000000 11162190.656524 0.000000 642.394025 +EDGE_SE2 513 514 0.090094 0.023767 0.232272 18.681434 -295.052416 0.000000 11510.742828 0.000000 1646.367741 +EDGE_SE2 514 515 0.658710 0.013018 0.004928 11.159348 -3.251856 0.000000 230.330528 0.000000 2475.540949 +EDGE_SE2 515 516 0.637378 -0.008635 0.019744 11.371458 7.817478 0.000000 245.848124 0.000000 2404.128580 +EDGE_SE2 516 517 0.633811 0.029113 0.032052 11.156620 -3.285893 0.000000 248.362090 0.000000 2347.128404 +EDGE_SE2 517 518 0.634675 0.007993 0.028090 11.168044 3.673667 0.000000 248.158131 0.000000 2365.253746 +EDGE_SE2 518 519 0.560153 0.002654 -0.012150 11.198833 -5.193662 0.000000 318.608437 0.000000 2440.339501 +EDGE_SE2 519 520 0.197101 -0.000544 0.405434 414.955475 933.778631 0.000000 2170.216473 0.000000 1265.665952 +EDGE_SE2 520 521 0.006002 0.005024 1.019492 163989.160959 490677.362406 0.000000 1468282.469392 0.000000 612.993310 +EDGE_SE2 521 522 0.414779 0.108184 0.270025 11.229248 7.935203 0.000000 544.113259 0.000000 1549.942078 +EDGE_SE2 522 523 0.644866 -0.002177 -0.013262 11.133525 -2.267210 0.000000 240.444921 0.000000 2434.986160 +EDGE_SE2 523 524 0.606582 -0.016880 -0.047652 11.213538 -5.164087 0.000000 271.469885 0.000000 2277.749269 +EDGE_SE2 524 525 0.576823 0.002529 0.018772 11.171018 4.163585 0.000000 300.483332 0.000000 2408.718278 +EDGE_SE2 525 526 0.607148 -0.019364 -0.063586 11.372241 -8.233863 0.000000 270.738644 0.000000 2210.012777 +EDGE_SE2 526 527 0.632532 -0.013902 -0.038859 11.179151 -4.029527 0.000000 249.750981 0.000000 2316.470615 +EDGE_SE2 527 528 0.639965 -0.031254 -0.079842 11.335080 -7.212289 0.000000 243.362638 0.000000 2143.974316 +EDGE_SE2 528 529 0.630138 0.005118 -0.025519 11.383434 -8.091842 0.000000 251.553301 0.000000 2377.128104 +EDGE_SE2 529 530 0.643013 -0.010371 -0.027118 11.138973 -2.535041 0.000000 241.767362 0.000000 2369.732519 +EDGE_SE2 530 531 0.632204 -0.021106 -0.076364 11.552220 -10.254093 0.000000 249.479589 0.000000 2157.852130 +EDGE_SE2 531 532 0.210203 0.000529 0.053978 17.069737 115.687987 0.000000 2257.218094 0.000000 2250.489117 +EDGE_SE2 532 533 0.010481 0.007945 1.006775 71059.615350 189815.528908 0.000000 507128.543079 0.000000 620.787044 +EDGE_SE2 533 534 0.004524 0.002070 0.671821 233294.669406 942460.043629 0.000000 3807527.338703 0.000000 894.459037 +EDGE_SE2 534 535 0.000000 0.000000 0.001338 11.111807 0.520333 0.000000 399.999304 0.000000 2493.323403 +EDGE_SE2 535 536 0.357295 0.039869 0.132965 11.474755 16.648687 0.000000 773.337063 0.000000 1947.632537 +EDGE_SE2 536 537 0.617574 -0.018145 -0.055950 11.288271 -6.664110 0.000000 261.790435 0.000000 2242.091332 +EDGE_SE2 537 538 0.579730 -0.014385 -0.025102 11.111136 -0.083914 0.000000 297.359512 0.000000 2379.062475 +EDGE_SE2 538 539 0.638569 -0.022758 -0.062503 11.280003 -6.281777 0.000000 244.755892 0.000000 2214.520366 +EDGE_SE2 539 540 0.636808 -0.030043 -0.090399 11.550435 -10.149862 0.000000 245.607132 0.000000 2102.660323 +EDGE_SE2 540 541 0.624998 0.051843 0.165279 12.763015 19.972919 0.000000 252.600591 0.000000 1841.111831 +EDGE_SE2 541 542 0.637879 0.044546 0.058251 11.141827 -2.677719 0.000000 244.543713 0.000000 2232.351783 +EDGE_SE2 542 543 0.119005 -0.001027 -0.027249 13.554992 -131.231977 0.000000 7058.031360 0.000000 2369.128157 +EDGE_SE2 543 544 0.004143 0.001613 0.643358 365523.202414 1309813.828807 0.000000 4693733.444673 0.000000 925.711464 +EDGE_SE2 544 545 0.011964 0.010101 1.076679 54873.490374 139170.850294 0.000000 353049.492454 0.000000 579.697285 +EDGE_SE2 545 546 -0.062408 -0.034041 0.835070 2157.534535 6151.646423 0.000000 17641.720853 0.000000 742.394487 +EDGE_SE2 546 547 0.004683 0.006620 1.031598 8884.576322 115819.915331 0.000000 1511737.642851 0.000000 605.709415 +EDGE_SE2 547 548 0.010894 0.005062 0.931876 157491.371124 290395.414023 0.000000 535503.600637 0.000000 669.856096 +EDGE_SE2 548 549 0.018521 0.007174 0.814504 46970.071545 98477.220300 0.000000 206526.818200 0.000000 759.318793 +EDGE_SE2 549 550 0.007039 -0.001728 -0.474679 102346.133104 -429334.075047 0.000000 1801229.739954 0.000000 1149.595399 +EDGE_SE2 550 551 0.012919 -0.003649 -0.620137 63414.169645 -176527.986637 0.000000 491503.647693 0.000000 952.437591 +EDGE_SE2 551 552 0.004870 -0.001510 -0.626201 393240.954950 -1165183.372361 0.000000 3452577.879626 0.000000 945.347676 +EDGE_SE2 552 553 0.131013 -0.071366 -0.571551 34.798953 -324.963500 0.000000 4469.148228 0.000000 1012.238963 +EDGE_SE2 553 554 0.656516 -0.001289 -0.033128 11.325592 -6.879883 0.000000 231.796023 0.000000 2342.241894 +EDGE_SE2 554 555 0.640736 0.024110 0.091367 11.781224 12.453936 0.000000 242.565349 0.000000 2098.932021 +EDGE_SE2 555 556 0.644807 0.029102 0.137696 13.068095 21.074909 0.000000 238.068451 0.000000 1931.468129 +EDGE_SE2 556 557 0.641564 -0.010754 -0.042948 11.270029 -6.066916 0.000000 242.724912 0.000000 2298.342233 +EDGE_SE2 557 558 0.615263 0.021826 0.078921 11.588181 10.969921 0.000000 263.357654 0.000000 2147.636202 +EDGE_SE2 558 559 0.005363 -0.000612 -0.410558 293857.680729 -960260.813810 0.000000 3138046.146667 0.000000 1256.487325 +EDGE_SE2 559 560 0.000000 0.000000 -0.505043 102.152456 -164.670704 0.000000 308.958656 0.000000 1103.677058 +EDGE_SE2 560 561 0.009398 0.003440 0.501104 22371.403618 147733.503165 0.000000 976080.093687 0.000000 1109.476905 +EDGE_SE2 561 562 0.177331 0.126693 0.638384 11.791812 37.750509 0.000000 2104.689083 0.000000 931.340765 +EDGE_SE2 562 563 0.597201 -0.094603 -0.194811 11.484023 -9.885231 0.000000 273.150922 0.000000 1751.223531 +EDGE_SE2 563 564 0.639558 0.013847 0.046248 11.252240 5.735744 0.000000 244.222662 0.000000 2283.866567 +EDGE_SE2 564 565 0.614599 -0.011365 -0.051966 11.395132 -8.481100 0.000000 264.363876 0.000000 2259.105962 +EDGE_SE2 565 566 0.005382 -0.000625 0.804171 2155482.804415 1641813.690713 0.000000 1250573.669361 0.000000 768.041369 +EDGE_SE2 566 567 -0.001231 0.000678 0.856086 48423129.554559 10395439.301461 0.000000 2231696.342135 0.000000 725.677769 +EDGE_SE2 567 568 0.583042 0.017568 0.046196 11.184172 4.544849 0.000000 293.831241 0.000000 2284.093607 +EDGE_SE2 568 569 0.628101 -0.010139 -0.052147 11.425095 -8.716657 0.000000 253.098625 0.000000 2258.328765 +EDGE_SE2 569 570 0.639821 -0.001979 -0.004808 11.111796 -0.399705 0.000000 244.274090 0.000000 2476.132272 +EDGE_SE2 570 571 0.348563 -0.003118 -0.043397 12.074353 -27.948587 0.000000 822.042846 0.000000 2296.364589 +EDGE_SE2 571 572 0.037203 -0.034953 -0.237353 9379.952208 16482.424026 0.000000 29008.326343 0.000000 1632.874389 +EDGE_SE2 572 573 0.082599 0.001138 0.282645 1044.389047 3750.080318 0.000000 13621.294688 0.000000 1519.592228 +EDGE_SE2 573 574 0.006029 0.005935 0.955816 43915.035779 243749.664142 0.000000 1353281.899972 0.000000 653.557826 +EDGE_SE2 574 575 0.017352 0.009648 1.009306 58713.654313 106982.648688 0.000000 194982.001569 0.000000 619.224094 +EDGE_SE2 575 576 -0.000693 0.000729 1.024139 92116121.130465 -24932672.587732 0.000000 6748430.711509 0.000000 610.181931 +EDGE_SE2 576 577 0.005808 0.005602 0.968758 61460.098525 300963.429168 0.000000 1474062.832839 0.000000 644.993297 +EDGE_SE2 577 578 0.020578 -0.005874 -0.365770 1686.236926 -19051.115635 0.000000 216678.422748 0.000000 1340.246481 +EDGE_SE2 578 579 0.649778 -0.007064 0.014101 11.251830 5.633981 0.000000 236.679123 0.000000 2430.958734 +EDGE_SE2 579 580 0.646533 0.021127 0.074055 11.501231 9.420338 0.000000 238.586536 0.000000 2167.139990 +EDGE_SE2 580 581 0.641277 0.007721 0.041304 11.309760 6.786133 0.000000 242.935131 0.000000 2305.605160 +EDGE_SE2 581 582 0.642222 0.008953 0.042003 11.293216 6.487457 0.000000 242.225126 0.000000 2302.512889 +EDGE_SE2 582 583 0.324533 0.007424 0.078126 13.971366 51.714099 0.000000 946.114403 0.000000 2150.804664 +EDGE_SE2 583 584 0.003585 0.000066 0.840201 4172109.666193 3878928.313892 0.000000 3606370.037121 0.000000 738.260001 +EDGE_SE2 584 585 0.609333 0.022255 0.117010 12.778611 20.669000 0.000000 267.307574 0.000000 2003.668573 +EDGE_SE2 585 586 0.610182 0.017652 0.096276 12.276387 17.274488 0.000000 267.194725 0.000000 2080.176547 +EDGE_SE2 586 587 0.632351 0.024309 0.024257 11.158994 -3.379740 0.000000 249.665755 0.000000 2382.989492 +EDGE_SE2 587 588 0.643770 -0.006740 0.003322 11.154886 3.173805 0.000000 241.219104 0.000000 2483.472403 +EDGE_SE2 588 589 0.633840 0.040950 0.080270 11.169866 3.729294 0.000000 247.815430 0.000000 2142.275779 +EDGE_SE2 589 590 0.644706 0.014870 0.073779 11.700561 11.612184 0.000000 239.871719 0.000000 2168.254200 +EDGE_SE2 590 591 0.632424 0.012303 0.002621 11.178752 -4.018640 0.000000 249.862554 0.000000 2486.946343 +EDGE_SE2 591 592 0.642169 0.006914 0.001997 11.128903 -2.028750 0.000000 242.448415 0.000000 2490.044831 +EDGE_SE2 592 593 0.271993 0.001273 0.212505 68.183858 270.652782 0.000000 1294.612122 0.000000 1700.485497 +EDGE_SE2 593 594 0.014453 0.008841 0.993097 64316.365031 135154.721370 0.000000 284074.972077 0.000000 629.336815 +EDGE_SE2 594 595 0.571176 0.080832 0.240324 13.980407 28.672593 0.000000 297.633480 0.000000 1625.061173 +EDGE_SE2 595 596 0.575835 0.004878 -0.017875 11.312665 -7.648565 0.000000 301.358130 0.000000 2412.965503 +EDGE_SE2 596 597 0.635351 -0.013108 -0.034135 11.154253 -3.193993 0.000000 247.578146 0.000000 2337.682549 +EDGE_SE2 597 598 0.604127 -0.006451 -0.039602 11.330957 -7.598611 0.000000 273.744081 0.000000 2313.160651 +EDGE_SE2 598 599 0.385673 -0.010715 -0.063459 11.952011 -23.555254 0.000000 670.939617 0.000000 2210.540655 +EDGE_SE2 599 600 0.008688 0.002526 0.814757 314076.796383 533827.575685 0.000000 907375.060518 0.000000 759.107091 +EDGE_SE2 600 601 0.021686 0.011399 1.028615 44738.476040 73830.093373 0.000000 121880.188267 0.000000 607.492253 +EDGE_SE2 601 602 0.018101 0.007667 1.024411 88285.368598 122674.329555 0.000000 170491.062574 0.000000 610.017974 +EDGE_SE2 602 603 0.186319 0.162792 0.780432 17.405089 100.856712 0.000000 1627.271409 0.000000 788.658931 +EDGE_SE2 603 604 0.621077 -0.063008 -0.240492 15.850028 -33.777361 0.000000 251.864479 0.000000 1624.621039 +EDGE_SE2 604 605 0.633484 0.018906 0.082620 11.773196 12.531662 0.000000 248.305264 0.000000 2132.985568 +EDGE_SE2 605 606 0.635159 0.014918 0.042086 11.193000 4.401211 0.000000 247.658010 0.000000 2302.146123 +EDGE_SE2 606 607 0.573078 -0.057501 -0.081034 11.215573 5.506259 0.000000 301.350193 0.000000 2139.248825 +EDGE_SE2 607 608 0.372357 0.012526 0.044458 11.194332 7.682633 0.000000 720.342546 0.000000 2291.701491 +EDGE_SE2 608 609 0.009981 0.001237 0.336295 44194.195786 204270.386082 0.000000 944408.518792 0.000000 1400.022844 +EDGE_SE2 609 610 0.008024 0.008992 0.932617 5618.242041 61880.517104 0.000000 682926.927594 0.000000 669.342525 +EDGE_SE2 610 611 0.619179 0.006175 0.002964 11.123375 -1.749910 0.000000 260.797662 0.000000 2485.245630 +EDGE_SE2 611 612 0.495865 -0.011645 0.002777 11.383631 10.376429 0.000000 406.201910 0.000000 2486.172625 +EDGE_SE2 612 613 -0.032580 0.001507 0.463705 22407.672171 40045.920128 0.000000 71614.770023 0.000000 1166.898001 +EDGE_SE2 613 614 0.006074 0.002811 1.037837 720992.332387 1043867.597380 0.000000 1511367.480327 0.000000 602.006419 +EDGE_SE2 614 615 0.468918 0.167392 0.304515 11.688040 -15.032631 0.000000 402.805589 0.000000 1469.067849 +EDGE_SE2 615 616 0.634148 0.014484 -0.051156 12.408628 -17.503753 0.000000 247.240026 0.000000 2262.588948 +EDGE_SE2 616 617 0.620915 -0.099361 -0.217030 11.933466 -14.077035 0.000000 252.081317 0.000000 1687.863964 +EDGE_SE2 617 618 0.637519 0.006833 0.010118 11.111196 -0.140914 0.000000 246.016254 0.000000 2450.167576 +EDGE_SE2 618 619 0.602001 -0.001093 -0.001468 11.111143 0.091989 0.000000 275.933653 0.000000 2492.676131 +EDGE_SE2 619 620 0.611116 -0.021079 -0.096329 12.090448 -15.813910 0.000000 266.467179 0.000000 2079.975428 +EDGE_SE2 620 621 -0.351742 0.001000 -0.051606 13.005075 -38.809484 0.000000 806.361703 0.000000 2260.652962 +EDGE_SE2 621 622 -0.288473 0.005647 -0.075042 14.769187 -65.879798 0.000000 1197.567688 0.000000 2163.162499 +EDGE_SE2 622 623 -0.003587 0.000519 -0.537149 1119299.663768 -2695881.271885 0.000000 6493221.297933 0.000000 1058.054588 +EDGE_SE2 623 624 -0.002684 0.001648 -0.642690 84963.761375 -921398.117942 0.000000 9993513.245668 0.000000 926.464498 +EDGE_SE2 624 625 0.007502 -0.002176 -0.658633 221323.684950 -560152.893180 0.000000 1417785.340096 0.000000 908.739498 +EDGE_SE2 625 626 0.007582 -0.000720 -0.618128 430777.189603 -746427.081854 0.000000 1293412.370737 0.000000 954.803710 +EDGE_SE2 626 627 0.339972 -0.139061 -0.410806 11.481721 -16.444927 0.000000 740.815480 0.000000 1256.045618 +EDGE_SE2 627 628 0.641810 -0.041240 -0.100917 11.422475 -8.468830 0.000000 241.456222 0.000000 2062.675227 +EDGE_SE2 628 629 0.640763 0.030371 0.071050 11.241212 5.491249 0.000000 242.883687 0.000000 2179.317557 +EDGE_SE2 629 630 0.608678 0.024217 0.085089 11.641507 11.694459 0.000000 268.956806 0.000000 2123.289866 +EDGE_SE2 630 631 0.520687 0.012252 0.020220 11.115021 -1.182335 0.000000 368.639644 0.000000 2401.885734 +EDGE_SE2 631 632 0.003617 -0.000095 0.676209 3189142.029325 3767706.315238 0.000000 4451258.564395 0.000000 889.781790 +EDGE_SE2 632 633 0.052581 0.076324 1.075605 146.388666 1246.996416 0.000000 11505.997044 0.000000 580.297357 +EDGE_SE2 633 634 0.651291 -0.000853 0.025227 11.269271 5.958489 0.000000 235.590568 0.000000 2378.482380 +EDGE_SE2 634 635 0.638650 -0.043082 -0.137291 12.248607 -16.238485 0.000000 242.925867 0.000000 1932.844002 +EDGE_SE2 635 636 0.635527 0.004328 -0.019084 11.269630 -6.120407 0.000000 247.419146 0.000000 2407.243610 +EDGE_SE2 636 637 0.632517 -0.030952 -0.100684 11.749524 -12.316243 0.000000 248.715635 0.000000 2063.548601 +EDGE_SE2 637 638 0.419086 -0.009115 -0.030747 11.156304 -5.021448 0.000000 569.055296 0.000000 2353.075434 +EDGE_SE2 638 639 0.640680 0.028288 0.078765 11.389438 8.031492 0.000000 242.870396 0.000000 2148.257386 +EDGE_SE2 639 640 0.645185 -0.028949 -0.069702 11.252424 -5.682397 0.000000 239.608542 0.000000 2184.813613 +EDGE_SE2 640 641 0.631149 0.010125 -0.010170 11.275857 -6.284012 0.000000 250.806675 0.000000 2449.915330 +EDGE_SE2 641 642 0.608456 -0.016443 -0.047551 11.220217 -5.312718 0.000000 269.804578 0.000000 2278.188510 +EDGE_SE2 642 643 0.501922 -0.014902 -0.065028 11.592531 -13.614212 0.000000 396.111379 0.000000 2204.032313 +EDGE_SE2 643 644 0.006192 0.003634 0.763605 103362.922493 435664.745636 0.000000 1836493.394795 0.000000 803.780315 +EDGE_SE2 644 645 0.147583 0.161030 0.956903 45.062660 263.875747 0.000000 2061.986889 0.000000 652.831965 +EDGE_SE2 645 646 0.624864 0.078137 0.297396 18.253618 40.874666 0.000000 245.025960 0.000000 1485.234058 +EDGE_SE2 646 647 0.626416 0.074352 0.291155 18.229469 40.732090 0.000000 244.184966 0.000000 1499.626982 +EDGE_SE2 647 648 0.630437 0.066336 0.168411 12.070691 15.073373 0.000000 247.888334 0.000000 1831.254626 +EDGE_SE2 648 649 0.592663 -0.072497 -0.334526 23.127883 -55.612924 0.000000 268.484510 0.000000 1403.737590 +EDGE_SE2 649 650 0.621511 -0.143009 -0.254374 11.297892 -6.619122 0.000000 245.678334 0.000000 1588.861060 +EDGE_SE2 650 651 0.144853 0.010732 0.805829 2122.876396 2350.861156 0.000000 2628.138776 0.000000 766.631681 +EDGE_SE2 651 652 0.002718 0.001656 1.033599 2156297.352241 4079208.548390 0.000000 7716956.136248 0.000000 604.518184 +EDGE_SE2 652 653 0.014957 0.011986 1.038848 34378.938116 90407.858801 0.000000 237837.637992 0.000000 601.409535 +EDGE_SE2 653 654 0.267736 0.151078 0.517447 11.125502 3.881714 0.000000 1058.107188 0.000000 1085.707770 +EDGE_SE2 654 655 0.563434 -0.005218 -0.003312 11.121867 1.807836 0.000000 314.964252 0.000000 2483.521908 +EDGE_SE2 655 656 0.610635 -0.014726 -0.011084 11.154711 3.346600 0.000000 267.986619 0.000000 2445.487982 +EDGE_SE2 656 657 0.631799 0.103933 0.278849 14.219359 26.720114 0.000000 240.811095 0.000000 1528.626076 +EDGE_SE2 657 658 0.640227 0.007103 -0.006984 11.187191 -4.208049 0.000000 243.861599 0.000000 2465.442445 +EDGE_SE2 658 659 0.497774 -0.026439 -0.071049 11.237681 -7.036752 0.000000 402.323496 0.000000 2179.321626 +EDGE_SE2 659 660 0.006409 -0.000096 0.600351 810833.659716 1147194.412851 0.000000 1623122.139710 0.000000 976.134174 +EDGE_SE2 660 661 0.169432 0.128488 0.653648 11.162367 10.620021 0.000000 2211.525163 0.000000 914.226633 +EDGE_SE2 661 662 0.629749 0.003998 0.069631 12.075080 15.212434 0.000000 251.179162 0.000000 2185.103670 +EDGE_SE2 662 663 0.621897 0.037784 0.101008 11.511766 9.929781 0.000000 257.209513 0.000000 2062.334274 +EDGE_SE2 663 664 0.007280 -0.002392 0.538314 970988.716591 843174.347297 0.000000 732204.084386 0.000000 1056.452618 +EDGE_SE2 664 665 0.026579 0.029587 0.878851 111.857316 2521.446990 0.000000 63117.159733 0.000000 708.199031 +EDGE_SE2 665 666 0.623804 0.018831 0.034452 11.115596 1.049644 0.000000 256.744183 0.000000 2336.250038 +EDGE_SE2 666 667 0.580478 0.005759 0.002114 11.128518 -2.229713 0.000000 296.729354 0.000000 2489.463423 +EDGE_SE2 667 668 0.608507 -0.000467 0.023179 11.259577 6.198692 0.000000 269.917040 0.000000 2388.013473 +EDGE_SE2 668 669 0.638606 0.001692 -0.027742 11.327262 -7.110068 0.000000 244.989751 0.000000 2366.855797 +EDGE_SE2 669 670 0.636315 -0.034673 -0.062258 11.125493 -1.838895 0.000000 246.230714 0.000000 2215.542002 +EDGE_SE2 670 671 0.308072 0.001150 0.052261 13.564460 50.513802 0.000000 1051.177078 0.000000 2257.839465 +EDGE_SE2 671 672 -0.576602 0.036531 -0.092061 11.350145 -8.300360 0.000000 299.337680 0.000000 2096.265145 +EDGE_SE2 672 673 -0.262392 0.011580 -0.133741 22.638322 -128.254010 0.000000 1438.090461 0.000000 1944.967298 +EDGE_SE2 673 674 -0.005814 0.002674 -0.655099 120542.083833 -528941.427411 0.000000 2321232.182459 0.000000 912.624358 +EDGE_SE2 674 675 -0.014637 0.005942 -0.615221 20765.078980 -88798.929746 0.000000 379950.502646 0.000000 958.243990 +EDGE_SE2 675 676 -0.006630 0.003741 -0.630060 23265.609241 -198963.775781 0.000000 1702330.544222 0.000000 940.876947 +EDGE_SE2 676 677 -0.012856 0.004015 -0.622499 54491.338930 -164518.778220 0.000000 496823.064188 0.000000 949.666532 +EDGE_SE2 677 678 0.191689 -0.090627 -0.451238 11.315076 -21.245540 0.000000 2224.105339 0.000000 1187.032313 +EDGE_SE2 678 679 0.570835 0.011396 0.059784 11.579724 11.761290 0.000000 306.296841 0.000000 2225.898166 +EDGE_SE2 679 680 0.434701 0.056384 0.340338 33.525701 104.470312 0.000000 498.028172 0.000000 1391.589518 +EDGE_SE2 680 681 0.616588 -0.017915 -0.025786 11.113788 0.820773 0.000000 262.808564 0.000000 2375.890788 +EDGE_SE2 681 682 0.634780 0.014947 0.049632 11.272332 6.178273 0.000000 247.873967 0.000000 2269.163993 +EDGE_SE2 682 683 0.300050 0.004977 0.161644 34.081549 157.239703 0.000000 1087.465169 0.000000 1852.652221 +EDGE_SE2 683 684 0.008066 0.002610 1.069340 655223.236656 694424.027218 0.000000 735993.720066 0.000000 583.816417 +EDGE_SE2 684 685 0.408559 0.177472 0.439476 11.545242 14.621378 0.000000 503.554260 0.000000 1206.510628 +EDGE_SE2 685 686 0.481253 -0.056338 -0.146676 11.487851 -12.495538 0.000000 425.557060 0.000000 1901.334651 +EDGE_SE2 686 687 0.633778 -0.013418 -0.036773 11.168993 -3.709053 0.000000 248.788111 0.000000 2325.801528 +EDGE_SE2 687 688 0.633546 -0.023306 -0.013253 11.242546 5.587827 0.000000 248.672293 0.000000 2435.029417 +EDGE_SE2 688 689 0.601923 0.011148 0.026350 11.127352 2.073709 0.000000 275.894586 0.000000 2373.280306 +EDGE_SE2 689 690 0.577060 0.031776 0.072952 11.203899 5.171117 0.000000 299.300801 0.000000 2171.597942 +EDGE_SE2 690 691 0.431081 -0.000968 -0.029004 11.488376 -14.095403 0.000000 537.744126 0.000000 2361.053797 +EDGE_SE2 691 692 -0.008991 -0.001137 0.532009 190083.391915 441924.473409 0.000000 1027500.439761 0.000000 1065.166196 +EDGE_SE2 692 693 -0.002490 -0.004336 1.036147 719.063258 -53205.166853 0.000000 3998572.017505 0.000000 603.006163 +EDGE_SE2 693 694 -0.004998 -0.000127 0.832038 2085335.472274 1998610.421428 0.000000 1915513.414270 0.000000 744.853827 +EDGE_SE2 694 695 0.001511 0.001312 0.796919 166502.359918 2031923.976353 0.000000 24798401.868961 0.000000 774.253197 +EDGE_SE2 695 696 0.013256 0.002978 1.021557 279104.028874 270742.205141 0.000000 262652.464508 0.000000 611.741616 +EDGE_SE2 696 697 0.014932 -0.001676 -0.254525 8971.193925 -62353.454280 0.000000 433930.455572 0.000000 1588.478599 +EDGE_SE2 697 698 0.334592 -0.212289 -0.657753 16.435194 -57.473689 0.000000 631.541865 0.000000 909.704543 +EDGE_SE2 698 699 0.645635 0.022320 0.112426 12.493854 17.721303 0.000000 238.228242 0.000000 2020.215724 +EDGE_SE2 699 700 0.637453 0.017479 0.051850 11.251293 5.735412 0.000000 245.770774 0.000000 2259.604267 +EDGE_SE2 700 701 0.580454 0.032375 0.057254 11.111784 0.437751 0.000000 295.879739 0.000000 2236.564024 +EDGE_SE2 701 702 0.576635 -0.068380 -0.117543 11.111180 0.139782 0.000000 296.573785 0.000000 2001.757773 +EDGE_SE2 702 703 0.620013 -0.001990 0.031996 11.419637 8.759800 0.000000 259.823358 0.000000 2347.383139 +EDGE_SE2 703 704 0.636789 0.025712 0.015764 11.253257 -5.779092 0.000000 246.065659 0.000000 2423.005361 +EDGE_SE2 704 705 0.643209 0.030107 0.064485 11.183283 4.074239 0.000000 241.110228 0.000000 2206.281466 +EDGE_SE2 705 706 0.514363 -0.039200 -0.277636 25.728836 -71.533878 0.000000 361.172137 0.000000 1531.530774 +EDGE_SE2 706 707 0.003881 -0.001622 -0.533536 106334.972814 -767757.982233 0.000000 5543943.675681 0.000000 1063.046000 +EDGE_SE2 707 708 -0.003691 0.001823 -0.654541 223240.622476 -1125745.646018 0.000000 5677142.471470 0.000000 913.240034 +EDGE_SE2 708 709 -0.067573 0.007248 -0.341732 1183.126036 -4897.853094 0.000000 20479.250565 0.000000 1388.700057 +EDGE_SE2 709 710 -0.014148 0.002189 -0.575257 81786.222098 -182245.919313 0.000000 406168.616806 0.000000 1007.481714 +EDGE_SE2 710 711 0.000644 0.000757 -0.611741 100340028.914478 -9326915.500645 0.000000 866976.800978 0.000000 962.386453 +EDGE_SE2 711 712 -0.004894 0.001455 -0.574644 304805.524713 -1037473.284048 0.000000 3531410.530133 0.000000 1008.266280 +EDGE_SE2 712 713 0.477793 -0.132293 -0.294292 11.342379 -9.563968 0.000000 406.624099 0.000000 1492.366443 +EDGE_SE2 713 714 0.567602 -0.077796 -0.205164 12.504613 -20.177539 0.000000 303.276539 0.000000 1721.264882 +EDGE_SE2 714 715 0.633486 0.028573 0.105231 11.969833 14.257268 0.000000 247.822982 0.000000 2046.604352 +EDGE_SE2 715 716 0.639776 -0.022007 -0.136206 13.517556 -23.552031 0.000000 241.616372 0.000000 1936.537236 +EDGE_SE2 716 717 0.632432 0.018685 0.086524 11.885459 13.573115 0.000000 249.026579 0.000000 2117.685003 +EDGE_SE2 717 718 0.776383 -0.078919 -0.173172 11.900522 -10.964942 0.000000 163.414455 0.000000 1816.421486 +EDGE_SE2 718 719 0.636837 0.028128 0.076417 11.355832 7.579234 0.000000 245.847108 0.000000 2157.639641 +EDGE_SE2 719 720 0.632529 -0.017060 -0.057232 11.329664 -7.218698 0.000000 249.541537 0.000000 2236.657107 +EDGE_SE2 720 721 0.638105 0.018029 0.070335 11.525887 9.849065 0.000000 244.982458 0.000000 2182.230164 +EDGE_SE2 721 722 0.025289 0.000135 0.068811 640.196727 9897.678857 0.000000 155735.617178 0.000000 2188.457812 +EDGE_SE2 722 723 0.006445 0.007867 1.098357 43580.586864 200575.333708 0.000000 923374.631033 0.000000 567.781519 +EDGE_SE2 723 724 0.010463 0.006590 1.077175 158723.565692 280363.009735 0.000000 495267.878673 0.000000 579.420471 +EDGE_SE2 724 725 0.010678 0.005468 0.639413 19006.567647 113303.006550 0.000000 675834.367551 0.000000 930.171994 +EDGE_SE2 725 726 0.290588 0.137540 0.458060 11.355500 15.286330 0.000000 967.259181 0.000000 1175.950976 +EDGE_SE2 726 727 0.635716 0.023142 0.032574 11.114541 -0.899732 0.000000 247.111115 0.000000 2344.755903 +EDGE_SE2 727 728 0.637440 -0.010740 0.003027 11.203891 4.667737 0.000000 245.942991 0.000000 2484.933444 +EDGE_SE2 728 729 0.638658 0.024646 0.059374 11.212224 4.859951 0.000000 244.701967 0.000000 2227.621438 +EDGE_SE2 729 730 0.629725 0.021040 0.039078 11.118875 1.367234 0.000000 251.883563 0.000000 2315.494262 +EDGE_SE2 730 731 0.635128 0.000033 0.013336 11.152896 3.145232 0.000000 247.858605 0.000000 2434.630538 +EDGE_SE2 731 732 0.123756 0.004174 0.448902 1070.432039 2403.087812 0.000000 5462.557297 0.000000 1190.863501 +EDGE_SE2 732 733 0.000083 0.001424 1.000990 11773189.473890 -20977730.743166 0.000000 37378633.397513 0.000000 624.381709 +EDGE_SE2 733 734 0.552572 0.038413 0.079326 11.142093 3.122929 0.000000 325.902343 0.000000 2146.024772 +EDGE_SE2 734 735 0.600091 -0.007820 -0.030980 11.196982 -4.783337 0.000000 277.560623 0.000000 2352.011970 +EDGE_SE2 735 736 0.005111 -0.000077 0.602090 1281626.650843 1806077.209424 0.000000 2545169.768506 0.000000 974.015847 +EDGE_SE2 736 737 0.008677 0.008287 0.804006 1211.768495 28855.042050 0.000000 693475.760746 0.000000 768.181871 +EDGE_SE2 737 738 0.598858 0.011099 0.020076 11.111750 0.413426 0.000000 278.741652 0.000000 2402.563911 +EDGE_SE2 738 739 0.625793 -0.054407 -0.056575 11.331296 7.301220 0.000000 253.215672 0.000000 2239.439570 +EDGE_SE2 739 740 0.522300 0.024647 0.064307 11.215445 6.082008 0.000000 365.653135 0.000000 2207.019506 +EDGE_SE2 740 741 -0.000981 -0.000074 -0.367127 18919361.341981 -39981559.645604 0.000000 84491555.069462 0.000000 1337.587765 +EDGE_SE2 741 742 0.011219 -0.001990 -0.650273 160936.661861 -313150.446277 0.000000 609381.105788 0.000000 917.969856 +EDGE_SE2 742 743 0.004918 -0.001325 -0.614408 456134.364729 -1245052.232453 0.000000 3398555.362562 0.000000 959.208992 +EDGE_SE2 743 744 0.009459 -0.002723 -0.537185 66620.250624 -253582.580605 0.000000 965406.035238 0.000000 1058.005031 +EDGE_SE2 744 745 0.002047 -0.000908 -0.591149 593780.161881 -3389363.396311 0.000000 19347237.473549 0.000000 987.457262 +EDGE_SE2 745 746 0.494445 -0.175533 -0.472825 17.183290 -45.841209 0.000000 357.183969 0.000000 1152.491455 +EDGE_SE2 746 747 0.638469 -0.005433 -0.034207 11.265722 -6.015279 0.000000 245.140841 0.000000 2337.357068 +EDGE_SE2 747 748 0.577733 -0.023010 -0.067174 11.326766 -7.878192 0.000000 298.912675 0.000000 2195.176966 +EDGE_SE2 748 749 0.069701 0.001911 0.431306 3186.109937 7428.826456 0.000000 17392.995499 0.000000 1220.323642 +EDGE_SE2 749 750 0.003545 0.004632 0.930924 530.021459 39050.161440 0.000000 2938698.139852 0.000000 670.516775 +EDGE_SE2 750 751 0.221430 0.155717 0.642978 12.335877 40.697289 0.000000 1363.426091 0.000000 926.139724 +EDGE_SE2 751 752 0.622533 -0.037077 -0.102200 11.559653 -10.494975 0.000000 256.672582 0.000000 2057.875967 +EDGE_SE2 752 753 0.636978 0.006588 0.064190 11.792803 12.647310 0.000000 245.754530 0.000000 2207.504825 +EDGE_SE2 753 754 0.633682 -0.063409 -0.161022 11.994454 -14.394628 0.000000 245.680720 0.000000 1854.637814 +EDGE_SE2 754 755 0.634065 0.020125 0.076284 11.582011 10.562020 0.000000 248.011279 0.000000 2158.172928 +EDGE_SE2 755 756 0.630931 -0.052093 -0.191444 13.935694 -25.795248 0.000000 246.683906 0.000000 1761.135371 +EDGE_SE2 756 757 0.634731 0.023338 0.098895 12.024248 14.675298 0.000000 246.962348 0.000000 2070.272980 +EDGE_SE2 757 758 0.593380 0.045763 0.126480 11.775379 13.406035 0.000000 281.667065 0.000000 1970.121623 +EDGE_SE2 758 759 0.549299 -0.065716 -0.139191 11.238871 -6.348958 0.000000 326.618479 0.000000 1926.401990 +EDGE_SE2 759 760 0.597230 0.041521 0.114150 11.646967 11.969500 0.000000 278.475751 0.000000 2013.968527 +EDGE_SE2 760 761 0.024133 -0.000801 0.183513 7939.377412 36011.249548 0.000000 163579.039427 0.000000 1784.818025 +EDGE_SE2 761 762 0.000826 0.001155 1.009551 175055.866129 2941983.942252 0.000000 49446048.586526 0.000000 619.072925 +EDGE_SE2 762 763 0.580729 0.162376 0.292110 11.211099 5.135900 0.000000 274.918098 0.000000 1497.411049 +EDGE_SE2 763 764 0.445705 -0.005172 -0.027993 11.243315 -8.065663 0.000000 503.190215 0.000000 2365.700131 +EDGE_SE2 764 765 0.008361 0.001719 0.638276 244331.555302 525026.230585 0.000000 1128252.931867 0.000000 931.463562 +EDGE_SE2 765 766 0.005344 0.005700 0.998613 53037.087612 289905.348468 0.000000 1584991.089178 0.000000 625.867778 +EDGE_SE2 766 767 0.002645 0.001415 0.929266 1998232.117440 4267585.657123 0.000000 9114261.878773 0.000000 671.669747 +EDGE_SE2 767 768 0.005861 0.004878 0.721092 1261.041135 46349.790224 0.000000 1718749.770688 0.000000 843.979381 +EDGE_SE2 768 769 0.614146 0.107525 0.156299 11.182444 -4.189539 0.000000 257.172044 0.000000 1869.819603 +EDGE_SE2 769 770 0.636280 -0.020581 -0.067664 11.405109 -8.318026 0.000000 246.451563 0.000000 2193.162494 +EDGE_SE2 770 771 0.070000 0.001891 0.559330 5261.360007 8913.246458 0.000000 15142.958000 0.000000 1028.167661 +EDGE_SE2 771 772 0.006744 0.005112 0.865896 64935.054362 294012.600872 0.000000 1331467.660768 0.000000 718.067286 +EDGE_SE2 772 773 0.581158 0.026914 0.085198 11.541618 11.055471 0.000000 295.017264 0.000000 2122.863350 +EDGE_SE2 773 774 0.551019 0.013319 0.021516 11.113346 -0.843063 0.000000 329.161850 0.000000 2395.795043 +EDGE_SE2 774 775 0.004023 0.000830 0.842994 2110367.484852 2837367.218934 0.000000 3814842.025573 0.000000 736.024077 +EDGE_SE2 775 776 0.192558 0.126940 0.615944 13.158809 61.827681 0.000000 1877.920658 0.000000 957.386713 +EDGE_SE2 776 777 0.634282 0.011394 0.058423 11.499517 9.594027 0.000000 248.093510 0.000000 2231.626302 +EDGE_SE2 777 778 0.632295 0.006026 -0.021506 11.341246 -7.412667 0.000000 249.873975 0.000000 2395.841950 +EDGE_SE2 778 779 0.635747 0.009144 0.017394 11.113255 0.711673 0.000000 247.364613 0.000000 2415.247629 +EDGE_SE2 779 780 0.227263 -0.012780 -0.131130 21.872372 -143.298917 0.000000 1919.305655 0.000000 1953.956841 +EDGE_SE2 780 781 0.009670 -0.001829 -0.575170 148004.400196 -361794.734360 0.000000 884479.796277 0.000000 1007.593008 +EDGE_SE2 781 782 0.270298 -0.114336 -0.431075 12.208626 -35.507762 0.000000 1159.889369 0.000000 1220.717636 +EDGE_SE2 782 783 0.611405 -0.011479 -0.001409 11.188373 4.449352 0.000000 267.339350 0.000000 2492.969862 +EDGE_SE2 783 784 0.240113 0.001039 -0.022196 12.323249 -45.688698 0.000000 1733.239839 0.000000 2392.608572 +EDGE_SE2 784 785 0.007959 -0.002926 -0.554001 55828.680061 -272963.055421 0.000000 1334874.506740 0.000000 1035.230954 +EDGE_SE2 785 786 0.004434 -0.000587 -0.590466 980656.281246 -1985068.949325 0.000000 4018282.809762 0.000000 988.305540 +EDGE_SE2 786 787 -0.002001 0.000044 -0.492560 5130982.209484 -10089392.987608 0.000000 19839501.318078 0.000000 1122.215884 +EDGE_SE2 787 788 0.007208 -0.003016 -0.631388 88847.369552 -370943.890957 0.000000 1548921.124356 0.000000 939.345765 +EDGE_SE2 788 789 0.007538 -0.002876 -0.554007 54527.813069 -284219.801981 0.000000 1481775.284964 0.000000 1035.223369 +EDGE_SE2 789 790 0.500376 -0.029812 -0.068057 11.139386 -3.307267 0.000000 397.957897 0.000000 2191.548808 +EDGE_SE2 790 791 0.628826 0.029153 0.097815 11.750061 12.398882 0.000000 251.712715 0.000000 2074.348338 +EDGE_SE2 791 792 0.315704 0.029420 0.702590 333.591596 461.723980 0.000000 672.202381 0.000000 862.422051 +EDGE_SE2 792 793 0.615391 0.019005 0.041490 11.139594 2.682653 0.000000 263.776793 0.000000 2304.781716 +EDGE_SE2 793 794 0.637735 0.016326 0.067824 11.529260 9.895724 0.000000 245.298956 0.000000 2192.505307 +EDGE_SE2 794 795 -0.033087 -0.024410 0.423241 2638.528642 -12185.315173 0.000000 56523.600693 0.000000 1234.193106 +EDGE_SE2 795 796 -0.015774 0.000648 0.650956 163376.535826 197117.295726 0.000000 237853.533044 0.000000 917.210485 +EDGE_SE2 796 797 0.294705 0.074097 0.255423 11.199896 9.754709 0.000000 1082.852214 0.000000 1586.206944 +EDGE_SE2 797 798 0.626641 0.006060 0.046881 11.448159 9.053531 0.000000 254.300351 0.000000 2281.105507 +EDGE_SE2 798 799 0.635666 0.023992 0.062363 11.254358 5.812774 0.000000 246.986103 0.000000 2215.104071 +EDGE_SE2 799 800 0.634468 0.014510 0.069489 11.626291 11.041861 0.000000 247.771504 0.000000 2185.683957 +EDGE_SE2 800 801 0.637847 0.031241 0.082897 11.380932 7.942930 0.000000 244.933506 0.000000 2131.894492 +EDGE_SE2 801 802 0.632634 0.019958 0.054891 11.241159 5.567715 0.000000 249.480486 0.000000 2246.595241 +EDGE_SE2 802 803 0.630127 -0.088612 -0.168062 11.300661 -6.683601 0.000000 246.777787 0.000000 1832.349094 +EDGE_SE2 803 804 0.635077 0.012853 0.053211 11.368430 7.800535 0.000000 247.581479 0.000000 2253.768144 +EDGE_SE2 804 805 0.636519 0.031282 0.073549 11.251547 5.744442 0.000000 246.083247 0.000000 2169.183365 +EDGE_SE2 805 806 0.606343 0.012170 0.038909 11.203672 4.912129 0.000000 271.793935 0.000000 2316.247649 +EDGE_SE2 806 807 0.189729 0.005119 0.292220 201.113736 699.449492 0.000000 2585.968127 0.000000 1497.155415 +EDGE_SE2 807 808 0.003371 0.007327 0.958098 50103.576561 -272947.437303 0.000000 1487266.786417 0.000000 652.035379 +EDGE_SE2 808 809 0.587431 0.097914 0.147917 11.191667 -4.670314 0.000000 281.877711 0.000000 1897.225851 +EDGE_SE2 809 810 0.627956 -0.080646 -0.136964 11.131446 -2.201546 0.000000 249.460063 0.000000 1933.955965 +EDGE_SE2 810 811 0.612576 0.015533 -0.000815 11.285797 -6.674619 0.000000 266.143624 0.000000 2495.929976 +EDGE_SE2 811 812 0.006046 0.000091 0.739463 1201081.516913 1357305.749329 0.000000 1533875.311129 0.000000 826.246472 +EDGE_SE2 812 813 0.018109 0.013231 0.985482 23964.289238 64716.524103 0.000000 174861.749709 0.000000 634.173515 +EDGE_SE2 813 814 0.002006 0.002998 1.002590 3587.558087 165756.923868 0.000000 7682316.480714 0.000000 623.384389 +EDGE_SE2 814 815 0.020425 0.007022 0.928829 67887.614244 99709.570495 0.000000 146482.982663 0.000000 671.974131 +EDGE_SE2 815 816 0.008370 0.002024 0.688367 256339.335199 529144.216869 0.000000 1092335.622944 0.000000 877.013540 +EDGE_SE2 816 817 0.011362 -0.004578 -0.661788 50470.023799 -176289.897436 0.000000 615920.695413 0.000000 905.292186 +EDGE_SE2 817 818 0.201346 -0.091729 -0.483386 17.453139 -113.332496 0.000000 2036.370991 0.000000 1136.139494 +EDGE_SE2 818 819 0.600994 -0.000021 0.016657 11.185144 4.434946 0.000000 276.785971 0.000000 2418.750645 +EDGE_SE2 819 820 0.604107 -0.012016 -0.038590 11.203011 -4.913481 0.000000 273.813863 0.000000 2317.670726 +EDGE_SE2 820 821 0.557707 0.002574 0.018330 11.169482 4.256080 0.000000 321.439373 0.000000 2410.809711 +EDGE_SE2 821 822 0.002019 0.000160 0.773476 9984938.759006 11985389.451377 0.000000 14386651.191718 0.000000 794.857685 +EDGE_SE2 822 823 0.012515 0.017002 0.933412 12.904840 -634.367588 0.000000 224360.656810 0.000000 668.792184 +EDGE_SE2 823 824 0.631778 0.009322 -0.078655 13.193602 -22.229505 0.000000 248.399474 0.000000 2148.695562 +EDGE_SE2 824 825 0.640608 -0.019581 -0.029178 11.111552 0.320195 0.000000 243.449875 0.000000 2360.255512 +EDGE_SE2 825 826 0.635727 0.086901 0.163404 11.286990 6.382404 0.000000 242.719295 0.000000 1847.051069 +EDGE_SE2 826 827 0.633058 -0.024805 -0.048406 11.131451 -2.200226 0.000000 249.121319 0.000000 2274.474191 +EDGE_SE2 827 828 0.640515 0.016631 0.035640 11.132900 2.250508 0.000000 243.562272 0.000000 2330.893209 +EDGE_SE2 828 829 0.604311 -0.016371 -0.038614 11.146008 -3.026498 0.000000 273.593060 0.000000 2317.563615 +EDGE_SE2 829 830 0.611353 -0.005562 -0.007256 11.111980 0.472139 0.000000 267.533817 0.000000 2464.111086 +EDGE_SE2 830 831 0.582292 -0.023325 -0.045648 11.120035 -1.590099 0.000000 294.448496 0.000000 2286.488316 +EDGE_SE2 831 832 0.567969 0.005415 -0.002512 11.154466 -3.599292 0.000000 309.920273 0.000000 2487.487168 +EDGE_SE2 832 833 0.256920 0.000340 0.139017 39.444586 204.467263 0.000000 1486.640047 0.000000 1926.990602 +EDGE_SE2 833 834 0.004768 0.001527 1.059143 1850884.389821 1989766.154557 0.000000 2139092.913935 0.000000 589.612746 +EDGE_SE2 834 835 0.011746 0.005469 0.781010 68236.467078 189689.298378 0.000000 527410.776663 0.000000 788.147120 +EDGE_SE2 835 836 0.015546 0.007972 0.947065 68058.939717 132897.198385 0.000000 259558.927707 0.000000 659.445803 +EDGE_SE2 836 837 0.017648 0.011594 1.040763 44125.577264 89148.384604 0.000000 180165.948528 0.000000 600.281370 +EDGE_SE2 837 838 0.013822 0.005479 0.865867 99632.035075 187458.017071 0.000000 352753.354065 0.000000 718.089607 +EDGE_SE2 838 839 0.001331 -0.000521 -0.216716 1187297.905481 7527754.381697 0.000000 47728231.706064 0.000000 1688.735256 +EDGE_SE2 839 840 0.014201 -0.005576 -0.560094 14691.670684 -78049.547320 0.000000 414963.402725 0.000000 1027.160891 +EDGE_SE2 840 841 0.018508 -0.004844 -0.614349 33618.056740 -89734.585298 0.000000 239613.242398 0.000000 959.279471 +EDGE_SE2 841 842 0.244308 -0.051175 -0.229250 11.937138 -36.275589 0.000000 1604.181092 0.000000 1654.472583 +EDGE_SE2 842 843 0.571578 -0.004308 -0.001490 11.121898 1.783710 0.000000 306.061619 0.000000 2492.566618 +EDGE_SE2 843 844 0.632633 0.008356 -0.006975 11.208334 -4.816449 0.000000 249.718690 0.000000 2465.486516 +EDGE_SE2 844 845 0.634632 -0.005065 -0.013668 11.118782 -1.348758 0.000000 248.265069 0.000000 2433.036002 +EDGE_SE2 845 846 0.637586 0.012768 0.002757 11.181094 -4.052879 0.000000 245.824022 0.000000 2486.271799 +EDGE_SE2 846 847 0.633522 -0.013243 -0.025675 11.116535 -1.135991 0.000000 249.044882 0.000000 2376.405061 +EDGE_SE2 847 848 0.158686 0.003991 0.484189 788.091041 1572.022678 0.000000 3191.702019 0.000000 1134.910441 +EDGE_SE2 848 849 0.002564 0.003351 0.928473 680.469413 61313.177701 0.000000 5616294.276467 0.000000 672.222250 +EDGE_SE2 849 850 0.350597 0.124336 0.356364 11.283371 11.069863 0.000000 722.488046 0.000000 1358.900004 +EDGE_SE2 850 851 0.642798 -0.027661 -0.090713 11.635228 -10.977882 0.000000 241.048137 0.000000 2101.449848 +EDGE_SE2 851 852 0.640836 -0.004293 0.015855 11.229301 5.239393 0.000000 243.375111 0.000000 2422.571276 +EDGE_SE2 852 853 0.610781 0.003140 -0.026553 11.369134 -8.138170 0.000000 267.793422 0.000000 2372.341770 +EDGE_SE2 853 854 0.603861 -0.006364 0.003213 11.160858 3.617435 0.000000 274.156807 0.000000 2484.012095 +EDGE_SE2 854 855 0.610860 0.010420 -0.000693 11.192009 -4.557204 0.000000 267.830171 0.000000 2496.538599 +EDGE_SE2 855 856 0.637641 -0.018640 -0.037084 11.125605 -1.844014 0.000000 245.725607 0.000000 2324.406817 +EDGE_SE2 856 857 0.637311 0.003614 -0.006131 11.143851 -2.774089 0.000000 246.164229 0.000000 2469.624632 +EDGE_SE2 857 858 0.636231 -0.022329 -0.050745 11.168921 -3.690286 0.000000 246.680327 0.000000 2264.359323 +EDGE_SE2 858 859 0.507785 0.004334 -0.003406 11.164814 -4.497374 0.000000 387.747642 0.000000 2483.056613 +EDGE_SE2 859 860 0.002497 0.001745 0.863794 679539.881456 2619251.092498 0.000000 10095943.152469 0.000000 719.687882 +EDGE_SE2 860 861 0.070325 0.071481 0.928711 191.497025 1326.435969 0.000000 9764.823807 0.000000 672.056358 +EDGE_SE2 861 862 0.652508 -0.024736 -0.055891 11.183497 -4.020862 0.000000 234.461196 0.000000 2242.341901 +EDGE_SE2 862 863 0.638309 -0.005836 -0.029014 11.203612 -4.654534 0.000000 245.322644 0.000000 2361.007908 +EDGE_SE2 863 864 0.606532 -0.017964 0.001104 11.356731 7.994878 0.000000 271.342913 0.000000 2494.489128 +EDGE_SE2 864 865 0.604147 0.028266 0.061183 11.165720 3.784052 0.000000 273.324162 0.000000 2220.033054 +EDGE_SE2 865 866 0.579332 -0.011435 0.001982 11.246334 6.225212 0.000000 297.699601 0.000000 2490.119385 +EDGE_SE2 866 867 0.156548 0.001719 0.185575 133.883281 696.034953 0.000000 3957.157327 0.000000 1778.614047 +EDGE_SE2 867 868 0.017881 0.010690 1.037717 52749.955417 96798.086518 0.000000 177676.543047 0.000000 602.077325 +EDGE_SE2 868 869 0.012235 0.005926 0.991656 143324.570378 238746.643887 0.000000 397740.398080 0.000000 630.247818 +EDGE_SE2 869 870 0.002231 -0.000124 1.013097 15395648.131442 8450866.436031 0.000000 4638802.180641 0.000000 616.894084 +EDGE_SE2 870 871 0.001088 0.001679 0.986895 2024.695825 -224276.785530 0.000000 24980373.832027 0.000000 633.271838 +EDGE_SE2 871 872 0.008015 -0.000084 0.694560 653702.249121 768245.705891 0.000000 902886.231030 0.000000 870.614924 +EDGE_SE2 872 873 0.008522 -0.003526 -0.564717 34612.893765 -198701.425503 0.000000 1141058.001437 0.000000 1021.100307 +EDGE_SE2 873 874 0.015858 -0.003778 -0.551904 36802.135033 -111762.498404 0.000000 339519.358447 0.000000 1038.030952 +EDGE_SE2 874 875 0.013521 -0.001487 -0.578534 110429.389804 -217905.190004 0.000000 430036.577843 0.000000 1003.303038 +EDGE_SE2 875 876 0.574406 -0.080596 -0.153354 11.166806 -3.991544 0.000000 297.175644 0.000000 1879.380673 +EDGE_SE2 876 877 0.574770 -0.024813 -0.080909 11.525988 -10.980326 0.000000 301.721640 0.000000 2139.743633 +EDGE_SE2 877 878 0.217632 0.014817 0.389316 219.643265 626.455159 0.000000 1893.056212 0.000000 1295.203276 +EDGE_SE2 878 879 0.647020 0.057742 0.054681 11.377140 -7.747124 0.000000 236.717936 0.000000 2247.489979 +EDGE_SE2 879 880 0.455025 -0.018050 -0.108582 13.346224 -32.372663 0.000000 479.986413 0.000000 2034.250181 +EDGE_SE2 880 881 -0.043409 -0.000133 0.008718 12.813581 300.540520 0.000000 53066.151297 0.000000 2456.973472 +EDGE_SE2 881 882 0.647486 -0.064933 -0.241227 15.572920 -31.371721 0.000000 231.690918 0.000000 1622.697550 +EDGE_SE2 882 883 0.642883 -0.072854 -0.185824 12.322147 -16.564386 0.000000 237.676574 0.000000 1777.868098 +EDGE_SE2 883 884 0.383517 -0.007350 -0.063028 12.396618 -29.287057 0.000000 678.343333 0.000000 2212.333526 +EDGE_SE2 884 885 0.004929 0.003007 0.590777 5527.682570 128525.333864 0.000000 2994400.210829 0.000000 987.919146 +EDGE_SE2 885 886 0.007741 0.006994 1.034072 79878.863906 258839.772996 0.000000 838873.176713 0.000000 604.237070 +EDGE_SE2 886 887 0.010004 0.001000 1.027322 633501.134354 474724.505488 0.000000 355759.975090 0.000000 608.267401 +EDGE_SE2 887 888 0.005011 0.003332 0.999568 444415.889744 1014710.716533 0.000000 2316903.025310 0.000000 625.269895 +EDGE_SE2 888 889 0.005294 0.002083 0.911927 808634.909964 1357982.238784 0.000000 2280571.939853 0.000000 683.907547 +EDGE_SE2 889 890 0.355203 0.095914 0.279682 11.296105 11.600417 0.000000 738.538555 0.000000 1526.637360 +EDGE_SE2 890 891 0.616728 -0.012401 -0.066427 11.650788 -11.642307 0.000000 262.267312 0.000000 2198.253354 +EDGE_SE2 891 892 0.637263 -0.017865 -0.031981 11.114783 -0.928852 0.000000 246.045454 0.000000 2347.451378 +EDGE_SE2 892 893 0.642710 0.035710 0.241471 18.981950 41.834853 0.000000 233.470505 0.000000 1622.059760 +EDGE_SE2 893 894 0.638528 0.083732 0.226070 13.210427 21.873674 0.000000 239.022296 0.000000 1663.065968 +EDGE_SE2 894 895 0.615722 0.105457 0.303953 15.507767 32.534377 0.000000 251.859007 0.000000 1470.334450 +EDGE_SE2 895 896 0.020155 0.000491 0.481484 47934.902135 97432.832108 0.000000 198099.713240 0.000000 1139.058627 +EDGE_SE2 896 897 0.528670 0.158235 0.274351 11.197167 -5.224460 0.000000 328.288174 0.000000 1539.436858 +EDGE_SE2 897 898 0.618615 0.002949 0.017900 11.154262 3.285463 0.000000 261.262932 0.000000 2412.846978 +EDGE_SE2 898 899 0.499807 -0.008373 -0.065092 12.019606 -18.779145 0.000000 399.287489 0.000000 2203.767446 +EDGE_SE2 899 900 0.683722 0.007464 -0.000025 11.135386 -2.218523 0.000000 213.865098 0.000000 2499.875005 +EDGE_SE2 900 901 0.579956 -0.019520 -0.061673 11.335628 -8.008145 0.000000 296.748861 0.000000 2217.984277 +EDGE_SE2 901 902 0.644996 0.015819 0.027799 11.113573 0.751022 0.000000 240.226171 0.000000 2366.593280 +EDGE_SE2 902 903 0.494510 0.003386 -0.042100 12.063405 -19.440085 0.000000 407.959954 0.000000 2302.084267 +EDGE_SE2 903 904 0.005815 0.000708 0.715026 912712.732392 1351574.977076 0.000000 2001492.072759 0.000000 849.960204 +EDGE_SE2 904 905 0.554057 0.035513 0.058326 11.121228 -1.780350 0.000000 324.412517 0.000000 2232.035396 +EDGE_SE2 905 906 0.630376 0.024475 0.068969 11.329543 7.239573 0.000000 251.055279 0.000000 2187.810926 +EDGE_SE2 906 907 0.631021 0.007133 -0.005018 11.175042 -3.916492 0.000000 251.041590 0.000000 2475.097597 +EDGE_SE2 907 908 0.637636 0.001891 0.024788 11.222935 5.123325 0.000000 245.840507 0.000000 2380.520611 +EDGE_SE2 908 909 0.628314 0.001550 -0.017825 11.210816 -4.913046 0.000000 253.205497 0.000000 2413.202580 +EDGE_SE2 909 910 0.147710 -0.043678 -0.369688 39.436166 -343.900479 0.000000 4186.479576 0.000000 1332.590482 +EDGE_SE2 910 911 0.616085 0.011620 0.061065 11.560202 10.634138 0.000000 262.919471 0.000000 2220.526856 +EDGE_SE2 911 912 0.605554 0.006436 0.010902 11.111131 0.071773 0.000000 272.675019 0.000000 2446.368619 +EDGE_SE2 912 913 0.580860 0.003431 0.006628 11.111259 0.205638 0.000000 296.374652 0.000000 2467.186590 +EDGE_SE2 913 914 0.630196 -0.006309 -0.024572 11.162137 -3.503890 0.000000 251.720029 0.000000 2381.524439 +EDGE_SE2 914 915 0.556525 -0.006690 -0.037260 11.309630 -7.863953 0.000000 322.627351 0.000000 2323.618084 +EDGE_SE2 915 916 0.178865 0.104304 0.546671 11.926058 43.487541 0.000000 2331.711773 0.000000 1045.066974 +EDGE_SE2 916 917 0.624756 -0.045966 -0.254265 18.993145 -43.113795 0.000000 246.938496 0.000000 1589.137227 +EDGE_SE2 917 918 0.518933 -0.035276 -0.074995 11.129291 -2.552939 0.000000 369.618783 0.000000 2163.351655 +EDGE_SE2 918 919 0.629099 -0.005797 -0.042335 11.375987 -7.994276 0.000000 252.388154 0.000000 2301.046350 +EDGE_SE2 919 920 0.629899 -0.010656 -0.016202 11.111234 0.171926 0.000000 251.961442 0.000000 2420.917100 +EDGE_SE2 920 921 0.634457 -0.008549 -0.051374 11.451756 -8.983787 0.000000 248.039729 0.000000 2261.650760 +EDGE_SE2 921 922 0.635258 -0.006313 -0.024873 11.163905 -3.534345 0.000000 247.721599 0.000000 2380.125761 +EDGE_SE2 922 923 0.608430 -0.014168 -0.060475 11.469047 -9.619410 0.000000 269.629762 0.000000 2222.998344 +EDGE_SE2 923 924 0.530888 -0.000682 0.019383 11.257903 7.101435 0.000000 354.661710 0.000000 2405.831657 +EDGE_SE2 924 925 0.009664 0.004698 0.510887 2959.553169 50448.307002 0.000000 863189.572650 0.000000 1095.156133 +EDGE_SE2 925 926 0.598427 0.009230 0.018979 11.114501 0.953220 0.000000 279.170216 0.000000 2407.739741 +EDGE_SE2 926 927 0.627907 -0.001812 -0.020475 11.186132 -4.264817 0.000000 253.558182 0.000000 2400.685500 +EDGE_SE2 927 928 0.640773 -0.000139 -0.006135 11.119254 -1.375744 0.000000 243.544155 0.000000 2469.604995 +EDGE_SE2 928 929 0.636560 -0.000176 0.001919 11.112246 0.517244 0.000000 246.784978 0.000000 2490.432549 +EDGE_SE2 929 930 0.640386 -0.014253 -0.078843 11.855260 -13.135681 0.000000 242.981611 0.000000 2147.946760 +EDGE_SE2 930 931 0.635431 -0.020570 -0.076099 11.562880 -10.322123 0.000000 246.953500 0.000000 2158.915046 +EDGE_SE2 931 932 0.639769 -0.010067 -0.055067 11.471607 -9.160668 0.000000 243.895776 0.000000 2245.845776 +EDGE_SE2 932 933 0.631644 -0.015304 -0.059766 11.413371 -8.500896 0.000000 250.193846 0.000000 2225.973780 +EDGE_SE2 933 934 0.504140 0.003029 -0.005219 11.159305 -4.292306 0.000000 393.395672 0.000000 2474.107872 +EDGE_SE2 934 935 0.005622 0.001555 0.696880 504282.663987 1107982.483573 0.000000 2434463.693063 0.000000 868.235915 +EDGE_SE2 935 936 0.001863 0.001286 0.945362 2184651.299423 6152115.682451 0.000000 17324844.542602 0.000000 660.600886 +EDGE_SE2 936 937 0.551720 0.024485 0.062876 11.219817 5.867053 0.000000 327.765518 0.000000 2212.966335 +EDGE_SE2 937 938 0.601673 -0.055314 -0.173492 12.866388 -21.406117 0.000000 272.165004 0.000000 1815.430979 +EDGE_SE2 938 939 0.633059 0.008315 0.027580 11.160855 3.443094 0.000000 249.431085 0.000000 2367.602135 +EDGE_SE2 939 940 0.636273 -0.027491 -0.082722 11.479060 -9.300191 0.000000 246.180789 0.000000 2132.583702 +EDGE_SE2 940 941 0.635944 -0.015109 -0.050698 11.282417 -6.356188 0.000000 246.953620 0.000000 2264.561906 +EDGE_SE2 941 942 0.551791 -0.000493 0.007207 11.131937 2.570602 0.000000 328.415327 0.000000 2464.350846 +EDGE_SE2 942 943 0.644097 -0.001397 0.091523 13.123577 21.416835 0.000000 239.030853 0.000000 2098.332107 +EDGE_SE2 943 944 0.639009 -0.005732 -0.053678 11.578073 -10.437551 0.000000 244.411524 0.000000 2251.770804 +EDGE_SE2 944 945 0.635846 -0.012134 -0.052894 11.381001 -7.978646 0.000000 246.980906 0.000000 2255.125454 +EDGE_SE2 945 946 0.179699 -0.002044 0.066572 29.818272 239.512661 0.000000 3077.654110 0.000000 2197.655692 +EDGE_SE2 946 947 0.406915 0.138311 0.331627 11.119495 2.108463 0.000000 541.380410 0.000000 1409.856218 +EDGE_SE2 947 948 0.579846 -0.001426 -0.021963 11.220001 -5.582502 0.000000 297.312605 0.000000 2393.699690 +EDGE_SE2 948 949 0.604761 -0.049058 -0.159219 12.704160 -20.309811 0.000000 270.041237 0.000000 1860.411550 +EDGE_SE2 949 950 0.636468 -0.025408 -0.243519 20.734999 -46.608998 0.000000 236.840951 0.000000 1616.721292 +EDGE_SE2 950 951 0.637412 -0.014316 -0.075046 11.760145 -12.330103 0.000000 245.353687 0.000000 2163.146402 +EDGE_SE2 951 952 0.637647 0.028692 0.246962 20.543292 46.058094 0.000000 236.016458 0.000000 1607.805725 +EDGE_SE2 952 953 0.635715 0.017895 0.077527 11.686555 11.642681 0.000000 246.671765 0.000000 2153.196604 +EDGE_SE2 953 954 0.632201 -0.012369 -0.013007 11.121379 1.566520 0.000000 250.095671 0.000000 2436.212212 +EDGE_SE2 954 955 0.636040 -0.066402 -0.167279 12.043873 -14.725801 0.000000 243.592003 0.000000 1834.808164 +EDGE_SE2 955 956 0.633169 -0.005303 -0.005934 11.112531 0.581642 0.000000 249.417984 0.000000 2470.592019 +EDGE_SE2 956 957 0.635780 -0.029022 -0.090789 11.591896 -10.635874 0.000000 246.396892 0.000000 2101.157024 +EDGE_SE2 957 958 0.610078 -0.010922 -0.028564 11.140389 -2.745454 0.000000 268.560860 0.000000 2363.074257 +EDGE_SE2 958 959 0.604449 -0.016600 -0.068060 11.543478 -10.642379 0.000000 273.065197 0.000000 2191.536497 +EDGE_SE2 959 960 0.605875 0.054020 0.088370 11.111191 -0.143784 0.000000 270.268197 0.000000 2110.507423 +EDGE_SE2 960 961 0.602054 -0.007561 -0.020089 11.126126 -1.993676 0.000000 275.827437 0.000000 2402.502675 +EDGE_SE2 961 962 0.630743 0.063738 0.073005 11.293528 -6.582439 0.000000 248.635890 0.000000 2171.383420 +EDGE_SE2 962 963 0.629692 0.069822 0.195655 12.835701 20.187165 0.000000 247.411650 0.000000 1748.752064 +EDGE_SE2 963 964 0.639791 -0.008273 -0.057447 11.572861 -10.365475 0.000000 243.797913 0.000000 2235.747685 +EDGE_SE2 964 965 0.633282 -0.006211 -0.001478 11.127639 1.984141 0.000000 249.307749 0.000000 2492.626351 +EDGE_SE2 965 966 0.413197 -0.005006 -0.057147 12.275386 -25.836778 0.000000 584.463061 0.000000 2237.016798 +EDGE_SE2 966 967 0.007510 0.002997 0.859092 325478.163261 626027.365559 0.000000 1204158.381440 0.000000 723.332943 +EDGE_SE2 967 968 0.006374 0.000527 0.902649 1307259.212480 1219284.216016 0.000000 1137250.475138 0.000000 690.593544 +EDGE_SE2 968 969 0.000997 0.000085 0.061289 54733.539945 -2337658.966155 0.000000 99861248.240381 0.000000 2219.589608 +EDGE_SE2 969 970 0.000000 0.000000 -0.000113 11.111116 -0.043944 0.000000 399.999995 0.000000 2499.435096 +EDGE_SE2 970 971 0.361971 0.001286 0.001712 11.113656 -1.383525 0.000000 763.211229 0.000000 2491.461932 +EDGE_SE2 971 972 0.616031 0.005441 0.007131 11.111841 -0.429263 0.000000 263.487396 0.000000 2464.722790 +EDGE_SE2 972 973 0.597393 -0.119850 -0.282715 12.960368 -21.775201 0.000000 267.516438 0.000000 1519.426379 +EDGE_SE2 973 974 0.636084 -0.002771 0.033166 11.443293 8.848623 0.000000 246.819403 0.000000 2342.069601 +EDGE_SE2 974 975 0.636019 0.005980 0.005775 11.114215 -0.856039 0.000000 247.181135 0.000000 2471.373217 +EDGE_SE2 975 976 0.637784 0.010421 0.013983 11.112413 -0.552665 0.000000 245.773095 0.000000 2431.524562 +EDGE_SE2 976 977 0.637920 -0.011711 -0.026304 11.125929 -1.864213 0.000000 245.637352 0.000000 2373.493056 +EDGE_SE2 977 978 0.636711 0.018679 0.044825 11.167625 3.646515 0.000000 246.400847 0.000000 2290.091830 +EDGE_SE2 978 979 0.635616 -0.004880 -0.014420 11.121860 -1.593981 0.000000 247.494628 0.000000 2429.430070 +EDGE_SE2 979 980 0.640402 0.020748 0.043464 11.139636 2.574932 0.000000 243.549790 0.000000 2296.069703 +EDGE_SE2 980 981 0.634599 -0.001102 0.002602 11.115574 1.028911 0.000000 248.309152 0.000000 2487.040602 +EDGE_SE2 981 982 0.582350 0.019314 0.039136 11.121253 1.695467 0.000000 294.536681 0.000000 2315.235788 +EDGE_SE2 982 983 0.606004 -0.005123 -0.005706 11.113084 0.717739 0.000000 272.279670 0.000000 2471.712344 +EDGE_SE2 983 984 0.606209 0.019467 0.054452 11.241333 5.825396 0.000000 271.705807 0.000000 2248.466280 +EDGE_SE2 984 985 0.610191 0.001384 0.017236 11.168792 3.853233 0.000000 268.517439 0.000000 2415.997974 +EDGE_SE2 985 986 0.638807 0.015817 0.032823 11.126330 1.886242 0.000000 244.888150 0.000000 2343.625460 +EDGE_SE2 986 987 0.637113 -0.009662 -0.040633 11.263641 -5.987507 0.000000 246.149046 0.000000 2308.579426 +EDGE_SE2 987 988 0.633843 -0.002158 0.009656 11.151672 3.105391 0.000000 248.863041 0.000000 2452.410392 +EDGE_SE2 988 989 0.637783 0.006714 0.004244 11.120373 -1.474376 0.000000 245.804243 0.000000 2478.914326 +EDGE_SE2 989 990 0.633086 -0.006222 -0.014570 11.116473 -1.130568 0.000000 249.472636 0.000000 2428.711760 +EDGE_SE2 990 991 0.638433 0.009419 0.020655 11.119271 1.382293 0.000000 245.278829 0.000000 2399.838818 +EDGE_SE2 991 992 0.608534 -0.016202 -0.037230 11.140243 -2.745311 0.000000 269.821049 0.000000 2323.752499 +EDGE_SE2 992 993 0.639975 0.012788 0.027838 11.125497 1.830546 0.000000 244.047684 0.000000 2366.413689 +EDGE_SE2 993 994 0.610172 -0.004541 -0.015063 11.126066 -1.962186 0.000000 268.563253 0.000000 2426.353160 +EDGE_SE2 994 995 0.582700 0.014385 0.047816 11.262674 6.550087 0.000000 294.185844 0.000000 2277.036316 +EDGE_SE2 995 996 0.603243 0.013060 0.027432 11.119936 1.525036 0.000000 274.662056 0.000000 2368.284283 +EDGE_SE2 996 997 0.638105 -0.021586 -0.064337 11.329213 -7.143676 0.000000 245.093679 0.000000 2206.895091 +EDGE_SE2 997 998 0.393437 0.003178 0.021791 11.230485 8.704766 0.000000 645.865055 0.000000 2394.505630 +EDGE_SE2 998 999 0.009526 0.010297 0.717647 5765.419520 -53770.217970 0.000000 502458.344534 0.000000 847.368232 +EDGE_SE2 999 1000 0.631982 0.082779 0.148351 11.188179 4.255373 0.000000 246.074510 0.000000 1895.792072 +EDGE_SE2 1000 1001 0.637485 -0.061202 -0.321633 22.788129 -50.803890 0.000000 232.146590 0.000000 1431.259099 +EDGE_SE2 1001 1002 0.630663 0.034533 0.091989 11.444015 8.924103 0.000000 250.338290 0.000000 2096.541587 +EDGE_SE2 1002 1003 0.637376 -0.055899 -0.180665 13.130018 -21.602372 0.000000 242.257264 0.000000 1793.439086 +EDGE_SE2 1003 1004 0.634119 0.020824 0.062770 11.323812 7.101476 0.000000 248.209237 0.000000 2213.407797 +EDGE_SE2 1004 1005 0.602568 0.019724 0.067274 11.426188 9.115028 0.000000 274.805024 0.000000 2194.765624 +EDGE_SE2 1005 1006 0.609599 0.024909 0.082661 11.561301 10.758208 0.000000 268.200258 0.000000 2132.824020 +EDGE_SE2 1006 1007 0.575806 0.024121 0.097394 12.004289 16.068550 0.000000 300.189527 0.000000 2075.940233 +EDGE_SE2 1007 1008 0.296743 0.004461 0.166242 36.620925 167.418708 0.000000 1109.865632 0.000000 1838.072567 +EDGE_SE2 1008 1009 0.169516 0.079531 0.456955 12.060231 51.919506 0.000000 2851.251647 0.000000 1177.735408 +EDGE_SE2 1009 1010 0.635352 0.000090 0.046389 11.616830 10.927244 0.000000 247.219830 0.000000 2283.251111 +EDGE_SE2 1010 1011 0.629760 -0.000818 -0.047667 11.628961 -11.160233 0.000000 251.626406 0.000000 2277.684046 +EDGE_SE2 1011 1012 0.630488 0.001328 0.037830 11.417845 8.582558 0.000000 251.254815 0.000000 2321.066416 +EDGE_SE2 1012 1013 0.638821 0.043192 0.110754 11.546239 10.055629 0.000000 243.492562 0.000000 2026.302298 +EDGE_SE2 1013 1014 0.624005 -0.081360 -0.179557 11.711863 -12.027816 0.000000 251.923335 0.000000 1796.809951 +EDGE_SE2 1014 1015 0.637514 0.038828 0.081332 11.209468 4.796725 0.000000 245.041047 0.000000 2138.069893 +EDGE_SE2 1015 1016 0.781423 -0.009024 0.004462 11.150231 2.443265 0.000000 163.706442 0.000000 2477.838437 +EDGE_SE2 1016 1017 0.603503 0.011706 -0.057436 12.662554 -20.153468 0.000000 272.907609 0.000000 2235.794200 +EDGE_SE2 1017 1018 0.577934 -0.006330 0.007000 11.203996 5.173502 0.000000 299.265589 0.000000 2465.364100 +EDGE_SE2 1018 1019 0.612439 0.031252 0.059177 11.128209 2.087199 0.000000 265.898770 0.000000 2228.450161 +EDGE_SE2 1019 1020 0.633556 -0.016343 -0.014332 11.142340 2.725270 0.000000 248.935660 0.000000 2429.851626 +EDGE_SE2 1020 1021 0.639472 -0.000168 -0.041050 11.499240 -9.510600 0.000000 244.155855 0.000000 2306.730360 +EDGE_SE2 1021 1022 0.070832 0.000271 -0.007651 13.732233 -228.486723 0.000000 19928.608606 0.000000 2462.179597 +EDGE_SE2 1022 1023 0.011155 0.000820 0.086100 139.654009 10135.503712 0.000000 799187.396127 0.000000 2119.338762 +EDGE_SE2 1023 1024 0.645203 -0.002963 0.025849 11.323339 6.969723 0.000000 240.001559 0.000000 2375.598978 +EDGE_SE2 1024 1025 0.648616 0.019366 0.017058 11.148143 -2.895107 0.000000 237.448652 0.000000 2416.843718 +EDGE_SE2 1025 1026 0.180366 -0.000503 0.006661 11.384697 28.945754 0.000000 3073.606781 0.000000 2467.024836 +EDGE_SE2 1026 1027 0.004554 0.001979 0.914665 948112.591095 1716536.548028 0.000000 3107798.392242 0.000000 681.952949 +EDGE_SE2 1027 1028 0.157112 0.092209 0.562259 14.094418 94.590688 0.000000 3010.265300 0.000000 1024.315957 +EDGE_SE2 1028 1029 0.581697 -0.003158 -0.022026 11.189449 -4.719569 0.000000 295.446261 0.000000 2393.404593 +EDGE_SE2 1029 1030 0.602428 -0.021526 -0.077659 11.575380 -11.062953 0.000000 274.727843 0.000000 2152.669156 +EDGE_SE2 1030 1031 0.635032 -0.016817 -0.051435 11.258521 -5.904986 0.000000 247.654252 0.000000 2261.388344 +EDGE_SE2 1031 1032 0.639363 0.000529 0.006615 11.118933 1.351453 0.000000 244.619567 0.000000 2467.250316 +EDGE_SE2 1032 1033 0.641217 -0.014716 -0.042294 11.197935 -4.487022 0.000000 242.999818 0.000000 2301.227383 +EDGE_SE2 1033 1034 0.158807 -0.001999 -0.209870 162.997809 -759.872169 0.000000 3812.666625 0.000000 1707.900606 +EDGE_SE2 1034 1035 0.008238 -0.003621 -0.612225 47839.602807 -238285.590348 0.000000 1187170.073357 0.000000 961.808711 +EDGE_SE2 1035 1036 -0.001359 0.001797 -0.564077 2434530.032209 6484761.501388 0.000000 17273293.058299 0.000000 1021.936120 +EDGE_SE2 1036 1037 0.377894 -0.111886 -0.234247 12.927670 33.853486 0.000000 642.006396 0.000000 1641.103033 +EDGE_SE2 1037 1038 0.646416 0.075596 0.094513 11.219032 -4.926286 0.000000 235.981250 0.000000 2086.883283 +EDGE_SE2 1038 1039 0.688482 -0.025514 -0.028564 11.125452 1.691699 0.000000 210.663547 0.000000 2363.074257 +EDGE_SE2 1039 1040 -0.001379 -0.000331 0.637825 7632266.679736 17921038.113983 0.000000 42079787.422993 0.000000 931.976618 +EDGE_SE2 1040 1041 -0.001323 0.000722 1.029242 43947061.658526 1853405.592364 0.000000 78175.908225 0.000000 607.116902 +EDGE_SE2 1041 1042 0.008412 0.001092 0.999819 812869.525001 684736.258072 0.000000 576819.734984 0.000000 625.113140 +EDGE_SE2 1042 1043 0.010022 0.000228 0.981327 666387.833541 467987.047537 0.000000 328671.866042 0.000000 636.836128 +EDGE_SE2 1043 1044 -0.013611 -0.010605 1.005709 38168.445431 106580.996550 0.000000 297712.956067 0.000000 621.446905 +EDGE_SE2 1044 1045 -0.002205 0.000124 -0.113838 68490.084727 -1183057.512679 0.000000 20438767.774721 0.000000 2015.095849 +EDGE_SE2 1045 1046 -0.013495 0.002112 -0.385242 27867.951272 -118972.940165 0.000000 508129.060237 0.000000 1302.832870 +EDGE_SE2 1046 1047 -0.019733 0.005898 -0.555401 16179.611132 -59582.091055 0.000000 219575.422578 0.000000 1033.368600 +EDGE_SE2 1047 1048 0.344577 -0.119470 -0.312747 11.437653 15.549100 0.000000 751.519224 0.000000 1450.701098 +EDGE_SE2 1048 1049 0.648714 0.010953 0.017287 11.111148 0.091735 0.000000 237.558159 0.000000 2415.755736 +EDGE_SE2 1049 1050 0.646643 0.027376 0.075802 11.366332 7.617483 0.000000 238.466970 0.000000 2160.107247 +EDGE_SE2 1050 1051 0.640459 -0.024485 -0.073431 11.399152 -8.175325 0.000000 243.147148 0.000000 2169.660298 +EDGE_SE2 1051 1052 0.610691 0.014345 0.058571 11.427186 9.005158 0.000000 267.673485 0.000000 2231.002333 +EDGE_SE2 1052 1053 0.402418 -0.011887 -0.047093 11.297991 -10.639018 0.000000 616.787282 0.000000 2280.181912 +EDGE_SE2 1053 1054 0.003611 0.000205 0.781659 3360883.673888 3794299.768961 0.000000 4283634.029810 0.000000 787.573032 +EDGE_SE2 1054 1055 -0.004781 -0.004680 1.092196 217607.587361 662404.612456 0.000000 2016495.376692 0.000000 571.130228 +EDGE_SE2 1055 1056 -0.018363 -0.010043 1.033833 59014.075212 99936.588877 0.000000 169279.247866 0.000000 604.379088 +EDGE_SE2 1056 1057 -0.018154 -0.006925 1.003259 94181.986455 126785.732418 0.000000 170707.431880 0.000000 622.968093 +EDGE_SE2 1057 1058 0.000938 0.000345 0.933655 30225249.079874 45961533.817447 0.000000 69890696.274135 0.000000 668.624102 +EDGE_SE2 1058 1059 0.584768 -0.021106 -0.077373 11.589927 -11.588453 0.000000 291.578229 0.000000 2153.812205 +EDGE_SE2 1059 1060 0.639269 -0.001644 0.007968 11.137057 2.461692 0.000000 244.671355 0.000000 2460.631159 +EDGE_SE2 1060 1061 0.453408 -0.013544 -0.118843 14.861134 -42.033048 0.000000 482.248782 0.000000 1997.108732 +EDGE_SE2 1061 1062 0.018407 -0.004707 -0.560522 25818.783584 -80519.505627 0.000000 251230.619305 0.000000 1026.597536 +EDGE_SE2 1062 1063 -0.002214 0.000350 -0.593849 3568021.016682 -7633088.462779 0.000000 16329573.254319 0.000000 984.114566 +EDGE_SE2 1063 1064 0.301240 -0.082154 -0.262828 11.122946 3.465125 0.000000 1025.683739 0.000000 1567.659011 +EDGE_SE2 1064 1065 0.616850 0.043972 0.123884 11.806351 13.175109 0.000000 260.785525 0.000000 1979.233494 +EDGE_SE2 1065 1066 0.592225 -0.017770 -0.054423 11.274422 -6.684300 0.000000 284.699249 0.000000 2248.589962 +EDGE_SE2 1066 1067 0.012072 0.002120 0.435817 44661.394679 166520.359722 0.000000 621038.078606 0.000000 1212.667746 +EDGE_SE2 1067 1068 0.005144 0.001599 0.677089 463864.684926 1176104.562755 0.000000 2982033.931716 0.000000 888.848590 +EDGE_SE2 1068 1069 0.004939 0.001172 0.172450 14196.268745 -234184.920951 0.000000 3866205.524763 0.000000 1818.659296 +EDGE_SE2 1069 1070 0.007958 -0.000773 -0.535379 282034.324000 -601390.067166 0.000000 1282423.325271 0.000000 1060.495466 +EDGE_SE2 1070 1071 0.555140 -0.067868 -0.125252 11.115112 -1.111199 0.000000 319.703282 0.000000 1974.424001 +EDGE_SE2 1071 1072 0.529254 -0.007703 -0.066861 12.056408 -18.055610 0.000000 355.981837 0.000000 2196.465215 +EDGE_SE2 1072 1073 -0.002029 0.000845 -0.507518 262958.959876 -2318685.557147 0.000000 20446281.115523 0.000000 1100.056511 +EDGE_SE2 1073 1074 0.561059 -0.025535 -0.032676 11.161259 3.916370 0.000000 316.967702 0.000000 2344.292731 +EDGE_SE2 1074 1075 0.609431 -0.004618 0.018200 11.282578 6.650541 0.000000 269.060256 0.000000 2411.425356 +EDGE_SE2 1075 1076 0.065495 0.001481 0.413124 3385.912605 8198.067984 0.000000 19925.858335 0.000000 1251.928321 +EDGE_SE2 1076 1077 0.014156 0.014258 0.821400 271.376246 8025.080869 0.000000 247458.480551 0.000000 753.579966 +EDGE_SE2 1077 1078 0.639455 0.059020 0.049931 11.521069 -9.730785 0.000000 242.081388 0.000000 2267.871749 +EDGE_SE2 1078 1079 0.600624 0.018085 0.067237 11.477555 9.863097 0.000000 276.583452 0.000000 2194.917807 +EDGE_SE2 1079 1080 -0.000999 -0.000009 -0.477168 21861087.771847 -41382475.748765 0.000000 78336011.010556 0.000000 1145.724571 +EDGE_SE2 1080 1081 0.531360 -0.067180 -0.117428 11.134556 2.812802 0.000000 348.582744 0.000000 2002.169815 +EDGE_SE2 1081 1082 0.224996 0.001967 0.288640 161.010437 521.488265 0.000000 1825.328808 0.000000 1505.486248 +EDGE_SE2 1082 1083 -0.010460 -0.011699 1.057628 18726.686416 85143.154920 0.000000 387354.631781 0.000000 590.481488 +EDGE_SE2 1083 1084 0.006499 0.006279 0.991072 59854.087388 264007.010053 0.000000 1164720.918244 0.000000 630.617587 +EDGE_SE2 1084 1085 0.020056 0.011249 0.977075 38176.449616 75898.227624 0.000000 150947.567649 0.000000 639.578299 +EDGE_SE2 1085 1086 0.570700 0.124357 0.228493 11.165939 3.931749 0.000000 293.059740 0.000000 1656.511362 +EDGE_SE2 1086 1087 0.610443 -0.014761 -0.013224 11.141951 2.815599 0.000000 268.167634 0.000000 2435.168807 +EDGE_SE2 1087 1088 0.601056 0.009570 -0.017713 11.411487 -8.927269 0.000000 276.432474 0.000000 2413.733758 +EDGE_SE2 1088 1089 0.071683 -0.000572 -0.098521 170.122570 -1751.356223 0.000000 19300.592801 0.000000 2071.681742 +EDGE_SE2 1089 1090 0.001412 -0.000123 -0.621871 12937756.646628 -21836745.706848 0.000000 36856777.365825 0.000000 950.402110 +EDGE_SE2 1090 1091 0.549397 -0.084430 -0.180259 11.352156 -8.676436 0.000000 323.419744 0.000000 1794.673157 +EDGE_SE2 1091 1092 0.637703 -0.006996 -0.017526 11.121203 -1.539154 0.000000 245.862562 0.000000 2414.621027 +EDGE_SE2 1092 1093 0.588555 -0.015042 -0.067587 11.600931 -11.646012 0.000000 288.008196 0.000000 2193.478870 +EDGE_SE2 1093 1094 0.004150 -0.003600 -0.406987 303638.185583 955915.435697 0.000000 3009539.565685 0.000000 1262.873468 +EDGE_SE2 1094 1095 0.025922 -0.007302 -0.593448 13559.452360 -41040.960104 0.000000 124333.371329 0.000000 984.609944 +EDGE_SE2 1095 1096 0.013621 -0.004396 -0.574854 32930.237834 -122414.831277 0.000000 455229.472232 0.000000 1007.997402 +EDGE_SE2 1096 1097 0.359533 -0.076883 -0.217554 11.145668 -5.017901 0.000000 739.746128 0.000000 1686.411461 +EDGE_SE2 1097 1098 0.655276 -0.022381 -0.058348 11.240870 -5.359644 0.000000 232.489049 0.000000 2231.942602 +EDGE_SE2 1098 1099 0.601562 -0.024926 -0.098508 11.973250 -15.083436 0.000000 275.001216 0.000000 2071.731935 +EDGE_SE2 1099 1100 0.019767 0.000659 0.359334 26235.559183 77565.286776 0.000000 229429.617699 0.000000 1352.968387 +EDGE_SE2 1100 1101 0.259176 0.070164 0.262689 11.115050 -2.328152 0.000000 1387.055621 0.000000 1568.004174 +EDGE_SE2 1101 1102 0.009767 -0.003058 -0.397627 8459.012576 -89410.542255 0.000000 946310.626975 0.000000 1279.845202 +EDGE_SE2 1102 1103 0.624811 -0.021021 -0.035899 11.112369 -0.554908 0.000000 255.864408 0.000000 2329.727795 +EDGE_SE2 1103 1104 0.653192 -0.005160 -0.029757 11.217748 -4.878085 0.000000 234.257657 0.000000 2357.602064 +EDGE_SE2 1104 1105 0.643770 -0.007193 -0.019886 11.128584 -2.005277 0.000000 241.242039 0.000000 2403.459167 +EDGE_SE2 1105 1106 0.496058 -0.003395 -0.027229 11.275339 -8.055101 0.000000 406.199361 0.000000 2369.220411 +EDGE_SE2 1106 1107 0.007526 0.002867 0.253134 18856.773417 -169404.055090 0.000000 1522787.727562 0.000000 1592.007032 +EDGE_SE2 1107 1108 0.625868 0.043204 0.005957 12.073074 -15.257830 0.000000 253.117791 0.000000 2470.479046 +EDGE_SE2 1108 1109 0.646003 -0.046291 -0.106175 11.383719 -7.866802 0.000000 238.127651 0.000000 2043.112734 +EDGE_SE2 1109 1110 0.614215 -0.005255 -0.051510 11.579361 -10.894385 0.000000 264.581538 0.000000 2261.065764 +EDGE_SE2 1110 1111 0.553199 -0.082221 -0.103442 11.711068 13.593477 0.000000 319.104424 0.000000 2053.246012 +EDGE_SE2 1111 1112 0.569389 0.118635 0.343250 16.481962 38.719218 0.000000 290.243375 0.000000 1385.563104 +EDGE_SE2 1112 1113 0.640195 -0.016890 -0.097447 12.284559 -16.483251 0.000000 242.648861 0.000000 2075.739728 +EDGE_SE2 1113 1114 0.617738 0.000372 0.015293 11.165263 3.685922 0.000000 262.000150 0.000000 2425.253974 +EDGE_SE2 1114 1115 0.584111 0.002651 -0.017913 11.253226 -6.328745 0.000000 292.947350 0.000000 2412.785348 +EDGE_SE2 1115 1116 0.648872 0.022176 0.034505 11.111138 0.077459 0.000000 237.232680 0.000000 2336.010662 +EDGE_SE2 1116 1117 0.098251 0.000884 -0.129855 209.328151 -1418.352583 0.000000 10160.208546 0.000000 1958.369267 +EDGE_SE2 1117 1118 0.002069 -0.000845 -0.611494 987546.746516 -4336045.136437 0.000000 19038602.480542 0.000000 962.681493 +EDGE_SE2 1118 1119 -0.002904 0.000748 -0.435035 368477.951626 -1990623.945676 0.000000 10754258.868008 0.000000 1213.989755 +EDGE_SE2 1119 1120 0.606241 -0.045059 -0.065468 11.130843 2.262698 0.000000 270.573321 0.000000 2202.212316 +EDGE_SE2 1120 1121 0.209582 -0.004500 -0.120622 33.301618 -223.063126 0.000000 2253.383418 0.000000 1990.772900 +EDGE_SE2 1121 1122 0.003037 -0.001969 -0.554282 3351.615045 159642.761466 0.000000 7629342.430661 0.000000 1034.857076 +EDGE_SE2 1122 1123 0.587650 -0.008795 0.015249 11.365183 8.406488 0.000000 289.256608 0.000000 2425.464195 +EDGE_SE2 1123 1124 0.579143 0.038116 0.096775 11.386604 8.868243 0.000000 296.584474 0.000000 2078.284141 +EDGE_SE2 1124 1125 0.646108 -0.002624 0.011822 11.168733 3.627591 0.000000 239.485218 0.000000 2441.921916 +EDGE_SE2 1125 1126 0.089655 0.001862 0.336774 1211.106301 3670.039910 0.000000 11235.483551 0.000000 1399.020340 +EDGE_SE2 1126 1127 -0.000544 0.000812 1.050094 84031228.496092 -41585087.528682 0.000000 20579500.003262 0.000000 594.829446 +EDGE_SE2 1127 1128 -0.002103 -0.000314 0.980680 12093669.618717 11006276.376659 0.000000 10016675.597149 0.000000 637.252248 +EDGE_SE2 1128 1129 0.011252 0.005103 1.008728 198520.561371 301067.442842 0.000000 456622.144090 0.000000 619.580502 +EDGE_SE2 1129 1130 0.583423 0.017793 0.012045 11.207158 -5.207167 0.000000 293.417741 0.000000 2440.845899 +EDGE_SE2 1130 1131 0.750481 -0.194337 -0.435123 16.183680 -27.603353 0.000000 161.320023 0.000000 1213.840879 +EDGE_SE2 1131 1132 0.640243 -0.002464 -0.021306 11.182068 -4.064051 0.000000 243.880425 0.000000 2396.780386 +EDGE_SE2 1132 1133 0.584277 -0.021867 -0.040363 11.113568 -0.831424 0.000000 292.516553 0.000000 2309.777849 +EDGE_SE2 1133 1134 0.266576 -0.000300 -0.098860 24.404478 -135.580323 0.000000 1393.907817 0.000000 2070.404863 +EDGE_SE2 1134 1135 0.009102 -0.002652 -0.559816 82791.558254 -291964.753439 0.000000 1029764.152962 0.000000 1027.527058 +EDGE_SE2 1135 1136 0.002258 -0.003305 -0.565768 971762.123150 2263140.796874 0.000000 5270709.266319 0.000000 1019.729968 +EDGE_SE2 1136 1137 0.306973 -0.042413 -0.186154 13.568352 -50.253896 0.000000 1038.871344 0.000000 1776.878994 +EDGE_SE2 1137 1138 0.654763 -0.011031 -0.017798 11.111312 -0.211469 0.000000 233.189098 0.000000 2413.330616 +EDGE_SE2 1138 1139 0.527941 0.000918 -0.077053 13.265063 -27.280422 0.000000 356.625570 0.000000 2155.092221 +EDGE_SE2 1139 1140 -0.002013 0.000175 -0.486547 3709493.048971 -8779833.609002 0.000000 20780669.837336 0.000000 1131.312847 +EDGE_SE2 1140 1141 0.002239 -0.000031 -0.555810 5310315.218372 -8816646.759236 0.000000 14638204.801536 0.000000 1032.825356 +EDGE_SE2 1141 1142 0.372375 -0.136555 -0.370794 11.343901 -12.055726 0.000000 635.453819 0.000000 1330.440997 +EDGE_SE2 1142 1143 0.629856 0.033762 0.085383 11.354434 7.641679 0.000000 251.102091 0.000000 2122.139741 +EDGE_SE2 1143 1144 0.612945 -0.010504 -0.034290 11.186135 -4.373095 0.000000 266.015507 0.000000 2336.981945 +EDGE_SE2 1144 1145 0.611105 -0.003802 -0.029142 11.245917 -5.880472 0.000000 267.628650 0.000000 2360.420642 +EDGE_SE2 1145 1146 0.609486 -0.000759 0.016125 11.188979 4.482263 0.000000 269.120272 0.000000 2421.284019 +EDGE_SE2 1146 1147 0.610275 0.036873 0.068649 11.128787 2.128847 0.000000 267.508800 0.000000 2189.121374 +EDGE_SE2 1147 1148 0.611337 -0.001965 0.012226 11.172242 3.959007 0.000000 267.506715 0.000000 2439.973063 +EDGE_SE2 1148 1149 0.074700 0.001638 0.503169 3846.534249 7344.890200 0.000000 14076.680961 0.000000 1106.431132 +EDGE_SE2 1149 1150 -0.006116 -0.002785 0.988331 626799.870889 997506.113526 0.000000 1587497.215478 0.000000 632.357453 +EDGE_SE2 1150 1151 0.014648 0.006739 0.987862 107400.301813 172549.549763 0.000000 277258.261675 0.000000 632.655875 +EDGE_SE2 1151 1152 0.009432 0.009802 1.036217 28480.057962 120720.157191 0.000000 511914.710091 0.000000 602.964704 +EDGE_SE2 1152 1153 0.010437 0.002034 0.996659 458897.357799 441929.724577 0.000000 425610.882022 0.000000 627.093176 +EDGE_SE2 1153 1154 0.277143 0.156011 0.537087 11.691675 23.815732 0.000000 988.073623 0.000000 1058.139946 +EDGE_SE2 1154 1155 0.634179 -0.005082 -0.053384 11.599710 -10.761566 0.000000 248.138569 0.000000 2253.027920 +EDGE_SE2 1155 1156 0.609122 -0.005838 0.006338 11.176606 4.113232 0.000000 269.430259 0.000000 2468.608751 +EDGE_SE2 1156 1157 0.580367 0.023367 0.106616 12.366206 18.881213 0.000000 295.153466 0.000000 2041.484648 +EDGE_SE2 1157 1158 0.608842 -0.050707 -0.133293 11.757739 -12.869932 0.000000 267.263428 0.000000 1946.505325 +EDGE_SE2 1158 1159 0.600995 -0.037895 -0.099499 11.464087 -9.658719 0.000000 275.409224 0.000000 2067.999033 +EDGE_SE2 1159 1160 0.637109 -0.021604 -0.142588 13.876030 -25.338115 0.000000 243.313239 0.000000 1914.964342 +EDGE_SE2 1160 1161 0.638306 -0.057065 -0.094949 11.118890 -1.344463 0.000000 243.484624 0.000000 2085.221653 +EDGE_SE2 1161 1162 0.639583 0.008532 0.053343 11.484272 9.323139 0.000000 244.042318 0.000000 2253.203316 +EDGE_SE2 1162 1163 0.646089 0.001306 -0.009750 11.142767 -2.689017 0.000000 239.527759 0.000000 2451.953812 +EDGE_SE2 1163 1164 0.642172 0.018842 0.080564 11.717339 11.822667 0.000000 241.677018 0.000000 2141.110196 +EDGE_SE2 1164 1165 0.530061 0.001899 -0.020695 11.314294 -8.367588 0.000000 355.709513 0.000000 2399.650727 +EDGE_SE2 1165 1166 0.004850 0.001220 0.493564 239307.954224 948357.988051 0.000000 3758451.305300 0.000000 1120.707645 +EDGE_SE2 1166 1167 0.000199 0.000971 0.944839 17209450.782475 -38137417.374455 0.000000 84515406.833935 0.000000 660.956228 +EDGE_SE2 1167 1168 0.004314 0.002779 0.911345 419892.583640 1190803.974162 0.000000 3377188.237646 0.000000 684.324107 +EDGE_SE2 1168 1169 0.046124 0.045485 0.829043 72.075115 1203.501414 0.000000 23769.649842 0.000000 747.295174 +EDGE_SE2 1169 1170 0.595970 0.008443 0.008952 11.118461 -1.409691 0.000000 281.483079 0.000000 2455.833943 +EDGE_SE2 1170 1171 0.643652 0.016020 0.034262 11.131351 2.158066 0.000000 241.208530 0.000000 2337.108483 +EDGE_SE2 1171 1172 0.608254 -0.008594 -0.059650 11.647713 -11.779607 0.000000 269.699888 0.000000 2226.461162 +EDGE_SE2 1172 1173 0.635753 0.004699 0.011813 11.115733 1.045017 0.000000 247.395251 0.000000 2441.965358 +EDGE_SE2 1173 1174 0.642740 -0.015092 -0.065577 11.519977 -9.706025 0.000000 241.521390 0.000000 2201.761802 +EDGE_SE2 1174 1175 0.635529 -0.015560 -0.030331 11.119207 -1.383209 0.000000 247.431148 0.000000 2354.975943 +EDGE_SE2 1175 1176 0.639892 -0.002591 -0.040430 11.419513 -8.473235 0.000000 243.910274 0.000000 2309.480375 +EDGE_SE2 1176 1177 0.631909 0.000862 0.005069 11.114395 0.886514 0.000000 250.429122 0.000000 2474.846416 +EDGE_SE2 1177 1178 0.638012 -0.011209 -0.043943 11.274194 -6.181646 0.000000 245.425622 0.000000 2293.963142 +EDGE_SE2 1178 1179 0.631478 0.010553 0.032543 11.171171 3.792944 0.000000 250.644522 0.000000 2344.896698 +EDGE_SE2 1179 1180 0.271033 0.000088 -0.003969 11.136010 -5.798071 0.000000 1361.277228 0.000000 2480.272525 +EDGE_SE2 1180 1181 0.006369 0.000562 0.838184 1136739.900794 1219876.425763 0.000000 1309117.124470 0.000000 739.881291 +EDGE_SE2 1181 1182 0.043362 0.037473 0.721003 13.218472 253.246510 0.000000 30444.337192 0.000000 844.066675 +EDGE_SE2 1182 1183 0.631233 0.006864 0.028504 11.185650 4.227407 0.000000 250.864920 0.000000 2363.349975 +EDGE_SE2 1183 1184 0.641740 0.028391 0.073043 11.303273 6.663120 0.000000 242.151864 0.000000 2171.229631 +EDGE_SE2 1184 1185 0.636568 -0.012623 -0.029018 11.131008 -2.164911 0.000000 246.663116 0.000000 2360.989552 +EDGE_SE2 1185 1186 0.637011 0.023759 0.069721 11.358319 7.617657 0.000000 245.847739 0.000000 2184.736002 +EDGE_SE2 1186 1187 0.658018 -0.006443 -0.033774 11.237521 -5.269863 0.000000 230.804698 0.000000 2339.315499 +EDGE_SE2 1187 1188 0.632380 0.009510 0.021371 11.120695 1.513079 0.000000 249.993325 0.000000 2396.475334 +EDGE_SE2 1188 1189 0.635906 -0.012539 0.021673 11.515314 9.760309 0.000000 246.794097 0.000000 2395.058778 +EDGE_SE2 1189 1190 0.298422 -0.000493 0.007995 11.214542 10.722954 0.000000 1122.783078 0.000000 2460.499340 +EDGE_SE2 1190 1191 -0.001378 -0.000184 0.920177 25978781.998107 25880314.470994 0.000000 25782242.304073 0.000000 678.043383 +EDGE_SE2 1191 1192 0.072942 0.060647 0.797518 130.506556 1145.096181 0.000000 10993.483679 0.000000 773.736998 +EDGE_SE2 1192 1193 0.612651 -0.026766 -0.132178 13.102394 -22.437131 0.000000 263.925490 0.000000 1950.341157 +EDGE_SE2 1193 1194 0.586582 0.016272 0.041820 11.166533 3.933966 0.000000 290.352323 0.000000 2303.321852 +EDGE_SE2 1194 1195 0.636169 0.007659 0.052000 11.487698 9.418662 0.000000 246.677289 0.000000 2258.959939 +EDGE_SE2 1195 1196 0.637063 -0.002513 -0.173199 17.787125 -39.066310 0.000000 239.717067 0.000000 1816.337880 +EDGE_SE2 1196 1197 0.631038 0.007284 0.010757 11.111259 -0.188614 0.000000 251.090831 0.000000 2447.070566 +EDGE_SE2 1197 1198 0.639335 0.035252 0.257911 20.557528 45.933130 0.000000 234.460604 0.000000 1579.938488 +EDGE_SE2 1198 1199 0.625974 -0.039991 -0.215702 16.676523 -36.355580 0.000000 248.600846 0.000000 1691.553532 +EDGE_SE2 1199 1200 0.642662 0.020896 0.068112 11.403588 8.210051 0.000000 241.573905 0.000000 2191.323116 +EDGE_SE2 1200 1201 0.632369 0.008692 0.054836 11.514278 9.806016 0.000000 249.617869 0.000000 2246.829525 +EDGE_SE2 1201 1202 0.636732 0.009332 0.021910 11.123506 1.708394 0.000000 246.587725 0.000000 2393.947989 +EDGE_SE2 1202 1203 0.605583 0.016194 -0.091218 14.730772 -30.544741 0.000000 268.864904 0.000000 2099.505256 +EDGE_SE2 1203 1204 0.604704 -0.076543 -0.148349 11.241024 -5.788533 0.000000 269.030303 0.000000 1895.798676 +EDGE_SE2 1204 1205 0.579744 0.012270 0.028212 11.125345 2.018565 0.000000 297.379849 0.000000 2364.692492 +EDGE_SE2 1205 1206 0.604024 0.022981 0.059672 11.234092 5.681316 0.000000 273.569799 0.000000 2226.368715 +EDGE_SE2 1206 1207 0.628833 -0.063349 -0.087865 11.148708 2.998873 0.000000 250.310531 0.000000 2112.467324 +EDGE_SE2 1207 1208 0.641879 0.018435 0.062871 11.381019 7.898378 0.000000 242.243300 0.000000 2212.987156 +EDGE_SE2 1208 1209 0.636239 0.001912 -0.003661 11.121595 -1.572688 0.000000 247.023047 0.000000 2481.795033 +EDGE_SE2 1209 1210 0.630195 0.024749 0.018688 11.212716 -4.940152 0.000000 251.306983 0.000000 2409.115535 +EDGE_SE2 1210 1211 0.632941 -0.047678 -0.070430 11.116473 1.127530 0.000000 248.202543 0.000000 2181.842838 +EDGE_SE2 1211 1212 0.633914 0.009606 0.052050 11.434554 8.761975 0.000000 248.470147 0.000000 2258.745224 +EDGE_SE2 1212 1213 0.635719 0.026579 0.075094 11.372749 7.851816 0.000000 246.746209 0.000000 2162.953249 +EDGE_SE2 1213 1214 0.748508 -0.025001 -0.220810 16.915079 -30.604005 0.000000 172.484342 0.000000 1677.427863 +EDGE_SE2 1214 1215 0.609440 0.015872 0.060134 11.410886 8.788375 0.000000 268.756514 0.000000 2224.428662 +EDGE_SE2 1215 1216 0.569604 0.086391 0.218432 12.447317 19.645507 0.000000 299.948223 0.000000 1683.981886 +EDGE_SE2 1216 1217 0.604098 -0.020910 -0.018798 11.176666 4.148410 0.000000 273.628656 0.000000 2408.595337 +EDGE_SE2 1217 1218 0.590246 0.008252 -0.050669 12.262477 -17.784784 0.000000 285.827155 0.000000 2264.686919 +EDGE_SE2 1218 1219 0.650992 0.006557 0.030598 11.205817 4.613431 0.000000 235.846718 0.000000 2353.755880 +EDGE_SE2 1219 1220 0.586496 0.026678 0.090738 11.682801 12.616550 0.000000 289.544235 0.000000 2101.353517 +EDGE_SE2 1220 1221 -0.001846 -0.000482 -0.452753 11628909.160981 -13576008.003722 0.000000 15849147.678198 0.000000 1184.558318 +EDGE_SE2 1221 1222 0.012937 -0.005157 -0.597307 24124.307745 -108858.692621 0.000000 491452.172995 0.000000 979.857795 +EDGE_SE2 1222 1223 0.011537 -0.003845 -0.559627 37585.948232 -154900.759550 0.000000 638583.281939 0.000000 1027.776110 +EDGE_SE2 1223 1224 0.574470 -0.089064 -0.182908 11.352146 -8.281702 0.000000 295.661931 0.000000 1786.644187 +EDGE_SE2 1224 1225 0.625700 0.003903 0.013764 11.124947 1.838454 0.000000 255.403355 0.000000 2432.575223 +EDGE_SE2 1225 1226 0.106504 -0.000109 -0.016731 13.283390 -138.281257 0.000000 8813.714781 0.000000 2418.398573 +EDGE_SE2 1226 1227 0.000000 0.000000 -0.000662 11.111282 -0.257444 0.000000 399.999830 0.000000 2496.693284 +EDGE_SE2 19 166 -2.459689 0.241111 0.252800 11.731352 1.696454 0.000000 15.751178 0.000000 1592.856013 +EDGE_SE2 19 172 1.067903 0.915786 0.149470 22.211594 -17.729393 0.000000 39.428022 0.000000 1892.102792 +EDGE_SE2 25 172 -2.539634 0.852630 -0.029860 11.348228 0.783018 0.000000 13.696833 0.000000 2357.130503 +EDGE_SE2 25 178 1.225223 0.672079 -0.102480 24.051651 -18.745770 0.000000 38.266385 0.000000 2056.830811 +EDGE_SE2 32 178 -2.020007 -0.239771 0.715180 15.237484 6.070047 0.000000 20.040376 0.000000 849.807581 +EDGE_SE2 32 183 -0.092559 0.424181 0.041600 515.079071 88.191252 0.000000 26.544031 0.000000 2304.294940 +EDGE_SE2 44 189 -2.265706 -0.570857 0.197720 11.128469 -0.353246 0.000000 18.300012 0.000000 1742.727183 +EDGE_SE2 44 195 1.302289 -0.133004 -0.005280 11.549680 4.530716 0.000000 57.916501 0.000000 2473.807626 +EDGE_SE2 50 195 -2.374379 -0.253682 0.216120 11.188114 0.699234 0.000000 17.460612 0.000000 1690.390904 +EDGE_SE2 50 201 1.291572 0.086248 -0.050700 11.777215 -5.648747 0.000000 59.014090 0.000000 2264.553285 +EDGE_SE2 50 203 2.550695 0.035722 -0.084650 11.152401 -0.417172 0.000000 15.326014 0.000000 2125.008969 +EDGE_SE2 61 203 -2.852494 0.122053 0.077870 11.127858 0.138148 0.000000 12.250754 0.000000 2151.826441 +EDGE_SE2 61 209 0.730780 0.072970 0.008890 12.538871 -15.710166 0.000000 183.975779 0.000000 2456.135792 +EDGE_SE2 67 209 -2.822142 0.138051 -0.004460 11.113900 0.062754 0.000000 12.522981 0.000000 2477.848305 +EDGE_SE2 67 220 0.783704 -1.176736 -1.412900 17.863537 -14.737201 0.000000 43.275118 0.000000 429.399329 +EDGE_SE2 81 220 -0.868391 -0.009825 -0.046880 11.522030 -7.053327 0.000000 132.179889 0.000000 2281.109865 +EDGE_SE2 81 226 2.836453 0.058719 0.049150 11.112174 0.037334 0.000000 12.422974 0.000000 2271.249469 +EDGE_SE2 87 226 -0.459640 0.184679 0.343830 185.785423 196.810927 0.000000 232.864045 0.000000 1384.367338 +EDGE_SE2 87 231 1.060624 0.863823 0.294010 34.429085 -29.740516 0.000000 94.681322 0.000000 4479.050905 +EDGE_SE2 94 231 -2.231597 0.316386 0.180250 23.930088 5.134954 0.000000 37.661225 0.000000 5384.101583 +EDGE_SE2 94 241 2.816677 0.483252 0.041400 22.259441 -0.288013 0.000000 24.450978 0.000000 6915.540303 +EDGE_SE2 101 241 -1.436886 0.314097 -0.098870 23.168499 8.096966 0.000000 91.505166 0.000000 6211.101543 +EDGE_SE2 101 247 2.168416 0.280309 -0.003870 22.564171 -2.567078 0.000000 41.493789 0.000000 7442.285250 +EDGE_SE2 107 247 -1.536762 0.375104 0.051050 26.954959 15.833327 0.000000 75.192472 0.000000 6789.136027 +EDGE_SE2 107 254 0.592787 -1.020976 -0.778000 30.649088 30.837091 0.000000 135.066803 0.000000 2372.453724 +EDGE_SE2 107 256 0.707309 -1.207974 -1.163740 23.417473 -9.695697 0.000000 100.872264 0.000000 1601.957964 +EDGE_SE2 107 258 0.976528 -2.202656 -1.227730 22.289493 -0.904508 0.000000 34.383996 0.000000 1511.249453 +EDGE_SE2 114 254 -0.931502 -0.024068 0.567580 77.556805 91.947180 0.000000 175.007037 0.000000 3052.121623 +EDGE_SE2 114 256 -0.723652 0.045801 0.181840 43.302820 84.297616 0.000000 359.313621 0.000000 5369.624220 +EDGE_SE2 114 258 0.306031 0.086093 0.117850 69.684517 -301.023297 0.000000 1931.422497 0.000000 6001.975262 +EDGE_SE2 121 266 0.737190 -0.017200 -0.118240 25.326151 -32.604829 0.000000 364.715589 0.000000 5997.789466 +EDGE_SE2 126 266 -1.480397 0.199141 0.062860 24.793867 12.913265 0.000000 87.064919 0.000000 6639.098888 +EDGE_SE2 126 272 2.350796 0.151313 0.025060 22.243466 -0.541415 0.000000 36.020406 0.000000 7137.772305 +EDGE_SE2 132 272 -1.375990 0.193564 -0.069560 22.622461 5.692420 0.000000 103.182984 0.000000 6556.181353 +EDGE_SE2 132 278 2.220707 0.319882 -0.000500 22.580601 -2.479176 0.000000 39.372548 0.000000 7492.505621 +EDGE_SE2 138 278 -1.378019 0.626427 0.016990 34.209796 25.223836 0.000000 75.297341 0.000000 7251.500784 +EDGE_SE2 138 284 2.391863 0.324204 -0.075755 22.750660 -2.473459 0.000000 33.799752 0.000000 6480.884307 +EDGE_SE2 151 284 -2.650853 -0.975732 1.454550 24.484817 1.146301 0.000000 22.802974 0.000000 1244.851357 +EDGE_SE2 151 291 -1.498500 0.364159 0.021790 26.317431 15.382872 0.000000 80.005044 0.000000 7183.530951 +EDGE_SE2 151 297 2.217429 -0.068852 -0.223460 22.895631 -3.456384 0.000000 39.962710 0.000000 5010.507463 +EDGE_SE2 19 305 -1.044094 0.006772 0.289080 17.951036 22.463977 0.000000 84.888274 0.000000 1504.458692 +EDGE_SE2 19 315 1.796874 2.231292 1.917670 11.894814 0.476141 0.000000 11.400392 0.000000 293.675468 +EDGE_SE2 19 337 1.676359 1.138847 2.369960 23.812750 -2.606854 0.000000 11.646135 0.000000 220.135719 +EDGE_SE2 19 342 2.451034 1.014379 -0.106190 11.820054 -1.302086 0.000000 13.502599 0.000000 2043.057325 +EDGE_SE2 19 1016 0.039741 0.374380 -2.852145 602.592071 -246.735273 0.000000 114.036309 0.000000 168.474698 +EDGE_SE2 25 315 -1.587705 2.017012 1.738340 12.043194 -1.708941 0.000000 14.244392 0.000000 333.399749 +EDGE_SE2 25 337 -1.901147 0.963583 2.190630 13.452340 -4.476777 0.000000 19.671370 0.000000 245.576678 +EDGE_SE2 25 342 -1.161097 0.702932 -0.285520 13.939899 10.682557 0.000000 51.452426 0.000000 1512.802847 +EDGE_SE2 25 367 0.878430 -0.159970 0.910020 100.995987 46.868336 0.000000 35.549493 0.000000 685.273881 +EDGE_SE2 25 374 2.840920 -0.557124 -0.601610 11.240233 -0.298749 0.000000 11.802326 0.000000 974.600130 +EDGE_SE2 25 1008 0.839778 0.868849 2.614245 65.217790 -13.300389 0.000000 14.380585 0.000000 191.383617 +EDGE_SE2 25 1010 0.208016 0.817490 -3.078070 128.288560 -37.883138 0.000000 23.358623 0.000000 150.324807 +EDGE_SE2 32 367 -1.650170 -1.061836 1.727680 23.555966 5.481395 0.000000 13.525417 0.000000 336.010748 +EDGE_SE2 32 374 -0.018221 0.098268 0.216050 10000.716890 -326.857444 0.000000 21.805806 0.000000 1690.585519 +EDGE_SE2 32 382 0.235335 2.451229 2.821510 16.224704 1.166981 0.000000 11.377430 0.000000 171.186695 +EDGE_SE2 32 387 0.993162 2.566664 0.274705 12.448992 -1.004261 0.000000 11.864945 0.000000 1538.582680 +EDGE_SE2 32 1003 0.362306 -0.196467 3.066965 108.121054 215.919400 0.000000 491.692649 0.000000 151.146840 +EDGE_SE2 32 1008 -2.427177 -0.386394 -2.851280 11.206045 0.712595 0.000000 16.460019 0.000000 168.550413 +EDGE_SE2 32 1010 -2.821790 -0.882420 -2.260410 11.209350 0.150567 0.000000 11.341881 0.000000 235.177395 +EDGE_SE2 44 437 0.696650 -2.771050 -0.205460 12.032017 0.446847 0.000000 11.327933 0.000000 1720.419675 +EDGE_SE2 44 454 -1.152851 -1.893499 1.516715 13.178717 3.850191 0.000000 18.280745 0.000000 394.704273 +EDGE_SE2 44 467 1.218289 1.232598 1.113140 13.331453 6.657638 0.000000 31.073862 0.000000 559.865191 +EDGE_SE2 44 494 2.154809 -0.649767 -0.306530 11.112721 -0.117867 0.000000 19.740180 0.000000 1464.539994 +EDGE_SE2 44 988 2.712903 -0.996652 3.047100 11.166944 0.211947 0.000000 11.915683 0.000000 152.634299 +EDGE_SE2 44 994 -0.892482 -0.642947 3.093485 38.865579 -34.860363 0.000000 54.896672 0.000000 149.194749 +EDGE_SE2 50 467 -2.756210 1.060141 1.334540 11.461044 -0.046083 0.000000 11.117180 0.000000 458.709115 +EDGE_SE2 50 494 -1.429190 -0.570621 -0.085130 17.367850 -12.471280 0.000000 35.969560 0.000000 2123.129418 +EDGE_SE2 50 500 2.268340 -0.490379 0.263640 12.680013 3.039151 0.000000 16.998309 0.000000 1565.644941 +EDGE_SE2 50 982 2.823043 -0.459737 -3.096925 11.157700 0.222838 0.000000 12.176961 0.000000 148.944310 +EDGE_SE2 50 988 -0.808543 -0.786485 -3.014685 35.481589 -32.415484 0.000000 54.227361 0.000000 155.108998 +EDGE_SE2 61 508 -1.449200 2.112314 1.477670 12.801726 -2.029955 0.000000 13.548517 0.000000 407.242490 +EDGE_SE2 61 522 -1.053664 -0.045704 0.099000 11.354883 4.375854 0.000000 89.660307 0.000000 2069.877405 +EDGE_SE2 61 528 2.466833 0.101003 -0.088240 11.198948 -0.676270 0.000000 16.317799 0.000000 2111.011691 +EDGE_SE2 61 976 1.165811 -0.076649 -3.054440 12.551016 9.349655 0.000000 71.820715 0.000000 152.082153 +EDGE_SE2 61 982 -2.503567 -0.322810 -2.934405 11.139618 0.360303 0.000000 15.665017 0.000000 161.503454 +EDGE_SE2 67 528 -1.085869 0.142906 -0.101590 11.172968 2.113193 0.000000 83.303853 0.000000 2060.155675 +EDGE_SE2 67 532 1.038480 -0.184540 -0.187270 11.121355 -0.898278 0.000000 89.877742 0.000000 1773.540133 +EDGE_SE2 67 556 0.875960 2.072499 -1.608750 12.194562 2.861649 0.000000 18.669404 0.000000 367.345805 +EDGE_SE2 67 564 0.934530 -0.521388 -1.425090 59.070878 -36.808963 0.000000 39.361868 0.000000 425.093327 +EDGE_SE2 67 567 1.078640 -1.127738 0.068640 28.794636 14.729412 0.000000 23.379907 0.000000 2189.158247 +EDGE_SE2 67 570 2.695842 -0.809094 0.129960 11.364179 0.564364 0.000000 12.369693 0.000000 1958.005326 +EDGE_SE2 67 965 0.918287 -0.079133 1.692110 113.199731 -21.468798 0.000000 15.625907 0.000000 344.948615 +EDGE_SE2 67 976 -2.389147 -0.017363 -3.067790 11.139434 0.425047 0.000000 17.489953 0.000000 151.085560 +EDGE_SE2 81 528 -2.540636 -1.571989 1.264430 11.150293 0.045554 0.000000 11.164073 0.000000 487.553422 +EDGE_SE2 81 532 -1.788049 0.441390 1.178750 29.071227 2.714944 0.000000 11.521516 0.000000 526.653783 +EDGE_SE2 81 564 -1.479377 0.271115 -0.059070 11.602730 4.003639 0.000000 43.715888 0.000000 2228.900474 +EDGE_SE2 81 567 -0.856391 0.288913 1.434660 118.478978 -20.563824 0.000000 15.049634 0.000000 421.758037 +EDGE_SE2 81 570 -0.839522 1.937122 1.495980 13.560960 -4.662733 0.000000 19.985567 0.000000 401.289509 +EDGE_SE2 81 575 -0.874481 2.499055 -2.998155 14.149112 0.594261 0.000000 11.227354 0.000000 156.394216 +EDGE_SE2 81 588 2.585410 -0.398590 0.032990 11.230814 0.636285 0.000000 14.493300 0.000000 2342.867749 +EDGE_SE2 81 959 1.715988 -0.147087 2.880085 11.804020 -3.896236 0.000000 33.019679 0.000000 166.057104 +EDGE_SE2 81 965 -1.915695 0.345142 3.058130 11.248005 1.439837 0.000000 26.255228 0.000000 151.805707 +EDGE_SE2 87 588 -0.567044 -0.325829 0.327670 19.376959 -42.100418 0.000000 225.541056 0.000000 1418.272639 +EDGE_SE2 87 597 1.033167 2.497995 1.747590 11.858143 1.168127 0.000000 12.937699 0.000000 331.158689 +EDGE_SE2 87 604 1.169979 2.733059 -1.279630 11.194520 0.099906 0.000000 11.230777 0.000000 481.073330 +EDGE_SE2 87 953 1.577352 0.448961 -2.823050 11.155436 1.074029 0.000000 37.135844 0.000000 171.048808 +EDGE_SE2 87 959 -1.472035 -0.337676 -3.108420 12.306884 -6.140766 0.000000 42.646361 0.000000 148.112032 +EDGE_SE2 94 597 -2.073375 1.943112 1.633830 11.708877 -0.635533 0.000000 11.786797 0.000000 360.383193 +EDGE_SE2 94 604 -1.910764 2.161126 -1.393390 11.355872 -0.402293 0.000000 11.772326 0.000000 436.428461 +EDGE_SE2 94 616 -0.567925 0.985809 1.728270 19.547380 -22.065015 0.000000 68.822033 0.000000 335.865437 +EDGE_SE2 94 632 -0.258230 -0.057031 -0.961010 1222.393668 -501.336231 0.000000 218.608540 0.000000 650.100338 +EDGE_SE2 94 637 2.180403 0.487495 0.048180 11.371804 -1.502621 0.000000 19.772123 0.000000 2275.455104 +EDGE_SE2 94 947 1.819562 0.355845 -2.812985 11.439117 2.406258 0.000000 28.763471 0.000000 171.952995 +EDGE_SE2 94 953 -1.765303 -0.154451 -2.936810 11.396122 2.414195 0.000000 31.560619 0.000000 161.306214 +EDGE_SE2 101 637 -2.066317 0.407256 -0.092090 11.230841 1.163903 0.000000 22.425529 0.000000 2096.153815 +EDGE_SE2 101 642 0.702540 0.058990 -0.158060 22.012272 -44.195550 0.000000 190.288971 0.000000 1864.137257 +EDGE_SE2 101 645 1.268565 0.117224 1.302975 55.348130 16.649223 0.000000 17.377280 0.000000 471.369465 +EDGE_SE2 101 657 0.970735 1.275733 -1.200065 31.327289 12.383774 0.000000 18.697009 0.000000 516.498549 +EDGE_SE2 101 663 2.721944 0.234701 0.154665 11.121870 0.156475 0.000000 13.386764 0.000000 1875.114422 +EDGE_SE2 101 665 2.743644 0.343689 1.484400 12.992900 0.403085 0.000000 11.197453 0.000000 405.039117 +EDGE_SE2 101 939 1.736598 0.040097 -3.139770 11.121070 -0.468281 0.000000 33.131371 0.000000 145.877255 +EDGE_SE2 101 944 -1.229619 0.290529 3.034680 11.913468 6.379852 0.000000 61.839764 0.000000 153.575457 +EDGE_SE2 101 947 -2.442020 0.327348 -2.953255 11.646767 1.607820 0.000000 15.937136 0.000000 159.966957 +EDGE_SE2 101 1138 -0.044980 -2.128090 1.406340 11.334711 -1.549412 0.000000 21.847605 0.000000 431.743719 +EDGE_SE2 101 1188 1.043367 -1.716987 3.078145 20.296004 6.412523 0.000000 15.588077 0.000000 150.319256 +EDGE_SE2 107 642 -2.988279 0.073654 -0.103140 11.111606 -0.006296 0.000000 11.191151 0.000000 2054.370375 +EDGE_SE2 107 645 -2.426303 0.162871 1.357895 16.787995 0.834037 0.000000 11.233646 0.000000 449.666954 +EDGE_SE2 107 663 -0.981564 0.359950 0.209585 33.867694 36.211234 0.000000 68.731953 0.000000 1708.704657 +EDGE_SE2 107 665 -0.965880 0.469964 1.539320 74.030616 -28.201297 0.000000 23.751280 0.000000 387.708339 +EDGE_SE2 107 680 -1.101202 1.597727 -1.082720 11.315853 -1.766538 0.000000 26.353031 0.000000 576.339299 +EDGE_SE2 107 683 -0.373238 0.237253 -0.978670 91.473664 -183.671027 0.000000 430.896755 0.000000 638.547590 +EDGE_SE2 107 704 -0.174419 -0.744617 -2.364960 56.805507 -72.228521 0.000000 125.281768 0.000000 220.790405 +EDGE_SE2 107 714 -0.001585 -1.518738 0.040750 43.298168 -1.345998 0.000000 11.167398 0.000000 2308.060399 +EDGE_SE2 107 730 1.719547 -1.998733 -2.849795 13.843772 1.215931 0.000000 11.652154 0.000000 168.680442 +EDGE_SE2 107 929 0.482300 -2.592003 1.960350 11.247596 0.654505 0.000000 14.249748 0.000000 285.268546 +EDGE_SE2 107 935 -0.294578 0.372182 2.191385 12.146819 -21.145445 0.000000 442.825321 0.000000 245.460450 +EDGE_SE2 107 939 -1.954743 0.111552 -3.084850 11.304032 1.688716 0.000000 25.893149 0.000000 149.826206 +EDGE_SE2 107 1147 -0.324254 -1.481983 0.140150 39.532534 -10.553850 0.000000 15.030118 0.000000 1923.162692 +EDGE_SE2 107 1150 0.364219 -1.279939 1.435915 18.388124 -16.646666 0.000000 49.191505 0.000000 421.323458 +EDGE_SE2 114 663 -2.629135 -1.250276 1.555165 11.663410 0.273309 0.000000 11.246360 0.000000 382.914669 +EDGE_SE2 114 665 -2.732868 -1.210420 2.884900 11.143210 -0.040214 0.000000 11.161493 0.000000 165.645759 +EDGE_SE2 114 683 -2.373686 -0.684712 0.366910 11.150086 0.451690 0.000000 16.345825 0.000000 1338.012489 +EDGE_SE2 114 704 -1.372213 -0.710183 -1.019380 41.720375 -2.264013 0.000000 11.278569 0.000000 613.061308 +EDGE_SE2 114 714 -0.579045 -0.714588 1.386330 35.416827 44.860054 0.000000 93.907456 0.000000 439.014644 +EDGE_SE2 114 730 0.273187 0.855886 -1.504215 26.282898 38.481991 0.000000 108.717525 0.000000 398.654506 +EDGE_SE2 114 929 0.575175 -0.482602 -2.977255 107.010292 82.154133 0.000000 81.490248 0.000000 158.042201 +EDGE_SE2 114 935 -2.487642 -0.577907 -2.746220 11.227888 0.692283 0.000000 15.215150 0.000000 178.136720 +EDGE_SE2 114 1147 -0.686929 -1.020901 1.485730 24.072771 23.324553 0.000000 53.083724 0.000000 404.605797 +EDGE_SE2 114 1150 -0.730123 -0.304695 2.781495 80.988104 -74.193686 0.000000 89.888157 0.000000 174.828760 +EDGE_SE2 114 1158 1.965070 -0.055808 0.083960 11.296704 1.644922 0.000000 25.690196 0.000000 2127.715200 +EDGE_SE2 114 1175 2.570804 -0.255481 2.913020 11.175699 -0.495876 0.000000 14.918247 0.000000 163.273564 +EDGE_SE2 121 754 -0.176774 -0.090674 -0.104160 764.277342 -1154.350823 0.000000 1780.343146 0.000000 2050.576559 +EDGE_SE2 121 759 2.795658 -0.372882 -0.047990 11.121537 0.122936 0.000000 12.560684 0.000000 2276.280256 +EDGE_SE2 121 923 -0.359940 -0.158411 2.816780 299.677751 -316.410365 0.000000 358.051835 0.000000 171.611249 +EDGE_SE2 121 1158 -1.765259 0.015433 0.094390 11.333442 2.148138 0.000000 31.866199 0.000000 2087.352405 +EDGE_SE2 121 1164 1.939145 -0.416391 -0.071910 11.388217 1.971985 0.000000 25.144479 0.000000 2175.822000 +EDGE_SE2 121 1175 -1.157476 -0.177912 2.923450 19.220682 -20.867733 0.000000 64.808438 0.000000 162.406633 +EDGE_SE2 126 754 -2.366181 -0.037747 0.076940 11.136170 0.410365 0.000000 17.831325 0.000000 2155.544499 +EDGE_SE2 126 759 0.608470 0.220030 0.133110 21.370901 -47.238010 0.000000 228.603826 0.000000 1947.134106 +EDGE_SE2 126 762 1.256487 0.430359 1.248090 39.878585 21.991658 0.000000 27.922912 0.000000 494.666638 +EDGE_SE2 126 923 -2.534151 -0.137367 2.997880 11.281716 -0.850942 0.000000 15.355440 0.000000 156.415757 +EDGE_SE2 126 1164 -0.226200 0.022965 0.109190 94.980319 392.781106 0.000000 1850.606209 0.000000 2032.020653 +EDGE_SE2 132 762 -2.439040 0.574751 1.153470 15.760986 0.874518 0.000000 11.275585 0.000000 539.091342 +EDGE_SE2 132 778 -1.013501 1.621706 1.561210 15.810999 -7.362314 0.000000 22.644082 0.000000 381.109374 +EDGE_SE2 132 792 -0.882133 1.768911 -1.797920 16.975203 -7.109142 0.000000 19.729650 0.000000 319.351840 +EDGE_SE2 132 800 1.214689 0.372313 0.005900 15.310892 -13.996183 0.000000 57.754774 0.000000 2470.759036 +EDGE_SE2 132 907 2.246094 -0.166035 -3.063890 11.307039 1.283425 0.000000 19.518199 0.000000 151.375685 +EDGE_SE2 132 911 0.287430 -0.091199 2.898905 15.641604 70.080974 0.000000 1095.174761 0.000000 164.457860 +EDGE_SE2 132 1084 -0.744736 -2.350749 -1.849821 11.115227 0.148119 0.000000 16.441489 0.000000 307.825761 +EDGE_SE2 138 800 -2.384799 0.661256 0.023390 11.548813 1.446295 0.000000 15.890090 0.000000 2387.028865 +EDGE_SE2 138 806 1.314158 0.976356 0.186155 16.125723 -10.306715 0.000000 32.294877 0.000000 1776.876918 +EDGE_SE2 138 821 1.339602 0.836157 -1.728640 27.615689 14.355051 0.000000 23.596586 0.000000 335.774357 +EDGE_SE2 138 823 1.391787 0.830084 -0.201680 23.357993 -13.427129 0.000000 25.832230 0.000000 1731.260189 +EDGE_SE2 138 903 0.257877 0.385262 2.468460 462.130945 37.644489 0.000000 14.253118 0.000000 207.810089 +EDGE_SE2 138 904 0.211460 0.361905 2.918540 518.619452 -160.188745 0.000000 61.672712 0.000000 162.813885 +EDGE_SE2 138 907 -1.344137 0.141028 -3.046400 12.828819 8.485440 0.000000 53.029004 0.000000 152.687113 +EDGE_SE2 151 828 -2.783661 1.064375 1.529770 11.244135 -0.044701 0.000000 11.126133 0.000000 390.641099 +EDGE_SE2 151 847 -2.892269 0.357584 -1.720550 11.773808 0.017727 0.000000 11.111585 0.000000 337.774286 +EDGE_SE2 151 855 0.421564 -0.036975 -0.072980 11.226261 7.937694 0.000000 558.283669 0.000000 2171.484605 +EDGE_SE2 151 895 -0.308314 0.072387 -2.940720 183.554391 374.539119 0.000000 824.593387 0.000000 160.986275 +EDGE_SE2 151 897 -0.653297 -0.340780 -2.145820 53.093226 74.186112 0.000000 142.204535 0.000000 252.622641 +EDGE_SE2 151 1029 2.658346 -1.322835 -1.612160 11.303644 -0.086066 0.000000 11.149585 0.000000 366.387340 +EDGE_SE2 157 297 -1.431635 -0.047784 -0.192100 12.991577 -8.198575 0.000000 46.855781 0.000000 1759.197636 +EDGE_SE2 157 305 2.323872 -0.569035 0.026110 11.551318 1.614103 0.000000 17.029536 0.000000 2374.390623 +EDGE_SE2 157 1029 -0.951615 -1.287326 -1.580800 20.706819 13.256279 0.000000 29.424395 0.000000 375.345582 +EDGE_SE2 157 1217 -0.999593 -2.295582 1.588120 11.945029 1.827929 0.000000 15.117890 0.000000 373.225399 +EDGE_SE2 163 297 -0.152489 -1.643361 1.294160 11.969142 -4.607638 0.000000 35.854192 0.000000 474.998898 +EDGE_SE2 163 305 0.683999 2.054722 1.512370 11.800954 2.562970 0.000000 20.633308 0.000000 396.070787 +EDGE_SE2 163 1029 1.123157 -1.269718 -0.094540 22.165118 11.817460 0.000000 23.744753 0.000000 2086.780326 +EDGE_SE2 163 1217 2.123761 -1.402656 3.074380 12.166102 1.857716 0.000000 14.382333 0.000000 150.597217 +EDGE_SE2 166 297 -2.448623 -0.097923 -0.181930 11.379485 -1.189522 0.000000 16.383459 0.000000 1789.602165 +EDGE_SE2 166 305 1.311990 -0.580954 0.036280 18.290583 14.744491 0.000000 41.391889 0.000000 2328.015008 +EDGE_SE2 166 1016 2.453320 -0.496114 -3.104945 11.376696 1.103524 0.000000 15.696336 0.000000 148.362881 +EDGE_SE2 166 1029 -1.956023 -1.332520 -1.570630 15.716267 3.136091 0.000000 13.246776 0.000000 378.321363 +EDGE_SE2 172 305 -2.223813 -0.584373 0.139610 11.218103 -0.907468 0.000000 18.807912 0.000000 1924.985691 +EDGE_SE2 172 315 0.916741 1.192284 1.768200 29.887371 16.398688 0.000000 25.433291 0.000000 326.245913 +EDGE_SE2 172 328 0.389353 2.701274 -1.418880 11.306838 0.643966 0.000000 13.229838 0.000000 427.278816 +EDGE_SE2 172 337 0.634889 0.129966 2.220490 195.557030 -88.592401 0.000000 53.663494 0.000000 241.043874 +EDGE_SE2 172 342 1.382392 -0.108475 -0.255660 12.384043 -7.102031 0.000000 50.735268 0.000000 1585.608223 +EDGE_SE2 172 1010 2.747473 0.046909 -3.048210 11.123505 0.162102 0.000000 13.231218 0.000000 152.550608 +EDGE_SE2 172 1016 -1.097321 -0.382262 -3.001615 13.480215 -11.980076 0.000000 71.691915 0.000000 156.123881 +EDGE_SE2 178 342 -2.376956 -0.213431 -0.183040 11.578392 -1.671546 0.000000 17.090523 0.000000 1786.245513 +EDGE_SE2 178 367 -0.259854 -0.863160 1.012500 18.840526 -28.383170 0.000000 115.336891 0.000000 617.260137 +EDGE_SE2 178 374 1.732968 -1.057467 -0.499130 11.142356 0.640290 0.000000 24.232266 0.000000 1112.401122 +EDGE_SE2 178 1003 1.826983 -1.529516 2.351785 11.166956 -0.600028 0.000000 17.558198 0.000000 222.529516 +EDGE_SE2 178 1008 -0.403552 0.156306 2.716725 12.710306 -28.871300 0.000000 532.343545 0.000000 180.975206 +EDGE_SE2 178 1010 -1.026746 0.040588 -2.975590 14.592518 16.700937 0.000000 91.228510 0.000000 158.174631 +EDGE_SE2 183 367 -1.618063 -1.419954 1.686080 18.191945 4.896376 0.000000 14.496941 0.000000 346.499109 +EDGE_SE2 183 374 0.060720 -0.328723 0.174450 894.828841 7.251305 0.000000 11.170611 0.000000 1812.470490 +EDGE_SE2 183 382 0.411911 2.011657 2.779910 23.397894 1.979206 0.000000 11.429930 0.000000 174.975438 +EDGE_SE2 183 387 1.173883 2.095476 0.233105 14.481439 -3.100632 0.000000 13.963629 0.000000 1644.144968 +EDGE_SE2 183 1003 0.428660 -0.639029 3.025365 102.305125 77.922908 0.000000 77.694205 0.000000 154.287027 +EDGE_SE2 183 1008 -2.366308 -0.712782 -2.892880 11.121230 -0.230529 0.000000 16.363269 0.000000 164.967341 +EDGE_SE2 189 400 -1.948699 2.200613 -1.116370 11.144116 -0.119102 0.000000 11.540899 0.000000 558.157565 +EDGE_SE2 189 414 -0.254807 -1.783532 -1.508360 11.922188 3.913799 0.000000 29.996898 0.000000 397.338159 +EDGE_SE2 189 454 0.831360 -1.515476 1.318995 21.578630 -11.156350 0.000000 23.001623 0.000000 464.879365 +EDGE_SE2 189 994 1.332308 -0.340434 2.895765 11.111898 0.181350 0.000000 52.882967 0.000000 164.723074 +EDGE_SE2 195 437 -0.591701 -2.641206 -0.200180 13.648824 -0.051289 0.000000 11.112148 0.000000 1735.590395 +EDGE_SE2 195 467 -0.091210 1.365140 1.118420 21.523802 -18.224556 0.000000 43.008191 0.000000 557.077827 +EDGE_SE2 195 484 0.655807 2.573505 -2.009240 11.219291 -0.565783 0.000000 14.070164 0.000000 276.074540 +EDGE_SE2 195 494 0.855236 -0.512254 -0.301250 16.102937 20.540136 0.000000 95.628725 0.000000 1476.449250 +EDGE_SE2 195 988 1.415155 -0.856188 3.052380 16.022409 10.041613 0.000000 31.642140 0.000000 152.236812 +EDGE_SE2 195 994 -2.192048 -0.521524 3.098765 11.750475 -2.253964 0.000000 19.057069 0.000000 148.810613 +EDGE_SE2 201 494 -2.683977 -0.793909 -0.034430 11.276756 -0.496479 0.000000 12.599187 0.000000 2336.349413 +EDGE_SE2 201 500 1.004735 -0.526385 0.314340 45.186413 33.298498 0.000000 43.650514 0.000000 1447.186686 +EDGE_SE2 201 982 1.557172 -0.467671 -3.046225 14.919173 9.340266 0.000000 34.020554 0.000000 152.700298 +EDGE_SE2 201 988 -2.053188 -0.978041 -2.963985 11.683303 -2.092334 0.000000 18.762142 0.000000 159.102109 +EDGE_SE2 203 500 -0.236863 -0.548090 0.348290 153.663942 -134.464803 0.000000 137.946777 0.000000 1375.223806 +EDGE_SE2 203 508 1.553867 1.875066 1.399800 12.536000 2.482853 0.000000 15.437455 0.000000 434.100125 +EDGE_SE2 203 522 1.780329 -0.307182 0.021130 11.822071 3.657498 0.000000 29.926926 0.000000 2397.606666 +EDGE_SE2 203 982 0.313263 -0.470658 -3.012275 253.866414 119.649456 0.000000 70.084044 0.000000 155.295388 +EDGE_SE2 209 508 -2.161765 2.058644 1.468780 11.180293 -0.053576 0.000000 11.152602 0.000000 410.180706 +EDGE_SE2 209 522 -1.785428 -0.102806 0.090110 11.132515 0.656456 0.000000 31.244975 0.000000 2103.775347 +EDGE_SE2 209 528 1.736233 0.012599 -0.097130 11.350617 -2.286079 0.000000 32.931671 0.000000 2076.939411 +EDGE_SE2 209 976 0.433683 -0.153481 -3.063330 87.280240 171.295909 0.000000 396.336584 0.000000 151.417412 +EDGE_SE2 220 528 -1.597199 -1.638814 1.311310 13.034804 3.414597 0.000000 17.172093 0.000000 467.976033 +EDGE_SE2 220 532 -0.939792 0.407621 1.225630 94.950637 -5.379789 0.000000 11.456320 0.000000 504.700895 +EDGE_SE2 220 564 -0.623480 0.251998 -0.012190 38.845567 71.101745 0.000000 193.391889 0.000000 2440.146629 +EDGE_SE2 220 567 -0.002013 0.298972 1.481540 21.284937 -105.664807 0.000000 1108.540123 0.000000 405.973278 +EDGE_SE2 220 570 -0.062402 1.946160 1.542860 11.165977 -0.913492 0.000000 26.320380 0.000000 386.629607 +EDGE_SE2 220 575 -0.123656 2.505837 -2.951275 15.792523 -0.664538 0.000000 11.205444 0.000000 160.127317 +EDGE_SE2 220 959 2.587973 -0.016000 2.926965 11.274656 -0.773198 0.000000 14.766597 0.000000 162.116000 +EDGE_SE2 220 965 -1.062787 0.305497 3.105010 15.212918 16.523642 0.000000 77.674651 0.000000 148.358205 +EDGE_SE2 226 231 1.660221 0.126920 -0.049820 11.505996 -3.114430 0.000000 35.674411 0.000000 2268.351350 +EDGE_SE2 226 588 -0.273207 -0.444423 -0.016160 274.806053 -156.291042 0.000000 103.744249 0.000000 2421.117227 +EDGE_SE2 226 597 2.185242 1.674700 1.403760 12.078039 1.038206 0.000000 12.225850 0.000000 432.671013 +EDGE_SE2 226 953 2.006857 -0.437847 3.116305 11.557944 2.329386 0.000000 23.254435 0.000000 147.545120 +EDGE_SE2 226 959 -1.129223 -0.150509 2.830935 23.235807 -25.544568 0.000000 64.928953 0.000000 170.345385 +EDGE_SE2 923 1175 0.749610 0.273000 0.106670 19.536607 -34.047517 0.000000 148.697481 0.000000 2041.285424 +EDGE_SE2 929 1175 -2.005899 0.102421 -0.392910 12.648561 -4.320259 0.000000 23.251108 0.000000 1288.528106 +EDGE_SE2 939 1188 0.696432 1.755817 -0.065270 26.430265 -4.946684 0.000000 12.708437 0.000000 2203.031036 +EDGE_SE2 1029 1217 1.008685 -0.037889 -3.114265 11.476877 5.630362 0.000000 97.781127 0.000000 147.691473 +EDGE_SE2 1044 1217 2.098504 -0.838430 0.479890 15.976239 4.188481 0.000000 14.717054 0.000000 1141.513725 +EDGE_SE2 1050 1210 -0.300235 -2.565672 1.536560 11.137270 0.317303 0.000000 14.960021 0.000000 388.552520 +EDGE_SE2 1050 1217 0.231465 1.668290 1.559140 11.493589 3.014437 0.000000 34.868922 0.000000 381.726156 +EDGE_SE2 1056 1217 2.128743 -0.472375 -0.931160 15.353750 -4.908186 0.000000 16.789250 0.000000 670.352902 +EDGE_SE2 1061 1210 1.269232 -1.441319 -2.909610 23.568115 6.644624 0.000000 14.655385 0.000000 163.558506 +EDGE_SE2 1075 1210 -1.662329 0.436026 -1.599840 32.701727 -4.997844 0.000000 12.268023 0.000000 369.868006 +EDGE_SE2 1084 1210 2.070374 1.896269 1.836205 12.355692 0.641825 0.000000 11.442098 0.000000 310.788312 +EDGE_SE2 1088 1210 0.609503 -1.485166 0.536770 38.204841 -4.021013 0.000000 11.707874 0.000000 1058.576530 +EDGE_SE2 1093 1210 -0.233452 -0.529583 1.494360 42.853783 90.090527 0.000000 266.801722 0.000000 401.810926 +EDGE_SE2 1098 1210 -0.378280 -0.172442 -2.937025 38.903093 -122.470929 0.000000 550.803768 0.000000 161.288572 +EDGE_SE2 1138 1188 0.583736 -1.006358 1.671805 21.764394 -23.563240 0.000000 63.228969 0.000000 350.211491 +EDGE_SE2 1147 1188 -2.232188 0.113982 2.992915 11.195782 -0.864255 0.000000 19.932721 0.000000 156.804966 +EDGE_SE2 1150 1188 -0.789302 2.834301 1.697150 11.120354 -0.063189 0.000000 11.543094 0.000000 343.660651 +EDGE_SE2 1158 1175 0.586855 -0.249767 2.829060 13.000858 20.975969 0.000000 243.941877 0.000000 170.512281 diff --git a/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb new file mode 100644 index 0000000000..cd3d9fd5db --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb @@ -0,0 +1,332 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from graphslam.graph import Graph\n", + "from graphslam.load import load_g2o_se2" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Introduction\n", + "\n", + "For a complete derivation of the Graph SLAM algorithm, please see [graphSLAM_formulation.pdf](./graphSLAM_formulation.pdf). \n", + "\n", + "This notebook illustrates the iterative optimization of a real-world $SE(2)$ dataset. The code can be found in the `graphslam` folder. For simplicity, numerical differentiation is used in lieu of analytic Jacobians. This code originated from the [python-graphslam](https://github.com/JeffLIrion/python-graphslam) repo, which is a full-featured Graph SLAM solver. The dataset in this example is used with permission from Luca Carlone and was downloaded from his [website](https://lucacarlone.mit.edu/datasets/). " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# The Dataset" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Number of edges: 1483\n", + "Number of vertices: 1228\n" + ] + } + ], + "source": [ + "g = load_g2o_se2(\"data/input_INTEL.g2o\")\n", + "\n", + "print(\"Number of edges: {}\".format(len(g._edges)))\n", + "print(\"Number of vertices: {}\".format(len(g._vertices)))" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEMCAYAAADHxQ0LAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\naDSaNoI2+BqNRtNG0AZfo9Fo2gj/D1KYU/J75gHUAAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g.plot(title=r\"Original ($\\chi^2 = {:.0f}$)\".format(g.calc_chi2()))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Each edge in this dataset is a constraint that compares the measured $SE(2)$ transformation between two poses to the expected $SE(2)$ transformation between them, as computed using the current pose estimates. These edges can be classified into two categories:\n", + "\n", + "1. Odometry edges constrain two consecutive vertices, and the measurement for the $SE(2)$ transformation comes directly from odometry data.\n", + "2. Scan-matching edges constrain two non-consecutive vertices. These scan matches can be computed using, for example, 2-D LiDAR data or landmarks; the details of how these contstraints are determined is beyond the scope of this example. This is often referred to as *loop closure* in the Graph SLAM literature.\n", + "\n", + "We can easily parse out the two different types of edges present in this dataset and plot them." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "def parse_edges(g):\n", + " \"\"\"Split the graph `g` into two graphs, one with only odometry edges and the other with only scan-matching edges.\n", + "\n", + " Parameters\n", + " ----------\n", + " g : graphslam.graph.Graph\n", + " The input graph\n", + "\n", + " Returns\n", + " -------\n", + " g_odom : graphslam.graph.Graph\n", + " A graph consisting of the vertices and odometry edges from `g`\n", + " g_scan : graphslam.graph.Graph\n", + " A graph consisting of the vertices and scan-matching edges from `g`\n", + "\n", + " \"\"\"\n", + " edges_odom = []\n", + " edges_scan = []\n", + " \n", + " for e in g._edges:\n", + " if abs(e.vertex_ids[1] - e.vertex_ids[0]) == 1:\n", + " edges_odom.append(e)\n", + " else:\n", + " edges_scan.append(e)\n", + "\n", + " g_odom = Graph(edges_odom, g._vertices)\n", + " g_scan = Graph(edges_scan, g._vertices)\n", + "\n", + " return g_odom, g_scan" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Number of odometry edges: 1227\n", + "Number of scan-matching edges: 256\n", + "\n", + "χ^2 error from odometry edges: 0.232\n", + "χ^2 error from scan-matching edges: 7191686.151\n" + ] + } + ], + "source": [ + "g_odom, g_scan = parse_edges(g)\n", + "\n", + "print(\"Number of odometry edges: {:4d}\".format(len(g_odom._edges)))\n", + "print(\"Number of scan-matching edges: {:4d}\".format(len(g_scan._edges)))\n", + "\n", + "print(\"\\nχ^2 error from odometry edges: {:11.3f}\".format(g_odom.calc_chi2()))\n", + "print(\"χ^2 error from scan-matching edges: {:11.3f}\".format(g_scan.calc_chi2()))" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nAAAASUVORK5CYII=\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_odom.plot(title=\"Odometry edges\")" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_scan.plot(title=\"Scan-matching edges\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Optimization\n", + "\n", + "Initially, the pose estimates are consistent with the collected odometry measurements, and the odometry edges contribute almost zero towards the $\\chi^2$ error. However, there are large discrepancies between the scan-matching constraints and the initial pose estimates. This is not surprising, since small errors in odometry readings that are propagated over time can lead to large errors in the robot's trajectory. What makes Graph SLAM effective is that it allows incorporation of multiple different data sources into a single optimization problem." + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Iteration chi^2 rel. change\n", + "--------- ----- -----------\n", + " 0 7191686.3825\n", + " 1 320031728.8624 43.500234\n", + " 2 125083004.3299 -0.609154\n", + " 3 338155.9074 -0.997297\n", + " 4 735.1344 -0.997826\n", + " 5 215.8405 -0.706393\n", + " 6 215.8405 -0.000000\n" + ] + } + ], + "source": [ + "g.optimize()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "![Graph_SLAM_optimization.gif](images/Graph_SLAM_optimization.gif)" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nBL6Dg4NDK+H/A7aRY5b1tCw8AAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g.plot(title=\"Optimized\")" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "χ^2 error from odometry edges: 142.189\n", + "χ^2 error from scan-matching edges: 73.652\n" + ] + } + ], + "source": [ + "print(\"\\nχ^2 error from odometry edges: {:7.3f}\".format(g_odom.calc_chi2()))\n", + "print(\"χ^2 error from scan-matching edges: {:7.3f}\".format(g_scan.calc_chi2()))" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nRqPRVAj/D0Fj/txvoohWAAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_odom.plot(title=\"Odometry edges\")" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_scan.plot(title=\"Scan-matching edges\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.5.2" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf b/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf new file mode 100644 index 0000000000000000000000000000000000000000..65c868246c0ca8b4c93122afa111070654a39624 GIT binary patch literal 276368 zcma&NQ?M{R(5<;`+qP}nwr$(CZQHhO+t#~nW4<#p=jxxTIk`x6Dp#qbs-LwwO{yRw zM$1UY3PrlGGP(i9#6ZA6U~gmv#lr(dFJo$F?qWf}%)rh_@P7{|dNE5I7gHw!dNCVA z7gG^aV|x=*C_X+YXBQ_^Lt7}1ts8C4Nf{<7WveXCQ^Puw?!QCBAGgXW!`STp; z+@FP3`fMvuXAM|w%9Q=6lLxh(8iPJ zivr2)>vk)~mfdXy&&}3s_4H>&_(JPezR*JdHQjDKMNSzxXEnpf%c|zRfjsq@T<5T0r_ z5-;VWagQwMD%^O)Dt2BffV4}89Rrhws2CVlx~y3ynVEC_T*cObBytw^ph}(55W4jW zozRJsZ)&P%_0yuDL8^AmSt>WQ2+mYWb%xRzj|TtJj9F;jwsJED1HIQVdC}}KX|s+v zlI_tTTk|K${02*&rNf{h2J0K!w3JCw!Spg~Am!MD%@5PirO0P#jE+35sX8d^X5~SU z_@Z~U`EKReL8zhpQ3dvwE%a%+M)b)MxxC>`b<~NuPt;m=owQ+%s;-7!E*rDmrMn`~ zCr{Rd2nh$Op$rWX1sc+gu(s-9&z|joWb4ur2-m97o8ScJ00X z08O1&7Q+-&1kdf8be(gcUk9ygtE;7fpqEvKflO~Js(WD{XR;X|tMyE4-zc3?T@K7Kv72xQUf12YaD#*NlO@jM_*f>zvC@ zLQ;t;WkTXbn(=yb z`BggLv?*}kVu;p-4sM4;~5A^0LhViqVD!N=_s~YjBx9J8I z0I7%5jN*QYClz~z<&@)&$hHkn0BV}4!t3-@eD6OaG@v`rWBNp#CUIs_QQejV_E)p3 z%WkR`Vke?k!^z%ku7&!e+bjXH!+uGBo>eVmkHi42ls9U1{qlHx>Du)WWbFI@Rprjg z3xE@(Z(D83M`8l%Zqf4gOUMB7vh3G+CW^$4&b9VQ58%u`3W+eBw~q)RY@ygeIqQ+e zj?Dpk76T5ohq44ViCoGixF9)zdpmdo`3dktAJ(vrTAP)l-G0KD1* zP0hOC2Nu=K2R8zC73e;OXtq>W&mveUibrOu2}_U|nW_CK1dkP4J~oVC-$nHMG0YEo zVIdH5#1tp~N#eNWHRG7&$#?aNH@K2)&{3{?nYSv%fTa}0LH9i~I_CXC_^gS8=yxkS zkJL3>_bVn-nWPZw5swG-7J}%A-|7ag-_MNO1%7-O+jXd8v?Y zQZ6+50l4i+dAz=Nw(lI9Bm{{49!EU`I!Ah!Kv#XI%Svbs3{m?bh{LXyw{tGBJ^s}dsh*j@M1C?gxJ@&Sxj^U?7+`m0HcT( z0BKD#C`WYq#uzo1VI>V!V(x=>+`+B>B{1?t{wvL7Iy-gQJ`U5mvtOt#%!9?~?13$7 z6(FcE>gk`K?4&S(cxgDHb&sqJ7K&{cKZkFarDlEMf3d)t?sn0$xRQb|XV_L_J>G!E zSO}z)$e@Vu7dgC5LXMVAaX~!5*iyj?2NqItmyGJf?x_cd$N@ozhvrD;Xf4)Fy2i6Z z;1##ez;44AkT=00?2I2N#oGPHq@o-%4(KX%^;91LV&8@zb}jB0lcFd8?rXHOPxxyZ zDet~4WrE76`X(yXK(My#KHWC9DF{5qua){V;-rz}UT8)G3O6K&PbpRAaw28BmCRRz zu_Ja8hZNj`PaF4C{I(w44Lws!;aD-P-<0p$H+_+j~qDh%u3UswkBVL}QkM$81Qs|JXrD*OHl0r|sFh@Lm< z;dWOh$DoPgKJ@J!WkBSj8z!uWBva(Vy=VZgU#>_8AUo&ue5s7{RYo``|{%)jn*Ru^5QRD zW9k!i@6S5#7C?I>-2|ciofMsN8`wAwy^!51z+6tOWNabqEW6G;!wE-~yzT3ZAe}EJ znB|5&8lq24)?KMW1FVKBUgp1oSPB192$H^^g3^y}BO7KvelxY(LYY#F8wNlnPv4So z$q*FYcTSl&$esI9vdrq1VK;tuw|E?Uvm3p68%H>$KWFm;nCV-wAQB{zue`?Sai`lq zPI*2%IQp;Bd_xMIi_0KaR&Z`4Hp`ffKCZ#)>?cF!iK6yapH+f$4~HlZ=xul9u8lom zX&(#zGy}UtTY_PaDaAHxN9?-QT+HU-re13?xb3UtWH_2}F6fMJUd+J76RPr4~ zJE8k|!(yxyOaUvnrYU$LfIDsnZe$_3*+`}Ukqf;z7dCGbA=iWeq5>u(uBc&s*g?TP zd@|6sd^{eH*DFUWnVI|ze-JhNYH-g9u`m-OAEK-S>`N)e9uE&lfzL$gp}4Te7uI2I zY+_A%N`7)3*heVWKt43MLsa_@BBPpNGM*PSlVLGA32(5d=`BAr91Xi`ZX;Q{t9^8; z4lhU(hfZ8NQodp;-Bo!xbczMCciu*CAPvU`636fMcm59i=B|e_ z7a1g4hYS&mPXGnpan<&ZjD7d)fQcnnc3U3h7Wo}8IX0i+P%bYo|JyOBDSMtHfMXCR z0<#?nD8#5uBlr8;nonEkxcwlIgyU?z?`n$wr3EQ+V@5CM`{^X|4?QXZ5~`VwAv5v! zt#7H$&O`h3^-O}a=zNYL##can*TRQi-qIq(B`!TLo6V=$>rsBoV(;A_V4T8&ijFbP zvKn3=0)LEj&^!=bm*f~J_dP$(+vy47A)7k;D*(`6`ZIHkLM3=QRn~(;;kaAurg>nc zOA|QZ$9K1A+rO7D$G9EgG`5g|@8&Vpw_h`~$zLeJKo|}N`SDnDN}er~-SiynFSuBn z^^g#}y}}p4I8fzGNk%SW?4=*TXPg_#)XwDpRRaG-|4T)%u>Vgv!NkeI@P95RwC%Si zQ2plX5k8e5BRX=v76kE{ERW`!Wsx0<@)M zOZIE}B9yO#AV-Nv`|-R{>bp0j4B1taVo1ZgoCO>L#ZDmR@$wYnP(E3R2_1i%EQCDW z9LatL%9tB{meK9#gmCvnBm_22FkmYnKDZ|&jHCbMD!5XD$WQXe%>DRC;Du-zJBG8M zL38?C((!tUtd5gW2$L`8-n7`|jJ>=MuY|*@f^&8D149r5>F}k{CP9i?{A-N^O~_(E zv&dM(1r>G%(Key15eOL9$r>j{g&J%U%fGx!rm?1 zgaEEb=zt}sfxpCZhHNp!kw0VnB(#daf^F!L>rGh{7LFN(nFj+Ql!-%e7&(gr+lE|t zBPvmZ1XpG&Gyh>8f`{M$wZ{Bbwi{j5?Gcc}IMkQfUXTdWb69gl1eP5W*yWwf2M{M# zf!x3tttkG__QV(6aCsR*I}U*jlho!FHq_T*Aq+GySM0zrjtPz>5KjrJ!WE`snhGon zKoKb)uJY8PM65i(3Z%gUTqT)glqBG?Uwln!aQF~Wg4S--QUjFj!SNH4E#Ke?lC2-y zrpTCwBbtEBkbuvCQxE{!t+s!bBy&q^y$PUlxhjH`mL}Mk+GPrWI-xi?LW3*-a`97a zh6M+@iJ@S9C)?$fDa@4$)C`0y7!7i$bvR$>0ZW~ijdDRqQ zCJC6`KNpc__Yw^3+e`cUvWSw3wV72mEcmGuYm%f*;k(!_9z)8VH33Ro17)DP52h0|uNrtW#Osn}R#dpc%=iqL1w3wZfPbQar7AI)nHCpxD_yX*8Z4iXW$ORJL!k7T2vn z!A0e!*hnqyxsdtD@%{qBPj&Q2KS8*j^3Keeth~P1mm4qbrZ?`x3iYr5dP=lU z&mWVJt^O2M?1Bl<)YW@mBUp`^$$S@I2?uhF5mbEg+pU;Y=!#aAU1zbwo@kp1qFmGc z$aH3idF^2>&0GR06`dlE%60}3&~s88I%YZ?B1R+dfd(N%B6h&QgMz_h1zJWcaFBk`jP}(h)3hz83u)NHq5el$woooTrW;K90>ugSD1rQIjPs^HA_WHbpm*lDz;DK zriw^|iyY-zIv>@^E#0w?_xTe%LJBStxGoVvu{BVcD4r28F1VSlCQ=gU2;#HEuXuId zLE93T6aYc(Xvn-%#seNI|J74_MU@4(paJ-f1qCJBDOE9GS}*G~+x9wx;@@$KDU7D) z7*9u8j0~uU-eA+-Q4S>83a8EF^h9 zJj~PDKo0iuq{XPW+p_LzIG#3&y0h&#s^+RYxZuLw*tYAFM z+pJiizm~P?Vfk;S{&5M8)qC_x)RI`mI61@gOj+DEIWIgC0iJDTdz=W3rHlw0l?6#a zP{d}20uPf}2t@XM*jOwqliv5mS)1}p*n!g z8XK9b;fuqIjm*VkB1+#lVU$1uD}@F>M<})h49`_=s#ED&NzaAb3o-Nj0!opre+ZbLn*P6aqeJ`ta$_kQF#ro|@5!sIlwUxLul*j{g=yi%` zU(KyZ`(=s4-Jls$?`8aAt$j{EJ$l8-(-t3YncWsHA+OX2!SgK*n5Ow90{X3zV}!fg zm;0TH*X0sXT(*0HzeYANSUJ#NBO3~17Kw%%$DQxnL-BmU)H$c5mz*Pa-0v2h1_jA? zE4`K4Sm*M3GnArj#BrG{@sfT-3(05ojp8p)+>j4-H$*m({i|z3gVd6U=y;0WFj+!Q1f1tby=R%ZHVx%T4aW0lxXDtP7wXL=Lgs&ZZ%NKxK?4 z=G8BAQ1G!!Wm0;F-?DF)+>;A_6Z4A+lbq%>{tpHV$^PX0ibHK1?8N}Q)Rsv=<`&)P zCeYw)Fpy{N_(pvc`p{uD1NPU}A!M?^S zJGB~rV&-uf;xH1gNGpSihxJ(ols<+MT~Uz9eS%Y6QrdzX{BOCOi-^O?GWTnAMd zlYx^jTa%$N2Ss*s^6v8JL=|tA1I_!h?B(a|$dark-~aRZWPemXPd~4Ib$WJmdGYd~ z&;K(e>vI^(;DXPV38}|1cx)R-k0#E1`0f%o)7V!! zZ`7qZYMp&4Xa1Bd>uRaz=jBeag{&g6JYPTE-`;Mb!_KQY#~!`x@j#}dxl4D1 ztE%0blV}|&)sh`!QI;Tfha`)}gc=KDzw^9(y87tU*Z2J}F=?q#6tgEBlsYGXpPjmZ z&v*c%^C^U(D*0uq52tUTO6?T_@00uhsOm6V4H&)b+{7m~xQK!y^SH7|m7Y*4y>Wo_ zjPIA3xj!}Z&+Auo4LwH2_i*2rlD5y)S3jYYegY#dg6a```#l(Cxq9^b^~TGwwSx?N z@1zIFi%m*RsBa#k68dbEj<9f2MdA@EWKmxV(SA(;FJyh0Lc=9S$@SDK?Q~&w^pP#D zswXT>!y0d)Q)7JIzW)3Qzj!c2B@~^Db%VNWvq=L*9@5Q30KdE}ozYH>{XJ`0oKv^< zSlvGDFz#LC$QWVwaMY^VBh8tf5^8)$;_H(3)l^7M%h(De90zbv7gN%O@Lj6|r3nDG zlY(9)BHEhQrQmK~(DmVJ*N-rur4H~I*RQbsGt`!zZlfqf{oU5zj1+2qmaXY_nv>Yw^a@t`%~_^OpIouQ|1o0k5pwo^Z3MuS)PKbp2OxVkbp3|+-!Bv8<& z&?7q7s%_B-5l&x9J#<4HgB4+5N0rKd{)%W6;9xMe57!)!DF3V_!HPPT;gu zP!=RPP%3(XMx%{vlG+h|O6c_Akva*Gkb4VQ&pkOTryx7tItpbv*Y23dgEnK60;^O* z>U0Cb5O*ChmPjlHV^DXtMutAyJ5a$C#O%Q%>6|fPdW5V$hFqBlFlE?iwWxUJA>gAd z1{7`!S1yIE`2jeXn*Va5XJTnoOr10dVbAQeHW26k)gpykB$VJh(;z<&C9Nko>KHc0 zG2CB?vOQ^(idQhFV*X{8-yUlxTC>6~TV=mcj~SyMFws5`tPm7xleEp5kXZ;`m)*U(KFrhLC= zWWySt!!$%7xt}Gjd5qppp-KYe&FL`LTI(*l@K?f&>Qik;_f;Cemf*lj)Wr}vr!`?p zZ^o3`j45#)Pcjz3QY7`6uVe>oly=JNowV2=%mqQfHi^>p($Ui&mv66{*2qzdM2K|F zHM?Fb&pcVGE-wE~&l<(n8x!JKcO(tM7nHkA1d(A|V^X)Rz32C#Q&CjGO~`wcDFA~n z5S7_yj@g!H2_97G7UUs|mq|=_%9(kOV$7!&?5$v|!u%U)F)_lAR0@oFh!o&lF$xtk z^T1ePDpru*!EH6!dL=Mh#d6W;y#p*pTFpfII=&cqToKpVLo*21#_(o0Sl15F4VZMw zMFVmda?7k5+;W^kB2FQ7rAX zC@Zp3XN^7P3k-8jd5NtGlcL-_E8JA75*9|kda=@FYLQKnOR#0KWrV8C@-$zZWBa~F zRuCaX$a&~%?+i^WM>tnc(2J=?F||6Ei8N^|qwZwZopeKN?cGobr)HbYFj_7dC7WN# z>QJ%-5F~vp#Z|SfGkDFb&C)9l*5P3;h7laV%d#ej?Xr7a@2Rh%kZbn4kTjceT2j7v zSy6p+{L>S;WnrbLAl3aCo@cq8Odps3{R+uiu^A#C8qzPxmssgs>ztfiO}+;ensTg2 zsG4{&a(X?vlkY3=tzwa32(R$RDtrIu>kl_6u#mfJ4M!QEK31CSbD>SRa^3)3idUNS zz5SqR?+Lv-N2S!F+OqCe;70G0`oQZ&q@8^WkIUg?evp9}$Q;~RA_f;IF3EdwW$-;1UQ+6dqxwZC zEO6r_oFb#g#*h2zik)rsHFGF3*dlj6(FtML-db8ey(0N(HMY`JiRD?x47D_d1|=bI}gqmb(Z*r)n9-XMrHVdNNvbE0XyiKabexNUzmxRz?+2IM}Aq6 z%+t+`2X!uPpNZ%Nq4SZ9BVGm-wA>lw^lpynBv=5zMvMvnBOh=$y>8iB| z9;Rn#G021Y?eu618#n25+8a`?wa|WcZO6{xN-&P7Q7Da)#s*c}CeoF;Kvex{DV@S-NTdK$ z2Ujs1OG_nfSg5)}p)IhxFcz~3b~zSGS1}+_Kcc1}pK<=1u@3%%bJi-x+oAc1WXeE~ zND=NCfdazih^!rqsh%lj_|}BY%0=4Tln|t>F1?xeM3q~kP;FP!@+DK%AVzT3gRY&? zyizz+2hKY`H-f!j;`U*Y!yuQD$k8aj&4o-9J_vca zf#Gzw%K>P09=jWayfm8o%gFJdScK##hU>LyBaM^AyZ+YC#rLL;}C9h51Fa`DN(@0sm=!EpCR>kQ}XWQ-@ z*Tj1uZOMS`QBmWSM+ynh#S#oe#F@TEH))Ho3j3-)+NwrtIk2o4Dx)R4T;{gi#fsn> z`_clZ`-0v#9Rb496yuh|bJ4%QB(_d;52tARlG-C&u{LXj-^*HYS!}(i2MF%6IRQ8A zNIz{@M(bbLy~CKO6BzudW6hr_0~T%#YsEm92@8E~8&AIckBITkpUIhWLnO(0y6mC$ zNPVUBmWiY^uLdM;T8F$}x>4qJ${9Hw4EgKm>!?8mCvIgBG z2cL0CfPdb?>r8h?2~f>i{RZ$26}IDE=o{|)YdoOMJvMLw4ioa*3Fh9~Pz;#god`h5 zIy&r$al+n$zx(?^?Sx(KhBG?yREKFA;d%MkI$YQflpHhi`*UD|-kq@jmbhOacg(jv zJOx2f-(ic!+V<2h&C%k7#~dD+-^t{ALYFf{?%>_da$^UWjUd4?)+#DNgkq>l#x?^& z1ibxw7j%lWRiwZMI&!d9k=JP+3Y`5eEexT=j<8V(GA}JG(iJoq3qTWvYOAc&kVwbq z;LF4(~azg`=?lhw;&_xLfQj}{vUy8)FB|;fPD99 z1MC~xRag&NvZLY?`9SSPCNjuUS}B<8$FX5rnU6%x*X+?D{aksoi6vI<`j{5L<_q9h zN*QTf){Nt5z}Gj3!y{m!I8#sui=RGVz50xw3=5pkkO))zTF?;X=oF!()P^dV7 zSc|KredFiDS{vQD+q`B8XxpbtnoXE8mr9x~lXE%>`;4iaGXTKZ$RRfpl%LLSVek#Z zw^g^W7D0P8qe4?Rw@BvAoIq2(?4tzJ3T_hqI2EP^wgvp;S8MnVZ`OZ4astLSUQ>Jz zZ;O7|flRm<1aC;i%Kccr!h@pRkpAVa`Ys;y#;b7`FX74*zP)FN^oY9cHFLBIUrzv0 zCTTX&g{_a?o$?)=jfI6rZGOnP>GSdS`!SUNm7>CR5o688nXDd;od6h?@PM>_(FfP^iX6KJ; z!)v5Sa$l<98O!ND<*es*vasF(varpr%EEti8hSiQ8QlQEQmZ9}j6+Rg>R{~{F< zd0XXj!`tUOF75u2g~HG~8LU=ge3cTDJ#EH@&Q*538!fG|jqbsCj;BdT!f6*zz1VI> zL)ybS^}p-I>{K=Jo1eLarhEdZikn$FT`m1)corizM%^

h@}?sWJZXhc{G<|4(;= zo%R2tqRGt6@_+1ZXldK;tRecX*B>0yA>`$Jl?numg(i>1LanGJ0JY&$L?*TEMo*Pq zkH!6Y_d6d(?eMPDwMXfqdnQWUCNP_u_1T-jeVkmMT;16mMl9=~o2!Q&h8m_Q7)CWu zADy1u$nLHzuba>J{mM<{;T(rh>Za%%`zP_rJJl_WU>f%3kO@@_A&r@!a77FG=B7c| zMKzH>%c2-*L*@2MA9)I1+(|~fuB66TOdFyR??NTLz=?58homEoY!sD@aN?T&CgPEL z#Rnmri^@mv@3Q7H9vQU!i6?8)Gw&UZSST+93Icbd9!7ayl_moxe@>a)3&@|Ls-sm4O&y9Wr2PR6<9OPQC{wRdb-pR1nzf#1H--B zH%*}stT-E|T)e0I=2v(mq}zB#PIM+prIHGNA?t6jN#h*u(&#Np=`WhO77NC<5WNm$ zGv+oNW6m@Q`pA^Q3IVo$;h;iQl)PMjyW=ytHXa%1TRKu}UbGGigZl;+2E+!05=<(= z_As~5Ujo!`7(ftQj{41*GzF!9@|`#gCm6?xz-bN532ckN5oB2gK8XMf2ZGYjl!y8? z>Q?(8UX13Q)&Q|9`NoJ2n|Ak@SRfc>8gPh%Xy|GyunoZ-@c76=OMidB%upZz-UnM0 zEksT9z@R-FjfR!`JUm6QXc>qM4D>=U=tkYogNHk7j)CVG*%?-R0KL+);-UI>ENZe= zB%=ZjM%fNU2?%Nt6+M2NNY{e_0~nag_%`)kI3=`&OfeeJMYddt0}mq=nY1l=maY*Q z6&5P=dJF{q@5&_F{@0UGLxzq-1G%X4Mk$owiL)`r?n5*jG~lEW`7GETh$>bcAH6JP z^`R9}M<^kTo8|=#l*XgdcE7V&6$~U#!K)kz4ERV(!qH8qke89xcQZL(iECiCjAA0F zxXSVVScj3dhMF!RcUdg`XAf;WuXIV^q?(_gvr2eUg-4_wXmUbP1fEc>RJaqDOf4W4 zGhZ5Sygq)~WauC624NZFB-e@oij@>gajMP214on1FhF@IaU9M_&;hOM;(kZ55Yhk; z$s-pDv~aKx_+J(j9HxFy*#zDK;|~Ud>XCKrAD-^Yc#547g$pB9PqDBa9x2rzdf+!F zN2+E^@bgGW%6CsN>JCN`Kcjvy*tdv0qFZO*YHWLWGo#^)(1v8dHvg{h{wVfHQ#mUgp+&$oEh>*&j<-V6T=fB`5GT9Ap>ddN0N*q zf6qyVnT>rzPV}xD-8MYb27{H2y(;W{Jg&?Rf!K?zICe_tS`-^P0%U(LW;fBKq1RGz#^Ckt#)CT$wNKU$64l zo+@=)sq+1#R%I8yT!K6IFepO70AjjLdRQ>~-*?GCAuIdc#2NSxajFMwdYLom`3t!6 zcO!QW{zDvx0frxrYbw?=9#TA0aX~Gy7VZcge`YFfqhMt#@U44<0MobZZ}1ylDQG+u zC+9nkxtx7(9;xu5in9=mON{;fllYE)OT3-^lQ4hxDcXE^x8qZ9REu!jY2R%-WyC92#}o)j754`XhMz@|~hysPXEjwk+CW4ew>$9$WKhD?IsI zyK;k-Nz>Ib{c6{P?famW&Ia1c49}RBC;Pk+if5QbF5ghXFz&A4c*magPsRdF_-uya z<-xHBf}}Ww1b6w>pWvAdJy*NKBnf7Q4<7NZ!)^jDEK4v3iNddtYVNfM%YeF#5(bim zU!K;YXa`qs?mts*Vj+cDvWkeGDrCv_(Te)D7p}biOjX6DYIH$gpYKN|JQmlU(z>k_ zj%iAjmgW?3^yB9l`fhor`+{FT8ij7aon+6}9t}VU3s16ni4WpQ60DfU?B{p1rWLuZZnxDL9tsjy zepKRe@(xC zM&tMM%#Ks?aEDU>9)_38<%{e6HQHEN2ELv!?^j-lR^BrRlI?!}RF}(a9{c;>LCI>i zy&B`r%OP&NH=E+jd7gSvKjHo|)wK+%h#vD`yDZA|LA>LmP>82VCuSRKC!&55dAlur zQf`H2nH&%$!5M`(ICKp^pld(_U;A_p876bghDN^0VwK+J@;TRN76`4;8-v9NM#$a0|{XJ2~?| zJ4Tybw|8_~++};`NWqN@vcIIz(Nmg=G{L@vAjeD1tGRjFHgm*H$WQ9#hWFjv8uxTg zlf7^S^jHxuDLGZhxP7vTcGTP|l-{0**Q)89D?I2suNvlID)is$iGJ+Ve4?(gdj9~P z@Akj{Cv9;u{!iLsWa0dOV2j}Yza52{afO*xi9vw@RLGba)Yv%`MYv9g&KMXJfrSl7 zn&jMx)6?l+I5h^g!#{5T(avXHUsS0mDdo=RT%a6On9gTilp_(u#(cp01p%z|dXHUXQUO~@zg z=+x!w1n2<9oLx=+=OGyxnf}Kq83`C!SUCT83l0+j2O~Sv|6VZ@F#PY3fRmB+{}?@E zTR>G-w$a&OAeLx>l!T?+-Pt9Ap8J5R?;Ij|{^eoShw?oSlst znXCX4=Lr10H)6mFFmPZ%A^yOJ;J|>0@VuV{Mt~Q9p#UkkIs@I`1A2gndWMK}b^`Y7 z>=69{6f!6V@GRik052SXR0t6gaG(|Atc*f~wKa?LTtCet4cN>A9Uvki8vP~1B{+f& z4y*}42mnVkfOGO+Tfn*iT?o|<5`?V#ry8KOixcRGbawFY@NfjqIml7W$R&m19sr7M z0J{h{Ak5&J0KfAx2_Rp?xDD)w10Nioe5iN!H~XUl3ICD+*VY!!(FsJLV;F%qfN}={ z(4(w!BIZH30U#JXVMDkC3FAKo-U>7zFI)oNm%9=OD2ibN_+;GQeH^SYG(ZE*L4tGt z4-zD03ZFtn?i?eZ2aO4kIjZk z;{&<50#{D_#dC@X={o`-`pksp{AsUdI9xtf`9YjzA!t(woYcGF&;83!+xVJAlg7aAqE}O(DoNi=l}8I z4?PPB186CDc(5-I9S|Iz{pD{2f7#^bwp%A#Cec9rJb=7RZ3H z0DX0sgiiw)z&;<0V=Iv7uK{y#6e55KPZEZ@a6yI;Q^>a_Xl_g=HU4o{(<28GX7o9R=aD^0N(gZxFkI2f6Y%13~>V4 zG?tYerWM`mTH&?rqev)xIM~Qa!#LPsnlUqU$P4~;#=o6|WC?g#I|5^yiMM9SKn{F` zC=0OcoMi=bM=%CNy8X`d*#{KuBGvGBO3RySmxI^@yPfWK*%nOvqo$VMVZo%BH(@_K zx6)4%v97)J17c5y?~DpOp0cutWSf}w@0?Yi2N!>7_EmM^U$FSviC4DEuDP=x*SUko z3Bu76nXtcz|7)8)q9DSeM z#h11ls-BW&&+w7Uq2B5V>TMI=MWl!YxbJ{RbCFl)t5%8~Y zf?S6aN!z9fhIv$U|L6rm=}P#3>|rsC;zgZB?=N$^&WDFF@;Qogou0wX$WhxLi$9WB z?XvvuUPooQHiWAqKN;5WN&ynQYe58VBAQrt^-q?Yz@@|5G8_0?6JuI|F|$W$HQerv zg{M5ik1WhZMQjz{!z0?P#;m^d2MJnP2AN-7!Dr(omuifWYmD-;eLus1LD3MZux{$C z5zMe*kr^(uL)Jb7{(x>Q%p}nw986KE~A*7 z|Nis9-+b|mYK*lD<$yM7H=?3Cn!>Wxc?7#wTHJLhI(uqb!BOJL!)YjqLPTSY_`rW1 zmgxP$_U_eAkL4+mIhO zY(&UR1FJg^LF$9gWQ)K88)5ElsywpnY#tV6-H{eM-5EpSDg(KQ&q8J@*)L1rLY{$J z=J2L_WS?ad05`CL<==lY@D>ZXyo7o-E8H6u`%ZsQ{n5*niohLpC(nZ7*Ffv9^LCA5 z$178fvyDW-*xU-tB>QTEHBw?xd}EMtvkwFrRl{+o+*;mFF$u3u9~TXgJ}}rAyX#)b z@b1dX;@3%K=Aj8nPs-9%&9)Bh_akl(YUx?sAh;5RJ8DIOa%Z#T`Jh~DcM%E`e~tn$-AkgBf6ZijeR?Bio?~2PKaWuNpT6Z~iX(&a_ww$^X!+o* zO+}22<-Rj7F$^?C$@-nfRac{vE+%AF(9uzEGGq>v;=&ugP5Y?7UZ_HBe5;mJI2Y{i zNE=7%hXOmYxRGM4jjYGmeE84ETb?wkZkZi;eD+W95Z5i^Zx&VWVrd2qikb}H9e4`I zwozuF$!z25>FWD={l`(#iUw6kRfIPr-ti23oMNq@iXYz)B~~Wv5elmPX1A2$_N81I z`pNYW8FMJ`Q59$RO8l&@2GS6`7xo`ZT>(DU{mk^aa>?DtJ9&SKk5Ji>|9S4W=5luZ zW7qIyqiTez$+!jxU$bq#p>v;e3o$1KlO#NI%qbT7k}i)w&G)et;@}jh+Ssr1o;xu@ zTKwUcTtKO^<*7{_cMV9XUhw2)gen}+OsRkBG_ab3`|&!X=meItzs=w#5bzSZ)uZ20mhiTg~g%W>+R zEtYzj01{kzehZGMW5ZHT5p7m1uF)g!o)rJl$2p$SYmzA*I-6Sv$;bCk)6qm#nwzm| z61j~LvVZm8(;OFq82;?hW5-j?tz2Q(jZ1oaNNm*4+G!`LaqyK>(Ft|vEMx7HVcECz zMmX^`|Lp>Dw1K=aE!c^TJU>V<$1D+^OYKY3ga6J6au9w8jUy-)g|HreK1S*|p7k7J(i%-)LjzuAt zIkmy9CX{?NwV(#c2T{DlBPJ=x%V*}hvnBf?r+k{(=G_OuKUH1!<^IilJ{R~75WxVQ z>hrl5m8vYzsc#YlBD=DFX!f`{Ur_@3j=Ri9##L#Z zngkR`l{jJ_y=3@e&XEW5YWk|zf*l72+|_F;L`b!P?)BO$(EHv@F1_&6H}KT1IAh8Y z#^&Ig3LRy z9BVAru}p~-imGo#Bo%4)v>rL2L8n+fc}ThTa{p$1t zIoLzH?c!F;mVOA7pUgCFhI=?K)XHB;I=E37FMLHM2=KJlzKXxZI?k^o#jd)6d{d&G zmOVig)A6_1N0e_XexHXg>?W(`%?D6JJpM}M@$r1X#9duh$)kFLJKGSQO>cfh-C znIl` zvwn!&5=ybGK~ESj=QXmC!$N3}f-z}*?75p0ZF8^zc^U1WXZOHv1fnXXc|cJ0mCn$1 z{?PZ?vhmN=d#&+frfbRoHX>n8>`qvl;@wi;H%pO`@fH@eG~7ndvJT6YV>0#Q)qj;^ z*{RO?X2VSg92HkilWs>E#fVfYvy0TvbGh{kb4cC>dpMx8T%!0W7FU=m)rbC6s6Yud z{}F*I4EQxMstA2I@~#)6vY&lr`hu{eM|buR`-tu(Od=E6(I!(Ux`i1#C#Qvq>NyIV z$xoi19-owa6Yo3Ft1n(ucPm_wJxiZ*A?YzetN)9TbBfW02^#d6XKdSNY}-6z+qP}n zwr$(CZQJwC%zpnSo9x9Vd(oA2Cw*J#>U!#dCgcgEpJth@J=BV3b<;(Vm!yUdb0ZJw z7_$g_=G-^iMdA~V=%SX!AT^k-hj$mr+d5Li3CclbyEnvvdqaXU0q9tdJMCxF$zR4H zDM0CW2_tR6Vc5c#l5Fk3K2|=28_1XY9EDN2C1RYl)h^+gZA{BKTnW5|+SIm*%rGLW zY570zg!!hhi^7Al!wl@zJgdjvPdzl969-k1S@F82ZP!(;d1Fd&e!LxOlu+y|!m95_ z%_CtHV^`I>C}ElwL*>dmtf?41NV~Nb{*0YmI%dg63|WIK!wym|$nPrYdWJZ8PR7i+ zm@)O(uFy+7=P;{mc%s7;N#6BcQmC{P^-J1mq3r0!rxAOpt|NpCo5_7WMAzp$eFLWm z6eqyPlC2G{q=DEuBTX?Ks2~H*?_Xv;M2S7fU)F;7(3RY>eaJK%Zu@&wc4|l&iF`%{ z#T&$NE;$+-Q^ldiwDn{{Vrc=JKuZcHc-yx`TqDUn!X$x_hdmZgWngTk{{av`)7tj84}m}hBgK=+e4NPxMK1Yr2>)O)fagsVB)@wuUE)b zk*ox2=kBsNGwbZ%6x1aKgr^`p6eD)kItKJ1wx`5rX0%QXG&;^Dm^l4>pa*GC1f(d@ zPi3lyX{bWj$Y}(lArc2ZMe&h&MqmexBA8F90ft%Lt)v?FlGU}7`3pejiO&_kd zY02sF?bk=aMyD~!V8`}O znrP%U9P`+AB9c*IXSPSZKQ3>RR+|=yCqJpRF!lD1rKz$!jSrWbh-LS`BUB@Huswix(7E-Q@ejjTZOiWcI7IGXF3iST$=%&=E!sSZc?qzl3+yJf2@ny+H+}Lukp1gnn{bw3D~-&G4{yF;%c}WygYCK zkE;~?LnbIu5$}O|deQOUtY!(C%kDO?ka{1Mr=y*@96K$F@UGsrG|LL;%4v(*dHLIm z5;v*r#(I4|iUn31+^5yNjy5&mabg*=zOu;tP{vfu5SkS#uHM*+BK(o&P@M|OcyoGGF2knj0mfiD4a4tAI+ z++#~J(-b+DArh{ZxSM0(eMMyoSf{4DZO|n=piE%^m>ZQm+X38~Bqc~mM#ktf{oRnoUPjd*x z&#|}2*=XbvwC~-A#h|v)lw-dmWQ8|#okbJ`r*x-$VCL!5r|fTB}oTmruqUuYp#>;K&lj-i=Wy<8*;N3Kv4pZf&yf6B-@0^Sx(5Bu6i`d`)0&)EX96XgMnVTu?)5!36h`D;as-LW?fOjnPtxtH!Uqs}&rb`mS{+}(DCOulFw;yykCH2i|X|1=t zTKoqNgW(HRU4PDYIQix>^6vUAn-fax+wK=QvhFWAp)oVGOA?kVl%BGN1ws9Uaq3FI zfmHzMmkoGhBR;p^4Y1ZbbF#0U(v~q<34h^8&4HJJnbkz+cF9(`Sk-F=o1vnpXDA`L#l)fq!#`7K=d6${`j zlSg-9-2Ix3c!=oJTfeG9+mi-4zsxH76DBUKAH=`0S^t)ut9fIP~X50Q|wz<9;v#-V>;z-X3RJWj;;TsDU6oTq?G%uIu*eri5jjnV_Y@HRQi=`P3^}zBw2vVDj z`_xnTAd>DOR_QQb9#J}pSL5m*$>T*))?`;{<79>gWA?iHtPuV3>MPa+j&_;u?c7~|g*_41?I-kT8qES6j=n6Vb{uJ@Yr*QHxX{S7 z7B$i7a3t^R2E@&u{&lNFPOT}g?_Y{V@>Qtwi>A9**ti0%P@%1hRR@R{j1M3v*wvO+ zsI?5yj#{a9EUpkDXa62(K_9P36&l~wi6p@y#5fB%Ne(A^<{8>x!_TUK*qmExQKiIg zhU>*apeEgREUFxIvDE{yhy^1wE6ta93I{eesY8&6^^VDCqL8F&4*%GUC$rhJF;qwY zc7APt^<>dfY}vF#zpI*!Ie^ho%Hg~QE(Tyn-AX*0zqrNI4F{&l_K90qNp{7YoU zc5<`FuxrhDnyo&pn8>B4Sq8NY$}1gL?od^QvO6+zrsd+{Md8wNFdE8%Z55<<$WdZu_gUydj{q>PTdWqCu-DrCEQD-raIg5*CX=H#(wi4D%fuG z*+qcsHE*JxPz#LKY$~R5;Fx0dXwVcHZ~hY>q=ePl<2*SiVy`1-{GM+uE%KmjfR`Wwvd4JjKzmK{52Ri_L5<{G4oPv%2YcRHSWlHd0S|@f(MTB(DSdA6j>aIj8ZH ztp}(;LD&*V$sa`d5iF|a{cPpiDRK5NW%&_iKyN!_=KhDLPV_im>DF1@hWep>_Crbz z!1jnm&Ph*y#A{+DW497La0q}_BrCC87MwXc7)5o`_0ZPR&%I#E>XPPyz0iStf*XbJ z*Djl+g|#m$&psUC9?Y^TGb4Z|%Ux5LhRgp&O&r}CTAq2ML)7!v?Z_&eRp*R__XRJ& zN-X+!K;G_{$yJu-x22zYQd{)?wKdJ&{^tARkHei3YcM)J6bzGW7C&55{7Q zYgEw-jxE8|0uEgVLocesbkCtK0FH*~NkYWd!2I=5*u{Vp0e>~(>87r|@V6yGh5;+K z4t5=9SJP7@ZxHtre;89P$g4T!a>e;UGDz`u2_J6kD?0L%_1=6ISU4|GYFvBZ`*T01 zLTm8Txc3lw?TbH0*s|ySmDXib$|!~xB;kq+&%b((Far-mMd@Q4J?B>v62PE0 z7V7z*V;TzS=?DWqaFvZ)cXJ82feQWIiXyVX>TA(FjYcxd)$diOlj zWkxsG;8!zE(`B09Z@4^Qm{|R0GdHZRa(cCfc5f{Mm17oz>E%^w@ zyd>-SFcbC}fl?Kgcz@xN)^;HrS)nA7XOEWengQ7XYSCxl?=6?HV<5r28iK9P@%6Mx z##Keg_F*x2C7jw5u!^+l1D<~g-FM=pQ|@iKcx%>X&tre=w_0(-Dy&;3&|OPRS@)W_ z3<5CR{qhk+inv-*V79mEve%Yfn*H-;4-sXJ>mUqC+%9(5M0Fs#8BYE_0Yn@@DbUD& zw+)H>QDS~p3b}I|r9N5ndnshCwc3FE+FsQFX~vSyOGhZ!K|0S-QvS1NJ%%&* zgiW~_5h%ttNpg6VaRqG5Acu_!iv(i9xiDpOeXD(42Mk72Zv?OmpVO(%=5LuSk6!UH zUdJ8Kz)QT94HZw`d5Nk!MFeFZ9&05d^q)bas&0A4>S5G8@^2-$`R#WTru8d2J|oY@ zQBsCpD}cd=DalYyKa8@`O^ zYkVBzc@CfY50JJ7WQd4&l(r@*~YOhL0>4QY9wJK6jy+d=9LCYPh`Kqs# z8vI<)t!@-?QC`2-BOQbs$?2yCqy zfO~eOoM7|6n`MW&I z-{II{qXaN(4%pm-m$bEK(a0Lg6UPxa6L5mRF(;WJ53CFJCM2m%eBQUbq{Hlf+f4+= z#w0}!=kBnSeAWX6L(NN1E#FMkf!#*X9VvBiyIt%S^f7oum3k&@ZB7XlhM%$dV$-yH z^4{!}vrsey9?!mzJy$$35M%tuwY5o@`ST!rUKk1&0;9|be3gMJ~hg}H>BYc{Aq%hG*! z9-cF-WQ|(fp9Kf%gzv-x$C4ETp^oHv2`5^bqCIo0WyXb}%G92k#`0OYQy1VBqkW%; z($B2y?Pv;AKbl%bi$O&|d==y&0mu6+BgIjPJ~MkYH`Df~8nCqAy0yK#$c1~T-=pc& ztqap|V78NYG;%NoQb~Sk&WpY-bJav|1JN0LRvCGK_rZ|%f?_fO$(Y#CY^L7~e_7jq ztxt)O(TqjTk%tzv$81SN#ioH%BvjQplLS$s6)ryvEXm(lYC1lkOk%&Tf2!ZAJSU9h z@4I^ob-g0^H=a0ZGU$^;Ez2Pni_&_JOrDEY?>N^slSvg}ThPfsWSDkUEamr9I~6Tr z@av%9H!D5ouJRqhh^Zm-Ot8@xT>7{J%?QbqM(?Ue5R%;>h0`CWTvwQo_ zm^oXpY@S04#<9kesCNY|APzA)~K4 zw>Q>C?UvpaO^^f%0<&5=k7a~{&2$gGw=9~4ok z8u5Gt@Rpc?d!UKx>O@@oVNRC8;75S_R$oc{6Tr>nn`(Al5sO}>4&euCrU1(U`2w+k1*YZxf z)S*GuBi~>|byu&rE_@5=$!{cxKQff^b$9LZ&Ju*?WOgsA#1BtB%^co$tJrL+(OS+% z(6TuLW>g}OUjr%+glCny467%jT0f6>&J$Pw9*d>Obl6O>PUQmvQyHBoDO|o)f=?A@ zW4qkjv2dj4S23`mDg763dEpfNqI^Z*#i8=N*lE2)UchONI1yIt^F8!U#0xFN$o@y0 z;crNV`SV%O8&MZGZNIsgDAK7@Zg&A%aLyOP@PB0&{S*Z~V9B&o5YO3|#kr#~0392L4MR zkm2)ve@P4U39lu|!Gn3RsJR7zVCYC7M;;NTw`KlYH}TR{b@r~i>dSWrzMTl^+0 zkek3PxYIQQ3~|3O1B8a)L7XrRO=6c!h>*zulS7(;D9v%wxGv{IxJKK@pZXmJ<;`annvwMeS_}<;Pc(}mm@;3fH)wKQc zdgi*b0%{CE5H7%9?%!Gud%>d<&_Ehl|Mj)>rLCYg`4{qr^`rPdE`ADDZ-GE#%N~xv z>;XT3@2PW(K>>I~?l`~c-*!V+&XYE#Or~kS7C@V#(BJ^x{>bDMoc_t-37Ea3BP__f z2PY8UFP=D@`L`M#?(h4g@Lyb@K)=*4XSrXhjh8ws{dX%tOyFNU>5&5q#{r;FKZu?9 zptK>t1;W|yQ~U41<1hP3UlBkL^4pIl(V?N~OL*?SY~WWMp}DQ~>3!hU=Yrr6vYzHw7DV3H@)r@qU+0_P5Tf1+AR8#}+wXTy)wRJ-3Z>8f zo8_Aa$9=B%t_=6C_ntg__+J=#)EfuYZ~MgHd$Ine_m;AHqxYV)`bBW$I|%{6<~?!& zVtC|R<>$WomgQYIeqi&Eg?~fjBXa%=W>8-^d9Fctrr_YeC^r|g8wR%UzmD!)bZLI^ zR}(`=2!Of-2DbpAJp57q)K?4LpCP~QLH&B}bzB?Y(E)9a@lvkxmrlj(?HCuQ;}_EJ zQaNOjsx_YGnGe{T_svab0@%7D)*gN62j$C z7OlCHkw{Nbhu0yi9@Rf8b=Ey=4}K00tFJ9$mH{`)c{8pKDE$hPBfYMd@y<1G+8;ht zrvF+BRe|zI-@WdEFFmTs1%3mlKB*d;EYNVs(J9Cw(0A*2UYCcC$n-|f2~r23%$ajP zUbj5--zv4|Sr&68in4TPa*AAvKFCtRu-yd@X}ZYV5ir9|x*;EoFhmI-=*gqZaD_JO z0u;H_m$4oRhXV^Of{8jPeiMe*F%R*WPi-W*jP8D?is8Aa1?}Wa!&JEyR9~Y za2}GWQa)kO5lzuRfShx$epsuV=3(gV?FR zu%`DTu;;NJ^FPtQpTlO(%IJZKw)V9ZZiJPb5aNsiuz*nu(Hx>^W6${7r9G|KH**>o zdEIAUKt|z=!b+r27{#hlo788nNB(+X!}#h9PPAE7lU!yNouE^`A?Urkb7V~XAjbHU z;7AvgCSA<6R8X9k-V*8b{cxyM$^j^DVC4r5OhEtk@cp%#aZEw#8MvBdvJgqjktmA6 zc~?FRv_keUa1@ll+>VrW+n2xczSMl1HMES^=7`^)5#*WSAHy~dh`&iuH`JN>YNJ33$V4$ZP_aeyYq8fn5 z&7~iNaOSKGt~l9>OR;p9Ja8|>mlq|fo1U2nyg;EU!*58CW4Ie(<$WP&TYPOcrpG;8XXZ@Dbmdt4;yqEBJNSO&T zE;Q7F95Hk?@J*>LolxJoi@DT=Cfy5Dy~OZ`&@;S{@ypxpvl%Ym9*T^q8KT=KuUgrS@#uc-DDBs6K=F1+C~X07^?YGWw`*urBUbjq$}YGjcI^GOgIl= z5f(67ISpnQXF*PIo757N3U|*tmZUQm;3g8Vc6_&0ncNKZR`pFYKbWS-{)1H;dZ?fU zlNDLU0rXaE_ydQ2;gmDkdvnXJoiN__}jo&;>Gz<@K9REng zNqZi$icoz&Jf!_%;=>@7OPt`8+j#0nu*k()rC>d%oC`S1OM7{lI6ONw(@1f6i5xOMoX3o=s> zp~e6kW4N0bsh37t8D>KWMjqEGrmz|lT7}|g$e@X{q!(!H!FF|@+Wy4M zkbHz1n}stU^wlk-QzK(RTN`=-ufhKWCd^)qCoV5n=>YrXLFKu9-t6?XRw+3K3RFuJ z!0;PlfFFzvf{U!%o??~h|$Qv+-bitWI_`v#Dv0^Ut1 zv=ERBJc5ZfIxR)OIhL27AT}x5AODKwVT__vUljQdt2;%W$ZJBVE!vz!_p*BLfNJKqviK= z%93te2c%F9tln%A>cL>K-EZ`v9jY~D`P2c7vmdc`eqAN3Eo#s6vX_WMBWveW4p4TJ z>L~u19p>LJEZ*dL+?=*sf4ko`mIQtgWD?Mo34S9*K+-`OTI$Gu?H?1JVEN~9tK+~8 z=htcYMangJu;My(5f@JejG!V=ymnz>UF%j_MRgQK$5w#|19MybQ3EF038omBjkkQP z3IyAx=OT4Doap41iRv(QS^R0_?yZ|fZu;Ft^hAA(T>Fg>@ci?JuNXSn(vBVI=rm@x z*CtmcNIPo+8+`}o;USD-&VH%`4Hx(#W`zaa7J=$#evGBG{3(=~IF&r%e5VekdwLJb z=q2df$45(+k2AFHat}D;5#t7Mc}l=2%u0D+?@@a)&i3Jl!mcJ*f=9G+#0U7%otJUV zQp9UOHUu{8m5)&IW{$Y0=`L~+FW$RQ_KqnQDlXw^Kd=l<&dnn*=Cwb1JoD=pQ>bPt zH7lG9>QcYy>47tp%dA+AsMfCr5^UxBV*M+l!@MMu#s8Pt>MBw=Q>R*W0#DAE3O)v^ z&d;>#yxpN(;L^!}vc3{X=X<|=!{&*eLBkm~ilSphO^5|Wl-d~^zXNF}8gUU^r7cd4 z!o+H%T1lu$fJd#7tuZdsfDvAB)(_|7+>eFD1PrfaMrT+n4G6~4afiTcMJgjsrSnrZ zlMj77zP-6dqS`|zN0uEbnVoF^cp(Vz&=bYU`CPeltAy*bzYdGb&8e9SQw@Kq8UYD{ zs25K@)N3G)_Y=ior5L7-)$Tq_eVJGarr7aKX^ck$y(qq6NB2QzPT+i^PGW6&_~<%u zi(*>4v7M~UZ1|5(gpmxgo5-@V>jU#7D*6x9wxDZc&vr_&O7f*tbI{EQ@8uqOwJJ-4 z(you>`j!)CoN9C>|L>xd>uG(}yG4K)olP@{6%04Zy!s$3aez`e>-4WwL1e*Cc}OF@ z3!r&ATS?ZJ%Jn94hVJPGwR^_@PmiovfhH~XnL$(;)|!Av%50a3$$wg*(EQR}K3Mcj zQCHi&>|B_Gt|^fpYu6uolR8K|^|qCZJyGi#A!I64(o3pcf!2M3k6}*Nu4*pmWfL$O zW)?GsZbPg_J#xII8nCfXXt-Q0mv|js-C;`pO=nvY3{(B-guA7&Ngk3_cu#GpB%M1q z8z=!}<`qQE9TY_%?#eg#6$E{~uNv6W)P7MDc)Eyl9V~%Q{*|SX%9SU`OMyawzFlF%Ip@xAxC_|xp)XT%H|Trhl*rj`yG*$ zaMP8Ys1E2>C?(nqUJb{8Q>yy&nOTj0MXr)@1{FOf6EFz`o5HQJqj0Wvz1VJ{;5Q@W zCy$xw1c?)IJkRc_dMm*p^|K$WC5io65QjAv$|@76J=Jb-0E~#%?N86ZZA51{C$p~z z^=P=3wCUvpXn}A)-89aiY$Bo4p24)&Xhhw3c?dt=6PL<{EmRwZVTcV@n|X;yH1c6P z)BEpYs#(EfHodgc)x~ZrI^a|DdAtuz0Aye^U9W3TJO$@b_l`*Bnzg0>5^+*r5~UVe zG6BV{Pd-84>6-HvOv-q2D{WDRH~9*Ey^ltd#gi*92!?_hqr;L~?Na#QPO7)=C$QpE zx5OCTZ{FggYl;X<)_%2E55uUMr!$jCW3s&Ep_5ckwi7gBw>z4S;!M0owcoH-ILXQ0 zt(23?Z50>;55n+PA5_VWhUNEVo?FSAv`gO6Iy^ExrjqEH(tJ((&|ja;#y8%yG5Oe~ z1G@l6)Mi8JX|P8mWi=Coq7-tDr$6k&6VRa}X_fm{~=NIwz zA9rEBeYylY>NWQ0>e^8rc^0(P2}kTc%-$l#?BXr-H@d={5w3^Mu_MSM`$XC&kkies zugW!kj)Qi2B;+1qpdDfI7VDa6o;Fc);|4IvHHv5K0Szp--evSEZ3!-bq_lXu*7NK5 zh92jeQYU%oKd2RT9o~qHI#FN!ad*dz^R+Bw`|thnZQ9=VO1d2ezS8CX>vn=s6P;?m z+Lt*mccGC-W&UD{t*&f&`6%DelmMO;hAjG7WX_9V)X{jzkE}3ziuElSaM?jZ+03Zi zWcoCPf9aV}>54BKMTMOfVfZ@x-E1;+TuJ7qP|?*u0lHH}TFk*$|LC2J;idfz*OfN1 zt2Kd=hdkdVm;AFKz1IO}K11gM4kAA#JnDWeDxDmn87n+A&;@@YX?mpgS5iI9oBVpu zrMvnx6fzcKeP~R{7kACX@Bi`2koBpj{Tu6=ZsQF(kqY714y zXCOL;Np)ONSdia*ENEbqz5CQaAKM7e*P3<+eiVF~ewSXz7szo?gAHjY1C$tuoj@N{ zUbp`_b=z&SMt?OL$3htpeiLm|(Am9pTvvmrOb+5t&Ed2n`h3TUv}UHAz=1)lGt#>E zaKCc@HKpTAxLNe$qFUzob3a1vrIQlYSRbR`yJLOfz}$Ah%kx+Ibot1+%Jk{*_#|O1 zV@nIv^cyOq-MUPS<+QYg{ahU96)_bJ$0WQtgeR2Ov!L^@NyzF`qb6@POh9e2Rf_)M zVD=b`Xf_m)V^OX)^yOjQFty!Za%wO-3x+7 zP_rVx8O%0^>;y6?A!2yGrt*L*z*}2&aYU{5#I-<*gxBj#oYU32^G%byRI50R8pUhdpL{(h2ngQo2$=Un zXm5&U-{)ICMQ8b%-oeDa@tN09B6ircBM-0*#&cGh9~5W z_k?afjrn71&*6}qu9wCJdydyllw8}0{o8%$I2tW>D|2T3|7(q(M$aD4w3ij$}i&sGt+bSWf zltgcM|4g6)f%uo(_p{^l_{OdETKn;(^`LGNW*c!@B$O2Sp04LB_+^zpKh163Wzu~H ztqD=rcXtv+WXNxX7~8x}JfZ0B__=g3nKC3=qIVrwCA)9DUJdfUjDPZeY;u+n zAa0xTr6pgBmK@Rau5v9tU)QcKQf9$blkNe>T3phK)%EW^b)f zd3V4Qn*|Kx{BmN&`n?%d6pldM0fOd8(&>PjWm|g-Mc-; z>a5};0#Kmix?u;GJVw?E33c5mybAh#gXPX>B(Y?5x^9yqIv#F28V%t(-Gh4PO~@_2 zFs2a*aJ`{ICrx%uX<Y`ms3?v+D%A<0JWh}4g%zOypjm%w3& z`gUb24kc!bTx)VKiq-5>|JKU;vDPSR!||w|lQqAHd_%Y@U4(aHdZ1hi(Tjlb zb~QSwgM#nYm|qG@774<4Y59o}ITc$)psvV97^@eqOZjmr!RW>92YNC7n4;!oPn?y4 zNO<)~NIiL~vh<4k7-#1s-y{@aZ_jr>FTfx^jDj|M`Y@h=yjl(wvf+JTRE%170EvMI z^87Rw?6f_-J*W8=4pMO!)akr_gVNdS@|@_GsB3c)jE96If!u{%;2=&dPr!`xq%#wv zt5M=-Q&zijpQNXbp*#>r)l>Z9YJQd ztMdKOQ9FTO=3*VkJroh3k&+18bI(If>G7KFK)({cPq&T5%$Uf2!O6o`l$ep@7unbl zfM;;jbS<76LJW~z%;CBk{6>?2@nJW@#@jzVR#_ii9~ z^Cwx+J*L#g!NThj#ZGyR|5rkv6(42J#RE--R%XF)VM9h-7iJx9Dppt63S3OLBi(k* zqCGGd0ecn)deU3A5EgAjR*_+l!udiZQc3ecnjdg1=jwmw!9bMmtKCpsqC(C4sDA+_IFMxupbJB~+tH+}Z+Y8Hm0l=4K%>dQ?%qA??U-sVHU8!mu*7 z=d{|*=2z?{tSy3<``0uN5DFF+Jl2e8Z{5w4f`y9F>SW}k?JZT*Pg0aUhtKqJ_#Cm_ zr=X1_B|mKuQXSmd;D8{Z)8=}5)){8|iaIbjXl4m(1TWnHsn%Prt+^JrnU;W5@v(hB z4%9IM~^8UlDU1;lFbz_+-J+}SfIdwE9U49 z$EnWhdnu4TZ69QO)!Sn__>c94x6e=Bdhef`#R;8b@Hs<*L-M5|gybzS!#uS~&(_4K zU|HijajrYdh zr^^*Hil!dQg9s!h_8jeoM3u`Xap zhDvl!+Oj>4=)NZiq|X)A|EJP5^SKycyKN*o_%B6h>d~es^e?YTN_`LK^QxV@>SRyq zu*I!1?_Ft+yOBz;E8K@!a=mZQy00#{Xa4A#;N1o0_VK)W zu~6eJ`d#O09MGNPyNq@wM)$0beZDm5mJp}Z^K18p&^CMfTbO<6s;7ZU{+o1fe?3bM zRczap*v~FzovK0V411e_HlKalbC%EJdBS4!U3A0Xm@vmZhusl7dW3A-;$Len9a!H# zN~)g?KLTV#YyuVV`uYE55A}%5Kb=bRZz-VV_Lou%94BK4jO}aSe!mff<5W5^(|xo{ zfzU}7JGSs>a)wjhMZbdCZXW)U3(7ekA!|6=blYGLxB$5umn;mtwsoJO4CrK z-3cT#BzrMb{8+`g{ipB3BC;pt<%`8d^5+kLXavdaeIIkZGG9ql}IbZiv2;_5YY>Aw12!r9~ zL{>`9tS8Z)@NKQ5#zs#f(7I*B8w>3>jm!i=IYTdq^vm@D~Hm4YeKtdYqOCU|^j4|8KXOEgnwYTHPz zgWQ*%okSPI+^eIH@`jQ26#;KPqJJyDI?#Z=o ze~pO1P4)5aGf-`FFb^Q8R*FOiUQOYw|Kj5`@J;6C#4!bi zd^c@BkvgtBui05PkS-F~(<-ab$yKGwT#%+nOOOj6hzgMyJ%Trz$rps7UoerH#a{md zX`FLo$kh4A&&u6>v44P+eZfxU3;xxi#&6nab%rJygT$qCb050g!~UU`93IQ2-9B?N zE*nbruf&}F)(u+^l^EE|!{Y%zdF!mf{W}R;&4pA4t|>zy7U9L?%2}?Iz9CV6H!u_d z;lX^oS8^bWql}VWJKAP$F)D4iKqVXAR z2(w*18;dGi<2G(FmP4Vs?Z&M1XdrWR4%;>cWp}7x&tClI7D#V5W5wWg5DQ*B2KP^j zUTJUVYGuK&REvuP2cPjFD;kFm*H4KuPD3^?zAnUyK5sj#>LZP$M$VqfWl zg7}9m(cB`8@jcwvaPj+YMBn#C9_DT1EA&(gmSH0d=H-b-aJsd`qoiQ0HVzF2euX8G z^}{l3BLR}5MbL<}$)r<@PQk-<@6~P^3OdnmL@U4?PfJ14bz99_pKafz!CRk5q&P>| z0L%9x)Houm|LtBF0XYYC^AZ{c11*oGN!qSa>rY@Nofe2fLHiNSik&~3?p0?I={9~Y z%?Vp|!Y*utR~qwwCMkZ51$x8f^}Rorv=FA45T|5Rin()b(q-@c+M^BP5#mv?Y7ETc z@V(fsTio=1&eYQRRWrB`k}_5H0(VCJG(R2(ss)=^7mn!@e~H`rb0jN{P(=ls4C+w} zH1qHsXlDC*r1#G41pPx{C0{i|4hrA>9TVBC_+*Py>lbaU;5J!|3P0YJIj~L z-v7@Eqsox8ky?AhMb`DIrgKA``Bl_?jY0fLOLCfbo45I}@lkSStZ?G))mxhUBSD8V z{X-=ro6`y> z8$a3Upis3clcoxopB%M{icc)7RLHIzhCvZjJkl zFaT{hz~uA6HEoYR`{cIla%0KI%;q9~$?%5z9`*@`C0;6RS`R+fq{FLpR`@gR6Bd;bvM2~NWLhNO~cdp37c8b#e zoiK?0D+p#-_Ml9f_o+9H#oTBksejEzd0+AQu1;xp{sBeV7(eC$j)hi{+Ohm5R3&Pw z2r78pEI8g$1SVy~>GTu10*Odk``zPhU=y$a>UGptr{q}=M4kk z;7FJLO*k=JYsOC@0Uv5fJBCV}hhP}G3)cB5hFP*^|ESf{-|9&E?uH6qy6Ij%(BQh zK}w6I_Q~8-4=+ueU+Gw$&yrUF)u@p<;p6xv7K2q2!+Jhs#Y@;(l0EPTde%ZvtmR0t z;(AP3N?L$85x~O=Z&72GO-trdM$cN4`kE?X4+C#a z90XLJsOS58E;UI=PQ^5^M2ThV&bLB-VrH{eIXDxnh@6h>{O*5l!QnB*ksdB~Bg6OQ zyPMDpkGT=#MDr+Aqe=`b(yU z?hBRQ%meHW$8V#Tl;d6qOzvtVm&!*QCpHa7tg3bDo|sKrRnHO!7;g0@WwU($4Snr1 z#)OyGUyE2DmcG=8Q>1pc9aP0j!_pS=*86Z=rl=fR3Y_FMOT;O;%vs0bj`#Uhg=$hv z|D#3o#M%)^8s9Rgbh(!hOwRo)M}+xh(PZazKI)t++3Z)iGN2 zKv0ImPOR!;?({@JEayTo9?CP43Lh9L=+8lRdSb;fH_cI;^0Z5)Pp_6(Y63%(<>4I@ zJ#=4Hj*E>)lBQ?_S8E|IDOgqR+{cERVw~aP+JBL^C$ zsAzMds>(BSO5^$=-aWFhmUoaj(+;+$mE~hm1BKnl9m2F5zH9Vl358TB}7w-|bRiTVz;~VDl{j;qqaHQ?Iz1W!w=r50T zrCLkfdODc)dF5A`LOnQ4U%OiPMzv`_j}Rr=N+kbG2Fu#>eE%M~b20~BQ*nEP)xG8Cq5s>^#SIUAkZUYV zV;+4StW3;8b^fqyOyuVFb@j*!_ZZ;jT2iFXWh0YM;L47W`G?3!{esXN0i$l_l0V1} zlXhmKvg4Tmktl+Q!($&^X>!ry)}|lPl0GIl+wc&zCE3k@yHw1RGXj5Xt^C)Uu_6d7dH zI$oUC#s3E|XS!n9S$J$d&&{<@*bx4csVfnY3?ROGz)&t;32) z6;XHXIl)QD2g7v_32tyA;@nVOPi%=6``i9@z|-&ycLVK z+ozs>mxj}`Y9^LA7Vo!M)A&(~p?skgKug*=SO>o%w3wAMN8B429aM!9uetng+OE&2 zm707s0y86gQlC3fS^O?0;IC2f&yA+=&;kvhjxLq9nEKP?a-`x);f-Ln-K6lT&%gA5 zcCZ~Vame-Y2{zQkBjqQpC^9j%VoIVpBy*y{Y(Q924QK^ZDcE$V8S(`Zy#8eSb?3!9 zvyTa(V#h6_emOK;!gfVPNd~0n7gQqP2p*qLmVT)fTIei0@~sbemZjUFxCbMrgob7f)x zlugJDYXf1Y9p!fC9qhSDA!YXEL$|%o*mfv+!IGg zVDXJteSDJ)Bav2yd5@jk$zkrpbODs!`JLn6I1(?zG6IwtXHW$PoYg{{uMusC)r{ps zsN2m(+t9QWlqf-vuwzRf6ejn!JKP5If$A7NXO_KvKao4%f=Ftl(O^s+< zi%YkgN8rM%{c> z?8q0_m=k*o+Im(U@Iz9_h=kH~J1#oUV~-xi*Vr8{P<`v@Q$kIeDF#vm#j!|ZN||nG z``xSQcUSnBwl7hYEUYUQ_Q<|yAb$t5C39TP6l4~^hzQni2*z@5FkSLeHJZDl)L)$t;I2;-q8&UlUUc{*=q^+EgPJix8 zERW#LLmq9G^LP=cb+v^ ztjgT`77ntK?iGJ5#1m$Eh?%cxJ?+-}o2;*)@nW^8Zeh4oxT&D?rlEVKE@y(Yp-FS>*>QS>0 zxnkO6HKJqDKXb)}2Ay^_#d)3zB&}8OaD>;^Da`_J3chin5AB}zM_)#y;-L7oJBKuM z7fAhZ#}5fztzgMSY*g`G{eLJIWs5P)+a`d0aOmoa*A!2Ix#Ap#6Hzm)y7`jP$Y5%+g( z9UTsVduBGo6QU7;$a_$OYd|^t^YTg1C_rz`^!(5up+DqhVa$o6U*0q-0hf3$CEuXKa;!gj|A z=rJH&K?t|>A+Y^erU0SlR2KF|+Vt502|$ki^{4uY>YN5@@zaCHEwk*s9ufE@RM7%B zb?@n3=J%7Q{Q;Yf4&nIHh(A?Lzf@8Y=0A$JV@L59K>p5<0}KfWsEysuKAoN3_!CzH zG207ci2-ErZ3!9H_-9rLWNI9VU5r*Cr+@f@PAM+fKvwlPHK7ty^yfL0y=>=@?xUwk5%Y7oaj zK_@+ox@-KJuY11lVg_&wpo&1@K_BnG09sxAd%nXp!JsX@KX!Swknda|-7C|*nv_I+ z;$w9F_mEJ4{NyNO*=HXSwKM{LWVg*ogz~MsC}4MXf8x?EQTm=8b^t7iBhFU6AAo`Z zxnFv{e5H8_{6?>BmH0vW4gp07eYt*?(XXNewV`j>=xRbgV!t(y<;$>9q?x&bK_bC7 zltEd)tKy2Ck2SF4v-Gr?q)+x9vP4+8auW{79FlsW)P!*-Nnc#!XsXB?@W-bZblhyZ zEBoQi!&a@iA30mYyct_o#F?2qT2H-qQmmZWcnEP*d#2E9p~>igeLb^W*Qzb5)MaOg zia0q?__RBdwktX#PeKDqSDbp2pv#eS(W4zjc)j&cem{UMTa-VDS(xxbB6Ic--*Yyv z;l)OgkJ4{zF_sPRk=<>@9!@aid<|r z8tVwENIwUUEKy&#N0x6by9<-!z&ut*hOF6JJ6_v(vyaZ4^j}-zve}gMd}Q0aWA><@ zh1-7RK_JEyE7zCZ`Sn+UcQFLCtz`XqrlIj}om!vdcD;{1rdU{-f4%Ttlji?A61Tfl zq}O6g*UXv7pQ#5iY0p%uSF5t0t3Ttk@zlt+b&0q)B_(}Pg@maT2>3i30qcv$6|;J&v^{UQS{BK_N=7Lp;VNB?|{9g9tIc{~+5S?E~E zA>*fPHHNPM-Z`lpyMBHeX#sAVzB!?*LFAqR%~q4IoDj#zN$p_A7FJ zMc;4s*Qfbzy&?zsOB8YP`HhBGQxe4C@uInIQsHXlNZ?EVV3G9O^h$XyBzMPfzhNh#v&bGl5ymLHB>Q1rdxGpk~ zNjs1imE_O)^DT6dV2 zBE@(gNv?#E8E=;@iq9Q5qb)gzX)5S+zd)07zfCSM^wRR~I;Es4Rwtm!v3_rUJ^48& z55L7xa$|1`YWLn#$|D%CKG?Zln}gz%R`K>6<+SFI^7W}ZQ zubXvds(!Yiim$~Q1a+7v{v+OHKJghD-SzEW=D}F*!6~~IXh|1j2w){@{@rwb^RM9+ zO=^?Zc+&YAsuTC4YV_7qX;H5ItH|W)>Z53`db6*^g=I5wq#^mEMsBAkoMW+6UMm1y zDK?cXOc>ZavoweZw?;pUYK!}2O3rk`kP6aKJ{ zZLVV@ZyU3GNk*rB%xsstdhZ5pb*!gUGJf6Tt2}dn+E{Y>%OhIi%$o{Pn$p<7HN=Ao zhb-Wtqi_q7?PQv)nELgdGr+w^$_Tvz%xXF+8r9O3EmV4u&O{n)En|DW69q*UU351G~}fr@?{- zN8rkViI6fCXJKRU{a0`vptQA1))!`dOaYX<)(gK@>q$c z?ULpYY9nniZyv914z~L*=uX9WS3N`n`3tVph2BjM^uJdC*&6anR;e=La4^)EX16!3 zxKEAuv@gW9>0r(q2YG8H%EjC_g{)G-2bf$W9>;1v)YDsHK`Mx3aS&A%5C}C8)mDk=ZzzFZt zd6I&*n>9Jb&c5%@!XmCoJV?IUN9`qxzH(hE~1wz%TRMOw7mScZ~`dwOavjz&QKXF%XVtE z75MB}-QcD{2WE*t5JPtCGU>uS=5;Z?YAHgh+iZSFjZwK0YP58roLY676aXTOu~Xq~ z)9tmr9QnV>_oDb$8WAvaYBIKTB-C~^&0+Sc@2`m&^~diZ514&(meHdlhm2g^W6Ero zuGQM@?2OaPQHkpmlf?^nDUjKf&Yva%$LwCF&$%H2T++ zQ(%hqG+Px{8C$=>*yEw0~B!02Hen2 zdN$l0)&YQdQjaDBp%no26l$*ix12A?OUAqpm*)YDpITx=EsC$8?q2@zBH;(4wZ$zD7#vi>zp(Qs6#CO#!J4We1d-X$E5E7{Qv3+?bb{OK|WnxMrN4kWTC!no97u zUb2(6>6cK82zf08($ZR7eMr!xKK2C(MXUQ0%i5BjvRp1Bbdi7maFekV`F&a{e0W&F zd;)c!+DrJ5L&mjSh;%~^i8Od>O%gb)(Rm8%G)SF+20F|qZ(E?6Z%`37+Mif-pfHXn z2c-76URNkMXt`5zV90DpB&Lch`HVs-%qy&5GP>+Ax@@&fYKeqe!HPiiE()>0?b4;! zLz?Rz3>gvl`$V`lvr)p3?>)4Vm|4=Cki#h|D8(KjzXS!2r^6FRfy@F%Y<61ds&_J` zWLq<}96U!xMRS2w(h@*0G)T)jC z9nKf`&R9mVo-i>~)Ox*-NrEufiseS)elsKQT2G~s(tHz%X1$ZvqpPYVr@5eUF=#_*8kAWgUeZCcgu$se-6Qf_UgXn zz@{6kUy_1{ShR;~)jPu(o~Dcq5<{~-BcpXn4!bL};G*7B;RP$hDS(N+eW3>fg~pfe zU{m{x`&n4Ph6i1?Ry`kiJU1ycMTdP(J;l{zSW_W{Z#Ik4263p*x-{zY96}oe7bjA+ zgmo~-jVoOjwmmH*E&$6GOmo^Le5)wfuEF_6#FM#DxW>QLe{Q$LR9V`S}`y?7a{sEdR)bT`;{`ero1JF4@$@ge^7o?BYicrHYLf(KZ_$ldaVIW9`6twUb!Y6_sud8% z8c2?FuE`C91#4ODoU=BwV#m;+2{&I)9zD9p zy@WiRHVWWFr*{c@g?Ai$#84FNrrM_AKakxT)`VR$U{z`A@-VWso(+q+xcQB!nsdlZ zou);;e5#l!rooG3={xtpuKv?yUTU^2kyZf*3)!Vnittl&I+gr$o82qI=X-cbuE_~C zd$UyN-y*D55re^iq!saYj(-)XhK-PP852C~dQO*3@i#Kwkn`IX31h z;+wI1NX|d{+kNi8<5pa*6Pu|{X zS3~YF+c|dCFcovn;Ngg{`Kb`c$?XG zIJJ#U{P3C4LMOY^(UY8!hc@ww8pTc#SBL1*o<VE^|`B=?yAz00G$&Idc+qQD~ZSb zW}sNCS;dG+p?2vtOTu|GWa3b{q-hqI{5+b*i{H4KJ$Bk65C?DeZIc&koUL5apfn~7 ze{=pQLrvI}509bMSQ7Uw8Lk7S_l56_l>{fbzO?IWLKl&6Zts!jKHJ&LQRY=vI}}ODqtqJH z{rs~(XmntEexC&}oDTFVd1_KAtR5SqzD7VO6UigKtcaQ!r#b=yCEO9EE824?F=z!) z;;uN_7}t^^rn=bfTgzzcYaf{sQ+#p9sTZ%z>Oj*SDg^B^o7tc?K-2qz777#V7{(P+ z_9cSd19H=lNB^T1t#qWgARC=ui_CAOtz~dTAu_zC@uI;k2UhA*{+9V}H_x8}iY%Gh*XML7k_@J+fXZ8pFZY#!T{%v!I)a|VOzHXA{h{6_i^-l{ zi$y`SR{)zmvtL>rbRB%LAr>75GpkMbSw`HA z?DMW3-FIj=4&l5bgkI+Je~RpOhTe5}%Ry**t(%)X>fAoqlivJzd!CT^I~kgA<7-<= zR|_k&`HGCjd36O&75?oP|3zYs9*m*+E>=F=GxSL3?%C_wualL%9H*>)GQ9VHU=lTN zN17$m<}*&d!rzWp_83S;R6^7_f?rhU91N>|mf}X76=06=x??d-jN+nug!M78T=2W_ z9<;Jn258rp6CK=3?r2EqhLmPVF~KaR!D0U5g#zlv>`L12AF;mg7M~K4hkc=u z%KnS<%-ZN^{vF>X?bu;jFG=?7McfIN`&(U8RbDI!U(f@&E}bB!%fQairPH_W z3zM%D$rP`82)@2l%F73$KOZD5q3AN${D6WFte`?XbfzY7aTkVv5h(ULel`{f!3vcC z6?ON)I&yE3#!GemsgU&aq(Z`V3=1ue>mj_QJe6MLdm%q!p@rb!G+*ux(~M>Y3(DR6 zi}(F9Z#Hx029-s=!!>}2_J(jLe0I$wyBEBDu>ra$efxEd)-vB}$#}Eo(NKkJ@f^h4 zd902zxqxE@q%7>va9gShx09+;l}$5Cx<qT7J{5-3&>-fcgla$mRH~STyAD2%`2D zy}g48dC%b&}=gQR$*-d{RD5L-Ge`?Uryfoxcq~7kYlz`B=n<$p8 z#Dw*sUT{s+x_KISGaDJbiD%Gg-CsFn2tQ#3;L`1LK98Sm@ukVedv|(ZeAw?)+$EkJ zxqi`{GVUxnb1xIVeGYG1$78sHF6z z{nVtR%85~CL5Ae#+`LcOyv-}40072cx&w!-xdT@XvrmD2+=^ZILEdrC)E-q%%*N-M zsGaJ#_tJh@H5R>b9tZKUt)H4ni!z1W0-x2u$+yHf%<1;JZ6$X--xRuW*=0GYpy9P2 zvIP4Xa-!R*R4*v|yC7QUMFxGIsw76@XRMW|zY=EK3bmqxItR}}szo>_wcY?HUM-7tu!5A-4NW+n?r16y*2*8VYmLUR?Ub2%19X5q1{K>=@)Ij3#&Sja;Qx@_1i z(u=q`M6Z}S`|7=*hL2nFV6S$2%r9Q9w7VLsOpJq1qESh`BU>E4g?#ZhgWY!HftW&# z%GC>p*v7u#N;+@Wj{!15wyPG*8_ zYmm|lhOMXzOYpt|HD$5(tQ>3!YP$IWKbG~8x!rJommcNi@U$19wgOqlgA(i|1Gmy` z;L^N6zn$Mn%R*CG)Lkei>Svr>NQ-&Pzq`6QSGa?uraq?k%O@9>CxxLJiDi&LHFO z>xoXhroro0m|f8W1<4U|&Pax2FZ*gx+m=#yT>8D|ia;{6O)Q8%;sBNFtl1*0aDPc~ir=k?TZH0$hp@hMb<~_>QpDG?Inf z7G5r5;c!vYi8{r3X>xtQFdT~DJFKP#AoTtZ_Xm;po-4S-Q~QH)+^!Pb65%eor4y#m?4I^36>Qrm(GphY zNa*b!{F2t-?EeI8+5Z!;Wv2h%yp^nMjQ{KOe*jxn4yON4U|SOqBrd@w{ht3ZN z2S#w~^GG1fGm8@jO5Wb}|JGIl4(t^GxW|DHf#uCW%KHoS+hD*r(4*V356$4&@1F40 z0+?8$0mO!dA$;CC`9(2dz}15Z0A3IT@vOb~6tav#=0P`x_#y86gSFH)vHWde4)*RI z9u5In+wA&wToPz5eqW|&F9@xCKH6zC1IQrY zz&E(E2$u9q*Sv$c7Qi9EH<`dr$;$v4w0dXwbsP8qT>q2S+C6;z7p*0j`$uanEz=sI zAueG3Hvp{&W%c|><)e}JgZ04u@>qNQ2*}vhym`lfLF|Flw}E}+;D7*(n*j4ZL4P%7 zr?KGd1={R81hRap$DS*vzA32qt&j9(X7tDhU=LTl9uU~qK7Q7^+kdvI{-B&dK7UWv z1@l{5`O@eg{`*412e)+uCLjL>Y<1HA+^_p10sz|B*boW;0<56|yfn0&ekkkAZi0Ss zjXh3!_xktNLQjF}dG>;=;Tu5r{0`nZ1H1bHLbP$M?Y{bg|5)qa-2qq;tU&mouE7Bf zzmVn^PBN~j}Pv}v}7SPtpD}2tcZN;zbdoRP6YVt4o_^&5HUT5OsE&b!|+b<#* zhfr46FVI%v3a&jJfb&{6Ox`c7H`vb~4fV9dY2VQ##5_;TG5+hUA70@wY=i^QmiYjJ zs_S37<5=C_)R8O#`8u>I*oVtPpnsS6D1l|NRT4uShL8CY0TE;vcNO(S;-)ePI7ug! zu3Q~@RChx6@k)(cj_`@SQha}*UJ|-TcA(C*0 z5(*G+P#B4lFRa5@$FpEH&<8zWdZ)k?a3V1wxb)w+*x(E@q+G1y<41+h02;w*>>zVF zI<>~}H^KY~X+pR%KgZmO7rt_!*yHFyy&)k@Rj#{3uBIBBjb&>UE_u$TCVNeb9Rv_ zrWdBZjYS~jkEu_ss#oaF2C~~H$jA{rBzs!n9s1-wEcB#9z=^mUa;UqqU2cAFHEPIp#!Je76JCDi_m!0;kHw-D&PexLD$mV(?IRl4N{p(y)ma(cGpMk))|Q zGr7h?pno>N5k-H@bd;QhpxjCUu3C3_5vK`xl1UNZU2{Ki!pz5J%bnfyfP53mf{*Lm z=na+`YN@sgsd%c&BQb+64&_KimCi2Xl%EkSUsyf+I&QRgi8YWG6fGzft_!gzk5-M7 z-z3JcMKwsB*7%feFB%_%VLLq39ICy)M3zhI zvyGqKeZzz8*_kw)_RhHg200-pRPN1hd)*jE>D}_<68K}7`@MMTQmZ(gXiUr~N`c}; zBj96PwPy^QE-+Ga>DJTMtOz9bO+${Aebb_4Ihq#FpGr3^DEr0jSuE~;C1Ncyhbm>~ z1?1bBru4U>{_<6D87y}BOIW-}+cid8uJjBU1C9ku^?MFvlpyLkMD=uzM<&7%;!}{E z@Lp>E#n964;A9dgP|~4t6Vfg8%*oTR6*;?EGpWZkl0EK=$eelrYDXnp(}yVCLXXsB z9^#>4D^71D8rko5YnuVQ%|kr&9U{3K*qj}uhg$ytw+Lr#xP8<+YB%1mt5gq(7&#~m zH$N&?9PuYvtu4UU!jpy=VcV}?qE5Uc2alXfOQlc(0_WgI|h>&Zsng~UScsOVvp zy0(Sxr&G==+AdR_dRF2tg&FUJ0qp^@mja>X%DOJoi(^Eub%DBxcn8!*y~?^!k;Wr) zyjdM#?dGhe$$b(~=>1FcWkbz@tv6%Yh4Wz2@$QaE>YQ66Kj}iapr_~Pi5}b%Hz446 zdPQR~sNxkeaRVREi&Zc6M_EiJH=>H7f+^AU*)$ogUCt7Cl;pfsIv&MPvNy)78Io~@ zK58XOM&sU-2XQ;x*e8vWrHb6D>!LnoVSU7_xh;~1@>DIm={R{qEm>4Uu5?pF8g(2o zg0`~f_)W`hKhpThsQK5aJtM_ti)%^cr&cHoDx&_0NCPz$O7iL2Fw4M)WGSfaDD=|S zPNG6ux)UlSQ!60S&%8nGVq8T0tTTEiMluYdFe`$~kV#w-l~$s@{}|oth=VjSso)vC zx;E68;4P@rAtHM5`^APhs;7zLkh1aU`952K*E01G(XKN$mdjt%Lh0MldDhm}(RRY0 zVrto6MU4xCi+1xF25VhLfUw?{3BQH8cj^i^pGFEhr4On4&zt`9drTs;7L0^(F$HZ6 z&y-7|om_?dQ`wPfZe?+Go5b;=O7_FZ`j-=HS-6(2qG?@kWpN=%IVMUckmWHgk+w&k z9H?qx^efBbM<-Z<%hout$_fZCZVjX(G!Uy&9J$Aw;vRH%=L^hvc#vWKj}lSxKT#Ex ziBG3`0FjRS8mdOfH>qW?$`y1HTxpIPr^w<;1s$8M!C|8_@M_XROJRs^`<@hqgd&Qh zJ`3#`)w&vRH2$CPvVY>N3$^5Erzy#>I)U-gg=Q4Nd5?5Xi%`;2u4cSSk25BX3y-=2 zM_kBLS%aH}a1ZP65<^K1)In(-h`AvWOGtEClnamCh+DEypFi2H*8agB-^F}WoVGqF z;-x0sQ1cteAl{pc2VeJo@xZZ17e#8Ztp4uBXV^nM*@>zLr2|L`$!H1wO5<))9on4P z9!)7bBkM1qWWe%}HD#cO4W$l2RVY zOOW2+Isiq^*p*{;towKDtiyX`2`voSx2{${kmB+8|ec|*|x z?NL|=Ez)5qaWwLd@;4s!$W6M5?u!167=B9nwlO`S=fC25U^bVnN_2(wBvG$3!cr`< zd~x!$1AF$@k7t{!O%cu`zAkLyTv#*!dB;B8u47n;2ph(1qGKb0`v8aJ!U^Wg9Cu-K zi-FR&KiF9ocljbhf)7h?y7YKXPQxsE<+F`!b2a`a*_mqXMbI{#D2g*J&tJKATYV-3 zvM`fM)f?`5L=2D-x_9Y4t8X}5c_qV@xkmMuJF-}NNs2s{rUE~lSG>8 zub0s8)G$}6SSq>3qrQD2-r&l$nwXEw*geLyc;I>Q#KBG0K?U?huZCRJG+vAJ4Ra_+IUsAHn^(wN zBLJySfiH~nvG2}6!Zzry?11HHrcDUw2RNL{*iLj#&_EaE-O|X`%-r81k`nz8ipNVG zC0}c#nH>wrXyajnzV}!lkaGQ}b0MUq0uoo5pn5__(PPHhvN6TmA565}gt2gr!NEN) z=RP=02=Tgb?u=c0O^dlKFX0!LX1n;5Ye}CchbR^9xwh$QFUgO66EBDg9K*tfESz@{ zeBt%}sBLc3{LUr8%8AZ};fZG|QDRo^< z&R9c)9}){G5uUEAcLi{`(Bkwu7w9LbruvzQuf_q|!7DutRbd__nTAy@FCv+m_|-S! z60G)4$0HrFQ5s*Z7A~R9#RXy6@WIQG6bgFK8oCo=YYbjZxy-aw<8aIq4_Difb9l26 zNmEum0_v#wCMBn;1H~YuG2ESOo|@NU?0>qCr#4L8}Q3`l% zx5IG^B&9#fhLpT|_GiFDN^6($%FnLhD;Tn7==?wwNws4_m=R*F`>;RvM!ENr z?zgiYhaXTGrsbO*;ga}ZAt`E?=ERO(saU1MN*RElA6ZNmN-ag%EtFzn8S(YxVjtyb zW5+yd%!c>!djS%P6Y{hOxs|q(X!-DafiON!i%AHEDM%PyID)03mIMh!Alm(w7iUpt zHYZ61`kU`cCESF#aA`7@L5q?U%|;pt>;A7Mf~OTyUW_vC!y?%Qw*$WQPhT{6YPv@_ z%3HU&K=_=z@|Y)MG0~e!nv?3TN!8S*#%Uly(uc5acf!5MInFckC=YC>lB7z+?T?eT zZ47&v+^xp$X_C*ui&i{ZLAMP^m@)B1qxAXG`?CwB@Q4K{o3Ul8?*@pL+1UawFCqSv zn2-SjB4QP>hCB}%ZF9HufY0M~H+ym?H6d%r!JBy4(B+T%sXHr42Mbl7JCsHZUXpCk zBx1D{`_67jMlH(a&HCh)H?|NZmIluD;9hk0$L*Witk`p|vMy)u3>;d;Q$#~Y#S&bu zna0t8rqi(@->ywYIqCg~CY%mZ)#fO(s;{##V6)FSLIj7eu;`m!UzvsP&M9Kr4#M(L zy}h(cQ0qM~>B39Gjgg z@8dNU-9NVzFpp;psZdpCeC%TvWCGcKU>jLhmKPaFC@RG! zW~bExL57&Py*xjIwCq!Pcb81dTo^DuxrH!~47YTLJXCX!AjjsM{MmFeI6j_5f?Zdp z(Q)c5bvd$M>mj6-Mi}CPB-`fcNMlWBVEUyi6$2s zh9{czl%;c{j^>Xa!re*`#3l1Y!~VE4Ds~<{esA$PSEvR*jHeR;lUHxbbk`W{{Ro2? zEYd+bk-~hIU^bJ?b|fN50l7KYK!_&JT{(pGgl3JMNID}4pN-!b$3rJg3$I7jlB>ON zg;tJN^-z~XLS95r-hzE5tP(_)7<&sptm{i+6&EtXmn@a$9g_t!Ra;G62y2eK@)l$CWLYrlMovhooEOpEI~~>R&k-0A18^HOFy0 zxNgQIumr>h%8}8zsk$g*qoA3v4a#7ZRq@PHsXl6oVxN<#Xuy%HNiC*%&f|3 zQ<*D;W?w1hX5_PpPybTlm)gweOnULIplU(^6~*QzbqqK)&t>LVzzV!s%E);-UC9N* zklORg!1)-8I->v`v}61}9m$l>dmPHSUz5pO+{utBfz{BxO?UK^#iBViqEZ?*Y>6V< z^X~KKUF`z9nN_51Sia**EpnOsCwu7l@~f^5-8(@2m$#$KF(Phu?pQ5uJ7S~U$MZmF z5z@?`qFC518s5Y)v+d`yfyWIAyB=x521kT(JmC=9{NeQoltFmZ64#k*0h#Gmk41Et zX5k{29Qn0uNRcm)15$%@bM`-$ZAr z=Meq~ ziuQ)vp3vZQ&%FpF*mGe$Va1EvQiG^wB^q-R#F;EPjcqS#@@eaIMDTXfECltbMQ7#5 z5o3_-SE6^ymWEUeBw{T4fXR`v{ADDHjmtD?IdTQ95)2`p{a0;JW-unN_{U4_YC;51 z0$B8jj*d+0>jPmTPnapLPKFO~77%HI!ujQK{d&AA{GJkP)`?u(8);B_IQySU>rIW` zl`OKqtdE0Owj*VVg(E}A&$L&22vnZU{g3H*Wss(kV{>PH9WNdqCr=DP-*b0ec1^}Y zWNqsiN6SiMrNCWI7wX125;5-^fDlrlCYdy<<*IZm70zn45ReVn?x-jzj}4Vlk?DK+ z0w;q2&EK!%oKa@ESmeoOXmRFI$Bjt$2izp&D3~}9pk2M1WYe9qO?&siQHh4nSeUem zCn?YdFmF*M?ld6j;*A3P%&`l6NX zd!_hHBY5LhYTr$#{ml)_0Qb@9Yx(9oItMN)O?uWyS}b1(mB?pX$Sj#`u|?pin-}SnIgH1U~X{u2mf= z>nJk;*vWtFg*}S7TwS^?d?+=>2=bNk%6zQ9e~=~-bSE;5ZvUro~5#T7i=n3-3}a&f0d zurU)b<8MjN6X3$GCjCo8r&MGofVvy6#P&3$_3bncd%Gg?&Y`HLS9f5ie$_Pz>~d%i z7cW~9dpvoM=0BON>LFXPOMk9AGn5(`YiBZ#6~y|W7(_^2BnSr`@d(~C8EZDugTvhm z3O|p}t;3*OfGH|972S-IPD(T@4)jjX zC11caM*A+q&n>E^M5dQPBEHBUD__&?k;xOZkt2enaF^oiG=CA<-rN4(hL)`bfya@TuZSgJ?NGb%#rTa38RbiB0g zBu%@7c_10OtwJNlZwT8w<$4GbSVrE0g!yl^g<3b7jr43(NF&jhJ)$RvOu5R7bjbc= z>8{skRMJ$R=Lu1n^>Ju|)?KQ&sN240DK`4UKP5ql%OCNH7}DL6W#p-Az@>yKjB|R0Kpp#Z&xspYT3J-IXT7RX%rPGv(W;^yX!Cq)Env z<(I&iCpTcltT`53>zLq&DwKoUB5V4lWzg)CfIY!Hx@D~Am4f9rd7gom9dG7Wtq5d6 zK(^I4&k)Ta^nZZR^nd>ogl1r)`=6fhzt%7V>)-$R`(F^6fu806453xP6&JobN|0lv zi-Mv22Zc)_hhi@?AN+ZeuoUb=rgX4+mZ zGp{}#|0y$PPF%bXbQhKn5<&>7@+d_Esd9jLL{V}}i*5x$fIy({0(kugad6)Ms<1xB zq^Axbh4T-@LXG_#=Z5pcJu**@B;zMi2>7zAwdy9frx!hAcw_+ zk^61wA^Bqb6Um49=7+JN#Z7CIr)G6g6;Jj=1JPnz`}zh3V%^l(`gWqCfj0mX0jcY% zc$A_R=fh(m%nGdc=2mO}i1v|K-JG9OLxZ`yy50t4&3=j|X2G!ldO?rP5od$)^T=Ju z!EPONdx>gMA72bV2XTPBJh0wdv=PlN&VhybfU&@Fj6sER>5#3VpwPg3(I8LD%s}us z1dw~On0z>HLB2QPd3|+uch0^AeRtd5)`=9_={Rq0S0Rq4=N{nw>Tv~3x zx?qPTL|Dz`tQFgCOY*@L3HK0HS5T6Wq>k!}$&O#3bdbc@5AU?%?oAvY{ z`Js;X{)C!ygFGJ!{&~5~sTMCF-`kZ$AZLEJZ$zv8NJtww0=%11>3x^dC~a*rzB53%{aaP%zoWr1_v)B>kW|+#OWm?2LXYC5)B3V2Mc?A zisv8(z8itxIh5h`BEUpHuQ42?e$H3F5P@31V*{{nXEbACu@?D(HGKj$;fO)%`#hmP zd-A@i4t)e(XQ+QLM}HdrptG=krleh@eEFpIN&jtK!H0x1-O{83o8{Lx^?j95Av(30 zrzF^m{b?*~^QU8s6PX z{m~mhnixiY*yS|zIXhPCe+lP6^GotTRr}2 zf$T*6v%jSg{-$J9P1MG=ERj>S;uN?y6~<0;(v6us<2b_If;1C3{}hd8Ikxir7nSbr zY@+HzyZ!Yy1lxZ1u(is`sGS`u*}`-I_uZ-TQ{@%K7b_O?mzqhJxMILzzGEg}m|&gy z^oUrb+UXc=02f4s`xyJB?3r_nEGC+)v|glIZ7Jst>BDLS3jIBm8hSWe+6|C+0h`ZZ zz13yZ-y7*6$izB)R&Yxqmh~MVV<(sCuBsSE(=g;%AW6lxD%2WW<)z&I_%(X(5nPkZ z7hZH&VW4Nn%ua;^bJN}bRKI~$YHvQI9jybSdW>4&w9ZU>)>)u^9X_fkh%r821s6l!$@0Y?-f6YI=;Hn+9D^3Ph3L8tGiwC<8LDv4RrruqD z$AsSZNKckdroGNckco=Yd1X6xps9Vw&-~6(D6y?PYp!QH`}toB4}Lly>wQVRLe;={ZdWV2}j#2c=R++neNK`IzUb!>k;Gg0Oa6*FZIdm^`LLiA{sx&#E<6A-Nb{vv*-dB(Q2jI_ zIxEX18W*4UA|e&R-&tFq&%N`N0uL4qyo`9-i9?u;UvlNU)IIT7==fsmMUK|I8fP># zQ$g5OLMIWny6GKm!$kSXM+sGAc2Q_N1j+mgidN}JQOT2jTSZH?=t$|feP=LTmPz{{wV_-dKn^s3bHr}&c zs7xr%Qb(n?ZrMJ0HzpWiH=Pyh{a3tf`t4RGmKy_)JoL{K{?s5jIL7pRk^~narZj@@ z%)TK&aPa5>Z0;^De}8nK#Xr+bYz?u_vo(~UMc!ZJDJ>*m!{xOp#GA@L4$LnHZMR2s?iUEA%W+s?irK_Y% ziWD$uxJZ!UbH35Q%E#SVSfwgD>vEpf@BV>DaO?JF%1KlGw~pgLLpFeKl*?(;~jp9i%wsk+SbVGh0T}{|l`Go@@r(6XNu`09@ z4VzwKfXIK0m#FlP-MmTaEuX`qE3|3idm&xz@|6;j$Z9bED?p@ZL_lI22KI+Gg`Q#A zDEWkmAGDauR@%;}N1URfN*5-fjo$irQT={+FoZO5M}0Ke&(QD6oJFLgFpx9!%4hJO zcf}FNJ%kYeO5;kSrdq#UE4?i*Ic5H`<4Oa-*g9&xpKH6L%$HulOW9Nph@~JUi_U{e z^uprc3tQ$ZE2@(C1xa26+d;GYAZE-qlkMqhuuA*)WXMg(gMjPyG-Dks7DM<`&XQqY z;)1MR;knfWKK%)VdjC#mqzCqr>Sk=o{z65Kf;xNEp3#1qUsyX>W41A8U3Y3m7H5M> z^gY5X&JBUxoT35hwF1AWlH=F#%A-IMlux7dsRW{8K;Rf9f0Zg}K%<93&*rk=ZR7!) zGJE+Uwum7x|G3F^7>7w>gvfGO$U#NvzenKY;#qPcdf=lFM8oH#5ykoK+6(@7Y~+(> zk_)aF>pgUe7xxWwdsz5c_w~6EXm5;tQs-)A=Hl!F*RNAC_vHtb`wp_UnxjZZ$L>dk zIOj&Lw(jl-!l2MSK`b=3BR5?OxbXW%*m(41`e}c%4ws1TlTOtl&2r<>10hCnEOksR zu)uK%QqO%144&y^8HDc|`gS;)S4LB4& z-dVCtXd5-m(pby4K6?!O65l*w+)kuaS|ZJ;0j6e5!4@t%5|p5u&9_9CEZ(mr`9l!# zMaud)wlE_T`YM}qtDV1x0*}LspTK&PLZC_DhYMY5W%np-cTzZ-nhwV&6Auc~Fnq{P z0alZf0-!F5lsP00jB_~4Jwt%=pdoa5ql3G*!P)s@j8^yU7j>7S_~evjgJan5N%rw3 zyak1h zAIg}jgx%c?&oj4}MxrV3o#P0%!g|HSVGNe#Zfo)uaV|y>q81oQ%ueY4!aOrmoDj#? zHy^fMc2EHqr!FlH00c@r;7rmURZXDmjxFykydM~;J^ki=8AMR_BNQqYd!|`e)W3VYRO+MaB z7H)O@t2)0`N?=te(TAY~qh$rM%^Te|)1WKrjIa2!s0oa@JDak=HzGoebn zsi~JRq~8hy8LPSD<*P+fjf<9xE&8z$Srbg~t+MI|2 zL45w6kZ|c!Kkz9(tIE;)MZwF$oTlP%18X8bdg4SLB#njA%`_+xl_9F|K5|!tF=Dkgt`+#kqG#^)LVEblqx;O9Lx?CQU8B`A zIg}C4vL=TwIgNFSr4B_8n~$2*NyA14>XW122sQ<`NR*h0TC5l9sJ5Y&^vUXU&`s>B z$D(G~|F+tV1f=gk;g871>k*Uy446La;Ke@Sor50(!NsGidYvMy3db8vR$WmkClg&8yv84jxLWM<|{+gL-ULp`pZd8P{ikF578UeSj0s z+<0X+WzgpD98}^TQSluEmk&~dF<8hgHB{}H$lzcJ5WV)@C%XIomF4xJ?#W{2&^$l~5P9Kvi z%i508AN|c5i*W~m$f!erVAeWGx5z;&Yo9m8oUgKE)Hqi^tnOHP68TO>t-ENophQyK zMTk(28Zp0lU)y3LyDNfs2Srn3gVGSJB+RpWw!~{sMyWGPH9l8Lu11qD@OFvy8;B;F zjJXYhId*<05lt{q!7>r1BV(}^yIP+h`?05rbad>fu$Aw?Y)b*|$l`zl^GCPNsII2~ z=0_H+DnHG+7{c{q#TkbV5aO+2gf&OOg~9Yg5W?0Z9xon(1F639A4}|gPSTz2Ntot6 z)!RlWgQB8tV*RIS!=t|dFBNXpsl@w2ZiKtGybb#wMeqYByNBYm7+=r$6A>nqf z|4X7;(Dg?9W*O%$$$w1~9X>n6)QqbNc(v8Tx~Nh9f$!w$?AC+Tl0-bRr6{)_BzFjm z1sXM{5;r9~%h~2mCe3mnN#8KjELNK0WtW^}@dNBz@fyLyf^%^ozA79-6m4QIy=1YK z!4zJnK2d8(P#!#dB=VTYPwO3x_guwl^Q3h)ET0v{)Fj+a2-cRqiw_5}>( zzH{nSIT4;RFeP&vM5%m&RmAI(X!94f;fZxNqXnHumC`N5qqkw;&<;0pjt|lL5pPdurymNOos!ij0KP zHoY1F?IGQK#M86yo8%}<8^3x1)O^r4r_8ymgN@63Z|W{w$|bX&!eP|juW$V>YKr8< z+!+eTV>CJp&0xMyHi-ao)hr(@{KRG($Ut*OY(~{s$emui3Bu(h3xkQww!|^Su%x+= zp{?ZYP>NKMYaFhqJjX4^L))DdiTqlMv*2GNXJwO;VYm6XA7-YUo3poPQ!%Q*nbPN` z9al<1(uiJN;7h3Bm>4)`lTygFbJYaC?1~|@r=pgcV_bBnsuc9FJ8!CKV#fb zYyyEBeT!bNYSsyRWG~dRM}=UwO0%aC7pC6RU@Fb)rieGYpV9fyt&V+2L(UB2V!OQ* zvQ38HD6VZrE&1B_jt-;DLV+}5JDnC`vsbu+SZB9SIlnh~Jby_ZEcYI6b_EiBGS4?c zF|R*N-RuPn@>6jIP~cb@*UBhdAe?TuN*}e)MGCp4TAXb>>Hiuo)%Onj5`lh&8!6kq zb-`vX^36@`O}?_+Jl0yzL&a&*I4;q3)t;b#%f$+y{Rp>BdOTphW&>>N zg_l9fy9V%uJrB{yh&-#sG@glV{?R{k%jB}yRMyHS|8Wm@7y4cSXhD`}bCP@1Qd!cN z?t)Px$gOx5OgUL7kY>b=|15o#7m+0KI=}MSD znC*_sKj7Q_F1{QjRynNOIL8<)%?5qR$Y7fj+8W8XEoO2r8+C8X2iMX|}Y$~q(=ld>{~c&(UmtT2w}9^2O>RQs-oH-?YZ zSMJafXEPR5n#kvR_y{?kT@`k-K@S&WI^EUx49j%BEQug8_vDg0Bzzjhrhm<#Y|{P_ z>v1NYES+OfxKwbySaG(EL!~~_+5K|I)cWs|8$5)cB`8(bInQ3lD)I%$wp8l5a`(*S z$&FXMDDE49K&pHGGeZq;h~!LepU+j`4mLou3Y_=t5S^`maU3 zg^A~bVhWTTyYnQ!RKIe}fK{6&l?>Q9yLj~9awE2pPxBxsxYDUv*P0<)`br4Yzduh% zx?anrGY0Ki4B=Y3_Wp~EgHG~~y;G7!MyQ&R+b>6vyPvQp~*z%$cO$Ur<{fm*lJ99i7*XDqSq-^;v&X zO*H!iG^rRfet~l1E+3w+hbE*O)f|NIT(+EuchdHqErWsibdCuaDa_(t)oU`-opbf* z$O5-h0ps9Cdr0-;nw#=-C)RA&rzRQ!pr$Nv- z5gSmhFS7Qs$#h4p9C!|wvzE%q#%^TjaNz54%)FJtII5X{3pQ)>#LThDe-z)%+Bx#t zV%Mxx1lwRQx&68`0N(63glIxtrfF@gKnQesp0}L1Oo}4dLa1I#{utWd6I7YfOXxO+ z#O!n8GaJ5(8LrOzBbI=^P{ByJ;dc~eAjc>Vq^Eb_3v}uw~rkXtgJo5dxPHnSWbei3)2Qu@hvJ8)Ioqm(RpM&=My8DXZdpC0d+u zL|t0bV=Ri2;lQOA5?h)lchERm_qi~SjhPSoap~RcH@hu4bpH6h-V+FkQ)I%PL+hl( ztEr9V3&@p`XC09&e01z+ob9WGB$3p3rk9&%#n`}B`$TDAyWoe4gSafkLO5>iQ$xWs z5SD_>A{xekaN8RR-W#a5Dpf>)m@4dy<(zRbn7P?-^0T~PysN<3^`0^sE9sB{ftA>e zpWqTFn5d@tHrK0EIovbB#k=xcmbO$?$X1`5n311kYYRl9svgdsZD1FCgp@eaTybbm zS9p$WHS*p;g2u#;zHugCF-qV0-8*BS?u7@MG!YNq|ou@Niwz9EHjIk_el* zrKsI~p1HKOh`*wRT4x20ey@3X=f>pO$xRhIi_194D>|4kM_mz}%`;^zs`H58D}03E zt(U%<52~Py0EReI*H3My7ype^KP05ID&r63YNkG!M6GS89gy=#uP`GC^vOvY@`od% zuWklrg!iUqOttByMfjWoF}`{}i=;c~*G-A`4#gd~_HeVi0vC-y&@9LB?mBl`km{1N zh_XeO@o8=~qlEh=^Kv?oE5%CBeJH%agn6vxsqe!i zXq^gaz_)mwsU)8s~qL4^VSYabt%o-krZR`t=?mfC!{O7wL z#nZivN$Jv)e}6^|JXkHUm`oo@Ur;7|__AWhs%^|)OVj`CdPJp_#mZ*`p`69|++QVG zGDp}2khfc&s>&p;50;6`L0@xH7$yi>aTQ7-x!n_m4$E*H98`nMSa;_TOlKSx8AW67 zMgxaUPX^2kM&38wC>`wF>a|eMhhq(TYL#K#bF5foes<&jB%w_tG$|2in%m>2iE1yr|So(pY7Sx zqKLyWj@W=<&&O&^={;v}>{=d6{PlXPyHG<-7zS*@$^zvwxVK0U#Yz1PE3TP^ zg!mc|RP#jj&$cEzZpmk4PJq__VxyU6J=J(IcIbEcfh{IMxBpLAl>R?qQC7PDZ<#V3 z9TPpnf8wHa^vulvZ=Es>K-kRE(a4?vAZ)4UXe4N4U}Iu3GhO6{Yfr;I{zF>Pq_Pcg3<)M{E z4M;S-)qfH=oEnG?3hOjbk_Nc$#THCWovjDwF-HU_>lc@AR!&aJ8KR4CD()<@p)m*q zc{-~G@RhbSBSRf{slX&JuSv`g3?G@{(WNDzcl`YLcvxTmWDvxz5v|w+q}4C83do$7 zEVqDa7U#CZ)Hgm1_m-!rjz9sFv65HX$9(Y*#Gq>_kM;JhO=wq17YXZcAjSs-Yh6FkV0&34ttNZ5W9~i)U4T=A1c`bs$2Y7^X z_3jrT~9vSY#fU$D419^3RSH0QC5i-ZJ|ZSP4A#Jk<;OC$hX zf`goX|LFk6X31Ea!2I}OIQp@D`!RUGA^&ly|FIFDr)_Tb!J7Rty8EH~TL-%4{%Lg2 zuY-A#q9hyGNe%YuBh}>RLt9HYi*u;|(xa|sl8};w1gf$Ay(JNwz&MI)S`A{)-0+^j z;4{wTbCW>>1*ho8>gTOP2W0Hb-25}wMV*#5HNmw1$Un)WL@EuyKKUF$^D)?+kp6Ok zk=JDieY-h2*gXbLWo1uyCFqg-2Dj@$+B1@v^1Jqt#qJ#k31;nS1=1dW0#@b4iSv<3 z3xVvV{ML9R+Xt@||BP~71Foe1A)p1S*yIVt?xp-ebPvnF{qN5!%l-jSZTVLKD{$rc zPi{);@1I;uo~s_@A6WV~$U9Kgsc&ITfH&YJdW+|Mr^}G(2h(#5_Z9GJUwPEC8_~1G zGpB7{cVFA$-Ujkh=Njkt4gLmH+5F=VSX=!9)maXH(&+|h%)q>ny-V0!>Wm`3sW=0$ z$It)!gw%z9Cxkro>`D-6e*69~xiMghj9{97*3|$SUlG3#5FkLd{ESB<9FQ3LbT8U> zn={nu^jVIt=>D`OG-Bf-9M|=~gid?OD+pslpR3`g98MHrdaM=gXtq?F+h%9P9^PM-5Q; zWjQDC&}~n8X=Ouz>&s^$WpS(Bo2wGYElBxQ`mbf3{9J{{ylohMq*O{~4PIGh?$A#O z>ICyo>acm%qE&%p#`UwM6$4jnd^wRhG*0fo(mij*0{m;uX_50&R|XiDmc7)*RVt!Z zZdbT2!IPf^tIx$!S>Gwv_v>?Ii2wst|NR258&oKPZ@x*3HeOrqIKOHC;lWGiot9Hj z26bhmFl;8MNN{3#UWX;UaI5+j4m=yZF!FDFurnCsy|eJd{_pz9z*Ad?M$R6G7Vrqq z4hhVA`IWyszq;HQe)wj<>g@9;i?1o!J3IKYlTBq<73MK~&bSH)$5RhSqTF~EQE3F4~~e})mT|v803MWKBbP5=zZ%#7sk!<6LTjB|xL#xM*J)nK!$lo3^EvB6RIr$kg(5+=k{b2Ni__25Z`$Az z_r`=X40hP+bc^mtOPT(gXS{H+5H&GOTG}Rx>^`i4JmtD}hyWgHPn!hj=0-q^63r5Y zQKgaeJJqRlk3lA$2bIPe52fmT^z zj@X+upuq5T+B1jVXgXb^L!&jY%4M~OQQ6L_ydnLJUBtxOWaiB@+sA5rFxb#*Y)OsY zp+1qbtpTZ>a*u8hN4P6jA-76##BaB_z4H0+PaZY8W%;Q&no+S$_Vsn9j+6g8DVp4^ z0i-mxyeT;TI}6<0U1@*g8y^Ml+rhJHDj7tPa93VeLp1V%bIcUtTcGdjVl>xqKU7KP zQ6T!2U*aA5+V7zTR!yrcfVs}I_>uqD|nDUdyJ5#f@Trl>Z_l^gF$WJzu;t|`ae z(#CDxy5B5t?mwFY-2@%g&Qe~kPm@cLP>1uxbA&_<;|B@_PuUmX+re^T$U;3B^}naL z3@0MPt|1E(klIVYLUoVUIw(-4A65V>lfn34{`^J5Ly+=Xt+RIIqu|ai`g`sP3(C;} zQSxnZ*Ni>Ec$8YGdzRfv6Z}eL!g|N74b%rP>m-_X>TsKGw~^3nyt!O$*^@6yhvjKu zE=l_tif21Zva{rI9+Xw+f9~0P@9-#0rHCUr!37f7D`R5Yceh!& z#cd;`+A(!go>FZ);``cOX}T?c(})k>mQRk}2^7pNBdcx7b$u66{T8RbI&xV0J8FO` zwUB{^L?r!(+u4r4_;v|27xvW}^%)rXZ$lS(RZb>)6;khp0&JX%mvV zm49f+MrBxUP?&3sKXg_>h#gx*r1Q-1Hp?6xm%Gv)RnzU+LN6ekV&1rV&R!pTOLZhA zg3#429ft3#fkX`7`J~XfLT%FIFOAsM1HQj}L*}3#&*Hv*GK#CC)l4L1fvGquwPo~d zixq!l1(7*FJp*@4vo)gRAq{Xz(1;VvbS*FhjRV58-u_4X#*;+q)y|( z&7Ko!@s5v(!%6G56;;No=A4Dk8@r#X^sD*FF1(^&a5}U1Y>z~s;NO-Jy}_=$;*3Z) zOD2*>m>-6Z96cjA&guzE_6QT{>e>UMg)R3gU6pX0wEWuFJ;Fmsw>o>HVafx3dE@Vp zK2&NnM_JUYrr(+*pbM`?oZlMv?&KzN`E!7Qb3;g^U2P*D2W8P|^mE_hx)x~h2zKQBv)(<*_hTjqQfFMNCvn((%Ol0YER#3k%VYTbiB?mKm?HVD@=U=S5{`3KcaUr02%?l#0|3MUky za*9yN8}mFvYUFp7r>m~Y1H@m`_?@#uLQU{``lFs!5^1uFn7Dh1qwfrAi+eAuRcQ-k zROC^32C_L0z?+~tAz^H$CNwICOcajQr;eUDw$*ddG3L(O6D!SSwCR35kP{FXV3b15 zCa-AWiL1kmKU@Ff7k-_L&ff*hlSh5y$7E$vr6Y9xG_>2H9w zmDT|{IhUgKj7y5YMCuUDxiq&iMd{?cY5TPWhi8k1SyJf;7FW_tz-asLfMEaTJXWdj* zkL8uy5h{M=5#O|oS!w|RWe>+eM#h7%_m7)r)!_mA$VBdxu@!hYhce64^ zxh6@L<%TllP3sN$aAeYB|HWIAH~`5xwgS!_Qxzp+5G@pQ`_mnEINus*N4;f!1y-AL z9GqtoAMSuK24bZNJ}bIiGg;iPQS@@EN!NMzjS8>c1}DYy!ZE*pozwIZm3yL6VF{$n zG1>7l8h@!(Yr_JyRTb6Rn(Q%hQhf$8$3faXg(-+}1pxq$ag`w0?j1+$Llne%AgR8l zsMeNHL=0V5@&-eLlF(Fz<{TWY46}t@Jb8I(ymC=#5rbJYWRvLTL%YvEk`$7!WC`a( z+E*m?8FMXTalq0WQS?sk0yukOmz?$Y;Sh1l6xgJS%QhZ+{;6>hPqbq145gLeD)Vya zLb9i@?DlK{nibIlkz0r=v&^Cz+B?!xd8I0H6_E(UcwZRgo4qTrr`~yqH#t~tJZo{S z6Sk%NC@QhwDThNFUHc0jnu!jOCKs8k7OG;qB3H(|a7r7W5zPe33nzBotEtdNO-y3y-F7 z(MF%#D=BzFsr+S~bt0qBo5C-M-Ar`20%I~VJgky>pOnQD*UvUX>&y+q^9fvil z8dLTT7FZl(e-}u%V!t>Wj7LgNcpmvudSxSbvXzey7O~& zBt5!hHOAyfj=;p=63Te`ah*D+uus%bi|PG;Rh_t+RgqiA={eE$!f+s)xv`M+F4N;A zTVZUW<$teMu{XR`OS3+0ajeNP<0>N!4aUDNIZV9!~59ccGG{UpHHR;p1aHWg0Go#l3DEJg`FnC|6Y?Hc;AEMFLzu%%1R2fYTvwHvNnP*tBw6KGI;2*HeTSW zst9g!$*Q%5xMwiXNUOzlqb`u9xmVFYVfY}!%*6UD6%y9{F;tKCyFzfl(Cl3;R|J|_ zJn}66FM@{Vl2G8g}7?T zWc@Zpn^lWD+96L3{-1&eIBKB%D9hvC)@jQjD^Z@9XFhO%xy-OC!jjCSLE+ zDgqb~TNTPwtYDG~)9L8_fm#pPk>xI-+=Q+WgKzb|v>q4i9NH zZX6XWiz`b?QjJgoSF-}nOLj>yjwo#%EUL1JP#xt&n?<|b58G#N@AqQh9qI=lzZ0^8 z^eqbWCjSO(#a~T|@HE1=J`q0!Ze6O>W&$LKjb~tzf|e1`~^IP`)9zw zm^`}67B}TuZIfs_)oNTvV%jVD(sfH$Hic}`eJ5X*yWBn}Ox1+I&lsHb)7_I8E^pgK^oug0WzRXn=Bc47h=bXM(QsDf(j8{*V1orAF$skz5o^ zYCsZ}^7p@dXT{H#5xNPInIKWvm0~~=TdcA) zdN~ica`Z0Fh{2Z^u&umzTP0Qk6c|DGC+wVD~kATVazt8#{ z-b|17et`VFk>#8o@(U~s{x+z?Ii1X-18_xQiu{2f0%9$@P9YZ7jY_PcCMfm06DC$o z_;2V}VMPbio%r+Nl5Lk`>SE(SWmoNCzsibpBv+Mtwd!^~vrf&%Y(())N`}GLgw&VZ z*mOM@csLWYk^VI_qlse2R&J!ODmNsP?lR3Ev4amtCyPTpVs}LT2&soB6D@nc=YLgK z3(ey?E#f2l7XQUwt*mtczy#4sXX5?{;(iwyIyjnegxz%XZB|lQv8=N5c{RF@Fs+J< zNqtDx7Qoedjj^4bbZ7Vjt7yIp+zMJ`?&Qx<0m3MhDI9jWN08`_Cx5m>$d90NFOfRR zxgF3#j)>v)l5C{1l-sJ}*sX8%l6kz(;gZvqa$Me=gg|k}%HVbd#c*LVs{2Q%3vWf9 z0Y+}f!8@`U=B<`!2V{HU&07Psv*5tpH$;L7fOH2tAySxiNaIM%DK6KlGhQc0isoY- zgW7{z(DCw#Gcc6cD?mP~g3nkcpQc-MR3}lecK|TypOn!|u~H?C?mW{YvMc;N?qhUM z3hyGGNhGYcM=FpSvZBq<9B~kpo69%Yw=rcL={g8~3UOtuyrBQXoR0AaCkMvIG*O3| zDz!15qTKanO|xdl#)m84WI$82GGR!oVN3IU5V~m&HH%2PEo@=Gn`OgKXcJ41U9hl( z{rPO^HQXAmrZ45g(cebtkNEtH8#?YU3d(>GZCX7Y0rf8GgSjo)2Gw9&g5f+2m*=$a zjsDr|un4u=w=ud z0*nsoM)i>~wr8j%gIj(D5pQvB!gNSh8m3+xGHy0(>#2>m1^kPbHnJZxXez zU8d~8g)b$yX7V#Tuy+*rr4TK8jVcT0Mj0qd^Ck5mbtL3kBX!+_j}7`5>hI2vjc@j! z#wwDum>7@N-MZ%(Z*q{c>zsu;^0Qa)Zy4%A0`_Kt9(?QsJ|OILROH-Ax94?cSQCXS z6njM+DOk?PFV|oQyMhpaOWOXq2THWTy*mM0m2gz5d}vo<=iWbF@=xatP4an?*Rg!@ zEhO1|VS5=mQsrOCgJJf;QMQ=DJkZ6}hV|2~;n;~S*Q(pcn%BcNLUJ<7Ih9gJ{CAP| zGd_t;_*f7;v+~fo)%rx~>v1X0UO_k3Inl3fNXo~-+G^%9%;sjCP%bn>)5%GY8Zp0UX9%1K|nTq-TnuQR_Z$wjDiPUra* zf@=qskJeoHjm%u|EH(jadii1l<)RC5SawzFRq7(L_e~tBtb*2VsLi;?rZlz!#$+jl zL~%{v!AQq)uFPx&{zopOYlVAtu{nBLq@PR*(Jz8C^(oMjs-R89?X2*{*{k#|_pmEE zFYJDw5V3u1ueMtucpOS*lFv)-Pwws>B?7o9X${7QbbCVhbXx1@!KaCSBoCUdBAW$l zH)3t<3J&uY=L`Ms32BkBG1NxY5l#}nplsbSxDO+K@+Y*a&E?rb6B2qlOgDn3uEA-w z1S7=U9CdwE(T78rpkueGkf9{%Cu6+l5x!iL3y+oK*$RWQ_qE%YGD`=^z|dtFO62<@ zk|ZKC@HmsUoSyc}5r5p%yPkLQ=s_&E3fV|cvG9}EMV>M0+{NUc{+F{VZfvcR{@MO$ z6dhw5yq9k*KHL)r6`i!y-28L+AHE>N)D}?}S2Ytu0GEb?_6|1KH8WZG68D8dVSw{# zfmU11b9xFJsvgE*dfS{4L^_3`O~*19i4+F~PMi*d26)*lPrD6_LyBFzto?TVr5J`! zi281KN$V+g50>Ki=Bf+#H}Hp2pach1hORvq;k6Rg1U5wNN9W0UXmN=4T8 z8t(!EE4U7i5fDJr`hr^LJHr46MtE2%_c(z%J{7A2|hP-cgc8V|BGvL_@6tI1U+PVh#dH;n-WT`Ah4Q&=t zHUhYGyV$*J>cG^XFFU?4NItIy|J}fXQm{x!##q}oOc4B?PW*ANg{?!X!?}Y{6qKH< zA+jHWwTs?~HzdMU)vE@$Ci@Hngu%7SYN$vZi1-b*#tl11Et<-Dnw1xvMB@J;$Dk2sP5}(}Nwe`Cm}3&AT4A ziJ&G&`MoIJHNK5OcDrL*dVQwKaIQs1Lx&AawuCO^tGEv;)xfjcQ`Jv4iO#3S--f?> zrBs0kg?wna7xQ$E!c4@dD-kK1al+2E*}$JFTtg;1S8;K5gavtxaY;?Kw5 zRq=RutZ&SuzA_=^tz>~+cih;#=9!>JXd?>`b*}+9hKCpe^z^zcOE_>6x=~!Ce~ZDB z^62;hYrgi!=R4|c_NJ~GLwboZMOH#6JysRR?zhoN=d;J_Q+;s!Q#^12isupFoi2F} zXl?8Tp;t>z&*XZwgp?vFHdm?zSzC&oHq)S0{-nY#byX2G4fW}6ptUT@1|%43{9zy3 z63tK)u}+OB+4nH!Pl4Gav(i|Gj@Jo1qwH!cCU8<+3+*LfnyoJ-SoMg?hNC^DR?#!3 z)+8xWu@-W5#)S%4hR^b++&`hUwdgXHQv<hE|)YXiO%18B6MhN~N8cPc41>OJHd^>bHc@k^SVH z=HN?`>Q|^tx1-~}o4{k47uklfh}hG1j%~R4HU^CfqCxt<>ta~E$(4Hg5FXC+(%C-B zE|Zi6k0$us%Y19zn(H#9INRi6vz$gSUNZb!Q$o-2jP<%qo0xyEYFSk@PMmEabCU)^ z%Tl8ajv1N z!*!lNVwNXojV+Oq5Uh()#RYbbkR=d*B=LI7NRvOP;4u5@?F0S&b}5tum6DFWvLF|7 zN8Std(Ukh*aL05#P8s=kVnPxI0JR3EW`RUUpsb4DS`rPF*qjn79!=w_qGI@{-~C)q zOLWj2j;y>OR{vEx?5SF-hA1HEfi&pN^!sTT*c;mNYU$3p*dwV7Q+495T#mw8v@%{q zk3S_%6+95$DtG{x@K4z=36*B6i!al;KgP^Rh`q2p2_IcxJrV{Y! z)=|hy&)2Rq$uzo(-sJDxOIMtsskjVQrd(!^&V?TZ65|t*!@nG(yCaQp-7)7Si}_P! z4anwI(K+^19ertOIQFBj-+Bh_zrggcD?%(DplA3>8SAAe*BPIedW3O~5amLix2^D~ z^-85Wit-nOf;P%zbGDS|M#9eKaiXfebJtC9jM^EgC`gM|(?$hKa zlD^DHNzY`!mUuojyciljH>kozJgf7W<&a0b4`_S@?I%KRtALt|5hmaK>OziQ-kmhq zzlNFby*Z7!lQRx$#ej}yDv&^j;p~x}u(w+&sCpGh!mAy4aQNPo*WB}wwy$OS9PiHq zG_pTfTDUCUP9^bzsgQ~+c&Sp>CttGFNhK!jD*sZ=hQv9xsi%t|^Vg5U)Dm+W)DnN$ zXbC-x1#}<)lBQ!2*uHhW@KV)`y?=CDJTf-Qu00LG z^29}a%FXzQW$!zC<~boh3G8Wof9n$t^2mN@DVPc8oRdNiN_m5KiK8AXl+#$XrY> zq+G{b=}9Ot+90bL^0*s^f<@|71axWg_gpJqw{ym?adAP#_Bz`j!Xl6@>&o^8RMJYR z&`2~14>39C>h7f%#@^0!|22d4Ijm$~;crA%3j&r)gM1k|56072iqwLx-&@;Br99~? zv*+Eee@x`j85|U5=K{nEA%lGMBdP2trPa{EIPrb9VL6RO^v$-_>K8B~RsHSN*)b&g zNVAA))pU;d?c(EKKT(e?)?1{DJ1{TdNLfW4k%)ZhB;u83xW~zV>VH*|`FcNmbgM;2 zX;7A6vg#i<>3UXRotthI)^fdOA7PT%2pHvZovn@*3Do}_bUUlGiE?bOCL;cL)}^E5 z^bw4n<>eC=SjANx5X;=ck`YW$Yz0F@!uWh)?(jdSszt7tx~xkRij_JtV?lUG9cQl1 zS8ft0h!oA(oC&(6_zqLAVSr8%q#XyP>o#6bzT>~{hXfZQpP$#B%gzpiv8x*qkco%jikKczrP!%}e1P;9L zK%IP4>xj_`D}0R|Au;j77FH0mh|zd!7jdKsgrb~G#V{<0Eq0V+IySv8t4qtLeA8|Q z<6N=9S8{?<^XlM#q>^5a;B@nMePcPQk@%>_UnTC&ZJ_?CabzZ>$seQ4+-c9#496Z4 zSMHH3E=uz12?~=V(ER>njzbKge;DE<;yOJEThvi89jCCJ&q;k#8x6V=&r?PvRu=C! z`MziAOZm*m#4nDgLLC`^o*g-_hTm5YmJbaw5ipGRv{OtW5x9Fox`{|jU5k_+fGkhb;2OwqKk8TlB>!;!G33W` zlPD-N2R1*2jy|RT11o)bR^a408tZb);98Z6LFZ+5lt|rlg z2*c_qM*z!GR#fwgu7?Xk^)r@>r3K!pv%;(lC@q$KASN?aj3;@0smU93?SR*KZkVPo zVT(ZxF^EeH6x40|$dmZK6gwy+?c3Sn{C#Sh_2n*+?NA*CSUkNdN<;GGG%8s{BMpjs z{d_$r2XGPubUO~S4rUk0y>iY&9h_nz@!O^}%DEUx8Xlg7^N`o=SxRiSm^luAT7U*S zX<_u?_>VU4`<-DBtY?ln|1uE$#7v>;aHUQ~x9_kQ4W-bJ98qA$zrBA|=GvzO2mjOk zTyXE84NoGII*_$SSKdL!jHPCa56pYlp(aE!1oq2yJg}}!(p%b^4B)wC9Wsf3=r^2G zc*4buCL2ancE(HB;bBv?bKpCi2BUaG;jGq7ZTh<%_a!0xoRFuIoi(+7?5SCyj@)d| z2Ws`e2drKZg$elTpk%4ly9HDqSetk5ycX4d>;ievHeF#SZ@%`-D*K{J-Sw3J8cwIu z9wRGMPr@2i-aDp1ay9;Qs*j=cy>rS=G!vkW^IjmGuyDwUh(ZF;9n4ar;z#z5yjfIl zw57f8ek=b8RQ7p1yd{V1giWzJ%Lhn;T}MZD`^X=kXK;iWH8s-{$29&+jtC{yzGo5G56=S66{G4UX6PS!1cyzBC0yN@w9`rGRqLH)MJ zO4oF|S|2D0ZUSul%fdE5t{E)zYc^}71k+U`;y;#!xORPc0cYzO)+1$8QDcdkLZctF z4g5oHHS^G#v69RW$&qtsjq1+_tFS)-2_&QaR-E2-?_42+R7AH}<=&pU@xq}_{s0{i zW%2EE*v0)FsnVCkxGl5}VUUQUSon&OVIqty*z3nsm_I6{%Urwpy=jca;yaUz7A(xx zmetDO!rT(@=#W$bkt#e#O4jYvx$xf$Y^w3xIJ~-HQMhnq4xG#EE*96!7h5X+Y)q7%rA^aqU$A2x5~#Nxa~C61?D1~AH7YV-j+L>tDX&Bs zl8D|fbepL7uO$T9m(su``##NOs(D{*l9+(+mg9k(DNY<=PWl2uJQBqQO)pvUYtoM^ z%nct%!ar10;uXYoH?D9}CGQ!DF?)b8owb-vm;tW&2s=~5OlY} zsSN7(+ZJt2|A|>$dmkBzFtsW#irDt?wZ`<_#RmQ3F`w-BXgr=Q))jE1O29%lecvxO zFX^kIxjj@Q4Li|+;YHIhbz4H6j)=0j&sfKQh|Pmw7=;YJwQCzy1ilBITW@JC6&rs` zCt(AbMzoV?&}cs(e}rG+MG?Q;20~3&x^;5@@Vzqx_Ne)~Kx(kSvDJPmP2^}#v#u|G zvdH++6bHpxs6$i>*2EySX#*z2NmuZx<-gi`qD%@EP#^3!4u!jr73s5*O(161TAMQ3 z!))9-&u!Z{*?fabw4~X^J`Hv+`=6|0oT8Ctv(hNe@Cv1ck6mVyF19E`pNJIu$1x79 zYS3sJnkVm6GK@=O=qz5={pMHII!->jbhPMjeXw}jxHkfW(~+21=-}VUYT`JmnADHd zIk44`FNauaJtbc1s?2Is@D_b!{2k{aURhY)rXalq+~*v@WQ`xz@de%KRNL5uMp}(Z z!r}KEPE>!Jj{x?k<<=%fFeH@q8V>5#CZGHs5dJf#i^yyrm&qL2-J{0X%xjjVy+Lga zY$hz;$(FCB)8lfve?ijJ((>+>#N{uE??798lmh|8qP0b6pQ+zBRG(m8El2RgTdk19 z7w!sSwC+|}asZ~WD=Dji##WWRyjpWY8Q?j}I}=vp$ME>6E1Ye6FAFUeuattugQFqT zOr6RB=Rgy=+$nO<^dbGmuvf3ciR7?HZ%Jd;{Y~XP2`ZZ$+ICwMo?Y8hAE(vC+=8`7 z2E^Ngv(NvsLQ9Re;bRu-DpT7=5&_A-r>358cPXQI#}P`@CuU8%zz&hlCh!(Cx|gA- z&qEre_oiZeqrAmvnKpNL%|%7rS#tjPH~rXoHpdEoKu4kdbk1Jo@f4N` zTYF#f*cnDi$Z@Ee*@Lv^DW9v(@_ww!&oB?YUA%s0R6qKlV)`>>wYA`si^Rw9Q5;N4 z*D2St3p>>@xjt5;LY_fhcXxc*V_*zVxd3Ta;;cQ)k3H;WE<~vuiK;CVu57Dl2~AQ? z#HqDg{fOE*i*U9&%mc@Ll4;a@3DD(Ya>))9#NQGmo4LmCP?s{b#X*CPH}v|CVEn_P z@J^W$?^GUaj&9}IlqlL(*O>XhYJ$X@kqPt7Bx2M1A*&_kxgG1ZepEO6RszfFFoDf4=b= zvD7f+csxVo*tj;Lx*_+m-8N~933=e87B?#sV0#{M*(+>VL0?6wQzm)a^r#ARFpP2r9xM0*Madkp9kzJra}Rsiw!-zB zhawx7d)^4-y>h+S5Y>*qYqqKsGRVmwUaE9;627mHMoW*11SSsI7VpLsLGck2!=R)9 zC0iHCS+oanxDLV}O#f14^1T$RPJFsjwHFFgc|M#u5BMAeZOKM&oAQoJMQD9iQvG7* zE)SdCHSc@UVv&mSU(>u{acdcgND~$oNnZ%le0e}YJ@Q7m^cRYg?wfCeItot7o_f*S z9zMBVu%q2o0%16lqK2hU^cf;AMAh|>Sx}p6?pjM>4#g76PA#I zS>H2Qv^nI)uVHwzGUfE6%?wwnd2FslS9J?f8gZB04o@u=rn|vKF$yR5CfGsKMR;yc z*7-mQ1(^jNzY|Rrpay^g7wXPJ2S_&bTZGUw&CI3h1+Vdui-JjJqAwGS3`icxW?>H& zra8pNRrd{vB9Sws53Q;C$S5(=$|F0QTb6)!FA%uGHRCE~M%9Dcj!EVaSDK7eFezg2 zuD3U$Jn1nt&%jjK8TmMLSdtzd7EdfN89^5%qQJsqgBY4%inD7QZ@k z$ovg5W+NM=ozG9nQGE)2eYQ&XpAuW|MHkdYyeZ|(4ph4ML%S>+L-sAG!|%TIY_NxV ze>3`T=N3M*PPp<57;`aJ|DW0(EdR0X!Or&I^$sS2e}r$=|9<^%2p$I~3+MkCg4YJB zlDvt2CreDMy8uI!BV6XfzEA)&_5WRLM+DmoN>aoWN(&O~5K>am5Kt1(Qc}KW&;Ga1 zy}MesU1l{Ir&qf(&M$mTcx-6j-ab$WA+#!}fa3RoZ=fXsQe0GK1cLeb`3!ye`3M0q z(-2`!fj{za2F!s(yao{MOMNWK@d^wVTBR^zy3`j0djhiZ=mZiN5J*Wtk!ZLAHt?=M!#Vrnkl;J_-WFaQQtQGaS@hu|Qcg+1@Q`*r+Q zDDD=gpV_MV38f&^)hTd}0pBw6m|!4Vx^~?419!tOVZ=R#=6|)x(gop(A2qhT> z2_!^RKq%uArRnziS+~J9En~ z8RrCb;DNvTDof}3%+$f50zEr_(ya3PR}b?6+#TM%i4E~88Sp7Y@WUFNzp9LX60v`? zS$xk2;(C zBKPn?j$hajf3Uy){EFxQHu{SqeItK!qnyb<)oH9sw(IIw-u%G-Bzp+>zL?KDigRmx z6wwP8`Nn#;Zuzb8*F8`uhhKtY;0~=%f^)8fv*xT&$$vf3#!dB|ZMDiA7!J=BZT0#g z7?D5rNRHx^!e4({%YUEx{Sr*vU$bI1FiY;VFLsbF zC{0TU2%MGhoBkc#-X&SX>_TkPO`@IMRu0nW3pn`OB|cqN+IBS56;YuY+@fxz#Xc)N z@_rC)Toa@(Q-8c^Ccm&XB7D!dvq!f3NSMLF<0YTV{Vx!c@fX;m9hY1uq*Vjy4}Z>+ zHU%@%!&!chu(jY&gs;SpT{Lb@dv2+xHI}YU^P5c&>CVozlB! zJcuuL<58Ugj)Kg#ng~QG3}O$n;MSUQ5}e=5G`D-yPrZyJcwy*l0PcXDsa=TKGZnED zEYvS+dX{-!cGX3_DNPpBk>D0QgJgo+l<|ZtIUtwhu8)>5xl!?4Cjb zs^jeTa?wn_$+l7m_J0~&PWN6Z-&2UYsj!kDrVW~R_3Mj!CMY}h}9JhrTXDc9Ly(%QeOp$M)^ z)|=??t(Mh``()k7{IQf6LfSbrngllSbw zA*I!)`lagUPmEeh2yrB#{N4@SJZvlUb-7sAkR*$&M3TByam_HK5ZWoi^(5^*F>UTVJi)3H`1*n$!yAxASl7Ywj^YQQpMq?4DofZ zHOMHm=dn3Cil8jpXV3{WRvK}Te4Fh$5X*6ezPaULnBPuf(Ry)`rWSN9z{Tp=CWTn- zjnsi8Is~UpLE|zJKD4d85H)gArkkEH6df>~e|r+OU3L?5tADiPRrdTTgCC(<|Be z?IwaB7ws{XIo2q9sX}j)>)9EcjB&$_M!_|^-DD3v zS47K9-G(8zMPAWzcvAv?+|thTgz1s?cd6XO$mPiK64HCgeqZasU~!K7y;cE~7mC`; zIupn^K15%6zU_9RD%H8CjdhQD0E1xGXUrRK&CKM;OsdD$E1c8}0pg!(t9G_ICmO~8 zuSBvre8`5z4_TP%!TIztE_z7h`geww?kqT_jfH!s&{Du(ZgjxS^pF>~CS*Jtm|qWG z$78(N+4w_V?3t|A;PeVZVfXeU_EfKy;c>+zH{v36 z5Yv#Mog-GfU{AH$Ht9(tiiFzdY|K#Hy6b=r8ILwwr3m)NC_HPzaGTrCEDueN7EgPt zZAovNla_a*Yc?>JclDIXQyn|LZY&EDskz>ag)1sc1*tGZYI33vT|ea4gB0wpY??RQ zB=c025PGKS6LFAvZR+LX6WB7&JZ-I%UjmUN1V!D6P7HSdASf1@p$h8yKGn5ATgn=`M8wK~O| z=|f7I0}5#{F{}@dvPyJk=#sIW8Sf}eQlANPC6=Dd`T4k*3Bdoh^+Bv_$OJCJDH4k@ zkhq`tzK6);{ifT~%^CtNM-xqccL9-?1X+t-rCN;Cg+_wtunMU(n>eb+qc^ebrbKWmp zn~{zsR|#UDXO~6nuqQO=oR`{xj?T4=<%Vtau*Bk1>HT<$T#q?#!ibKRPLFeYNwvBa zj<#^?@YNTVn+5fTj~GEze7Lv689P`g)6aP0YpauGhb#^hY(qRxU0pLobx`uF&p0_W zW9#tQiRNw+EZd%68p*8mE4n=Ol#M0#Bqk3j zN-N=C{NWs_!w~thXsc~CI5J)-L&(=a=rSa-K}xh#T!p9Q<)<;-IlZD-Au(xU-z10L z+pY8;fYH0Zy{d4IR$GIW=2=bL9%zew#@L9>;QhUW_7#MLthhOhwl+PzM-E(& zH%Wp$GHU0q%MswC@~Cq)1Xt;#3If`jP#1+`O}UtCuk4!|uqUP88LU=fU%Nc951uOM z>X*w-`{_gNCiWX0LQ1}gr9um4V*|7Fy_@bFL@AyEos6i=W)q9w@G?R{;dw|b>V0Do z`n1vtBV+ZNdyG>HDsImP)joV_)ymUZ68VmF}kubebs(yZFkRaFpV2S5)X`MRIZzuhZo{YI<9o zqO4iVapldLF|{BhOJ7h1wv#^l%yxM~nQxjaKF|n06HR|3k?kdoB5iR8VbTr~zlYMu z&7{9IhO4*WKGYzS_K!-$hiB?`6(TEge^aH&C?i# z!0y&b%`k8n3v3X{^>8bJ*Yx#wQGCn0_d0Tsb*7+S0sN z9#aUGCWxvS`1)ipxiuV506swy5l^f*qYdla?NHeKC?cR&E6N!k=k`zHjw18AX+LBZ6a6#-46daF8Bb8*N?$7~-y zk6^1U<;D+HTkK4|xvPW{P-DU{Cd06=idr0Z9adgd!kFJ^KbhGTb4yPZUt zc|fu_EWx+?e6Wt2q8zn`lELl(qz8n;xx%8`8GSEt=X? z#yOI&6(+()`ZzGN&I4N#)jSzhY$EqF8FTO$QDWw*>&xT*a3;be8?MNcaNnO3Q(}I$ zxY?jz?_z&-NN?enleNFQ_8S}JThB649ahitP;yr(b+9_tyE>S(MlUIK%wnTc1-l1}hHvGCAZPTs#v&^M7=u_9~wQ)eyV3>Ch8A(iu{ zHS{A76c;hh&J73-KLutMrk=Uk8lQ^;g}=>HfWl*cZZma%+bIqp+m}(%5+T?thTEnY zPlnubtDJ@;9NDNwNmOSSQjBx+JH}+iLy58W{z1UhJ$e2^+}pwkC+$JFl_oWNkdeGI zaU7EE=p!Y$7xkCTkl#|3#N!_a=yZ5UBoJIA!$-Pkq5~(w3Jt6W6*yKrSaoAa`~fqB z-uz87+E=U(G+qEU$0WuyJSus6wX!+aU&d_qK6#5{2-9g6M=dqs1ESjdIl@MBvo%G( z-Sn4=Vao0pDb03fw9|!43#+WKy9qqY;a2UE%A<^LXpWsI?JRgWd&xwnOD%K9_J|q~)l8l5&tXe$22YU|rKC7`#1E z?CymwR_I(!Q}>q;<=v!%Z=DoRTQQA<3_gQ8fwxt`@`n`Qocew2Ua@YgH0RJp4r?-w z!HgTAgmWfs&7ntQVFjN53Thnw6u&d6Ir8A7v`lmPSK`p-A;+XZuHD1$ckv31t?VW0 zBa1+BUz5B}q7Qg9-7#z&c0495`A>R_i`P9RRFp93BQej^a(ia}h`U#gG^tWI4eU7j zNbqmmRf(wht2mh!q1&*OTiq6pMo&pRr~LAJ z^ymx}$|$QS7%$~@VgGWyj%PU(-}Jo{2H)n+6g~guk`0c+OziCY_Tbrkh2dsX70r?j zdzmHT@RVH$c}x*23XE0+Wi?V)H}ic$d5T2uqAeCu2J%M;c8h=D;a1+s39XW~N#NZ+ zZMjWMMO}H@sMvc++=JwZ7hu{vB|)Jse+iF6vgd0nM#wzPDgw) ztR33*iX(rU>GF3|(92YbUhIhq_EK(1O437F6REo*LIHWs?GP+x7hW&bJ+^pA^7LnH z(gAT#G=>y7=a6gm6sm#mhZ&h_M<3%3b+vv|?Z?5_8tsHptb)+m;PddWqi;68=3Ngn z3L!k`4sD5j4&Pd@-aw}10?V2us)U;)kL6b#!l*gptnKeDsC~UH6#Ih^YXFmARS0fy za^tN)d_Vr;{rs!c7*)gL8?f}ubcEIuOPX_R37dHkT%X?lUhW1I2;yv%f(BR8Ga_o2 z&>YZOK3p5@!_~G5HdGv}Lxc}J!ge;+IL0g2lj}iySl^=u6BZJO@OziQhP0AF9^P$w z=ZlxkD23&?nJ{7b3-WMv&&j+E4*DkEiMhLG(7d4|^Nk%npT1TM`6y4fn#R93((o)tB=MMfk$)FJ(1$Q`#q{PtLxFWSupe3S@vx zkw~CivlvFvKf*Zn-2+y6R4r`p0F^n}5SuedR0P>RRk(pEFh?dcc23l8;$j^RRcpW55#p{LM9}^`n}b?N^y_!gO9g zt>9|ZedvIGqXBi>^k^;=2mb}T`6{$DaYxtU^`2L!2xvBS zdKG<_IOX|Ws?avl{zg5SkLW+lt%V^JTLb2cU+7gjb!)4fAg=ofA9D5G>n~p025SIB ze%PNT2D*6Gx(_ccUs#?*cRZ*C7jOC*nP7~P56X)J?+4s+> z*ILq00R1PD-f_NWkBJa~ zWmt3C>E@f(Z^*#3y}4ygIP5d8@99&Y#gPnD>`qmxu==NgBs5ZXeo*d!gnb|}wAtFY z_po~>z9ZYH?t+8UU! zaxE0RC^kF1^2Mu5vgqD*xXmj*C3o-9O(@;fx!e{^SErp4w`8k;h^zj~R$((M!+NOr9foRP(+xU#O%f9Q| zI*SnR-!UU1lRIk=Xli+JvVE6$uq<5AeOS|4Q7Ny9kJL_}GW5Y1gH{d}7qwM$^!}bH zoTVp;WulWNM?F*ueE}6aX`e_6o?F9+LiV}7wl{sW)X4!R-RSKRc8ko+31p_OCX6Q0M6t?@JoQqo*Z4~ zXDce5_YqP;Ajh0qy%st{z%V$sA8HYNrXwALZI(~7pL?3=3(yn&0t8}7WvoLKM0$05 zpwKib2RDs9e`W6$xq-IqA8gQ!J}2YE`vDY(&{gn4Y(Pnk@}i^sqZ0H}qtt);H%S&l zw6PW$H^8q>%Vi>(c=%Lcv3Hlr{{#y6Be<7kGDITxQW~2Eucwa^O181MbVr7QMtF4Nzmc+%Yz5AnD^K>-7qaiS23pzb- z4*9_&0SQN&@*FjbSo~#r`aYz>kX5##tq&Y9J|w_ zGeQZ?>9Vzk+fxdvh2}kv0?D;w*66af%ksA0CRHYi$@l8|Ev^Zw99tKv2kmi^2kLU& zM5c-Ultb3(>FMP9N(|GGD`_Wvx;a>m9`zD(s~GQ1q#|9#WU>PvUy(Sfb6KnZALTmZ z=oJtb*7t8!G$o)6+-ukFP5jcP9j`tLUOhO1jn6t(f4|OIMa{nSMppB2Ak598Ixp5~ zvKowItOdk&NkTjV5yDDSez*Ol0NLOI9HI)NS#73^*C=h>vZHaqDoVU86GAlfH{V2` zOW!mP@p&bZ+t73g>E(^i2@Sy91al<4yl z_=nVn*dlbau>ylA7vYm`flvnoRFC2$vh>zo*?|^Cx4KMKNGlA(BU`nXb?UyCu~RG? zcpE{qQfB`7^26}Sy<#s}{b|}*Bp={&?}FE_VgQk4f`a&J?1HS?f$doq(f~-TGSYi& zVMP^`Wx!!bq)Z&xGZow{i~#?rA7V?m)*M_eYR{d_tiAH`)o}FG8dE`8c@zHVh^uw! zGizUc?*)`6*SP*N3(WE4L7g4~$ek?sBgl2qocu|HwgSJ=ldJS!7g`7xEad@;ztmj9 zqxR;$nLMb9ol;K0J+XTlL%0!?us61i%BcFDAQ#Q89V!_8B_N=?v)9qw7g?GyIO3wn{5 zb3`QnhzDx!tE1~FkQoxQvl%n`@E9`Uv!ioar+UYS-Kg+Z#rhYtH_1?Yjyd0lt)_Pv z*567SiH&gE9qbVxfvn7PDsLFx74+u`w6^4>7! zdfwsIjRFG+azvkAYNYNCG@!uhE%t!>acgA7`y$pNaTU-xe?PXY&`*xqLDoxTI8UuA zCJOOxqU=_@J+@R7gBTVVuA7NZCe0puTr_^q*6LH@IEQH>^D*3xHjf++F;7T6vCc?b zwDHy6*G}?H`yhr%p~rs9X!O#&dkxPle9wJc%(n;I zy{1|X+9HAWH6X48U#G3Fk%L_ixV>0$)Z>ZQu?2rQ}LU%TS?(ayktxshzYOcrg-Y zWH>S7NatO?wL8mkE_8=~b6cjN4o^Y9cR3%jQDV1{q6JC$JtP7wTj;akCPi=-4wZI}{j{S?-5 zmxWeJd#pKWZ?9e7?XehVp+^D%qj+*Q6Ti_!-2;$j;Amf|T6ZbM2R9B)FR}8qk1YF| z$-7f79T>Ba5hE$&lC*miemeD@3-9=nIG`fs7RdHy^j9q5-#VF@AF*Dz;-|);Vdyke zWg*l#Tt)7+3oAQLwD!_rwS8Q0M7FksBcJ`WGt9#Aee^8)^`{wNz!ES=F0s^oRQlz1 zSr04}A$exSyOYOIwA@~kf_ULQJmRJY5L=DrbgP31Jx^D8LyDk%?MC(0ZN;L5xYSaI zjkJEh?>*fh?L}J?(u5joRU&(zjViz<>7fIX^T&H)$fb{(2A+?0nm7b_1zGA&DcKLXxbY`Bq78>g1>IOI@>@Dl`mepIlV7VIA^^9i#TIp7Q!S z`ly3CvCEI4HtD$J)`Ai>LJ_Y2;|O4h3ixD4iAV13kzNO7Q?%NKz>r@2@LFnC# zom4bb%~pls#*TJh5hKZ|D;Z@Cu|%Ursjm>Uoe*4M`p^zxN4bAvsIuerT9|2b^a0?v|cjm}mbg%(tfh+HU!8GJVH zeani$9IR-Tj%oTYkV{x77DE7`ShR{j7;%p{HpMGa{^|u{Js?4sjKWCRCVxa}NpNvxi|GfCvLC>^YPlpbrZC z)PGaYp8}cS3@DSmf5z`-TueLy9vuYe0LIP%5+-oS(~Y2j0Tmz($FQ;lc;?-Y;6KLY z4*?X==LL*_i1cp%|M;q)LBxLC!Gs9KUEmmjp~Tq$u@3AQ0{XJz5QkBS00D?|`Xcq% zSdow5-og8J2H-gRuQLMxtfImI80vfa#|4BG?ciXvAz@wLRElrv7&>XHhzh2~UEDB% zf=Ry{c~Cf@!FwCAs6Wn)wGhSdgTHm5#5jPiU#cKWlfr8#fUi$MmX%+k0~uq#t(*f4 z0FL=65(l*$04IPJLG02DYufE@kVdk_zOMTb)iqx{xe`$c=b0M-O@-b4UKfZqDvJw8GkJf0qbMl}eF1-h2pj_lB&2kZ2#Cl?;o{=~0D*onM*(1d zt?~Q+SvwJ9B?6Z6t`9z*@@Tz(O8|EIN`v9=W;MJdvTY3iy;SXhQNV>9_=$dJwSKQ3 ze#!6k6@ToheqY0uy0^CchPwOif8k-=!n+KAiS|@3LkDC7=#bdKBm9-84gE{i(7{5z zJASd3{{}cF> zG=Vw}Z{u2IllcoXY@K~Emrwx(h5TeP#=q$TV1xo0j|Xy42L2re{2^*L3>ozCufiap z2@x=IpaanH3@)9$j|X7Nc0!xzcvxT5Ps|Uk-GqRYy8|^BRpba1?U3^5^-Azg~$G&$;@YQCV| z4?!ap{1<%ufA(S}(-%EP7}eBoM}iL~FQo=s7tW7S^bJ^rebbyOP~f>`H$DPdtxUtp z&WyErLq!6Ec(ofB;F?2Ftra`lmPT|@fgB9Ci1UGk+x62@*<5DM^Ht!t`~e(kC%Tlc$;!+oxWkUp1nvjg7eG8NK+oRrtj^ z(7SzT%j(NZ6}*k`jLTOg_08Kxi%obSvG&vr)$y@D6zdIQRx_yS)Ve+eA9iUkoESER zomVKt#18|+_{eeMk7~kG57*49V0ybEU)nQfV?WJ>lbIUu`qc(Gz+I1&LW!k}Ix^ZQ zQN%EExbZSNi!rxI7VRe1#!L}8sg~W2X&SPrTc3;bw5|mEP010MhPT$FnqD~1mS>@+ zU_H|mUz_RmHX<905(2}{;cpPGR|2ubGDId{UzIz#7!#r1c~QBL61U8Q>S@#99agsc za|3lC|q*jz~T}fxxviM~JooPHELvdUXmp#NuM=OEhpii4tkxhw((rk+wOn*oU zuX{3p_I+&!tPIZ+fQQmH=yj9KM>x>8GQ(UhPOCg65k-a*J?hp9`-*45UYp%KR@@iG zQpBs!!%8dqP|FBYRc$yn(&uPaob#ZW>U3bHTRg`?m<|k-ry!*T#_R^0Di=7(Gls>} zPbbvKaLbcxOZCvGEZ{#rPD}IrAWxT6agTVLK~=98vB}XH8^!M?GgVD^D5P0q!w!9$ zs60Ehl(vrg+|<7lW^!km8TZt-s#?VEX@hyE6?$-0X{+vV8{&nR#Qt2PZ0buXdtx$+iiJ@J5o)@}Zh2 zjHAx5QalsWu7gcIPcjevWnb&RnSo zFLNe4<{a55y7<+%l}cPho&U_~l0Y$~jV)7k4SD#+t7YjAfcThvIJF48Don5o>d7ll~--Q zxz0ah(vYiMEFhnnD#h55$CZz%hujgp(-P~H&fp;r*Ozg=kn?n3xXEM4{PDLc_xpP? zsRCp~I{6#+Jhk_Lo{~=$X=wBly9r5}68GB=o=NiiX{|(WvJSYCRGGgD#m%m1&$!`b zaNftSGRN2KnwS(F7|RIEM-YamQo~I5IjXJGSr0qTT{)eSgP0}C($*QOxk~uRXl$sG z8IE z(;MbWKk{lvxYN*92IN~+1B&FUYZj~S-yIZscwor7b^v`Ic9SkWuUK~qN44uXGxnIY zrgv1qU2N}IY& z&zlg2zRpu9ie6b6@^!~EgG|_=)ta($(E)7(r&A163DD$B6;XV>K$iaUTt6@n4AAoF?+jbK~Cw4e! zUbp5Zxx{T?k84i^{X27%^>Dq=-pV(|1bU7isYne0BNtqPBB)-!dF&}xy>5fE_Je`s z(XUybWcxhNw4G~dWGNnp*Xg9xz3xV2Z&BsXwyVt9vgRK=k;&=1&NxvYRcr86^<`22 zlpom{6);%w!m>f4o3m-yXN1a9%+{t@9-(+>(etJ1h)B4R?_cNLAW9@3^{GRsEhXww z;pm*M44umJx?#k2nBftfzeCh`YcbO87A+3h{SA0FHZXROl-9=+N5DLA?hqg`#_xKV zKAuLq8Um5*l;J`V)i!y!gy9s+kwkVL8O3gq!^>wkyur%Z>&Q~H@7Wn4e>3;LfR+r{ z{%IEz6g9^ae&z7vffEcTVQaNzOGhXn&wZFeqp4V`S-*VKDbO=YChstBGL!M~o}_m; zOG=5`#k0MLflx!=|C=_1ufhR*2%{5vTx`;-5ATkTUEXZ3qf6YYM5Jci%LvB|wjS*ofDm33r-v>UQ_Z)o*^Ug2)E# zAuzn+BR15#+6^?=?K@551U(>Iy5B(nRr%TSu$TG;`S@8oyXy0oTwmQ((p>uKBnj*? zh8JQ!3Ao9w*RQ~5waoARQ@KmMaNc6pXHm|lq_k)tO`u74=7dtIdXrk_Nf++Y07YC=S4rzJHO6Fn);j5~xq7-J!~ z`7U*-2*N{#z8zlkkd-X=gSk2yW%m(B){L}9np;bfMXA@Zb+NQ-5br4;8g>$%*sg5g z_HnQr*I%QA*pznB3L=iF4DDb(jlpd{yJ$qe4Fzp}ZMjkMFv8I!K3Km+#pGhmbRO<* zg5Q6++&2^Nk%qhPsf4I&pzZdx>!B#)?-k~0w`=IcX6rTZ?@xK^5ryfz1sN1%?ciXmY z+qP}nwr$(kZQHhO+xFeL$;HEY_#WyPR8mQ;HRl){t-Ua-IlG;>>GM&RFI9W(d>DAX z&y3DrDGr9e3Q4&XZG9PTn#=avWHAHXc=RuI{UA$;x6nEomz_Bo4#q*{;wqo>!*99= zEz`VRIZN?$klUO&TXAgt#T3cc)EI(GjgzeKz0&F>1M9JDmze+t|NPAy0zL*Z?k*NH z(`X4i2fs+dERwB#e$4Scx(-Q;+Z$jS{Q|9D@}~-qI5PigEZf^-R^8D*|IqdSdg9Z~ zR1vq=JvKOh^muU|wvj4VvVY-o@QF4i$xc!vGxL^M@w^LLBXWcrD-bo-u$E(HHL19q zvSY6kx>GY*Jed(D`ZP231()3V5FH424h!1wb6-SAp;ZjEg6d?`d3o_|63b1k#cGaT zq*%5&%|Pp(_s1tNzs~Jbp^>_>J3Q9uSc?8^af8*kj=G>R}wD`Dk zFJ$*gXd*^lVGyqrh^aYdBLnyzadgW-w6o)w8pO*(phL2ZRMgPskZ=vZRSLXF$DvQG z2erZ;a?1E(Yk6dj!`7H%Nga_LHMsKKpF?Vj&kLdc8m4d5X~PB7a9y7^q9X*2(c1^G z?o68CmXo^qac0@vLX49-|D8#X*qh-u>I*gUf^tysFE(Orhn8D}>CZcXM*jnun3e&~ zlPsg4M}pR(Ix2g5y9Bo=U(xJCyP3XLHe*}WMMhFKX&3x@*sayDe-+%a|D{$T`RKu^ zv6o?=|00fMJkePru}xcV0blDC_ctSZO(S%N6vbf~bNj z^z`nrO{qujh9BPr0!+8xf6y`_sL}X4qoGI0E#tKk69dC!bb9avOM>;7P5Dj>L+<6q zAr~8aVng^iM->zt(2U3>>p`Sg=Pgh9e2Y={QK-H0k$O;p#EitPFGnjlbYs@8ynZ*z zR6EA7F}p(|>TQPD+~m(@ZjnMhxp)JvYfp+IX``_yWXW2M@Q?8T9JO;W6_e_fPuKEs z9;n>)!Z6lrFLAHf*J6$;oeZ~ZMD*3)>!kEQeag2?c$?Ar??-3fTH`2RQU!7EJeDeK z)WclT=^S(hhJ{SgN2S#&0~y{|$lAp~Fwk|u7~r0nV2+Us zqm-N^sW&~0Itg4Y?jTmIrPf&~A@vVQ!UkKSW`J&`E4;6%BKF-Z4E3lz-zl!n)ux36 zuh{z*tq(Do0&29euB=f7E^Ih$&ogW-ehltKLOV#LcIJ8Yw0#arH0i&W6jBYN%cUM0 z^1r5Wt}k)8Ix#pIfq@Lt_rg+nL9^S}!{f%xWs#^EHQ-wSlJWx|zh%WEh;MQ1J zo7H-^l!B^icL3-yn%l(8&=k#&Ze(etSbz@cY8W#}K|9`)V50Q=vy6>2?z-0C?0@gU zt6|$2->MQqnqK2siA|{$EX}sM+2eikq*Xm%)M*GO+*Bp5co(kkwlyUW zDvn-NW;>($iiGm0?^iBEJnDQ|#nZOupO87YDV&EJdRx3=E~q)WX9RB7FRv7h7^@_? zQdZgFY)X!}0wYhe`0n_Sk$kMnC}i#0UZFX3RW7<2QS1q?aTn4`@unY~cXOC}6da!} z%31!sK3V=^9x*!J#aP=G=WP11)F&h)@GX$bgaq~a>8SawSatra-FZfyvlL;nkx5YL zIxxvh{yp}`b+OVd5yOc%u2#uR!qq$<78+aiE{!4Im3_0>#NxItcx}Ybmi2?l*~?3P zl4c8C_3)>P{L_+lJ3h<~9*uoEk*2%1qKiJE{oT!M5Y~d^gTR1!FDo3p%&JbIc(RS6 zsj1+(*%=gPzK``5S}qqJ>ET+SBSYuOpPL$&O0Yazd0O zcB{}}P?l~}XhAVhJuZUGUP3xJCZN+!+=K-dmHq%4F7k5biLz}xZ7)$va*AU4)o`eZ z_*#la^8J+C>_2NRFl`)o&I^3oC%iwsG6hJs=m`15(W91t03lmMau)Qbgs~V!vbpzz zlSV-U&ym~0Jr-da^*GpbVA+E-U=G>h&{e2h-?A@(PHnM!HR5k7~8b)Kd>P{;{K`dgT`a0v@~O{!r4j9v|mgHQi93gi=(6J>Mh) zmrTK1McKeI<-C8=QkBbzT?ieZ|EKq;gThoQ^!vT5@`l?Slo4gO1>E(Oe2IX=!z?z$ zWEHsC8L4R_Y0b8FOsrvG=1RdK)2;f(R+d$A#m;!m zN@3v6CGmxr-mAtfh>`LLlFo)9&FaCEa-I`)%8I%?&4fa~K!S8wuC<-?sU#Jc!t*K(1*hnseLYt$*)dlr zi<|qiNWRf2?>w+zbr>HG+XE0Osi() z(dQg-J_A&B@W=Q|peKj26&x7jho742zF-+HAzp0^t6~ivcCxW>3!mn& zBm4k3gaW{bmYUKCnj=}<`x?K@F?9@X!{dU37F`s~SytQw$%8Gth~0_<*gw$E-6#p& zWkvNeqfm zu^VRBY!Mh{^m`0xZcHkNed-`KtaBhU@w;3sbVjDzU}`|7+LW<*Z)eZu-h57wPg=T0T0C5`_RBE>;*zD@ z%(ftNxY=Ff^(@$RZc0|`Pw{xOLnzrsiU;ATNy4{beaRXJ+BL+g-F}`iPbpaRaGPSH zUHHe492EQ=eYO%+$u7~mH(i#TOf@srTB2yBGr*+{7nH=w6hzy+g>v2a@0!=LokP57 zMEWmBQ>fr!!i8&ovih8r+KfW8qE-D@ynnixYAR!LE8*J;sFe{+jTeYI#^XO=%`!%bjyuXKnHRcGc3 zZWI)2**0>Pj93PY^q*iBL7=mUwc$^?IgUO~>%`GGO)e7uev~}0I8d~ZJ3cX%=>OBX z^h79U$!3BD{cR!=e~fSo_$h-1246zJeB+-iSAVe@kH@Jbrv~T+4_5%+A0wM(SN+THr)$P^Svq75-mX1{hd*MZ# z%;Lk5?nP3gl5?H8XvsK?TXi`4=f^|zlk<;`36?~Ca z!(fIdIdpAzF@D3X_acdWE=Y+)gEALNb@V2l&eM2^gsHny;(5#+jm7EZV5XD()U<)6 zLFIQkzhz+~KpU8n%o-l+)26KU^d`|c;abwZ?v8jjq#G3q8iEw)Ih>b}NqZn$)U3eG zejX;%kd^^+2YEBe&E~KRQkc|zoywIfd#8|%EvDTs4#DAKL8hX|jqB$AboDQcPNiFP za_15so0gUPd82}ir&dVp*gHGH5#8{FxV|@tXk=(T9A#hZLJv#~E)8o&Ao*C+xZ^d( z*@SaU!7%GQ3*$9wAE2X(c5_j@_H2>`ENT;sAB`qY?rxJVxc6^#J+vCamxtG;OPs;t zNgTG~9C_+%YDdNw5yZLH+#ZVBVd;^W;JUc3!vvb=e?UiD%|_CDHRx#QMFuPF6e8+z zVBGl4&MF0y?4wOIr{2jj0y#*&T6wxjx070rRe% z`W`;CC+IO=tvHu^O1S38JJuAz9(j^!e z*w`8W_s08wsuD${jph;v0>NT#ccZ$azLKqnto}qw_S5;9tIsmbE ze5iABbTpbVEF51fp1 zU`R7E1ZfXEXbqr=Pd+w`V*KZAn~@*p4B(@Z#TDAqKNbf4qf7|P5Y!2{!yiBn%&QJ` z4B-R$VPzii2*{liC%?KJNZt*I<3~dEJ*f}!?a~oI`%2rd?33!ljj-+zub&?ZDm(~j zZXWo`9HtIvGYH_qk@AY(4V?<$%=|qIqA5%;_aLB#zm8|_E8(P55O^4fWdc_4A>P=gL}IZd{l3+*(tb0g!(NAigsMX7m==nLC@` zkGuQGQ7;N8EPUrrBQS3aK#0>H@w>f!#Q^{^KK3=ORh(HamqJ*cWb z7X8=Qk1?p~XGreR4X_h<$DVgQ4yy0{^YJz5K52lOAod0KckUORAuJ%ZBRQ0CQjg~M zIyo`04Y+H~y$#TM%R3u@R#sQQzi%;U*6(y4An^C^pF z+`#WBoHM|t*VnLn;*HkYB4)W@ZfgI%U&Tj0pPSmhEB3v->(v!Ozq7z0#;MLDo*o&V zoEiTt!+}l#?hK-4>7$3r;xll=a;kD)U1(+KKJqx&J{vsO!zdP{MRFaDS#Jd2q zuj3Nbmm}~m%k=?Jg-46t4LU&svLE|l{SE+W1H^{>#RmikyWkUt?<;tL^Ndvb#rpFA zz~1yLDk#Sr)r$bPiqru38}sh#mFJ52)_VNPW3T=L#Vg|f6CkJJum5ZM2+VH%3!3-k z`paKahMN5o`qd=|aRvkod`;7@s``t3zZAWgL{9MgPxC-CyZ;5}ZO9$*ybJ!z+WrIF zp7+=FpNRDD#-ZL_1?()}p5OH3L3PyRBLA;?Q<=dJ`0xD%NWhi=Dtgo-JXC`IX2)J^ z9!sLJtu@zSZM@uqFQ$EC3|dBhKbUcu3>#8&V`FOa7nWtpS`WLgJwpM|{e{!4z8mL{C};-PzQ z)#Yd6(FngfDOo=9Lcz+il2U4kpfGK*+mi~^iY0GVJGc@M0 znhqO!gza)0mJrb(mHRhxw*sJKO#oM!a{)cKMuLGOhVGJOcS@jHucMR>9MfI*)bSr; zSQ>E3l?+9{m5Q8o>pUDxB_`5Wh_!SQEfFUij~)3vj%s+xlJ+B%8&OT#(_jSxR=5Zf z9iiusg?>o9Rmxt)HHwfBaxd!X7a5x`&&n^^`{^NldZJ3p!n47!YodQG(;0NNO8MZH zG?ohY%?4^=4QX&*RRPc-=YJ_wwP=FIk1acpMQcvyAxYKXz|Ak1J9qawoqh|Ij#+lh zUYG(@EL{(e2VUfCHx~&8Y7R9qj*&evFWaSBcQfSU-CTPIZ_7II+L+WAXQ#EUhZ@&i zW>pMFf8mKeI=RtzBDPNss)u4>uy|CyVk}351rc1|~jRfY}#<+T;9-KhpiM#nq+vZ znf#IN-YjAS;!TDAZeuI<`Cpv|-9GiP`slOR0RikxXBk4ruRnTTT<6_#SmxL{E2WS4 z6aT%;K;Z6HLQ;I{znT^_lCBpz&rmGbsK1oYjc8-<HKsI5Sr zSOElN{F&I^d!t$XGr5Gg1I;~?;A@2Q8jeIPbwXQ72vk3*V?AUkQ1J5tlTsghrBZ7X zx?*2U2R?~&^1?a~h))FLwybNvxu{PvUvWdo#-tUXdFx5i*AUS$t~Zp}nlE35Zk8aI z?sB=362BtI5$j>18$9fE!0}hWnWcxU1;@Wl+{tv?h9CNj+kB>X5T(d{ld~pz5}pt? zGrLn39)_>Z(#F%pvhs_{HFTzC_{TD4=V>5d2AxgEJgSG`# zhOT}cJ+=#O`L+ZH|B@^F@CncRAtyD0rq^Q~{ytLVK&&vcZ9F+!(w~`*I`5eX7oa~i zREZP|aXaR~TvlBl7vZ4;pdvt30&;E}=Xh?I1oZ$}rleu`r-lM-BxJ2tuGbk~sZeC< z2!tk2)Q%_e3(X=2LjG*QWpq4%dJ-{jLHXh4uf+7ujm+)L=FozXN!^)l|)wqG*A z<2eSUf;^Ct7hx6}$!9d~Ri#a0=2%7MB6@6F)Vj8!NP@x%HsymJIekorx%L2yg897$ z^4nQ_O2wOfXypCsE>65ggk>9Y2@fRv%{OE*@lP3b9qL&oVug7)88d7Qe5HiiwPmI5 zbb#DRUD}Xh?mmpHcG#`{_1B((Ze7Xp?PMwk{8m&USJpl6WPxpJlr|nll(mO@eQ$9h zvEfCSK}E*jV)50b)D5$LlcSK}F@Z^sxV;Yfa~O%j+GTFqLU=1nP`__AL#3L{0SrAh z0MpNXFGm|yV}}~{dwk}pN00IK02er~kv6u5{o3h9g{y|R3HETH=nyo;d*XqTFII6kR6$>ET}(0BW=?UiHR zH~*?R)(@R{@>B)sOM<}V!Z>CcFdes!lk}xvu^cDMG}C4@L28B*WTiV|LiL}hT!w)? zI}M#x1$>t9{$^$uve{B7j5GZs%sTbT9Ho#zV#Z%=`=}I! zQhi?=Kta9S8Z%Gqt6ILYM&%j+q6Z?8ZlYRIMHpEkRE(x2rEc!^umm*GfWUp}5?C{tTq@>b$oa7a=W@sU8_TJC{$%}r^ z#BCC_`|@xZo3?D5P)!9y@I$|L@Xq|+3$zC3zNh9*olSZqE!~(dC=OI61mVP(bCL;f zO8(~d`?T_^LqN4z!)U7%EAwV8ep#W;RcLY3dqQqASx>gW+*9O9 z_QkJn0XD_udj$x5YpI`y7`Ia*p1@x8pcgTy<{n`d2{GDRL)p~7C~js5`QK8XTtwFr}-JnL5K`; z5G(Y;PP^kgZ?||##mbwN7$Ih*z`7$o30k$EpjxJE$*VsNkM-{k#6l@fHe80GvbJ=_ z9_>p=4}KzM}b4Kz_j-o)9dFD1Vw$j|%+=G1}PqaSU~` zW2KWI&$?cL_7BA$?~3zSTewbA}YiQg93So*Z(Dzc|`TnOyqBEFEq^&_$T|B*>&T$ zx$<^0_G@saz_ibSQz6>zXFd&LaH+%`ENrkFhnD01c0c zkRl|i3G*UDO%6=f*#o>Xml^YvZmxBX6w#tGcZaK3v-Sq>UjJ}-+3`+Iw4~w`^X)@@ znm|Zrbl8|Ma$BV!=jG6KC)Ncu#CIi)GSn3-kwcbv{I@-jBxMAqR2<;p$Po=#u6~6Mg}KzRH*Bt$ja| z3h~Gid&S`J>$#tKNbv;(>>Axv&m)iT`76-FN`18jTi#f(gKe>J$QiAIA2d$loCzb_ zBboLN>}K1Zwjy|eQUGuGRSfTA-U^;RUE@=Cs^4C+%qF&27?ozy-i9q@tONL}@I?xj z5lM8jvKq14!3>vABdubP+atYh9@~UwfFl=|w;%kh!LMS~ma`Yhfs04Q;sjPW)<)7N zLydCvo-wK$aLMG2ebKJtV7J=5sH!u0Idj(<`}`Vce$v`u(DsWC!`%&gl2=MoBx)x+ zG{yJ6{vM3yG*@)Ha8&CnZgqzypet7Ry&h7?_tEy7|<}xeF})jaQ8f z4!e81>&Qz*f4bACud({xzD3W z7hoKDMed|J3gox3iqveI<0&(3V-^44w14)<335b*_kk9YL61wn5Y30`i?$QrI}YYy z!4y@3=Vs4Kt1mVy^caA76wy^?8#S+K^-OiJ|DNagmqC4PhTakue|XC%@6f(2R4(j{IxDT9UC zEJWU6hQ*sDpJD`MEpO!H&J|^ni7De!W40J_2l~82(PFno_=$a<+rfDt*Oz5^)^9%t zM0)~8KlLo=-H#?>Bcp_xy}daA;_Ma3Fkx?hDosyAD-}zc{gN>U9@4yIxa*We^xjK4 zL^Ua-uJuEK^{&#+Z(&s#lCT!Rn;{b?*|3Ca+oTOKmszCv3J@L>MeD6lUirbXuW-de z{Q7yBF)%63Yf|&jxBHN)W9H&z_mr4S)mhhJ6AM3c4q3gjIc)2V`I-}5VoCGUZBHr#Mjl;q zbb^Ee_>VeLxz3Bo$u7eOJQ*Ga+KDc@kK6^{%(wl^jh?R~cwIY0Ms251*zMfHi{(-= zWbIIV1iCQF5H}eoHk+DqjNd2$V~`^dbk_d1{A~!5Hhs9`ly@0PRa+|V5mj0VcBqnY za#zyCuZFz5GW;63hmFr=1D*w-FgZv@VjRE~n!-+U>~bo_{@Q1q;f(bR0GT9G4JZ(hwK70p~}F zx4cr_mKQGsxe5|_jfmex)3b0%*{cd~O6R*#I>xRYcrM?+F3b&D6s5ER4+swWcU_I+ zH;wiX$99Kw-N%UOT#Go*($W`5GsOV$l)AUm?~tci?I}O|`19H9;Wx%dYLcrDg$J3a zDf;U!3FbYdpIk`efk8SGaP-#8AXSv=bQ`a4L+0}mqGueQ7Lct zvWSEC_^#W=-sY45KC!A0w6KmX$nHw$kFE<@eJsNtmvWV!foi2%u`kfQ{}If?99+50 zMLlmsTSl^$)(^&m^?baH##3fgY<;RO+8N|)i;i+!I&fyPA3uK^!~8wl8`q;-E+sRQ zx493eU{0o$6lLpOx1@+L5J+?Os?iR2*#3iGD?KJimwdciTDR)<$17yu^G?ZS=qaRL z*1h9)l6loKlFLB`4tg^temuKy+PGJDirKCO6ADGUcrOYJhq!C&Hn(Tc-5o+B&X}^5 zP7u^Iit1QH_ci)NQe?G8%oQ)ZC7*#Q8uSc88RFw3WO%Vu#tzzbv&7!# zu*i8;dm&3qx6d5w(Y$9+n)m`Hiqxn%UG`uIZ?DOYx5DBL+NWgo1nkuy+=}y`QY12i zQZ|

Z6Q zNlR+ObV1!d0B8n3Cz`NuLG5HXT~@ZPWeI|Z~V%5$0H*;0M@$&`u0=x9F zV3IU`*W`Rpnj}I%eV4wWmxu?j&O}FdsoanP6$c?SKRPpl#$lAn>`6yUMxDMl{;Y&$ z!FQZ9v*rzR@ue!2<9lfvk+@@>&qj_q5znjAZ!C=hMu!KX=-@j(0BhF_HgjIauJege z6rKVHd^}T8B#qm2QWWuc&cqIuqwIntcxA*w(k!p%*BU%mhAK{>D&6A?)u-diJUxqU ztJLVWcv>qV=hmh+qf~VN*&9D;J?{0EnI$aq1;ejE_mT8Ip?E1P8LS!<9Pw|Bn$Q5n z+}lyc^bnubctxs#-P1eYRE&n*FfRMEI!!eZJ0WkM%RP+azPc~Dr3}034d0MoQQ-dk zLG%v(@}lr6*?l6jcd%cc=C3`l5%-Vki^pQV;pLxSxfL#v9Nmt(^e~6Gso}a?i95&& z*}au*F&?NaY$HUk(Bo(C_8yh}mAJMGkx%EQ!36Uq#sL$11$TRbCuxZCVE)8vX_eRF z&wT<+r4+Z;gCjhe`wY8~!4nR-wiwVYjJOT=9QsOT5U%v`^#tvAa>x9llUiD%%NP}A zAr858KUNC7e}6q@sqlcc^;G<0CI>ILg<_RrcJYe$pr03_HnJck(Vk*W>e+McPy7nT z;d7~#f=hEaTtGH(4=;X4NI>&#e58co^Vd^X?OAoms5P%!KY3WUp4l%9At`2J0b_-7 z#Q;#!#%lzH%0C;M@u?4{)MxL?-_08JCZZv&4XI9Nu602MA=EW@0dwB3+NG^UxNv+E zx58v$Wu5iM!*u80f^BMr>WnZe+q`_loWoQ{W}QN~Qs!=En54A4QE`;{O;{>7qI{_z zwRj0KB&HVlyrgnnP3N&NeM9L*CQLq`jglwGP}?)DFJ`a>#HNN?r>rZZU4|G7%II^0^<1fY`=hwZEUh{sIrhS^-nwY@C!VyNO z2}Uj=H*V_QO3f@Ad+6t=z^UaS9iWNA%jZe0qm0RFNPf{Wn_XS5#;$sH?c7&z$U3{l zRNECix7U4LTX=^pwkFP$Wy*nky%(yg)M5S# zzJHD@U4$MEGn9SCRaOFnmRC_Y7pVkl{oAXPlI$FMT(}XG{)**Ztv$yC)p6o%LAFPv zt@zqi0+xA?+4p#D5oJ}Xl<4q^fq`P~_=0eYGE3~)UPu4%fxJR;x<^Mii=5}~DR2y7 z0%yq=vhj23_Vs=2*xna6*uR=IvcT3rV*%T&qe&BCRBE??B@YF&yWBBLwOS7?)~*X0 z=l0r?8qRWGzA|VKufRiCn{KPs#gN?JkBmdeWROAXMJ6G>;)CTg2e(uG)YS|vhH!g} z2_6e%yyiLh+VGSLI4-~SbdZ5h4az(fN*4f&0W&kZVw>)s%yo>F~%Z6#QNnnLbHh!hR^;W;5GrC2f>w+I+S6{dBoUo z1dLSHt19e(c>+ISvuumvIo~$-z!JJo2w@hLqo`-HQFb_oFEFbMnYZx6oTgeRSj!f$ zqRCj^9n)_@dvXkTEIsZ-V+anCCa;glPLM;<3dY0O=vE#?V=TH_vsRh5Sb4 zHxFPIv!yK*e}maCfUm=3{`iR{&GSI3Y>{=;6cCo?k>Kp8eAFZ~x#~is$k8X3S$2jQ zxOyloo%z5a==Jz6P1?YWei2sN)maMe08y86kL*?4zy>~L-|kL$D}}u>H|L|Yb832~ zsl#iU(Lh9J*}x9m!md=N&j+W&FoPjAks*8QYqIV0AsXa~E9%_gTODpj>zzd$4w*Dr zR1vi=;aTiNUEXeW6Ve0&k02onR&lkeR$5CI?C%B1O zkX$2IuYUT-pT~|VSd#fasL^9?dw^hymkM#sH&n2OvuR$)XzkhVuX$M$8IBr$5GP9y zs}0F@>&fgCP}^I#rZ4@URAlXKJ;>x_A0fhT((yPI!9@!NUWysI>^=7%t0$zhkJ&~h z2F0_jufpSbZ#iM9wY5f5W>p0Zgq*Wh8K)>iMt4w;w@PviUrDp(kdBbw6-=3j^Uz1l zmFZ=v7_ZSGg)$b%Oj&e2c;^^`tuUA2+w;~hF(2RIYYv1SPmw$!KD2^hKnLU2BGznR z^}=^-yrqL=X;~!ry}=;aNTiOU2`0E2^xju^nW?}E`w_;hE$s*BGG;qh_JSO|4eL4*7CX?UP0AXq7vv4P};*pACY<;o@+s`Ui#+Dg)j(J^#7ITZnrQ}YROOoLOpoO&a$tVz<$=wJAX97N6s zCvOH`x=*>}Rm2SWv#25na(p=|T}b+t_|=x;jb85%+X)NmH5A>hIl-Rqw{$JjVOp#S!|Izx}z`!nWifu=t?V z%NaK=#+(HBQSTAukIGlzv{RDh*L2h>8|v2T_$329&_hie5 zViS&=JKSmD={sr2{*md^fj7TGhfvP`?QWPREx(|Po~hJ`EH*GM@?bH@Y(_Sj8tOL+ zwy7a9r#P$v{SICH+3heTu|qmIqF5yQ3p&y{Bs|?kVPkI>c%Jyy4uSW?ZF%`X(C5(( zC9{xEz8~&4uMps8$t{&x8+=zNIs{J3bv>q5-7Eaaf$Rf^8cf%-363C`x#Lo|b_*f( zo^W(ma;?cJaB1|-C-sW!lj5XP6g8L+7;Lt?mZL6cObV1xMk+3QK6( z0+(nUv$)%BRniI%E!ePPXp=%l>qeu3UH{$Bo%K528N>8CQxx?Pjw>+3gdsgVqGkca zjUGeBl!t}jQjJe^crcQrz+itY@`-I}y&=Ypq>rl{DbHXs^CNA$=$Rv$n>SJX)=BL3 z`@2nD_h=JdLW5oTuX;BGbj|Q!JE)DMX_{}P`jHVLPT{82QKa;y!_(g|o?2G-&&}F| zF>syYl~1db3Q9g=X2lL|Q2s@yU3E!nVjz=cVB1#ROiuLfH&DOP&lbgDiFq!bf0;z7 zEB)W%#*I3)CA8RPMO9aP8yZ)0k+PaKOr-bJ{JPNNDaI@+%`~e48JmTws599hhghO+ z%Fs6-e1m8K=*}m52E6`iQeO?CVUo6nxuTuUX3oTkX2yl96c{}7$O0Uh4H;K@&p!sf z&1nr<{&gM(6&&4Vaa?dd27B+|AxE_=UA67Ss{I~zkdq!7>?daP3$VrJMOfk&=)ApK zCDV{a+$6oLWJB2ki;uPUW<}89#_K5h7enV&aX(ETxfY!KO3bG#9>KqT6JVJ&DsECJfY$x`gF-cPo5N z`?UUBVI)qd*OY^g42C~1%K}w2Xy(s^Eco8#DK#B^1=42>7EKD7--n?eh1woj)E)_L z4|E!vOTj6w_D|{WOCP{8jyjHGKyq-Mp8@;D%Jimlh)Sq(K+UnPG`kER^=DA4X-3eS zsGuw?s-?!4G;+jB7J61V<+O*+ zA~wrt`A9CA5e=mNhEH#iKeCK#Gos=M=%8gN>t-E%x{=$Ri9pj{RDHOZHs|$W-N`e= z#=H@Lej(xh{;xAacj<5g4e_FAh;c==0)mzWw<`>~Syn;c*`}nQSx^~d@-kk&TxNgj z!Z2li3mFzCgNqvuaeJ;3y?oWHxf!614?m?Q@z-Ww4lw)6L)RcRN|PXRJ@f5Qte$eH z;|k~uW)5YfL_CyNpoi9xG6eL6v3ba zRnNkPkSL>+*x5MG5Jq|NgLoM@t8MHtMqAJT8W*4}lWxLj*O}a7n!pZ-rOdhdf5r=L zxSPgT4AHs@T+(Y!R(N+%T!GF+jD=XNO)V^7W+$v^FGvMJIFjzfAA64U4YV=)68f!o zFQ2Ma<_TaF|DJID5TAvj`whUYjqsr$?J)HN|1T9D~OLdb}E##Xv~)w##| z6IHt>c9-3UzFA2Z2KauuCu`!#4SrlE9L|m)T-U*%wuPMYEB#hn{5Z~?iR;2rMw1|R zt6SZ5o+v}@IGr&+#qaSRJeA&VSf@kN9hWcj$ksUJaW z7rx4GxO4gLXS8qZ*jSVVyOv8Zc_?r(REVauEsR+C+p*krq)XQZ+KUvJYv7EQj5qxJ zQ|SU$$zCmg*}lz2W@TX^zfd(vTZoPePGXl-RpA_z|NR!vv6g0AeLWS6wN{Wc^t$xT zh;SnNTc7nkedMvZM7BJzW8|rTEZKdc9;3U2!)tAa1A?qsg}0_)eUX6^vhGtnJX~vy z8rSfd22x&1N>Z0Zl`u|jiBo7i<<---OGe)gtsJA|6l}@FRMJd`>W5erG z&sv>it>8Tpv=emF-}^_bwb?~ zQ~0ZG`f{TdRbw9eSkIb{?oj!Th&=3zrs+v8iAE}aQa!OPIS%V%zdaSWC&-zrI zPn?Zj>qc4__abe;hq3&)9R$oiwW=5`CHyZ0xN6?5NweGtClX*5pimJ(ux;DI5_5zIr`ou`y}wtIx>|=%k+Y=KTFd!m&-GNK zCwQrb{`jx6>=uXy9hB(5!jfTq?=!Cl>DO{0iJ~;A&^B( zTf>C!f_rm06l4oZ8c~!CXZ|EjmfLN|kDGgGp6>1X9FPLl&qX5<<>tiULm+e2g+7=Y z_p?QK`s|;!P5l+xIwiwXv~RuX6h66nzAp`ladjsUM-YjZPB@gM&r+j1*6OjKWWr9~yjW(J@nJLaSt(FRSEf~QcZ zrI(OBy_98i(_8IlPDi*U{Wj9gkjjP4#$rR=kAqCnT;`r$j$dHZxRG?_tn*AyM3uXO zcY~$CyNlD<6_=NpR`JSd1755(@_F+Nkrg!XB-{Qs>IL6=VFEk0O?c@2=?W!2wPVsp3Gcy zY?DYZ0kO1ll2j?}na8;xaJPpP6OddeOiAsmGbXEFU3yq43=S61E`@}wD3ctAbgdps z7`j*|!LKSO7G+ok#PXGT;8}qn|0tZ7SR7#L0_BV7{rH`CA8g~s22qXL*!;+w*wG6U!g+rxKA5;{COtdKa&SCW_ zVcAd6f>IS)@Pe1e`&v4eZ_c?10P{@-hWHNi18oWZwW`NRTE>(p z<kO)Frs@1B8LR4J7NnO-tFg2f;HiIB&h^w>*UDEA#`zAlp z;;awvnAA2^Lal@_&iBVK7Ij&6ITTPBYw_A|6lQQW(MZ} z7e8lZ;rPF%!~frH$i~9T^gqU}x&Ct-UazojSNMzb`a8Q3ZRaF1_5l#l3qivKI!j1K zgf~Gf;84aCJEu8^Ej-733%#w)GJj0wdLjXqqoldBY&%jy7Vc@rLuY%d%`Xv_h$^Z zwsLcGweiW=Xwxfmkg34;{se3Scj&X#Rf4a9y|K{e|8WHR&4`8yLzrs~Yx};x?6=;} z#aE;Ew`Uiu>X&B|4&_<`yMn}r1%Far0;Dmce}Ys0hVuu0yR-$+rQPvM`=t6*BY=2v zV;tMSJUN06^c2c>^`{v^fHtT2>(t-9hYbK>`3ME!=p01wAb^V>PBaDy__oafA)h=C z$R7^)i#a>JfpP%tcIX(y{)3tDsfIB`L&a}%q%SM0Pre0ns^<3quU5x$u+iQAYrXQn z7(0jNOt@%m$9B@OZQHifv2EM7Ivw+gZQHhO+ve%7zR4N9gEQHGVAZbLd)>HzVID%> zzfD(#bJ?4F!fGAekJ$r+bvFB`@BM|4=(Bo!-3&MhM@fh$8Tvs3bb)G9oA_R8?%%hk zcXx!g_3Z}1zPqOx&3nVo)_megNZs-w!~wQRq)k`|cZ$D!3IasE6mbOLS|ozw6~42C&9A z3M9?#j8O(7m~|h}#11LP0rFv;xX;};pzNFH=x5|sU-g^g?~l7k)OB23&j4-D!H)vw zA(-RiH*5f56%Q^E5Im+Z#OzNPcHmEh8mJAZqx<_!DGY81QV`rCf{>ZK9xy$ApnzXQ zCh;JwO#ytM_Qp@%BtcIfLm8KFu7PbD&f!W2c*4-YgFaJ8cO@Ru4I&2^!%v8y9aLSP zf6ZMgy!hxDz?V|6%8zBXqz))iG)_DHx+|O5vO*=-VAh8M-dY@0ff-( z8PdkEnzLt_mKMap`rGNN*~2pg=-T|p5C(J;p=Zh;*Xru}JnHnELmdh4YvQ}ghjA6w zCYFT{xB(r}Qw?k0M~`0QZ0ujpZlK>Ex9^a6XT}*2*zGdLdlxPxhKH$`b;zMJ1U<26 za{!yE?(`15?Dws1ReseoI_FWL>Skj>Qxu?;M+{%)p06MuKv*d;&Muu$giPadB|2Xm zNB$o4wK`m_5}z;|-&XHSJ(d`G*p**vWzle4!f>< zevO9FiDHbNUjCM$C%3-1zE5s~Vr%G$3Kp$2cBXps_Au_Gkb^2w)E<&25gQil-onmr)HaP4U&V=! zEme)lcabDJ`HK^bDSLav&+=EV`YUzM#i#afM{n;~*?JnXixslH3Ys2da~2XuE`h3| zcwT;i0InHnyh-WHH|Q;O+CK4c&-l0FarJx>V#1<~PYF>ad5SJ2lGls%uJmDM0#Vh; zXC+W&6#M-#Kz;#p76LnOPyaNZ-`G%y_NE@fHkrZ&nk9v2MEXZV9|=LBQvrsitTn^& zO=#47twx`m(Clla=i!5um7)J*9o2M7y>T*69pG<<7KNJ7ekxdaWh^9yMX{_XXzJ z5QN?_ELHq6&rmA4qEhQGSGFo=d{U9wgnX&uY4hfKgN?3QmCD~*td>1{yAum9j-Vy) z!JJ7`^;mUG3n4~eCOc@)xKv@}6JF)}!;9b!4wF}SPYOc{b?8vOHVe9H(_LdS)%QiB zw+|kXJFdfN^~)TI$rTG+M)OHCpOYGeNkpuz3G|4n1es~yW<=WyPD3}bX~h+1$* z#m;&^81LMn@b@>FE3~T+YOrcBXNc44%VBT@V@+WhZ!&`KtoKb{js*Aj+Z zN5)D1h_ZuT0})qvv4)Q92@o8^$+$#}K9?dfHJAdkYm09BdLNy9qIth{N#l#fz9M48 z`p{o3-s(j-6GG5t8`wEg+*RAj)l(C;1tpr|4si?T(MCr6?%_k|%9rM<%dV3cMtl8C zc*iq{j?Oe(jxd`)SV()GwZDifbT6Z^FOgl!9?&;|n;$8c(796&mU#AcuIhVjCNdgg zt4O1fc)5NZ(tO^q*n*0D;~Wz9AvRjzW=Xih;_b(BB*ot!9GP)%Fl;bCv{ zO}K)=gqKTAI6Wo)<4ujpGWIxS`|(GRvocgjl&0m4q_tDAvj13Wh=9;@!U=jF=`X`( z5+yBPIN3tfNs<+Q+SuoSQ>&p$U(2#mo~w!dmkh(pAm<-j8v1B(yCCLMss8Qg-DJ5u ztv~D6#7#!>RmW;LZDc*ZdC8o$6%Wk?xn3QKkY|O{jnPWeqP+JG9lNFcn=D8qNe9^> zs9w_&YVNW;H-ws9cAtl3E0XkO7DgS2&(aG`(th%%5l)(BWQ_DLd}dKFCer$9m_KHF zd7B~Bm8Pafm$ic1+G8seWyYHX6P&JvCzE+nX*+F?!wVm?HK(#kr&JQfzG*)m>;q?z zVfY1ndk+g6Pt@@R7edEH!=5dX*elJu#rb1A(;Ee_6Cq|%NIiPPFirx}^O?_+o09B? z!>J0Y?^p4XxpWh>)53J(`~qT?s9MipoZO>;KxU7I@4 zEf%Amx5Xr_9oA*q5h&4OT7sdYKsh9l_}XF?m>kjG?2`~-=0Rz#=T+$yC%l$*#gSF+9_$|j62#IvWesIg1oLB1a@SyW$s zR)eTCAXCl5qiWF)`NzE+fsT=?a;juqsM8NFwrX%XfF~MZZ~5CK7LDPA!!UV>u)4N9 zjkJrDCWgvPSTXjJgZ5{Fj@xxOp!3$7rt8L6|MzBr*=n`sq{npMt|48~x`oDQ0fS6& zASTR8v&{igcHc(nQuXu%tRS+Etz<>tzYcaCqc#ShH3&sPXHy;Jg;dC$oSHrDn9pkT&+XA0&F0YoLic z%Dwkp(EUjz_nY*nxLzJ@XDUJ?VerHyV#p7KY?Ex6tf*7?^ zeu?Q#Nv8c3O`5fdHA@j1O`6-E^c7tsPM$p@y0FQW=Xs!b~i&B1JUvIbajq0R!o8eTRfq;_^Uan}CDa@^AIGxdKz&+e02{_(? zf0A)i*nB=6nz1Ru*I}XzSYB_JXsGaxwA}d&*}?Zl-y`_cjbu@ciQ+`FDLp_jKf*pt z|AMHTA@OjhZ#qvF{>0t~gL{vOjZ59m)_|s(Tz0`OhZIHq5J_K|f-2fpsr)FfRwK4| z(b)sr*gVf3MMD?{uW&BCt20nPJF1E1c>gZVEP&c_8^(jSxAxo|=vUt^O!LV`b8rf9 zAUkB1;0|hv6+}JGW`7#K1CVabFNW!b8TmD9Xu;GZo97q;EOs!cdkt8K2 z5Dx`=8skLJVk3nCyZx}vl=N)mPm7i=;cx|ElH+*Dv|98r>( zia!oVbmPMkYo=9go|cP>Dy;N;fG&~>{L5TZ@5Wc2;zjY;FHFo&vi{67>wtzPDL#}X z<`PE7BoR`;LGOJ!A8+hL&nO{xjc(50XSUmnRqw;m&o73CCYFeSB)Vjntck` zn86=Sez9{J86Cgr4&@AEdJpwJNAr|77l>i78Z=2`2mBGY*5!o9Kmc%Z%#kT{I>~wK zb~X$SOF7^uIh-$~n0`As-V7)>gj-~Uh(t&(YX)X@E|s)9{U}()=Kie%;SJ7UAXrYr z5G}R$Zo?fv*1OMNzf^Nh%C5tZGI(_=fO~m|PI{lB@_IvJES0eTXD8?-#ZVNZA9;%+ z&aDfIc{(nTVjn8)IDaKMuG;=WB%$hgs0y*ic7=S9gI*;gWk8*O4O=PVJW^vGJcDNt z_{KM{eW9&W?8roBAldV_iuyJ6U?P|nZ{l<;X4)#1f$E(jVxVqej&-N!y@Wo)BP;RU!DFrB8DhV zx6F~X1T~bp|11Q?$Z75XwYZp8&o!FHqOPPyKe6xCj=H1Uez8_=!mNEbs1gtHjsKMf z-YU1l<9a)__BP@Ub(6Hq{;@lF0uVA^kbc_JYA(xJIX+<}Fy__JV#u>ZconIx4TxzU z(l8BMY?;_+XD%6!8ge)y`OJN8`q4AC6bNgPMq!yS8}_qDev;N4&T}5X$oZPU#0|zz zNJHE_Erd3+ya2xWn>nxiDK&mF9#z@O+6Kk%zM+s8oVoARZE_yh*td`y zj}7aD3cndOMnOum$O5~^a_bUXG#}1s`n5w<_;g+m-tjg0O zCtLlln7C2SB8X-;A4H~kO(ms*0JYLHEbj>~7r6XCp=xkZV4;&^4Ix#5)+I6fL;#5I zi-?ZbP}BW~CM8vcmyg@@4}Ib{>akAqo|AK}_|-d9saFGB<_`(oo+5{!$esjMqMykc z{;`mH7K=ZthP7hT#7N_BApp#leEh>)GFPLP3Z7opsyVf<`bP7L}SCD(!&Zlud zOEv-NOPxOo;V+k#(A%1va@P16v{4U!BEcKU?U$zv9doeTI_ zFdbam#P|-!<7->ebJmL(A`E-Iw7uLZ+ssj!m*`Q&o%Os)4BIW{Nk-FKXvGH}s%A{7 z{H#m!(h4p&7@$8!qMTJX)?phvv2ra)VASY&YF+Na%2cX#b> z_pF@P0%57@i*x5ngjnrW8FNZ_J1S|H*KMduavEfm# zZ$KSy4;Y7oeya=wc|bgT(TDkEucQjW+Dz1j(K7UpQK^0MZowoosS=Ip2bK&qdft_a|L#4{xVB>n2H%mw)sf) z+KZ?v%feK46t6)O;ADNK!)irC_!hO&PqT@1-CDKIvsqEFtgA1pVX$t=J+gj#293I1#CXhr<{t3M}dwdXCJ?yx^YSYok= zrAoGm1IKvyG~vf<#_Zzk!M?tzXmdtCX;*3lTc-Kor5X0p_KHQ}fo(8vZw8)1;SaXa zG$?Tyn5&SB*m*mh78u!XfpvaUI&mbVETa&!KrzcL+qTqnntTD`)nU@7M z4WoqF$F9wd@~}3`hz&`TSf-d#u<_(?1`W9J&9C9rcdPd<4M-{NRBr)yHvHPxQz8R9q~PFMCkXL z9CgAW7@y*e%i;dvgO8VKy}wN8!~FXpu&tB)d5Ll5u-bH+(`Y(GP)mtGo}zk~d~N%; zs7Frz0~u>QMmUx?jf+ez{e}6&g0qE6pET0G;WP49e=Jh>8KHh~ z1GH`;n)%5%X_{R4g>$*|^KnCsqTQ?}f-XL{Xl&|G2OutJuP7~**POiDJ0_2WLpN5k zyFk(FM7^L%>sJc9ygskd06p$}n6VQ%2j)FrW$h5@4aL&yO8^66czQ|xF*&#gChoC- z1)ccGt!LMag+qb|FG7Fa&2^k@wMOE08exBbJ8t~!6#2F<6Gsn&8CuW@sb>Fdd$X`X zZSp=2ULlvrN*_N8(K=+VT=N}K#X$f5YTnl}t|{URj(3&Z zl=T;wYvYK-Nw?c)+P#rjGjdB<1JOksDS;e*&_eh+>!UOw?OY}@uB_Nu8JqjPp>Odv z>zeXz3nc_LJe6s~sqNXe;L6#qtngd#P%?k@beRwx97?R_;zn|h=CdNiR8>K6yM9B0 ztIL;8bR{#97UXk7D=y|u?)dL+f)rpwV)B#PZyidV zyYn@8zaw-f>EE0&1Y$)6$NnNj8?P>T7~pL;{^nk}e4Tn72XREpY8EwCpd<~59=JoF zV255yen@7NCE%gtLh5!TB__(w_kL$%;jo5P56KzsN-t(8du_~8gn*n;G*=^EY}WYW za4cl9_FGXS-2-4F;;^d85{W%7{6*uF`)>)4qoC&3p~;gVfG-k_Jw(x7=qnV6W>xwg zmB{>AS}+T&KY-u1m|5TsPIaI$(;aoc){0Uo_DR3=DyVdBLXuK?-2nfWYJ(yu;$w_c zV=XXmPpnSTW#@Q{YFLUR{eY4&mSd`*_V6Hcdc%=NLlVX*Xw@=wZ75j7Bp}~dRNR2A9NM+D~E$k9b_XyRxONi7h)rVV7&a;vJ*t_|KT|S!X0uRV2 ziMO-tI{WjM7N;Prhm$G`vrv;7rt9*tY7Y$ogetkXTXHu`eFX%-&D*7GqEI@%@-~lt zu;H$=QS97lBbGP}balt(38|6ud*WovLQgWEq@rqP zPb?m$5rzi#hmel%@_{rBwVlX!k0DTl;^O<9^(3VotJ{#+cGfSlfgdxd>(A~v47#N$ zM$xu-YEW=?Im36v8qj2`00$>(r)<2UmOI;JL~N*XRMV%cPH*5X+V+m!_4o_Ta1~I@ zuV;8X@`%V!E4$4hV}s0NviA4M?cFh=F0p^r9K)SECmSE%fnUk`n8NtUwVk7*Gvw~f zE<{uIKwIbA>_lq|JWjWsqbhv^c+^usJNYma5{mxrY;!@n6%1ogjR+0dn77;1XO6ga zrs4!n%zPx&wUC6Wkx_Tnpz8>I|D?!6p|q9nSfDy1P!(udEO3vdgXnNrIB0UDx4d+B z5cb=rY>rDAm1DgzTo!{q8k#zXr)oO++Bg@3%|k%9%@hyq!RDSyU0JddwFIyYk#Z%& z$(-yxufkXxDzUXu64|cNDfld5W+(iq)ZyaJo&cW~+~C4-vWlVd`=kt^#ub}+8GPdj z&x7|RLe}KDh!66nrI*K|X1v3KwV_$@z%~_71Y_^0#R9a=4c!S%0Xl;3%UNljo(b#N z2cI?rZN(oJQ!vdkslQO&bSmYzfTX)Fjm%Y!gj~|m5(^_79bu7+d$@~x zFzY-WAyh;XAsOC%tk*T)%jS>%#m90bTLYlw`Q!4d(|a|It;y4bcJ~+w2{-I;?*u#w z^l))0Sqw-pmyiL8GGJ!77*uRs=$rYV;Y3;FesovqaTXh@?w{ZJlLalkcx76<8o3 zf>@Wi22hjG$$M}O0fa!MQ^4!vRskglNUH#YCIR5hfSzfH-kFJ?8z=vNWOT65FL`#* z;Js&rf3|7LNf-m@reL6)phb@aJ4w3$tjT@#-1KZz++_P>BZwvz776gr>rFVIzjGjI zc~IYCGte;s+=SU4*|}~#l=olM!Q7_cX`#5A+xQ?N+ARpJM&}Yk>+F5Uws^loLO{f|&PyY#V|If%|(U@`K`EfsrJD2H|a{UMf1{ zIzSIw9$K)5dM6fuuYqbs69PPh=!i-Qd=w~HFra`U9m4)8vn2-rC;))K02rJE_!x#1Dg3U- zx4zziBY?t60Uy}#-*5#Z2neIJJiZ#Dim@JR=mY#qs0V2Gfc$m=c1k0UHF3J%C_w)z z)%u`c&6(girJIm|Ms|ofKwv=oN*TU?8W#OaK7Y`@E5?7w?|3{lRlZFJeUD1GsV7AZmXQmcl==v|J;=7uUXfy2d40770gtD;157_b~RsVZQ1_ zvIP}6B0|a0pqsx*(gobM^b5=&LxouPCpp z{PhnQ;Dllq1U?i40{75+j^zb4zzo6!)7lOSs_{cZl%xgWOTh=PTIzv)IvF`pl0gI= zpFuSGkzaeNH6M`!6b@3)I8abQZv%f~{hmh5?+E@7^g_NNQiAL@{5xTG8@}Lw<_K4@ z0tJ~~t7v||{Pg$eLqiS1gA4-zp}}MzHszpNGc=~BI-biCWOXlz)9_#(;yYLe#NNNi z<*lIGROH6I& zx;7$GssMx&lzIWDVhbivWS;RagZ<^|nOD~|&*#@|8Y_^8p@d4wy=t+~FUg^nR!NUW zULE>5M46M2F3X|uWos-ws}k=up;+J)R)w4D$u>Q`@s3r5nr8&K8l5WxvsmX9`}-|^ zz3&j73PMH!dU{YL!uCwzuiOp2rWB!z3pxq1amw0!nQvHZ-vK)EIt%|4JLOlBRgAUoQq>h4$!wBqGxnUUsxXJ+vh019Q6U?B8GA9R8l$;Cq|iR^au0 z+@Z&@rl>Ffi=Odsi!iU}u}dB8V(@mpYyQ!!zr>#puQnj;(@Z4x&o9&#zv(C_d=_-n zwRS7mm^3OTzc*Ke2m^2BGF*%y8lm4Ey&}dgfnVV86lX*(TY1l0E%8NPp}h$U_dgr~Mf{3^xGT%a(x|sgng6xTAwp7n!FAm=4Nk@|O534epA>*j5$Pr6{yU zSHgrZdV9)vhVIqihzFYE^_$MW4wV7^8c>HAJj|5o4wEIe);Uy7p=A|n`9BMZ`2AW- zZF)H=z?Awl&FwoMvOpZ;6xH8AIqq~^%Xuq3A};7H+#1|bV4*m9BQ$)=buqLc?6n|z z1SaT?nGa{yl-W#Gc#DoMd@^!|IO*wqOV}rAJhCmmU&7EIcv-uKs4jR5hV<)X9XI8E zYOdcd%dPD_>GXJy^wwYu*Q4pS_<#|`#I+>WOj+qnlF<+cl2n##O=e4!)hMnOII)1i zM{xF9yON6keV_x<$)oe*fy(lxnY|Tc=lJ4S?ZH_?18kkkbmAS?5s5F9g{Cv*n3m8w zUeFXmOSSs0H4j3te}*wVfKZ()Vvynxj^ z@k9PT9s|W_ypgEnk~|(&F_vAt^AA+v=1=d~xCr^~5j~OkQp3e;a4cR9^*MIN*4UYl zfSu&zkizP;G$m%Ub#UYQN3~0HDDx|v6q5h~2sV=zXx`;kH-Y_iuOQ*p+WiPbh_4M-ALt@r! z+y10E1ZGax^Fleqdpwg_zKATKZ5%|oA4Pxj0~O40cHY@XTtmy%V*-LhWps7fl0i%{7y3%;BugD!VR~6(0vxlw?^C-_Rt&7 zqGqM}hNz(es%M{e^6kwXguAo#2pd~bF7XpeZ1TG*k5TIO@efq6$E6L)>uf-Ml&U+X zv16l{+IIy=%~hg^W`&%?%pv|gJ#oT0ndVYD2+Lasnp;NoB7b+_1WA_Z; zCfd-+wKI*mQ~+$Q4)!Wl{VNbL8*%rbk?JvzR^ZQEtD8%wFlUz*=wST+@ts1T@rCB7j-*1dIOfPZwk8E`cZvSlU1?Xt+%#`$2M23uR zy4>PQLKM%Wq8!#CMZd$-qH)6cW`k&#s?~3^6ne8Xo@+enA|xP+9d0D?x1nsG)UX5I)QZh#j&p1~MgZ@PDc4dvi>r)gHR?zP3eA zE>&RBR~^W+7rxp=5^XEISV48lsT^RXG0BZ=H08-(FzLuAfiv2=p)--y0t;3~661^N zGjwqMOQtgAmTS0`{r9YWht#Slvr$Wqr%EVqiKa&K*Q7avpG60-%mBcb6vo9w%w6)E zbG!bVCQfPcMp@774KvM}m$~oM@93h7gVcn4yH?)O=n;4W>W`FK?MUEQ(<};rkDh57wlIn z4_q~rd>}TY2QvSWxvFRo?b2uv&Mi2-?cj*OdAGe1*`_wYD;4;w>-%{$DIdEhGOl|2S11`8LpfkUZ4!WZ+D_ z@TfLt|65PUllI$Eti$>f_$eM5%UN${Ev<#tw3VDuUI4Bz}n|d-~v~6;9kT_Q( z_RjXQLTxtbJw#U~4R>AU{;Y&cBdI$wZJqWSbw>vA!laU``iFvFm+GJsP}v>+f~{8a zH;wU5B#8bb0rMq#2`>N7eCToqnke&Ig5SN;P5)uS%$~w z9#+i^KEHM<_B91-mfRdc)OM$HQkm0~KOf4}u3*tgN8cerwbuDeZ!!<`UF&LPu~u$T zcE)$kO7COFja1kW^h}eYZ(6vs_!H2-YhSz1&(UnM$gf^&XSj!UjjR2)w)yK~K!{ zH^Q9<(ONmFC^i%FZpy210tB=}(G62RMi=jN_)IwK3&AWRer$?%iT?T_R$@=|P}0-S zg;sZtcWZDhWhmcfjT;b$-lOvP=Ec(%1zK&&)S|?RZuwPe#T=am#;Jm%$F@i$arD(! zx-*?I+~IF3;4IJNk@5z}s(f=&HUXu^qc2FKgI(|7+P_>YCUl}gjJrea=Egj^px7`= zS|Ki%rnN9z)gYW?prV=?&!U=ljR?GLoA0(&_u4nkUtY2ZMtC*1vlT3h+$223 zc;t1H+!}9MNj+Ja86Zk(Ma^U48dd7HdtTF*=o;9BQUK)wldh1^^(YOl<5?#QqYAaD zY;>`^i*L^`_u{l>|5_wbAA37Vh~w1+D27>52JSHPh)2$=zY ze5Ch_XBF5)|KWO`t;%B?f=0ibsc;f4s*;=eV&$vJ+aZWpQD$ny7~|Cr z8zuQC!O-9cUgdKW^J;s@sJT}?NC~GBx_>FAT>{2;&X#GpaO;Vwe!d08BvTzUi|~QW z-;CQWensC?ZO=ln;&C$y19Ewbn8J2Q=kURJ*7Q(KEO4`orkOj*@mFD5AnPqo_O2Ie za-!$URA%=6E8>zcL8-&I%-5(9tmV*NG?wOPxCt+NJfy{60)K0oX|f&H z1^V@OVFrro@GK@BJv%jFCBKFu2wbn1+QCXTnm z@3EGSuzf9`vJSlxW|#~z$vp*hR0hgwoXYIMcGZz=?W}sywulvyUtdS?&Z7(V<5ISMO2FB_19R0_<{f-qRKZ0!vX!(z3T|Sj_Rr*+o zOl`4Ze|>eT_E@T9Pw_jUs=qPuU2dI@5Rmk(|31Z1*ug+jyH8Tt=Q<6b$CD{0Syt2L z(H7I==MFMEf+q+xyMMtpgnZ)Uib#rU3bRF zg}Vhd7>TqOm$7T#wA^K?&JeuEZc~w1@TCEMLr%mIJ=!T?jxa-9AJz`G@^O{(dhB7) zs}5(|@6kKI__RMPvGb!U0|*<(gzd1nS6s5oC{bhcg12#M{qefa*jTNJSHN0e%VEN& zeLsC94H+y@kaGFb8$f9w61#bqtN)E$9rWw)7Pp9ZBeP}x^Y{;2hM^~qw-#A z5)rEZA8{nmH>&*}fmsP)&&x~og?qJi}DL(jy3_#<4t7I zXRhl`q`-`_0={^nkBip?1i#srsLQX67V$5mPCg~vgV+3R;U`nBxFU&_(qCAbk>(wY zb7rNOm-%LGYC+{o#HhA=eM_*Xj&bNc*kxUuV#^)Yfp}*%I$+n^(p*&PV@u`JgHH+X z^hwwTa?6C&&MtG1eFI|d{~Akv!&d*=h?liYcTGCNdZl-@m3uYcs!=GCb9H9HIUTvf zBEJ7K_@`jQc%-IWM3&+-v#Kdfl?z+qtVQDBTYOqZUGuLT-)!vQ z#G8B+LlG07G^Yn(s$x+%P1}qS0BT zyZD*32XmqD2+SV1k+#?J@y|)>(ns3bdJ~s!@AXwwzXW>?u!cL376n?>?U-m@Z>M$c zzT18^j22UHXEshxljTEl`h|sC3%lCKPf{QJDauSY4ISw(@a_p^b>+j3*Y!7KIIKVW zE6YT}x-QjLOd^zNS6uh7^&D1)9fV3mG~bbV(xnw)-qj+@PEeaAPyE9T#D)uU*qMNM z34Q_0l?PisJ6ir07yc>;arCBjVaC3@85YXu=^Yn`xg+y3AshL13>Zx00zWHlOxVRI zLU5HXZnNqZ1%mU%BPPQ%h2v3(bE@KJ1dXpW5d;B5OcQrz_!A@Q7uJzKAl8_D=7~I7<;+soSj9^%MZHf|ul&}qLE+y4}XC1Bp@4*WN)y|0__61x` zu)F0!@j;u9d%AQl(xTz>%`|2U{T1AUCpikzPw^2sRNXcoPI~>;J+64fgvMMK;F?>C zm+dn3R%bs?zf^{1j^v=F#C{d8Y&bWq3pQJh7_t1FndC{~ncq!Bju++_jw5eZ&`!3} zE~t~?neYpqEhg8Y<`2?cPetb}G`G{(j_1_76Fq4#L?@?@Yc)XunsB5+agK_L9MF{` zv59)52<%IK8st(6T;Vn5^;v}cBptn8{DtK~eEZm%>3mO`cb};eU+sb~;}4aQ+OG5g7RIfL8vM}4W8n4d=_q4P`lrOJ+x(BMM1 zZcNtm9)>buDsA4-(j1Y@3cgfuFFR-{PtXe;$OVtETPq2f3&qXSIBGkDw{9>Dp5!qo z18T}G+uQCG7L{g2sCygM2D6hUHnwn;-scob>v9x|M(~qHK@)Ra;SJ*hua;S5=YYpu zul_cZli@3!r~>(CObTnZx!UxVJRbHoSs=W!?k~LiV?{$xM}Bqa zFCxOFIL*CuT?9@w`r-j3<=*S5++IL0K;dl~wi%46`Br_WWyv*PAGc9{4ZM${#Pz9m z5dAxNOLL{BDH$kD=D;CAK0FpjWX@*#F^@$BJ()7L8cPjv<`-ELMB8v*H&%0tRUY6+A{-Fpve7XK!h%;Zs`0rtf3yTO=(?sF(H z!CU-;4m!W#eYLxeGv=j0=^d1(502J9le6Tr&dXnz3Eo-LG5>=lM&ev#WBecue|A>) zRK|!sw#EsV1P`j|s6`g(fNQj3>nr$AQ8}C`+n~Ex80cGt!U=;K@#EuFdU6gbnCpXp zjbifMaU3Jm8Dcvke2`YzUjt_HXVJKODt6lNuAz#9n2E#coUDv7bj~ZClTQcX&pB@! zveuhNQ0I_QtfXbT!4Po?iU)K%*A$6lY1|rR5#pjlAX>$xLVD6>5N;$P33Ss-)tdyJ zakVTCB`~Qp3w|BHWj2pjWn8Q@dfTtE2R;V1c;M$qzP^vvN=5&@13S9dD#ds80?Y-_ z^k(3lw}R-ddu4~nB0eXECVBb|la_6rNZ2WS#tV0e8mLS9^TZXGA~+4UJ_!8dO9vaZ zjRfvqGU0sYSBqnZ`^xtaD${r51N0fLmG<>FenT58SD)IurSx`<1JCpGp7qIv9?yu! zM1LTe8s}1-k8%RMh~g_3ctDar1Pff6VK666&vki}fbd2D3X+D?Z2@H4peMbMX5}p+ z4&MN-T=9I4k8h)>nkg{wm3n*iQYlOoJ)TlKVkCiZIWzshC^Vb11|wFhuzLqJ##w>m zfChXNko3$Dt_*CO`0ymtj0%nDGuu1?@BKCvl~tx*fz4aO0`Av8qcis7ldF~wU3#2r zVDtyDFXutaC!cW-Xa#^L<<8Yrv;__NLV`1A!U-{!}tx4?AUFEdi}H z@lU&e9}6C$L0WxM6^#x4n8o|8Yt!kbxi~8sj*&a*yJHWBFkBF2yq}SNzIQDNn;kC7 zJ!|@kI_Ye~=&a5A+2RbC@cN5-ZUCu1H(AG6#K&_NYGyJTJ?2>PS&%7z4!_?KvD=bM z#o9E77Rk+=X@@=&qk0v;yq{&cr#D%oCXsknasiwLOXLP-`9C`GhQtv%3zHg`bifK_ z_lSWu5$H#M9l9Rojz5;p&;DNQv^7&sMumgSQRQ4{o<=G(pnECLfM1;OPO%J`M7|xh z_Z3f|zywS;H6(&dLPlc!L3)P*A76N@sCjv8@FY~1fTsH{KQMm%cwbpso?pcua+5A~ zE9%e^l}DeM;)bGDjhgdxVd$F_N5PM=by~RfiS#EiFcmWa=FD}}B(uet*oAE-lr-i1 zVpLB9aDKR*)ZLuInY1g8GGmog&7u;6yy6>hQ7bRgv#p{+(tYAdA(zKwT5ZgUuOj(O z)7Al%#;iKQuWv`z4e~@*#BCjA#xu8nUZw0gvwkACCO%U4V)xs7_sK8{LU#euNRZoy z=t(e#QYa@_uw#jL8p56ul!~-tmdF~OAw9lh%%)E1jt{_iXEJX@?f}n~rz(SgF!_XA z5I79^aZwe0voZAo{brcs%U~jN%QJkOzF&Ck<>gX9m!3(M@2ZMxT0W{M2Z7j;85Q4C}Cml^A^x#49y3de3giE~?T z`oK%EQXDM8M-pW6RZsqvyGMSlJIP}=g0qOZnI^3r0BP?v*j*QNw0yLIL)uum2j2z^ z>r6@-!`Z|Xeq&o2BV5P;kQH~%>yJ0T^tebh6hDXJh%XH%%o`c++99~^!B!H;DyQK_ zs)i`_3aF&0t&4mlY`?C89OJ%<0mD@u&%&wU!9mpG&_n>l?&IEn1Z|*)xJLt6C|Of! zGvny>yMGz!Bg^vaeR>2#l{Lq$^ri5?DCeV-X3aLyRKPJ>A`M0t1}7b~jG7qlJUnCN z{Jk2`OseCGP3QldlTH2m`kwj{{ zxH!1}KZcC(|G*(@{C`Psbaq*oe3us_k(Jq47kAisP&lT=SwhLwe-;4AV3!hB$>5+u zR;c;Ay$kPY&zZNMrf&Nwt(nc0>#iH?9YJa~IWTeU&ba_VI;cs6&lXJhQcyRyKu$sMA49@3IQCG!u|iox1-Eeo#ekp+JfJ~vpgWkL zS1>M4pe$TmkRN6j2XrvW^mZXypm7@@a7fBkaCpkI-P1F;y81A_qPG>~UV~{UAZV!D zy3Zp7q!vgXkx98cAXAkzw$*Q{g0?a|!G%6tkTB10btni!Ys^WdKiOMbTiH{K+o4l^ zYtl&x;JXNcnxL$`^akb}wcxw%13bk-3Q1Z~B^WRqKqSa2RFt3s1~ zim4Qc>ZRbTShq>Ixl}b^imqTHKbSOMOa{Q8d^kW6@Q*hR{@yusF8Z<+1s!k4mBIdI?Qn`ne2)d-BfR<}3L zI+NK%af}%37!g}H=xhGro*DJ5i^B7L+xT#yZMk373NZU{?Ecst6d!=hrcmxyk**(z z6r|G7qZ@Ks9lW)sJR}PB+Rnutas}eXpV7)*Mj%8;0RjvG3ZP3cAn!Eoh988Qqcf;) z8R&O9zw_Rejk!K#gSSPnRSY9&zju)bHzrq5P=o1e1N|F+>TjI9KtUkb2rf7Sh~^-{ zxo^}jDY)j(U;zCN);=)fuE#z;RPWu#%gsV2g_kC$;1%zW@%PGCy)~8P7|j{e&)Mq^ zH#9UPVgLsXRPXrM05DMCs~}K!N$`!ogc3{Wr!M%2zs^x!3IY()2*3(3{8$sU^-T^m zurtvI^?GAKji68o4vP6L;v|BAkMK}}c>0rm?%($L!}RH%^n)|@(?W=)&ePGe2wY8{^a5GPw^ON&VwzX?#EyfG&h<^(1PhhQxsb z`9i=oCFEJnJUv~UW1*n_6XF51om&Fl1oRJxW&^~7 zvk3hB4_$Y@hGB5F8}s~;@%9RIIo>1Yk0cPFd$c1d2-Iu$Z9n*c!)Kd!)K<4I?A2A@%ADDyE{sZa6PxkN%=_7sohByjs z@bV7(z2Y&co1G0fe!-{!n7uH3uHb+}cn3_)p`YMRh6dSK1+Q0^4@qrlwhV_R#H-Xi za%zsi#wr?q%`Xh^9I!Por=kgr(mn^8#Mp4Fl4e!c_e=pi?U$97y`A)HmB&A8^I4;_ zy*mQ{Qn%ft1vvvYK@$sdDY;0rj@RKTB=LjiUi4;$OEu7gk9jp$x{?kh12oBdDo}PR zXQ$=#Q@@D`QD?a{Rsz^E;Vo_NvQXzvDmO;J>_oA`N=ge=XkgrR3Whq=4XfZ05UUJc z65J)aRUBYfx%1!y4P{{A6QmpqexFqy8gCvYwO*ARcw~<4OOG;P%d(Is4cnPMUR;yB zg{u7zW9Qf-SlDgb>ayKs+qThV+qP}nwr$(CZQHhQo!sOid6RQK?jP_ZYp*ru7%&?) zJv+|S@aK0eYd^Lrd9dt zea4&YVwKjOk_-SESH}J^+2rE&Jv^Q~BxJ48mM_f?@+mm+jN3Qx&^>P1<$Cm`&hm@s`A3k#jbD zj99bJ0n5$$StSM)V3j#hfeT%FR`+h7V@r^Q# zm21F9=UJ%t8lNG{TQ2WS9Nz{y1LpO&7a%@VaV6K`brt#0?fW66N0Dkn>E5TA9vKul5hBY~G%dK`DojR{Eso@Z2Fohsb@(rc%B{sQv&q zOvegs|DOi>ADoe~!nT=RLy*vB_Jx#Pm9oJeDy_wUqlCTJ#=R}K$}!>8CMiW_G3yCw zgCO$EPE;1K>Mx(T{|Z?4_Mn8x!M@B(;lwVne?fRM5=Q* zhbcC`q@XS#S!WMx+M=#XXBkGdE8H=4}Pt98| zE=G*kFlTOxyT`Ypc^ru#=*(Q&ZR$peFVFQgPdFfpTkuqwIL@y`FypNu3=K{@vL_kD zz61CB5Q^fwk`Q+PE+WPgs3^|>I^W$h}H;6;??jMPa`}oa!&dbbxyjX zK46$962@@s898GLv~#y?>p`>njaJSf^QYTSh=JETIWsRR#}{;a@rD?6-N_B!NFH9e z#hVuN{3=)0XYj3Sx9!ubgjWgX-UBI=YG7G`H+-X9Jt<-=*|)l)8sOE(7<;>6tN~NN z8TrB9i#5}no){~!1%=1iQG@%)rNgh6n)<3ah_4AF-Y1vR(?I63ILS1`W}GGBGZ9H7 z9{wV}FYdWKB@f%B1(C)oNk(H5ffJwTppo(A@;Hpwy7<#5I_nAy0{J+WO#j3@NdY|z zXi01vMme5vhAS!mh*pqC2Y*Qj#oQFw_>;;|xrG>8WyI3;h^}<5e04X*$j$>|ys)u_ zXbUb#BRqjZS@zcrl}`~T^Lo!neJ$BXiaPdJ?c+!-K4-xVPo2k=mY)s?&lljO0AfiT z82xtXk^}I(T6xEQWsDs89;%KtG(50S*>@0oaf`%8lQH5DWbQ5xjFy(!tW#4jST(5` z3IvkKKzTim?vImagtw1Z!L~v{BWNvSwXK3TuGv~jCh^1m;|*_A0{gfyUG^`Nz*~IF z`+>2E%TQUBW+suN^;}vcP(-HaR1VGiA1n}YiBfc?QCRc^UOR7orfrJA;o1supjn0k zGz!*c0U}c6`BBQVl9Uljb<;oIDnUHDb!@58vG(+Zq+^KF(h-<~Vs82pi{JJFe8DE2 zaH165OHC-Z)Qt-yidhgu}}foi|5$wIisLjB~_udq*~$GjuGGt#cY`;0hyU z0jBbKiZE9_;lhoXhnz%aY38r=uh&^MWFqNe7!a;u{!WlO%x@GsYYyNy2{&bc$bA}* z#IcY&qXvi|_B6~(hD(+ZG+>{Ve%xA&B_hT+&@naO+3Ua&H2M3k73G%T#yRQz#HCb; zcODym|DGT`l%6vmSHnEisnP;JLofu622AXNEzQwwWdQXj`m!kX?@%L@TwCm0y2FJRo<$J(hKXgky?F*_ib)(*oStyYC^$ETrpj7yth3wdAJUc~GgiGpu6 z2LvO-r3;?psvJ_>eYBkZ+%%wRaalw8ti=xOjjOJb3SH$vlN?^g!rg12vR(uv1`j^* zTONvfYy%!kt3HPt%y+ZBgd~(ALy`U+H)hHE`Rzm^F+*-DCX(}6H^6~LJurk|KQ76Y zP?#xYfioQAf;>!s3F$zvt@rt7etWlx3Jx~-kBB|3>u!2gZgD!2%NRG7X@ikWQ~%Q8 z_aW|ABD{4IP?~sF>*?-K4rIO2v9i6}6mG1k)6q_p;S_Cl(y zj}L+@f!yQdC}~4Pnk)JsOmL+-IoNyooe*xb?OZM~l-5%#MU4c=mK>qcZV z*7&hI61c9W-wr7D2^Z44a#`>rZg__;5*R2-!#Eu$bh+u)O&@i=51aYI1AhYzrWehi zLnW^@cT!Xi&9rhRYr^U{?GdDNX3u)by)S1{**oMMJoN!eRj8>SMj1pg*8Nq9g$WXe z1o`6R+LO*Rtg0+}>IR%-}K-uG1I7P$R-ntJH&R`MI8euZcqV zs5B7hp_Se+eQzMca8QW@42l#2oCB^cpvlklbQF;_JPk=|v_B-#jJhar?<|<+1Qg-m z0s2#7Wa$L zQFk<)1J5mF$J1LSwbMiZW1e;`T{!MF-5fTF))@_d{)Of2B{WIp-Cn3$_BV5~C$;no zY?}E{28T`9x-_LZb(3M#{ zjCvlQl9eX+x* zsN2yX!itiip&fp-xz17+CXojo?m{q%M`oKEt^o;FR!d!9e&^eJY8HZ#ah&|x18=Y@J1_U zrrT5=zDT10HU*r`OS;f3n+MlUT9W?qVubL?dO};Avu(=VSY-~baMG01w%&KV)Y%Wx z(5PkL+3$*wwTLIRWe4${*mK3*%yO&ATnotOef!x&+|*=49P6!Qb|xN%+1dAjSpgg| zi<(>H!_HiAyl*1)z?}7q4ou@u`yNPj1V^Vh&NN6DzxPQ8ea{waCnp|>nLwc7pua5l zMsAATL;%W+q^g!9>-mACa~yOD;Taf?vk2@)*|O2ONy$8w#Vc|8F%@dShq5>t+TMBj zeCg6o&7Y}aZGvnnX(+4d`|46a~0gCEp;J#cb0<5 zQlJAcN3<*WORfABjCJzi!%mS>aNoPR&b7^%AK!z#c%o{;B4Z#ZB^&sf=)Pt3!yI~U z2nk#fp&vYcBJLHeP9sb0uu6oeq`tFae@0!>2Wr8L_-?a>1rrZdjOtxLm$-<>=uTms zVf>ZClc)kHbzpZ_#M-ORhvb!dWOp!HPt(1Wm>dPTWkel9M|Ag<=1Yk>j&g65=xlQc z*zfZUmNL<2wnFKWuXlTGqa%wT*A#evYy>aeH*-bI$r^x{hG&Gb5Bnbg90 z+i1FY*Ns|V8gFv7g{q_dKceNS`Q4~>(r~LZw-x+tqdL==;Kqx6c><;fz#LMk$`{^ zd0M5|KH%Qc;)x=31Bk~RUh0&c&IWXKVi#gOsSS$5SYxB`F_(LTd9M}^Th=>Y}U<$#L)+o5E2;uu%Fc-YK&5A&mRm?T;52FrR6eF>8Qfk}3CA-?WUN+hKilbwUmY zb{U_TjjR(_91Y6^m2ZEbU4{dMar4PQq&i0i!*Pi@nr!5bmEB3eX{Oa;&=Y{AF~6X_YG{65Pk>u=%L01K~> zeZ({RyFX2%*j&84jF_lglR&$i9OZ< z-W^>e4c1B?>xWgmo>nUW*$xISI!>2xci&D7-8Kw!=Nsv9<5Np~3=5=EQ~D`nsy=ldK0_>a83Jph#Drk#8d%*F{2(mpE^;K`E7WUg+N; zCgutSi=%Ys)_ZT6L_x+gg;{@C2#*vSEfS8(AJSClcT(| z=dh7Cs^_%rr99qL92CA2n%>c0_u4ev?uBoXTD7|lEbQA8xL6J%QSv){7Z>6FUu2U6 zF3=}XdLI1lDXOPOPt2N_P?f>(IOZMu=R6B<`DEZ-DfTkKtN7H!Tb z^WjUo2;z_5dAk~7Dx@!G9V$p$XbGr%*aWrNfgpaMY|0f~F(229+VK<*wQxtwSCTK= zz7r6oxeB{ybRHqg6>K6x*MTLk|9Y&TI26^ec;zxqDY`cgo3~?rbL8kmvU>5~c){{Y zXBkz7%TVE-Yv@#8F>R>OuqfJT@ zDZKYS@HLLZBUmlMNE+LsTLmy4y*7M+jAoTB?-yRESZuBiX(xRFq&~7VEM$>8^B@sG zE4ikj82^CbQ5%AA**)yN{k8ZyJqe_KE@pl3iwiCgK9o-jq7FMoRjNO5!TYl=$ zso@^)55z++N75Xa-tJK6LVSr{Ce)x(>I#B0N@4>{_GN!cC|;h8xZBifpQEvUZdj3l z!Nua@nYYgYcV+dX*q_&+llCS5WYf2|zgJ28LJZN`{w>I+sKGu2#j0n{aHZ&X-lI7- zY0YoRY0tG0xZ+=Fn5WcjH&M36OF#TkrRWT#fdxq=l2%lay(A_1)Cuje@a`N4%PXkK zjs1D?#e+b%Bm{95NQa>6$oDxWs!h-J9i zGCLL~dk>B!l=1^I529w=nR)#3@>*hmfIX{k zq+Zre7-s68sT{t?dc?VL*G^1M>EFoBr0*$`4nlQ z!(my;)x9~x>!Sj2cp}kP%8ka0u8aGPgY;_Ea-8yvF#s*JFMM%S~ghq zyWY3-3;2Ju14zN%y-RN7&cF8>LKw)d(`)`?x;)10=KXt zrV)xG;t2vfg?q5+lftFAwM)%X!@Q50d=vMW2H4wdwUClF*%JtMs~pTWrp)@?=|9Qi z6Hkh&iI!Fd+TN6;9kcbrOg&wqI_|;xt=l&!k}2?JaBh9yM=Ah{2!rm@RX?;Gx0r5- zzAvnYBPrCa=rwB++%DX@SR8L?oowxF7FFS_GBoN3Ya19Fm}6jfq}b#?z+7y{xCPzv z%KW!0tFO})yl~B*1qL9dkG_aJ7=d=h-yG0k<_Se{6-H7t-3?N>W%fQmUe*c*L@T;S zCOtJVi14v(nDQC~tR`M*5ZHs+DO~(tg%lJ7TwVfIPt-o2sj$f*sU`jt=~|$#Q~~(U zj17-&m@r=BQx;k7R2T_{XyMfmy&!h&vAY2(UyBz6hQeQ{P_T!X7;Q8jy+NrVej!cD zqYQazLm8iUE^_hq-XknNQ-X4=XUn`Kn^Q&n6CM}l0-Bv{M!qXswvHPj_!T%dz@!TJ6 zw5VYw0*jo9Qyqf-<5#7m4-<<>oOB^7G*Jt6BNxn)<(M!ETX!tO9|tFpp!d7S^mWcG zv^5xOOp5w54r=-e1BpZfYtk8c!=peq$~8^(`T-}veo$e2u9fPo%btsnN~hwgR-8*N%^;h{ zpOkjJoci}8L6nSo1-qxw6G{9VBQ)e1PwuwzoawKVYDpx_BqvX3f$5mIRd-gVSbs1I zpNV8$CO_Tj-(tb{Dmbb~g-&Ubx5FTR-cES`G6asTN9~}zQbnH<8Ukrhm&z4>x9CxC zO*NGu?uIJ7z;EF+RTTsoz3!(b$0R*Gfjm{GC693Q8gnj4P@D6V8h2{&BfbamMT$Jq z(kmryP3Cv~Iu;-aPL=PtmT;2B&WATSNAya|@_{nVuyGPT(s<^BZ;v8k+_^z&4j6j+ z)%7ZAEy<|V+O$!%Bvb?{(kcxqxeL+)Mkw+-TJ>XnOm3y4e{l`Tem0v);sT6}^!pqa z?%!8UkFe{=5Bw=s9JsrpAH)6j1r62y+Gvku>D}~bA%r6+D%O}|%tJ;;24Q$ve^1<7 z*ejsX+M&@Nf6(0a!iCQlrC$kjC}w_RXx|pcNuhzcyqDb+a2}5GCf~DLU4Lw1Q!0ao zqE<1t_a@8mbzE0;pz~%5R^?L>ldprt0iXpJpPz6742nE~jGmj$DR4T)vigx>c+_~c&uYW_Ctci2`=LV5mN9&;)38iRN)bM!s`$gK%-5SPXfmIi z_62b{gc7C3K;CLD#D(!=89PSg`TY4bFhBNZ0Rf)8jReDm@U5A%=bufiwfPicK!i(% zEPHmdK$09t<`PpZNs0SFo8Ht+Y(GjQFE<8Bf`o`jB%j^DHor@8cAZC6!|asviCI3! zXVps&wHV&WOY4fdQz2X5rDx$1^Fkua-0 z2ywRy9k^*=6merQnrd()o001-%QQx_5nFkq#<5e0R76fV6sRlffg7I?%VP%^ro%b{ zao11r9K~BinyM7K3nULYApxCK+l?xaW{W*dzysSHkwjl5G_3t+_+c)p$vXxzVuZi- zBh-*0EQx8X6Y2JyW%mYw1 z{#Wo{g-P+&+ey_^XP;ZrvI|5wSI7H(Nui;QvF0#?)3@bWd&^9Aam%7 zSooO{F`kIWbkQgH0-^PQuMX7AF;MmN7GW9S=EZDuWmQxe9}4YCaS-!vU0(>gI_nC? zMVY;Cpc0Qw4HYNP^J>`0v+&ez$1!Uo5f%_0@X3_xThh;}_Bv#6-3-_CLDU`QJphN> zZj6wJ%)1R)*2|e{oV54kVE&?QYZ`t5nC22%5wam<%3Pr9yJG65qaTW=&=kIiz7g;*&cN+-Vs?3=nsdpq=AK-y`6DU?fw!{wnDU6@eJ1SfWBn4VLho*b4 zwBHt+E!_Eo`%wwEl{tz829X$t5Up)uv}+`kGfWUT^|^Q2s8q4u&&#MYT;-M>JED;K znmeE9hzk+SsonGf(PqRt=@|sdY$i!7vo|y)T#>$rX_B}hF4+5CE>joXz{4(BgiVx=ZtF~{uc3hOhY9776`xaMP+WC9kiD9AB0Ig1# zS|*}E5+g6chwHihfvUo_L6eR$Rx~i<6ju^pfhYw*o0$`MVvL6CW2AM6c+c5KGXv6m zh#`+jYfV9QB;HXK17;d9R0*zo)FN#z+cJaON{D07&1~~<4*Z>b!3_Ob11z5_FELMO z^~_xe4IiKlV=vk^@Sx^-d8~~xMzudZyW?)@&TH8sUXzK11|q<7@gd_T>PulkS`@aF z6LK1zXm}sx(iwudLtBpzYAUN%7rEt=z4`Cw!B20=we@N`r@rw6fNE8Om{C+M_0*jGS#i9dU@bZDu1MVE|AiiHpE{R+jmmh#&7$q z#I+k_ams5nFeZhR{P}?8x;_K){23GrHPt$>l?gfS^W3Egn6SJ&mKIB)c;PI#!H6Mm zqE}`1v=@}-6p{aIQwHR8D}(&2q}Az*NeWP_nh+F@6%jdi<(6pOJzPm3zBW}VmjErz zL3JEw@zO0c+diOjSsUZjYBoHxAFXzX^(ZBwzUS}Yhxx}TNgOLwkUOf(1#HR31eAy= z5rQG$WArlQQn=zm*3|F7Mg`?X!iF}2XnD_Ij80h?5`QAqeepMPoEs9``<9^(N~I*P zz%q?|Ynxv;mPhAB+!YV=ugB6&cS_2daldjIX=C`uJtu(6%=p-nMO$tw_h3W~`rO*A zK%HSC#b_*EDU0bh7F?NJPQUXgl23Xr8|Ma0w8?FX81#q-QM;5G!>h>-O7te9i9CSY zX#n}X9C@me)7ixN9oMqISgL2=ZL0>Pk$&q)i$0Q#Gqd6X;qRraY=qoyl-~Bf^z8T) z4((a~1Cvcm!BA5@ zgJo#PUS%7z%Ectpax|Fcl9}}-r+B7X6O;y)e6?+?r?66KlJPBlXqs7Ssy_ttMYcx9 zPB#CueS9KJ-bbHBP%@}Ez-TYTQe!{jxjQ%`FJ?>nQ+;9jtwmL>HN%Xu3R}H23e(a3 z&5@!=LsRFf!6GCgQZ*4Ly`eGM#G~x-9F(lT>O&8g$>sw zai}uyCidKsw3Pdvod-jq?}9)TB*2uul!@cpIBI*!Q!0lO&S4F%g#e8Q$5lQ;iuU@6 zJMbwBW#qk%JuQQ|WzSgF{YJr-4naK&X7}@CcOdinu6;QHMJSD0?m@cz9he1MIVFZ{ zMbBAwFyWZXQh z6P@hKgA-)u|M3rFht9JWMFWI=*ZBi!ElUR(K<+P>%0>;0m3w^+3=av7_OfOKcjtLO_F4Akqrp{UqWZ!O2LLWSM{~8GNOK{&6Krv!R@aHuav~2PMh%Y_RH!}|6KBxmf{#z_v zi4NiY4@CgG5pio2VE-CAqzHbP&r=DwLx2F?$o16Ei81ybxJ>JfPB1mJwZVr4IHn7# z_pfVf3A?=b^*69b@D0`wkPkq>XGf23rw6e37vRZ%_2Gx2=H?3U>k9c5#DL`X#fiTa zz>;2&?@O;)b`rOa7V+{ANbcrl-go!U#+^-sDj$F@P(UugvMeWB=4;M58k+gX$gpNN z<|LFZ=%B3(0Kn(dhli10UJ4B0_2HMy>&?ee3M&h}lJfBzD z)^EKwc3EKXK2PB9p0@wemIM zXSF8>glrKC5|n_2;al zwR`SD(P2z3(rNKN!J6&v*m`FJ&N-ov#Q+{oZU^flbl&N2QWZ9t$Hvw++(TiI7%_x1 zY?F}FP^v^38f!B|BLf6Fp`o);DF~QnCxSZh| zY)J#5)vOk!blFDWUw~T!2@lAeI4nh(adJCgCCZ@m_%)&XLRr&V$#9o6MnpVdMf6+- z7f5iY%3_Y73W&v5zj!A5ZY6jE2zV>DmAr|EJWiJrB=AZ#ZuUnN8hO(y7BREM<23WrmnrpTec5hq%Ru9j11WuB{3W3>rK&6L#SRgL{G+n>OiB}fEG_JlPF)MNF3)! zh+DJ3pBY&i4Oz~hr85r_QCT#`e%Wr?e5eE3686HR zXmyXX1aKq*l-;{5dLB?`Di!B+m^=1kqR@L+S7Ljh90=c zZ_e38yl)R*@vLiX+}-j>De^XFPx%hP?`s8<%GF?I{Se2*wf24rVVA z7ESEq%lFZBOV7+Ppqf+hvxFy4KfLXH!>X5I>^#AZHEJ|CDDtG5qZ4{L2* z%7M4gYU!^GlRbEYbb8;hFL7!M%Qkm)5e?fLgGLu&P|MOt=?&{l-gnJ!{WVFOfKS@= zl7}q(zk0);TrgoV>HOX(ViYREB%6|Q%Kzf__aus2TcKS*yK!_y>5O^yDdj3K-XZ06 zVIKDVZdZq|<0~5Nqb{knG^LcI9;eW^=Q-fx!R13s6Gdj^0;R{2W1O1?S#>A^d8pdl z2y<4pSx<;c^L9{Djs+3s))X>GzH2L)qpf%En;msWqvh-oSSDDd&b??2Bsgy_YY_Lp zK{7lm4A^I)f$W^x`pMqVT!`7i;4~dV&y7k$jq3#bTQ2KYCzZ>V`Kfm-*^~Pc6;kl; zAQm7Ef?p91r*PI=|2aN#;aj*?d-|0{5QGbzvcJ*6bi{NLvlS(bshv(+Tab#dZ*vJ# zO4p*F(8t4r1d9-fM47~RqJ9s8x!KbDeVxO;u@t=c$J3`i-wo-1T|;m)8r4|_jJ$YS z-Ek_nnTV*&6lcGy`nZS`{*eiap5XV~qKAv%HxKH~-T2L9<&8TmcPe{-+j#7wOdYak z@O1U;#A?#Y7ucH|1=V{+A=Mb>vdifJ{d;XP)76lbUY*R}TJJEwzl&dKk5lF8pT%T0 zc7ww}iRwDP;@Y50%hpDRT9$IW0R$td|SoYTFBanPL?@UV` z0ixX3NrI3KRg2Zw(`j&=5me(|H$wIabQn@7cwVlY3!%4)*N7#vHRIb9w3(EtPm5Hu zw|gAU<`I;{_oBQ8PR(i+=6fG0d6T?e0UW)RVkJL0s4CPw&se$RqRdj6eNS}V4mv)g* zQ$(Nt^OdVSjF-HJ0?zK=Dk{^z2%4tS^yioDZX154OERyx^jn#87=(ih;C2NUkq*HVWGEUQ3SOigO++UIU0n>% zHB7S$kKq;5YL>tE<>@y#3@9}YY%%Vw$PqE6Oo>AAhB0(h%YtFX-&2fmm&;BO8PN}d z*b3Ht^~3aeudtv6d*%jiV+hNdAx}?fcJ3k6#N6VT@1aUeQo;Z>U-90-hF&JuX4wo0 zV+P?DQ7Tx(Z{Apl5$Gx)N=yHgTnpZVXtCs*%k|q;Q{z>#AxdV@AXSBNkwA6@5ok8- zSR};n&^1^BKc&Knm%Y0om>wf?P$LJ;EVhyehA!SM4rUJm^U#-C(2+%;Lw8)PHJ6pHGcEn zT>8;!Bq#hYP2bNjsPeaq9)3VAjcp@W2WJ6Cv1#?V1T9ZxCY8FRS%hOp)=CdVUAZxD@i2C9nvm)l=QxBkfQ=w?fU>L`3Ej$%p z|Ph~3ODac z5LvGja#}4PcHHGKyHmEk^at@(p^mt$noo54v9Psvu~^4VW`b0-Ke#gD?r$R%nqv#i zRUuNoc1Ey`?ZhK^R`%ogaEs`R@dK=OrzFyo^{o*bF^9VT>ZS7%t6#W&Ic;O7OgCZc z-j$iaqO1Oa!fsUh9Oq5pJJ|;gWW8_UKU#G623o){Ro=C-Gw-!D;DgY+bU8{n&$0w+ zZvlg$9+Hq{S(OPN4m^X$$l|Cn0qKRPcd)%Q8$?Uq=jn))T}BU#q;fzsuiBGYySIAA z)ODieH9=Nm8B8$O;hHbGy2VcfB5yTPgI`!?|Xnwrz^1hG4eagJ< zv*x|kA_wzl)Y^C=L)LB{UfKkh`X^`^(zdKTI_$XFHrX7Xg$ZJ-pQ*JMjUna^1-!l{ z%OD1O`AmM+Cg8Wl3C7OWyGIhibnv!9ndU=X+Aw!oJ;sLHj zWd)+J8^V9yyY$HvA+Z8F*og`ZD_hbMK@tlrDZ8p__3wlQ0(fYVv^Xwas4aE*Y0$HJnD_q%D(Wn*U!k&3 zyg;to6w_C#P!OrxC4_vQ+HcBA-0e7DX@F;M&?Mx!V9hwR7y+ivk);2WQv71wgI8kZ z5c1T@C4~n|ZyVA`m->)OYxjuKa@=L~;%nwexmTm8D>=@&Ao}Y`m+e4JCfS6%18f4o z7{UeP+l)&v0Q{xFhSf6^V_cE^%vh^!5*9?*&ll2cI>2yr;>5uGhU8OQI6Mf>~^ z$lFkWx>B-U=UJ`y9bMN1Oiw>8j>hZQEb@0n4-dyB98(g@FZ4?mOs-E;jxaeBJ3FpZ zE`;->Xb;N`YZ{4Qn9%*>@5IP@Vs>^-+!E}~W)>$j&kC6y9nZEc;qhnm!c-{M0u}`J z%8>JSg-FNoMYYQVN5e4q=yq?HK1^7=U2ik`*RB4ZG}goyZ{d`_2Fz19O*iOCF8*D6 zvqkcu{|07RfCwA*$Om7!IkSce$hcV{@$sloF~y}nxY_MN&~U8RU({qNr} z8-y&y(tirAwiyFl%&R0BUxFUuBw)BAwH|dik^bF}GzHm+&$Ba?XR^6O|NfHlUWa>P zPHz`d@~@E`I*{8)Wwa4RiZt04a(MY2=2?ivwFoB+G2hzin55iK ztC^^driIt6+>|$@XJon*`*_I78X?Ih5dn<07VL$9d9kx>qA>idwU&;>d6iP0*!BGW=FzrTl8q$vzr)sFB742pRJ0uUDoN=1kC@n~NcA830T69~VW#a}9S zd48L=nKqo?l>k%s@r7IHdyzf4V+=BsJ#(0qDEOSRTXVQ^j&(zvPo>_*Bs)Gps8<9x zoZP-1#ZYzUeax^X&nnVu-=pvabp?%_F@mFOv&B~>;Kjfppl4~?L}1Tp_T z$CS^h*Ng)`o4?-2=qLyxT=95H#@g5vN#6&pr%Wi?49`ex0Jd&|Ji2aUFmyMXvW&+ z8Ns{hxHYTSjwnxe28iq;sj3TPWZv=|O5-~5SlsP8C`jbx2^QFCm8EMh2ivEe zj0L|?=Ia8OV27ERheevWBZ;f3nwN=G(78bf<|gbGWjAY0x7-droc(=({%_gtme==KO3P;%bx@Q9>W7DH=m(+B(mu7bmJAs{{s!PtqroHvHVZ68dY&TW6k+rnMkX8k?Dao5H5lbnz z05>&qb8pH%hnnhe9n^RJjwj+r=mnsmi4G z?fhHf6+>8`57+k%;V&Be4x3Zum5EFbM1-SzTHdL@9*I!pP6*Huclwj)erTR)37W-VCb|VY`@onc+ns0V7C9)~tXzUqh?bwfGk`|jTTXM%; z_Ki4o<|n(?j@l_tQ4sDS)d(Tblu1f8K!9y1^V$RVBlwHyhhV5Ue9Xauc+cK}_nD5D z=PFlfpvpe?T~BIR8{h1mQM?r%pzhE(Zo^4j1+A_>R(M%24lfrm0UjS(5@!vGoPBe= z)Fvs(w=wBVFON7S+gX{eIVnWwnyBdynTLAu6>*nn%uUvum$HX6mrfQ9|EOp)DWsoZ#xTz8N^KOv;aYYGQXm;zKb*kzy#;X(o z&k;8286e>EHnyOQWC&VQ5T8R(ZUT5?LxGh~wb}(87dtluij7r=-nh(7WYLR7#bwX; zAblb@j6_|1aeN7iz>l+g+%pJdYg)O6?4Sn=<&GLgmrsArpUf6fyKl%k%hhCh6I_2m z0_pm}rkkS^iq1iKiH3NOgr=u>B>3Ct_kzpZnPISrbrEsF*Lel)B=Dvch5x%Qf_rVb#PJ2oid7>@79z;WG-lEIr@Xh{JVijb2N_4ZF2$rqTi3 z`NfR-Zg!okP-A(R(uy3CdYGy#rY#ybzomj$OH{Hx7(j3l%7s37=EURWu4h0nw=`4joD*bHsV zvZq(mt7JehRs%!U4)QwvbeGi|R!l^AnKqpi*}gFUIY<$r)UeEyO7;}3Sxz2>22wGQ zk24;s<;(h8)q<*bJr1cd;9RBiO`WsSkQ8(&Cy!gCxJ=C$c0Od%WAkijam39eI6?v3paK?a6ZeN>3|yI}y_#+j!CSkY7u>hWPu` zO*WJIAjE{~#)rcd;q2i~zrXgUhgfVQ%qt7#QVIOKs)E!gIhJ*}%mwlzyfJ;A&7M6d zGb%`Uk{7JNzB~v(D7nO0iR6U3@nC+)9~R;{P&(^F*{qH1`Qh(hbNT|@16W_Thz{Z` zlwl~?>Rb#B5K# zC{6@Co;5o(|3l`HdviU8v&#>)3K_LC4P>rQK<~x&I;!n$ie9(mMxPn$QzCCaexpMW znuT>`j8Tyo$zSXu=%9YplzX9d3y={GNnBk=PlQzy_u{|~vW}7BN+(}hcmkPTdJ1bB zp>3^9cr_;)A$XvWDBl@n_rp8y$imz4Cocu+s_cKdIJ5nSi!%c=9n1f{I5W^Ou>Z%C zGXp&<)Bk3r{P(Do$Y&5)&9HTl@O_#-YQBSOl+7*fR+ib;4ngof?p8rt7pUv&YaBpe zf6z8=#*<9L@0apx>T=zhndK4>L80ROX`)|91Z1Lpt&5Sqf$aUEn%j@X>Fy+0ES()#8W3{YAA8tmK2#zKJ1`Milh~pp%GBeY7yxxf4ggGATDXIq zYXCXUT*lGKL7ZIEeRGgTAjb5xRlr5;Nj^T68lRxtzyAw0K+3j&V`1^|@L)Ev zb76LHwiKdc1bBd4tpI937of8{&>Zkr!2l%_JK#T+F(Xj{G^{`_|H#!HEL=TIoPhwa zz!qc%w08k}xY?TnodIBSfV!*#K-m#!|Btc4KL(6||MUjH#?1D=aR2fCD-g*3Z)X!T zGY30I6MHX^y(Pc`WD5i+ODQnBdb%0gI4+%PfJe04`QmRvums0MH2l^fa?# z`76AJmm~0RCEH(Oa0Pxojt-6h3vdxYKad3w{0GU$#l#&5aCLSA`uY5+_%}jgV*{9j z%v=GcKueH4((mYCG0@^43?9BS$P=K)3f?_70P9~r|9dh3ua~)ly{*@8^S|fIA}+2Z zEw97yPsRV!iHSLQ0(_V_SpiJ!T&w`Lzm|*#{NVTRFe)aX|D^GUudKa=1AzCRY{6~% zZ^rKbSpeGq90wiX-?5Y&z*`Fh(EeU>eO4}3Gw?6A|Ie%bx6A*(4gV|3|J#!P--M*x zY;FHm)Bdgh|52ORfo#40V*p-SH&^fhC^~@8!2bW5Y6Jf{T1B8a$j$EmYGqwbz=t4e zZ)y9#HiBHFK%PKz6_Bf$)j!+vk6iPwE3*aJ163ScK!3ef08HS~{2v|ow9IV4uMQXR zO8%_^f-mRal#=#l4(5NI7&{j?z{J_v#0v>LWH90a_^^R*(H!Xc_YwnGnC%^0!7c!B zd42#32WOA`K{&!ut@$7@vs6|q<$l? zwe)Yq0br5+jld)dzY!0BMe#QRQ!4$Y1jkgi16uy(dc0^ufJNgs0vD$F z8-ZE0|A%u*cxc-)N{7?SRO8-v*ZiCrx1Wv*XE?VR=+3kmxYrX z_-KARu>)8venT*cg$3x3AYl9(a&i0x-G7sC{iSzsbN(Y9*u?S=2oCt0pA+0;D=$YY zp#2{fVA&sptl(i={{g|BxA_Bt+wy1f;8xoGhJTI!cVsTGt3CK8{?LQVclezQ*xBJ< zYH%@*zt!Mij^Iz7{lBKl$@U-Vzh}w`&e{?Da&q`R4o+|*9BtiP{)i8jIQR2RF#o!{HAHaKqjHfZ$oV{{g{yc>J+gVDCT3*umkw z{(#`-c>iuCIFdKe`5&r(z0J(roWZkj{rh_Z-u3_DzyEsx0zH9dNGppDX8fVnb)g;i zHKIfwOb3&Kb5sY~sdP*}E6$y6k7)48bk&)`Th6zl$s@gQ*7qc7Z$wr}pMAcyHo$*u zOH^(D<@;n5uQqegjCg?h!N;9FFn!cZ*J!> zbEaNN<>DET{LZ2|ihOjp*<&6Syf-Q|*j>5_C<%1&iJ@;W$7iU0#Ew(s@Roc^iq;30 zJzE8eNOMpbKd&>rVLoQhs0OJ;+Bf&rx{t4PvF+z3143zt2C?=NYfGE4jhxAqajM&m zBC%X+Ic$K$$6Xd;8y&Y=Jr>rV->&k`*1rPgQFW}o1-A6~{AzI87#SU8x(oZXr z?H01K>b`^RgB*W*&Xw!?BgU_?@lvU4dmdxS)&tWZDBb>=gZ4N0xJ$lqA6NY9FRW| z_~^T0uq;v3M^FX?P7YRVp~*8DKw&9O=B7ds1NQ4;Vz%|Jcb3Q_X>5yNm5YAeCiacM zhjKyvZXHO0y_j=tzLFI z#?QT?06MZLix2OE5zLM;A`u|=1QuwphwEZfeyCxoa7gBng);HgV$fi0zf6mw$)Q&> z!>;t#iOWqw$hnq5Q1|)pz{PRbB2ffsP4`WAe_L3TSs+Thj$|nvMUz^x^dOhwN{aRP zp&m}@Tm2g3peitVH2E1BdB)hkNg#`ajkVMlA?;P5{lxB~q4{Asb92P%ax*t{tMVie zp|P>1CPR3Hz*zX2C*>P1ve9@htX^{0^*c`$0Zz6B;%h6+pYu%L9@1{v4Nx|un@TQ7W)#TS1w5-R;Ir;9-Swzfk~Wlnc8y$qu}*|z+e zi~8y(oWVo0NJ7>v;_@p+xd+7@9oCBRSa%=pE&QZK{rf%ulyi>LNIE$Of#4l{OOXrq$jb@8re_(iq(w{1q$M`|-Uu-4fDr zKhAU0r?=A=qYm_=KJ0~&)^VzCBB8PAO`)pb)QNv<_BDFss zzmu^h^yuU{ct22nf0(`-3Z&|<{5ms&$|Y*_T!SH=XOrLsXQxSK85;lP3#i@T|Z$raB|?fONUwHLxF@e3>M)=jBc zS5jf=AC1$$!T0ASZY8o<-1KGHc2cQGvgh%UXo=FPiz%=i3Y6iVb77T*Z~HC#u)J;_)kYV0mt>VdtHRYc?r@h%(!^JeDj7sUM_CO&ne%6lr^A=!%L< z)6xUF&l`Hsb``H}-cwOh0dR*~X6AOgm` zi=fRf7iyTeEx1LU?NZT0&}E$}Sm9SYp8DtZhE^QRBVN!BPXw$|QvL>hwVfb$32% zkUZdp04JRVga}%hbwf1GChQeQdNQ-5nh2khW z#jM9!puWs*>XF1?25>DcJXZn|;#<9y7_Zwv9w1L6Bk|ua=V#z?)Gze#B*4_!l}0k$ z;F7GGSU*n0!F-!zwBDK`-FUZic@juVB8p<$j5Tx4X1xB+jrrP*;e2m}{P9|d|B^Al zd!%883dy0pdMnoxdYCoUB^YCIm;h6oP0DlXeE#_J7QphwE)k}W#%FjcO~y2rfrly&PU4E zK<3Wz7j&P_C)x%{J<`Gv?Q92e?T+;Z1)=9qAcIQYx6^?4+q*RfEN@xG>3`R%*Wm#M&`3wg~$DIoA z67QLAvJh9aX3~FhMXL`;>8BfDHHv?GTb)0~H z9kt7EQHmn(mUTX=JpM$Ql!DZh%s;z+iMpJV59wY&mx-dOYZQXiRTY^;mtEO*r7GBe zP08%mE1~1*r|x>nwVJfgLa8M<(V>}NGwE&8==(wQ-Z@}?D~-k8$UYfbP9YB$8G$xM z1gY*QcWgQxsj^Xt*hgNfack|;&?dulv)BIAANRYlLUn-w!kS5;W*%hgfX`Dnru*)N z!q$4*VLoT#PqtLb04!%a(bsdAWbEF->nnTREol0*cEQrSQJ0%bhYV~}5ubRkMPvjr zadFZ}A3QSzX6*porn3u@LsmR{(eR z0ogl(g+e=|l(moemL4l)@JI;vJO@&UIwD@`2L3-jbMlYRKsi?p08nFM8IRkv{#}x5(Sj}VzDm#usyJnN9MO_oOJ$8f?E4+;BeXg zqU!rrN;sLVFGuL(uCj%d9f$$L3(PAzZ-0m^+vAiwr@S%xd1k*J)Qf=HrTnz#Dyjs_ zq=0Il68Tve)@T#g(CEXOC3Zrie>U!5EPu2yNzL^45_z$Yo0r_c{-&OF((3pYB%!2Z z+pnsQ@nMAJ`2llu-C<2x4~<1vEYbY%>I5_>hOIYz`>rr@wbml1*q-I}A(FJL(xd#7 zZ8&SHPEawWLrFFoG_9A}Z}_tX;+%-=m-pR*Tx}J^*%IIP1Gpv#KO;HCFZDak76l3K zM^1aQiK{bozb#N<>+>f8jzFoiPat!Y%cUr;j)o@N(*Brhq(mTT1CFR3u-G{&amn*Q zYCi)beChhumN!izWKt@(bzA4EIo+Z){k{(LANBn#fy34W%#e+x=p>(=LOhVoL&_q| z>l~EKI-Qek&v5#csXmxtAx;k&l=5y7mZ9hMCN;QSR(Q10l6)=v@VrE~;JHxnn zs989FPu2`VL|ukDMc@^-BjFqd=xz`34l5{2D)_Dbo>pxc$H28or6`$~SH~XTk2wbH zY%{U~&r8^pVACnZm&H#zEEawoTPYde#)^mb$fZkDFe;B|EEHX4;O9x-YimCHJ>51o zx9IdYMjIjr&M#3}PYjXCbX`O$%e*3tOvI2HJv2q~AAhWyyb6flm1}X&L#qoiSf@au zT!Ak`U!xJX5)R@@69`queV@E>qsg%$a?rBXH)R`WNDrxMtG;s*xSH1tXE!<&; zEthbQ%QVLkdPfY}Tapo3j|;Mx3VF6^QDgp=ar5j>6F6kYj7c-0zSk?!KE7h>^+bx# zlZcy-qI0t-USBz2chYFsR4whsWh9*ef8V&mR{RUyl_hE(`DHtLeD@M*oAXmGTcv%t z(Ju)hKSwx*LyIy?UMouC$C3d^1Ca~G2jgYK*;Z-!TYj!`xI&MiZ|yMqvd&Hyq9q&_ zqQP4_7$CQbz}}7hzN^lei?dlw9p^VE#1c2Re6i81<|OcHMbI07L{V1^ly6LBag5k> zyKN?Ag(GcNyHmV+^IzOv5!8?HdF2xbLNWR^c}5aB4TThV z!N}64ymnZ>;ZpcgCfjY+=;v!i(oGrfEwPKGIn^8I(XJEC(D_`U%Qty()IU`?kjeJ- zs?j!J1=vkA1ZnJcF9JpA3sZ4MinF*Le%z2gXt>Hvbk36PHS^2ZG#|8TTVdT&@9W6qQOro8mZNvyNgbIKW~he?enDTz8w&x98%n5pjZ^Z^ zH@=RzlnJ-FkF^gP>OXy=PrzAxRvq0bQ8Kmoz_8ZQwHcc2K#mx_@;0qGMoU@6G}I$~2h_0T?JKA7dv=4~IL;E8^ojh8rK@zqo@plq zphI0|s^<4=f0VnTgoJ4xp)R;=Qn+o%(o*Ww&<8Ve3uzTKfL`(Npi5HW z9V$`kDuTjs2gFRz$T?PA77?!Ww+vMV6&5@Q##Tk>SWzv%_T^iznr8l;PPE9RjVH?Hft+KA~~wW2m$Uy5`~=Zdqh~(zMW{ z^;@AQz7Z{>Ur-}L3&p(jvaEi%bB+4sKFc@=7aW?a-h)3z-1en1EuhC&3P0SaY?X}C zNydf0Ll1t^EXsWJpsTvH#EKZhahm7bHn*lIYOP+!3AciG8bU70>~L{FWoi{kK$3@+ z=84@Suk=-&{s?tg_ILo$z4CVP{SfR|(66x2ppF$$#208$wqV!srB{^WB6jgo9htpf zkRX0huim_QIq^v@Q-8f4m!$IT6|ULYDt_S81G+EVm}{3c+st5w=#leF1Wr}=Ow|j) zxSV@0qdciEB;r-WhpA+(&A7Nsq|~Pj)zAjL^-TfIp7(rjVS-oJgv}UkskUnozbmz` zi>Y(*hTVts)I&y>Ws~6W(g1SLt?T9KyrKQkJ(GQFuAz>BXkvwwMx_C1`mFxQW;)iw?*h6)O7VREXy%wxI0O~gsn@Jfl3e!1O zBvOCr2V_b9m@<;#G#I7Nvr-*6-9Puu9qu2j1|*ifAjO+yI8^O-50J(K_Zi30tn_fj zsZkM|267-kIleD1*T9no7eOv*Lh=3z7yecTb3|gckHa@Q`LH^e{4B+@urhBA=gpdj z?W~f5V9=@H5>a2t8;H+vmCw304o3pCpG%kR$bqGz5)){dz}2SpdNw?51@V%SX{WY8 zjZRM)mN-#J`XxxW9qCFF`&3$`;9X=f_v3GDd8zv54QRxoUuSE{p?-0?C=O^}iY z+wN9J*QwE-ivuHT?0OWv8sv$AQ&G&V0rP;@)@J9=x7iSu&!b*^B-w1#4x1DVH(ehb z*2L>nAth#5R zZ(U&L^3`Hz`M62OhcVQ!lBAhVLD|e}$i2ZeS!sxVF$ZHUNcGSVXZO*c4w|ej*up3g zlq6D(4=oK?inOT**gYOOMumwLi!rD0&nU!yxhoOE7A`7Jm%Ew~a#6rQQpmH(5bMSjqU$5zXZXQz$-Xe0DaV=HEbPW?Qp;C3W_j2hZOgt#qB+)~_)Q-t49GA=C!jA)H8$N~4Pu-kBX(l_b`)^{d9 zd9r&bXg9M#>`1ec&O&wHcwBch?u)w9R_T!vUtVwuEs{|rsu*SwziS=Yx_s>$%34qa(xatI4$9Meu6MMD4%Sv)=Q9pzF) z+yU~rQ7qz!6xK!)%qL{MfNYVcoMc9TI=i*>Oc}dB@QSm>(n5OzygCW-JUH+MnEa4 zsT#VFmwLg@F=tM<>&;kNXV2%pE|xQC^-W(n;oZ7^T&ucZ;y!ab>ZY*6g9 zrUrQ3qiW5#HeDZ{EGW~+i`-bO@CCl1pnlSJNoG-aZd>r5;HMshzsOU#)g`|P@k`5v z95YqiR^T*kg^a^bsOH(YP~ef6OCKIOz_z#>0!foG$0&O;!=jJDhpZOV4U@+M;nq-Yk+m}I z22*4g8NVZJN`1OGt;pN%p-wncoEA+I=6H3~jAy!>F4IkWQ|cuBlOFB+Xdohm6bXWZ zc)Hfs6GYUgD4ed{$NmZ}M~vX5__zAb!B3PJ#9b}0ak?~({x+ydCc$QPz}I8(Zd-iQ z>>tkwceKV}Wbm^`Fr_7DE9FZ>jXVX(7xAK1lf`l2uNN>3KOr9#)~@-iG|p+CiCEMc z-(`JDE=b#&8)SqbWAiaTek>7Q#EVvRie&c~&cuDc)e+uY(;QJZhfK8s@xpwJyPx-s zgWu({TDYBec;lfP${Lm@G-drX@CcD}@@mqh4@8Od9^Y@?ce7tIZ<9LW{3U;p$+)ie zJwn@b?!LlKjG1aclRbx!cQu0XOLSqXx)V+FxF@l-J3fB?8u`yLSjWyFcCt{HADutf zCiqxV^S!Ae~gb`clq@=w$c;&-+|M|c#r}!SPtK39E1NMa?2|~}%r({45TY0u{ z?it;^&pQ>Mg|@&}!7sYnY~8Qfd)zJC zgy>wYT70`e@9$6+vmMPy5&V!ogtlJ~Gn&vZkfh{J*Vdm|dvt*P9wQ=(t78N15dpd;;Y0e$90aI%$Z{vUG4a8tyR z+ahk_+`q=!kG#G7YVZ|?k33KNUgC7py=&@dMk%$RfKZnNdgtE$eeBXIob8za8@t3P zek_dXY@dsU2cMi-dsZI%X)7Dfiz-}3S@|-uo;}b=h*AVS&sYC2F**p zcCD|llV1h^znUzq8ap#+PGG3VTZ-Q`O`@(U7k=7Z!!GUpZvCS*Q9j$=B3YV~%!L2E zwLrxpPW~Dv4nyQin}96@LL+15Qq?i_S~k#;wn6n`D_`}bU*;Syu!zU#m+d1C4CKA} z(a9spix<>*!{c-4H@#oQNZ1r+Oy--3Ig5+w8|Cn5tF7v7!{iaqkbYE(#X{`w%0+D? z+;0!4>aj3GbbRg*Q6$ZskS->cirz}?9S1qe;EnYOf#glZ)clbYQaEetKVPQS3ttVC z-U*^|Y#oi+5k1;4y}|h)r&z$8k-86?>~Go6J~zmND+-%c4ZX_1a*@wa1QKuFDirXG zdTYvH5{WcPVz_tq*-1{_>0NmdRJZcPFDhNX&^~m^XrhaP=sQmxDyh?2jji79*r<$s zTlRrZbRgqs|SM#T#ElQf>g`^ne%0dibpGp;fXCuwro4 zqSX1qt&54qo_7x{C7LX2@eA`mQr$gQMNyaqAjO?a7+)?LR#U&A;{1$aF^RI=Btc^)4;k?pYlbXP+|GApEl!I9;+M%EP48{jF_JhO~t9O~5z zH+(Ak3uYG;ZZ1&i`zL@;+f{}g@#&`3!Pbb}VGJK$N=@A-y!kmAxFOvO5p%%20iT>= z=Co+KlJC5sv0ksuWCzWi2_^ErJFeJwv=Y#B(w?$mKM%UF)4{52ipMI%ub7kIi^w?O z#z6F|9>+Xo(`^TaaEMf(ugd&;)gLZBITiB8cXZX)dHaFq^AII`LdLcgk???Qeb08~ zH))$c=&&h4*#U4X<+SZSok`{G9B1$ zyV9q_Az8YC?_cI?7J!@Vhtdi|8}Ntm6V&2g-44%Hb(N+}T_z9epBiL?NhR!fly!zu zMvbh8_=Svg-T~;aV}xpV&EBwvb|EH2%#+lAuFbnOUhkonKj7VJ`gr@fv2}ao2I{ty z`hW{5|qlFv($jB!T1Juonl>xHhM&ofzTWa_`(ilsQl&HTkXs< zcql&cl?CyJRMEN7LR*VHKj<3TB5W+c`FD!zMpr*;)jb~c8M0W>pZEBRo|Sh^BoBOO zD5u48zbabGW~8%se2cNdyyh!`@0w>*>woTTyS@7y`gIIZj9isf7V*dJjJT^@UHjfQ zaf1va`_IfI%^RotE5c{+9)6o(xSp#@8+v}?PT1+f$n`p}vSTi{eG3gBmPOs{ZUn!vo zzR*v%HekdixCxs=dnDYK-rdx5HFu;;c$Ee*K2=HRpzcJWmhEA~_ZT)oAtO2lA8{43 zHcgrBl?3p6wq?U1I85MHgsRPrAz(=CGVghN3;lP3~~%DoNXoCZ~&dXeu4KMGb# z-yvyq>q|LX0EOO8JcYMR+VDhTIP5_e;Vf3yBNtlEynK+0A{^DVo;`ezsfT^k(Av8u zPeiYp5PU>Ypgdnc^}}@{n29~kTP-B%LWimZhwrSSoEH-xUv+s@hNo>tB$gXViwB_T zG7_FMV)soJwKwWXkHnL3oGd{!&V7O3Z*f)7pJ7@PST3)&2Q1?IZb|Bm_*KxY<4pB4 zSr}KCb9PoiGc0O%Z;O-*kM9TJEa!2x=f!2^6{ZRKq^qwc@9u>AhQ+y9@z%%`X`uq( zi!8)IB_g)dE}Qiv@Yrr;D)Ala!7yg&UvN(hqV}?0Xe=CS5$R<Ktmkhod4taB>aGXg76e=%Zea4t; z^HuAP0bud=Aeqa|6LUtqzAYcKA16WYG1E>TY+7>REt7x-p%HS~a}RD{F=`UFZ+y%3 ztW7*kqeut2ag!CI3+LKg0+Q9KMU+xx8hHmfYfDnE9d3AiUCqFma7TbfzkQ4VU2e zw9wEvA#tlzklcttGRjL(*KHYG_aiGaDrt%VddBVzJIfL-D(f%h(G)-PFz3!^O_J7+ z7J3NT@l>uPlsig7u67C`A+}bO?tr{Hepv2^cD5&da+Ldexkeltc-$C)cG>3UD7nvw z7TRq|kE9#zjlPa_$BS|_{6g|bY|xgikaXVS5=k=kY556MEaVv@Rjm&%X<9$z*XG?{ z<0QlE_`c2rl|f5|WWFlJua3 zHU6YW|99bZ3`?jAC3l&+yD$ib0nUjJDm_whXr;AkK3kP5Re7G- zDhnoYtOUU&a?H=4LKS*5I3f&*dS)a!b_%!vthfWvL$7a#nt{56iet{E$6u$fyh0sE z*7`O0+ngB-?a6NavOnLpSS>6~LOxFA+}cT}e4ob4?<|ywr%(rJ*Lp9@qlhYsZm|ZZ zm&fB3vaJY=nKslk4Ub=IYJ4paJ#y%qRL9V0NKu@in(qRLkGW;ZGTc5207&Ub1an+t zoNGV}~(rwirNx;W;^ku)P)-a8BLOe-&U0a3i;aJL(aD9Wpy86JXJhPZ6h zJ$#u}eP)Ul+!kMV*bAg#Ha0YMj*w$MH*V|cSXc5x@ZZCJYG|uq_0o_~QI}vFL=#z{ z-{v=sgQZqibdi?GhCV(qCos#UX`ewfv$jgnWE1KR>oFavRrPke>9gTWulS1bcs3ZB zkc`uZx2kih*E$^79x9hI_&om&xGeehm86a~JKPB`o%TWU>F7n8_{<6KVV zoh4AoUk#HXRNS1~`A(uFuV;fjmjcREq)V~rT|I%?j^eUmH!1UMq;%*7|Ni~lOV7r- z5v*&~7Q*Z|)=)(YUhl&hix+?dOiCO*Zb7o`DcbDvf;?%?3I5MXbi~v+#$XUivpsG& z+DGB&S;!G(53Ih{EGb z)Ivu2k;4zeoGFwNy;EjYCh)YUBm#7F;&e5%*EJm_2SIdH8sJWryKdk4%M2x9kn=5M zvPOYN_n2L_q;9)aswLYo^hJ@KyQ$12c0JQ*BeU^dvto4NbXV%d^Zj@wS-d4=ZK`AW z&axT<$n|cvzr%$+CznZ3P$FmDY;-b?jaflp$D+Wb8=;ryT^R$heAMjLna_}9Lw@;J6e>h>vQ|`@TjY9dApqv$g%ke-LBz#!IW%!GA){Y0(#3;mDH~Nonj}sUg z1!cv=sW5HJ$Io`SizN3=BAnvdu8KpFPQKPzza53&gc4!#^L32$2SqG)Q@@Dco6>s?~|VTCzS?mBfZ_3Bo?}wAEPJc%w23 zg-l9!*e2{!{(bn~-oyU#)Ba{T`$;}2?>qKWTbmX9D2O|NYCS|5=v_od0Gvg@X+xLx zqT&ESo-#@U?!9;Q=U!N+#mmluW{QeaLA$gs7r^+r1oQ93*x9x+OfNZFFh%BjvuiU? zv9leGZV#eRE``2K5)ed>0x|72Wfg43Y8+^ha}BFYFNxCJF6UN6Y3>hhjr5$J$u$?n z`{ds#Cg#v*iRM5kb)**?i_vGlboXH!xVqHMqvomVllzr5f8oV4F?J|eO>=E|H+;-H za|w#F<6X9K41%~&;qga4H0;)QlA%>DhZ!zlw|_2f{WY#0s3#cgR48X3jXW;k!uOe% zG!b1dad_<^2KMbQ>q5sOE|-F+T4(xGfKsh+p+1kgQB>s|DPx(Wo_B5afKH~b-%jiE zLXC^OM~}G2BRxm=H__Tge@;st%uRLA46+nL34Pgz_twKz{GkU6zXbAL(cN|u$*0|- zf|Z+yFtalQJ&Bkj&PB!d*OZ3FD=$V%YdnAEbq5jjA_Xa1EryYJl6U(|B=d!gZ;g!X zuv@)E4|PqxG6gfa&vv1_%%+a3p=pVkxYx6Phw*2E=%jJOjN?9O{WMln=2uZX4`Dft z2j~6_VJkc#6q%};ERx6VcnBHyT5V$-UFKa!v89VJrh@ggup|JV5}_n;Lp*PFr_&uP zw9)?Mdw=@)dgf=ArdKTExr#MkJxJbF(kg6e9wX3_`g~p`^SJp)vDz99nn^v2#TJ{m zjZs~e1$qFJPi?d^YwlXQ9J<*m@u;o^InNN=SObYv@ogiLDVLsn(MB9RnsstX0YWer zk&^uaPx`@EX1c$}Zu$QR-Pik@gf{D+so`S_16p$by$Q$-roR3vw1_F>91(&9S^y8CQx{0|>8HhxB|7s-D;xI~R<;FMINJlcHyr*_q0SJ}$+sG= zjC*Z%2okd7rEj-sr|0+7`A`wiQMczzhjK$&(-+|b#4pei83-bX7MiBfEE|Y>2sk^5 zNl9-?(Tu7F9Qc2gT_?-ZUFpzN9mn2=gbC$S%dT3yN5s)3sKgw!GSc54)~$&N!E$xS zxxM_ZF_feY$h%F`y3=I46g9z{F(iX7LEqIF7j+9`ZhbB;JemFk8#eb&{w$V`>0QM4=FCxxwasB+s7FM-J*+tzm2&`*`q66SK(>p2lrP?@p{zVti3& z0DeZSh#exXXE^cVq9tqB_tU|;V;aE6puFWD+>F;=yCZ9Jc+k7l#w-3O5Fsw5ZjRc% zCF^iJQ~D_*7Rr3K_(Qnq^dIZor-vLqko`iFu}`PrK;lm_zoHd7Q&NP_fGYBv@IW$z z9gbUkM}k~7b=#{sZM>U9F}kshU4uH5m~MltRbhYbZ%XKj zSvR*56NjqBbt=f|&8KMhMBj6ZfP^;PD6E*aILD{(M8VZs=vPWdtBVW)J-6;zf=PP6 z%Yh3`hx&sg8~U&kwk+H+DGEM))OUi=WK%f9QVaoe?_U*PT_`OeONKkP3giPhj9W3_ zx!Xht&f?zUSiy_efy&`%RwfN;*tyz_SnD;uDD(w8 z{p*mcZ@ztSD#T>4UD!|A054RgmWN>+*r^VdPt1e-D4H)WX-*aAXOD?Q4RsYt#mU-R zW0RT{i59K$UQ*%_h?QI*q0^yj$ENv}>>!5Om^ZQkecN$g*2pJRLtdpN?VqZJZ%!by zA8V~L(T`g34$#W~MfZSl zcOELachOs9#e4T6mEiu(G1jYW6E;Tar90OY+kZ zjt8P2JsC_O{n=Kvzo)nvF`9`Z4C ztjC3+ug*vQQlq6z7S`HF5;GpWFOZ%jji2iskIEMPBXeB1JAr5}7!K%=LMV zy&*H7it7A<@h}N5R!Y!w?($TAm(s?XM{xT3e5pZBh@7Q#lApww*-ReE6M6I+j)c5t zdUmGvM?|6!PC&7XmaVvZO!K<66kd!8*_A>YHsW5haUBj@oow2D$1-V7+&vOuCmdZk zUEUHL3esFypOVhAav)Dd$%-lKadE@&tL`@$g2Yw1ro7qE844T7_=%WBi*PhYo!wXn z4BdX1fi9`(Jm&8P>gLvtnnpVnoDd-K~{7-8&7!5WI-+ zRT0alo%G;BKW~ZqaZ&$#!<2LZcwdpvy8BtKtRH7^yPYbEHqH&9(9?Dr_vw zmx*5^A+p>FlmtHNFF&YE{b;c81{~XLYE6dQp!$gr41;yu zg`zsr;e*dNp(0^vbDWK6DDZQ`_FCm<0XSL+Wil12@^q*BnCx0cY5FiXMm_Mqd^!cj zswsz}d+hWK(*zBQ$Md6>@?APNab#Y%GCUY@Qr?gx!=iQ#*iLvkTqb+r$);pg^E*$u zAL0wE-^*Tf!gHgJosh$51hwnF%-ka|I&Ze-LAn$7&JXYru;1WD=?ZIv!pBuS!rl|8 zCVa@%xH;7bOP27siL}k4=MXwB1yvoJaemluLiyBRIqCR1RbxjZDhla^{N~HfCRJ@G zL<;-GPbIiREmQmf)E1*WP?*PNnB0x|rnXV$vF-yYcO2vW`MC?kxa&!;F*5Yn8~2TZ zOKUgmuR}wyw0%D>FHcJdp;i4srwzSEN`!_Tc>(4+8JfxyFS(u^uLm!CAvYD5HN1US ziocpS3a$^d2_CP|jSpt@21k_9`LjMc7EmUK^d>^{&LJ@5qr9PHA+Gq?3S%1Z$*!Hf zgElEcwvj0J8zN{|E6bgy8I&76E1A7=`Qw0q(I3}mqyb#3q|B&npqW_&Id*T>)y=IiOt&a<+K1tnL*m9<6fRsJpdc` zEZbgvP7T7Li$46^6f4-`@^qi%GIoJnMR3RCgk=9Y44SJ z7DR$j$?7c?`T;@$H-6dxH-1};r~0ff%>am@y4Bagjh~XmM=utQ_*g0q@A!OgQGR?M zTWOqwq?(5lu;4%DzjyAmM~`NDUZGZlp%+X2f{o;TxRfhgeHcD$aKUi!s^dwaloCTD zu(T*gOQ~Ny?A2JE67~S0lji~*vS_s_-KG;wUx&F#oypvIl_VKZ6L$X zU)p4tyT;8)-bq|%LsLAVL_*{=jn?^Y5kt>M9V8su!sRmNG}+2j<*?*B!5}wC04qID zplj*^-cq<3rh!4SvcpAojEI+#Y=k#d(fGzPUWvl{ul;^cu5FCp=omx0qrTGBB;#C? z>+3_icc3or?6M{Hgvuy~YO9mR zRoD?4J5~PTOk$kOhjw29EG6a#4RqQZxa^XSw+>Yo#VCe3HjkSdon(j>9<39Z7k!B> z!-osC!%(j%cYvpp1l+EU%48HZBng(07Pm7HeF{piwjB@^`9e^a*N8m{_cq~s5~1nf z+uXFU7ZO=j8AY@9#d`BwoPk(ijyY?w#QS*_gpiz#S1G=e1M19cD@rx*xW#_WFM)f8 z7<+=Po)k+T3w~tf56@-|`P&wd;BrK^2{;_*p%H~D8H;CUlcRIl26W}es1#ErWnvyl8}&Fx zE6ONbLZNC1`8(ttlU(n*0IMYNO>EmvzB6^I&Z&K|tN#D8`=T$qSM_?=^AI_?{J9sl z7`?Y;Z5iD=u8jB3$$Pp>mN@EI+(u)hn=i$~WQPw9)N>`GS)i<;)L~7$@>Am&nA>`V z6-0Wb0>Ykp1qs$|U`-Z`gnx{z+LzQ14T3Q@Z{ zfELGrIeu)s-GLa0k;QG##S0~{ap#TyI7J8rEjIb`FwD*;O*rX)dtFZ?I?q?&#Zg{e8kBebODh8OVn$ zhCc0+O%W(q|K+S1VW=qmr6Yl~$6$u@E9xaib73m=Wqo8U9 z3XRO~U>)Bv_oL3i**1eYshky+dQ~u?Ay|*T{k!kmjw3Hqt?@m(xa^f!k8C!+#J+1@ zT=F14O|lAwyk zne*rglD{h?*uG^mbpSuAtK*Y|>+je-4(PnQ@IbrFLSDb=D&GOHp1&!pG46c^jv9gc zWUTaDb(SOXw=K`fJn4)keM>Zv9w0o7m_?zQOMnSUNSNAV2aVzyA%`27P)AdE#?z~9 zPd*s^iK1?GnQK1MLa@TX1_R{MZ+5HOBXj#H)wAp5FpZq5NggGcQhv|FZY;d9=vKaJ zxhz4>@rn>^Yp#fDa{ezqZC5RQ%sZfoQx>WWOUU1x*Jo^VPs!Gj~KC2p)ePpj@(MJePxR>xQv-JmbE;V1< zPi#^s3IX}8zfb%*4-YvwrHMr&xe`wPwXDUs6HDFpmMl95Eb|^{)I!MeGp-x%CBK*#G{CClNKLaV{$*?$(%r&9<1X^9)3S97_t40I6Vk8+>}K zVvh-ii!N6WMo8 z;Rb3+fUvJa|D>dU=w<7Dni3fKATeFJaCB#X_iU%E)Z4gd3!AcPZ?R!jZ`izIYd%p@7iEOK6@(Lnl}3|LGniDs@o8@3U7jZsta_iv(5^To!B}R>?;n;zBMk@ zA)#OoC6od$7?8?!s`1`z|F$Y2>Uk~bg*u@s)emS4Y#I-BF{UCo&^6R;ky5w2nAdW za!FwbTk8n#6VheBk)Ht%`awGCGCak~d&iW-zTo^PcS3cWvvN`qjXKw|!23A&(wX-X z@jtG`o8l(vo(t}mIF3dH#yS~)?yuk9IOwTf`e50&;>M>5S`@(tmXe_AL3cxL?w+jx zRTCPut?Ur=!+;S2m`52FO?ytWzH;Qu?Ftgqz7Sob{y_K;)5DkzI!H`v4($#8B`b0D zo<7-vc7ZA9I8EyC9$E0d) z#XU@IwvV1bC)#b9#slGGXij+HlAPn8Ty^AFMe4R+w@Q*pjk*YWdYha@Kb2g@exz1q zpx&*&5gDGbJ(~+rdQh>2A$HB`Yq6W94@d}J|7*+aujj@MRe>YF)1(?(uuO2~0rLXvD4<+$w((+yxXBAYr2;{oz$gRmM}LGALK-GsTY@4Uu_4rg_y^u;?e3 z)=6gTQG9zgMB=U%;}b~=O1a>o!3vBc<^bkMQMLQ9MiAj?j|s^<_|RQ!%CM`@et(6u zq)*!nxVw4N%WQ}O5{>h5%NytUA<8y?(!j8ylb z`$Ue&LoOVJ39tIGF=*Xe#nT~{f=9BpY6U?_7PJ~)Bi0g>rGPniTZ}BSBhj{?^GR*!$$v3Ou79 z3?)(Y;-76UHH_i#lNyrz)X$nZm2;042a8<*Z5XX!*E+#8Y7Mdpx2nLc+SD;rmKzE* zH*Om5H(PrmLLX}bajh+RHoRfCH-2I_64>(Qy$E>VC90VB#AjMhwvsAqw%Ak6M*6!s z-VXx^S;k{n-r)wVK8X9cvxgkE#}7asbqe)?gi=VPIUZRJ#q~vSEvxTqNPbtjFdW^l zB6kB*%Vhu!t-Y7n4`)&awQ~{i7FKn3bL_R}WM7_R!XXf;2bCFYb7H_RQmFOuxGi+i zM1q}UZVWihgDUdr9MTkTcBqZgwH0yZ=Bp^h%F-DZ^%S4kwXp+rIa2q9sH#z{kek^f zrhTd~-Yq=S2ukDxUx6TN#N)?1l5*oD)!&Z75Elc|`Nfnh%z;C`h=jk-a?@^L#D`IR zuyOE?f8Pn*bR`Ib>*CInbAG-p9R?%rJ7fD1^;&LQA9W#1VDDLfpE;yO2GY|vArNo= z=~WKI61MN@dg{xIQXxl2zm(!fbLQ*($FgMHSdgPm+|4mCs4l3`p_)RtPZ`68T59uZ z@TdlnUi&*#`g*{c>HNR|fhFE%Fq3L@beVqW)*g4{;Zh=BaM*Vcpyrpf-GI04xk~aX z%ZG1pGN58#a4|nUSe>z}nnle!uT~qcGCdgRiyb3oDf|V>i@~3pNd@)}TFZ>-A1c+k zi4+}`3=xymT$~bw(rPH5ZVlYbvOwXA9dxqiSUvp8Ya&?5SOxGj??+mPW;= zKgd3Z56Q!sN>7wwJ3uGQ=-cDP%>Ika=X)nTJA7VVPQ$?l=art@u@o&-uQ}lxeg_xRxv(tNS8Cfq>n>i-LAsuIgqJ?|&a{X|tavou`aa3pzU z&D4ukWacq5wq(a#py8~@UahS$fn%i?sEMdTnFT?1Z0cbXhWI{8Y!0I{3o|JPvXu;F zpjbcRZBii#K@=o6k7*7epoy9w)?y8GV#@@N@m~}n$E(E*AhV}L$%$mzjl=Yr=4}>~ z4oAP<4fC3!Kwsz-O0t%OLzq-+nzQ${3L8emOyR-LIiA37aLpW~yR4Y>rHuZ>sXfl`a{QE18B$u!`NXQK~ zUoV-ziTW0b;sBFaau|e4rhBVo& zSitayZ(A`6AZ(nXacn3HLU~!r{?`$jzs1tm+R?VQI^YYGwK=*#dUHqvF9cz-OmS7* z$NT2u;p0%00N+Hh-kXN zq#$dA2&Xab=O!v6&39Y5EN1%Rmz%jlY8A`h>&%Y=hV^N)y9LGg*%yW=Fp_haa71{MtF@bzrbeEdV6aOE7% zf}nfcS$8v%|3-}0Q|uzd?IBLkeSZLVjpdqH`a}fC)?tr!zWQLYpz)@6;it)XxGD5j zHjqb8%E!_o-dcicE5Rt1?Tf_`aB^-G+TB4;t|rimyqpumwAFXgcS&($p9;ROZEr;J z{FOWe4$2p1gRn&T7-20qMsT!0iT{qs3QkdFRZ7+soGc)UZ?g2%8hY9F5Q#H9UGyH- z(HV%&CoO^+}Wm*h1C6L<20YoLoM%Inp(Kr#?H@cG8Y_B1AtS# zYn={WYHr;upf1Tp>|0E{g#HwU_uLatdC}Tkd^<;0NiGD>TE6-{`in+1V*nRm--m&p zyUnE3d%4dt?Ik1hS@9S>{e{Iv8+8HhfMds%&(XswW1*4r$0=jB@kRdpPWtjpjOUD^ zQf3YP)yyiEXYHTp&e$P=(Ig=o#wr4C70Lhw(q+P=4NJUQeQDq(9S0P33;8@JnXy@I z!;x^S!R$xtBrKLJ)XU#^-b*lxHlr{4j0^tU#3a?Rme<0O+4pSn*QTXA7{tEP_bWm@ z0u5qkgEn1r9h_nsUM`R!gPRs_l}hRj`ov*={;V1qcTSRD!CM|IiErT};w@k*Xttwg z4Ld7|w!zJuh#v&^4iBB8?(y7^7zqssp353T8zBkKi@A(@#7xDcvZb3Tc3m_yk)UR$ z^T?R>r2Q1gBEAGLL?j)Vz`$o#p{4}VjJ0ydF4;N0j#rxbPX{R+kE_)HWHPHx$85`* zN$mr~uDR+@;6A6~=&#flo2gg*ICil-E0codDXiTs+@77KZ(>K zB-C$6nl$BRV5_P&WN-5XkyJCR#5aiEM<8rSfxYodH|bCPT(9F=s3Myc3`BFMjw3Ny zXnR#mtuPr?=mEN~1_3k0j(0DE6e;m50rJB&2p>2i4CmN(;rExQX#Zi z4^ch6sYdnr(@Q?MYgc%+p~YywhdPQCeyUo-gJn+md$pM|n%8-PHJgjRxGnL);4i7- zk&@;qARDE9wtx!x^?W_PPckP4LBe|4JVC7UGrU#XNfUTJKF!unoQRcRjuN-4{|Vh@bQDMnd9*nK71 zEKD=$NTqUI*CND}V@Z!fFX2Wt%H6;z{^aDlxmPJsCUDz$lW{{==vh^xX^1~?frlxo+9r2u z9)qN3Md5H^;hlL;ARE{N;hwdBYgPBA=FJ=yAP_o&NwPrH;M|cYA?%j;=z!5QZ znb(*mzShj<8*z%Wy+hHjB^22ipYk3kn}w?>42W#d{xj_ySP0JG@)N9}F9?)`815GK zCmt9{;6dv8#e={@7lx&p6#_zU1Z25=^AnWF2jNhjZW#+gH5{KqN}94?N*k{0p;7HA?u zT~qT&K@$sn%TD}exo?2APktBL7hX9wH#RpuHy=IE(=*0~Q?=ku%^?+?q)MM6ph8xG zku?eN%m8R~6aeV2yR|iWLu#%^rXK>GIOt~}F5*(aki6i~V5L?Lb>#Du(u+udrOyC} z2q}QX$%+KViWr#~9$e-t{4_EdvMjjE5IL|0Ahdx2^3-Rc>E!kxK7fy}+&cMrg4G9c z3<)hQEq(ii2u0m4l)%gk4KfFjkDt%jN*65b7+6n-4JrQiO$U)$MFx9B$v}O2b;SU1 zzC(5t=NWT(0O>NKmJCE$0*ibM76J6)LY@Zc<^}Me^;tlraSiZ&ug2(IDQ^>#qdVFJ z4)!U9j@pG%fr5&I+G9as+nfO&xAGzcO|u2T1^Ntpz>raq-yJ%73j!#DN&KNg`V2L( zIFSdi!W;psgS$$BJsq)t38-Nx010t#1aVvV#lN9LIPj2=OM94JIw+8(Kky)V8<0Tj zS+MBP_Iy5YKEqoB2H0;Im(EFR=!nS5C^+<>`#zw0E-gF^#EyMu?QU+8n?##8*(VV6 znHhZOTN4dgkyBU|d}<4=qWB%_XeAWbIt>yD8UYd{1Vf_?SRw#Cf$;u2(P94r@}JoA z-K^(|cy4EU8No1M1Dp-n9I5+j_roW!D-VFafQEYtR2=O^>4`@MfPxhQ+?AlPL4h}y zt>$H4M7}<+QfWwisGgPlB!Jt$4?BVvKfQ!?Q5<)A&w6Jyl|&^CL=BQ&6i0ziG<2Qs zfX_E^F_6yzV-Wz2v~*x7HZt<-4Lv0Bs)0HHh`21W+6h|pjqcO=@9tf_sC_tjx8Z05 z0nQYkc+=@n2VOYD`~(>e+}%i>12!%Mgnt5IJ~dN-nIphfVmC#u&(_R~Rv_>Ivb}G& zCjiBs{o;4Wa&OJW6*}>Esx{)*kH!uq=&8k{fNmY?xhs5X68v4@mPA@O&lD6aOJIIq zY{1a{sQtUm*e)~pQs44FqM!!IEgVP?@SroBzV6{_de5nHZ0FyX=I*DDG&}ez#=Xrz z=3i}ike1~PO*U!4A;I>DA#V+%>{mJWaRI=tV^`q_W3oAZ5M^mh=d~=yQ z-)8Jb@lt|*;t>OTjq0%YG0}If4xVG-x(fV8FO;sJ3~R=w)o5;jBse}30V zax&mmLm-eH)2ywMhxgv=XK*}a1!#}sI@5pgtDn4vP5vNxB~0Ck&6$UA2CjyM_=#jh zrAQzriCjo;>SUTX$kNEN##&zgHM?Rbsy6wp!HXpDWx5(8pj)6n6(M9@dP3W~?SPaT z)o=}>n4CanX3hVjK#@KYg}*l^gu26X)aaBa$9vftx{I|#WPX)Y+_Z9JbseYcEME15 zprO}zfVJWBM-{tE(G@4gRdeq!Sn2CKLe>?}YBTROh*N&Eu%elRE&QL2N-NoEO^V&( z01@@v$x|=NWtlj6tl5l=B=tGk1xq33$FUCk6EqMH_b2_2K+bRR$G%a9Naw|SyyEi- z&~f~Q6VHq`MKs1tmI96u{&Kc$JE_W=L~%PyNvhAoNO~TY+Dm?%06%9-y(y$*3~CQ% z4NA(T5J9rmu|>rt?kq+*(jzl8a?mc7%1M|C?0>y*O&kUctaN2HeZbxhZv5V zP9G@9X5Uh@Im)dQRh{g;KE)X*zYi$k4-^&xW}N{P936uwln_-lxD^c)$UmR*SDy_V zP?Y(|CXKj{eWjucOdXn&!c@q4Ccvx!rT8ki86TsYkowQ2N~sBGsQUiVw0x_(5%(d za&HXI;iH5@Xv;@VY%(5SdcdqTAMp7 z)BY<7Tw(9N`x)SzgkevEdlAa5#sd|4NH5DU^C+s-!P**Y=*_cg&tRum%-wjG!>4`& zIdc17uD_4;AqL?QD{Pgc{iD8dt{-z}z0Qnv;Xk;?i-$Omo5>v`g%WwQD!8$eUebsF zQE?JK8yLL=6@)aZ{=6(wmt51rQ}8AS`(`5k(O;5Zx8+RT*yrQ_Q!s&wwi;f1A2!^* zGV)wbnS4#Nt(U{)i*5O6G+<;YdG7So>9-`X`53tnSG<|=1GfBDFK9H!>xz{4?rV)) zGhv-GCa0fK{L)=SCDi5Fq?iA+-}q9f{yW`w=RCz-U$@=x7%op zM!PzCUS>R_1xrZ0LKd|#?5DJRg0vc_01d;S-iW_?p6oQ2LN&du`2GC;)IcFx3 z9De>_gtatwhzA+z9iMG=bJ=D$sT?!z!uvG+_Wni{ugy|8|zG{f95LmQrO;8~M6 zzpZm#-n3;=H<&okXcawR2R$wv0;I}YV+cS7?ZIsgHMa|NDv-(g+zu1Alh zs0unKu5Bbs%Kd{l181&+=fdbLe~T|eIdLLU3&0~eEt84F+Y@nkzz^qo0VC;l4<-2A zTl(^Lcke~sF@n(1RjQt>5)~|TA{7(V*@V`Mk4^QCJc0?~h3b!Ec7*L`XaU_Mki(|5 zp4JCaSyxq_rk|GdM&a5J_9h`eFxys#ZWxPKIoct+wTD%!?0|2et$EzUD?d3g(?Lt( zb$;X>uFoX7rPz*Er${rTVlSY}(b!|kbLuP=Sz-C;aT7%U=rmcE;vOxXL1vz5#K**n zmHwv19O^p26cs}&v5KPdA>5`!f8`KRwh)HA!d4$z`-H|?t3cs2a&^DLA=hHV06 zJ|#2^*3P%U(QJUqWY87^N%+Qwjpi;nF&IBkO($&DQqfe?%yFUD2V#sc;$X&--j=Rl ze~U$vx$pXM%)1REU&XqucH~yVWZj*lmBb90}Mss(nAI4re(9~IMUeK?Sn3O>`ScgmJ_9#zt z*7Pog-^D_JoTto66KgJ;^1jroog}FkTugV3LX*bxDM@h2XR`1)%g=wvZ79K9xbomo}w6(QJdd_Rjm_;%5+76_54;E(>NkM%xDG7;9(b z{5;#W2<3AgS#uh=6H^s8@vSrzN%s@E3Xezmqen~5!p(A;(xQ)ANQ)v*=VeX)k-PF|NP-7?-OSDf#RW&!$gjLm?SAf2-fP1mq2l^EC7a#z44BIY~n!dvyT6+)nBw?o0 zF(!Of0tm1bdGVzoA&tTE&sB0kyTT*ITxem5I03-lX#Tn}!J z*8Y}`D%vRBI!2pjsv7SXnf>D=&N>SR=by`}e#L0=E)!jb4j9iHUQC3ZOn&JV4?27T zksx*3jcqJj&_=ZPi{MJ~VSRqJecatm#aPUR8PZ+KqDsmD4hGIhB_$VGsZ~IG66Uau zx`F@Uq5p%FYtWtB?pOG)<*t}`Z7;mriZ!%5Vb;8iVd6-KS11T>h8Mb397;CmyjfiX z?rf$oVn1P|BsI*B@kUFj!1*&+YxQfQTcD!;sWi^YnX4@oC@U;Gc47o@%7dY zfAcy0uLR!KJeCGdCFBu`@S&9Qy8V#z@%|PGeKXS4Fbn#R(^OE%EdxI74ze2~MuXtQ^@K6MnGrh$wE| zhI!LPlHVpf5%;laX4w+dyQfGg8+)_paXa zH~o~tP$KHzn4RdY zao{zH=7<9^)9oFKS*zNEOd0w2qSRu~TGY}EO-ik#j$AqRkHH_W92Aqg@Q@S`7yH;m zK#7}3io~2=6`({E#eYQezteuIdCM?y9u}1m3>_j)+4+u)w$=HG;J!OxJ}d>NS$ktD zCoYi(dB5$LH>0Xa4(3u=47sYC{$cj04<%oSHmov++G#`-b5JQg#XVKfQTjoGMd;2F zJigz3DjxZ-J0hA3sg-ugnH2t9w_y_F!Zk(nHGOI^U*VWSxV6bZrE|k%hb}kE26Yg= zxrHK=jy3rrpIB9jMQ)op%wn@q!T8mpw7%|vkD4JnU{XjZH9A!xWGU2}IfptG=i>Lu z6*E(OQ@{Avf_vO!sT+F=5@d?yrFRA{epkmyfSw0W?$sOxH&c;t78{KpuTGY7I4ENH{)JMju1T4%)Am32<5Boy)j&r3wMy!Ob0?VSo*=5wy5 zA{%~N?SVTz0NP8!tV!#LW`5WI#pUBy5*)rDD~Bw3uGt%1H99NzCz>7~yhHBLN~1wy zu|jlA4PmspyOni@SG6GR1D9iYbla~-P*Ng7UO5koWJ~(1d&Wl54I5os*S53fO3m@O zRbTyucb~9Jf9Ee-vl7eGoQCP-^?eE4GmAomNfTv##>$PSrOVP(zpJ+=RrHnGLwGgN z!P-%b_TI3+MTs8o)J#YN zwgV(IRZ&@Q((hb(F(t?-sa$I=3W;nNL3f2|+@EttYThaxrsTB)b1fw{Xr5*SF!RdK zwtM$8*o3=)uD^4~Bm!ApcKAr}d8?{-IIdT;LI1KzJDN+XQxP9x2~PF~TfN=RIFwyF z4_#OsQS`}aL$Rh7)TA%Jv+=PQ5uPB4w%2j-wAuNGNGmYX?pJ=6e&?%X9(Enb>fd=Tt0uYS$|hQhC>9Xzig!_#iBF5| z5;vxTE;W}v3R{wT{Q>%s`+|~DcKlbTBXb2$0)J-WQFUWIGAvP3C ztd$Gx3F}5nj77*{Mwk<1Jg{RoGqn*?m|zeaCfArJLk(c_MQ$XJWjOx1gPiqd9g>Wq znwNx|4V0mGNGs$lH3At#@M(6>Nji)tJfl1z;{J;8rn)1HSD(Mle0 zS1xO5@Dl^EyQY#T#KLZ42HMH5Kq^au)<8dkdWQ#%61*nXzFD9h3rM)es#5F!GvUmX zw8yR$vyS((kj%-?!f=*VAvE*5X8vYudWw1gj;Cj%U5R45NR4Oyi3W!0JV()6Giu8) z+2mW;BGeR*Yt`*1Y*2Zef>6}pY~T+T2*7zW7JapRQYe1v%Kw!mn4CKP_CzAA8!X@d zG{Lg)sb$3&|1(c=e>>LcQ7pGfkDj|89~OgPoDzoBN4}Xs7n-Reir_|jPH~>o>9%86 z5=`yC%h7P%?xd#GYDQ$iJee% z7}vwEusTPz65pl}!!g{k%B}Nsq;Ao~4kOxa&s^Jx#_g#Kk2l3p)k|HeN>xUqpn4OQ zkDrWxn#0>y`_h?=5iLdO_la5ExO|PWUw5;K(4c~@g~Rl>8W9HSW0RXj6r}x5{$X^d zwiKlxYbH_s{22af5%!m5LA(70^_1)X%E(o+>s z6?E69ZVm4Lq-nWl?V>YH1rH!`L&d{H)naArOx$5YUltOwE8ICj_MWou>hpPNW`rN6 zQ*I%%$2n%2&=DIlKUo~c+0bUftHkP7q?@oIfD7s{#O}o)zzXN$CaDiXnM_#uc=%z;wJksKTIl zI6dkif9QDclC4!VrPhQoQ_4287SIpT+{$ZaZWAMpUk^`RA{2ULv~eV$7I3pk(THns zGWa%fz?|kjf}6irXI_lp2Ex(NvAuTtZy z%;CM+B(}70>uAQfPb0lAq@_zL22GJbkN zooxQpCCSN1=+P#2Y*#m>Dp5GgCA*b7=6rN@lb!Yh);@MV4ur_ToTpjI2lQ3R484Q> z$mXi84U#s8oHQ1SxQ)3ZetWw`O^E|%XlA9hfQ0I8+WK^v-Ar?mYr048-UC*}yy--> zNwS~nbe6i|ESpgzrM#3FuYvQ<<5H#vGSX?9Oz`(-+a*{T9b7r(jc zC3WwS>TRT{Shi%RVUQ_PgPVYOtW0lG;t{uigGgtc94t=OXw9armu_R6BU*R+0p6n* z19~FXR#!gWVV~hK2OoLdRNM#pGfTeT#YM@2yGP{->5MA)NCOh*=mGkBdJx5v4wcb@ zyT({`7+kzPQRfQ%t;O89h>qv$Yh_Csd*CZ7yVTcvZ;2F>R-6gxo`<= z+uhsmIegxtSYk7l0=ui5Q+SR0>4fE)8Qs^3>;q)8R8r!xk=uksvk=|0-x}zY$i`W} z26^SG$AmX=GEJ8St+ujlEP6D?REk=4_FIHt&OboqS_0NV0y=^%b4N5)W2kKZd6ra# zWr&uum=mw3d^yPb6X~`kWY-H<@h90GibjhPA1!2@m07YKQmi<{zKV7xnyVt4wdknG z+;FF?p*A}{T$OL&QJP(_;y5?>{UsNXro~h7fTNN_sBltN>|MyYk$i~dFZRP z6>(2dekJ+ctFkXgu|U)`wmiwxQ9`Guk2_NsqF*cBNqi;+Z9xh`l{*sWazGcAg`x&N zDU6(cgq^+4mpjZ0@*tLt@o%q{(E2~yCspa(ZtD(|+m5+JW7XuR=wnpQ_9x9kI$$5b z;PxH$4K#_1y$mA@5t`bp&<>on;TYroA*16$IqC6XObcIjfToK$WJer+VsS`+k&_y* z`H=R-XbafPRKeUZknpD#^*R}lnPj~L*~q!dCnFG0jTHLI&gWZDEL4G+rsXx^zpjZO<&S|*sw#V#`yQk2Ot(X(pk~`UI5Fjc zn%4Mdx7wz*7Tty~c~9gtFhn)O=mnRSM;GgyvriC+gg=!myOMzo1qnDlv%y4})Ldwb zh=s6@jumueZGI>GNI5L&Q=WOHbMtiqZ?Pf0w|LLrig5HfA03xIq42iu$c92K>l!j= z>vPO5H%+5h`T^c{-E-t2NCcV2Np#*er~-E?w4mrlVl=^W4zxaCggczImAW36VH^vP zA=!yMBhM~YcL6ghL0tTs4}y;|Uc`Urk7l`FS90s9*?XJ*QVTj=|5)~d_m4p7ZZEUX z``L-UK0sO5F+!SDjww$Zn=Iv^HM=2S%H0^m{fm3*hs9fmH(G)vUv#X=Sj6>~4+W#g z8paxuF2~|)U_ZKCB^Ox%YatL)4yg1N`AHGnepP%n1(}kVI+V--&M$ey+3R{`fX@^?CI4Ku@ z1?_4wNX@j{M91xl&-oNjp|2fPkk32{JABc%9b_k&UAkr93ENiU*r-@>o!zne}~=jR?|@Utyd5&Badnse{8&@zboJ}T0?6F4Q^H!yyo zM%k9n$6#m$M0|XWRQmqLB!l1OEL`EM5vy83csGXH3OmIkWK1JzdSjSzr)c;3_*NbD zPmNy#rv5FGiWRXe2bP!bd3Qw5IZ~Uo#|bU$Rt?op0fQBfL$J>Cbe?-n#HaX?331-4 z_|=hd8_7Cz)2tw(#^oD^&5l*aE>-+hNi-&R6+>G?wS;s=^9#!qmn6GhuE22BcT|bK zyncRv9uF*?(kjUd@{Y6H(MjDDrd|C>tNsnTpmblbCtUw;awb=ZnpS8jk7)h(t;Jz9 ztdz{vU1@~13kibclC&xNgNBtq5fZaIm+t$}M;=eF%QOKd${oEx%9Tz`OcaAl?%Z}4 zr{Oi>)wP_g&#n^v9(}ztsGy+xCF98%lo^v!{8p2CDNJ5<<;5PpxRp+)SgMq*7&(fAzr>By!%m7wS5k z3`uF2ZLO7>W>{=^`Kasj3U|(N!XimK)YfBPA+**0pm_}doPyOz{wgO#uyg-M z@PLb(^Z&2@GkCzl%*@L2f0GCQv)(nP<)7Yl4U+ z=B6~U*1wIHT~rdwTcH86A1)Th+rV1yS_Spo2L=P102|F8bC#AaQtN$Hea_5fP*7M@ zQrN`R6~hz&K#(VwFtNQWBqTvZINB={3r`5)>NEjp2rO_?XdS`!?2bIC{?W5R^_MV+ zOpXG8kr05@%bXg>3=O^u85H_$0_}nZIi}?;YzwH!0#IP1U&hW5Be>kTg{-dm@D;z! zQU$JMK=e_NllOgx^9n8CTte2jgo3Iu@L%@NDB@HzWCPZjZJ<{NUwTEDd;c-n9Z?`b zySux&8M3#yjqKfx=`R5e5#jtoaF>Yg51<92;;Rh@fKj2Qckt`zix(OE zJ-o5FnSE+)81)=3XdT3sM8PnyBMY`PJPwMt57qi%V{T!b;Q7$u%nZh_gc57lbW|65hs+{HkXMz%3tHQ?agK%79Xl^fAEH-4F>t1PzXgybl(r2VzKM zrMeg&xr@aKmgac@K?a7*!; z%L^LDAB_jSZYnCwM1e$5NJxPpnMmNs`$u5Vx3D0f-@K7w6o<96Lclg!5j!J5zF?GJ z#zFw>^ZUhTI&d8UvoBy&C4@f#6W;JU{D6{JApU6)=`ZldBGB;-NcMU|4djdkItV-G zC@2J!r32@H0ZS<}$W%MM@Ht!;XLmyZ>Z^;GLcqUjM4u-!6~T7IIWxdY^~XBjbuj6& z?8P0E(6&io-#!jpWF(sp!SVZ2-Itd{Zs9ybgf!m6muk@6UC^L!$(JVWl~_g2@DDUH zpi)pS=1H&Wgh;g!M=xh|X57DVjbrn(C`4~kR8AtIzPJl347)yo07q=VVdwx~jxIp) z3IbqjWPjSLn4F6QNd9Da2ZIR&2(1NNK;HR|R6G=5=^GD*|BN0e zp-Zd}nEN)kr6D^sP(lW{zGI<-0 ziiroLR|Bx7XIB@W4w3J?*F{%g2(YcT&yc8&{rwzuN{4(ipRwzpMIv!C^T1HXHD^yq zFyz;u!*ccF0~Ci0?qqn@97C(kc+%kQQz_qj;MsXC)_%m?d)3e1`F+c($Uh4sc2|6awoCo%J`cnW z7lMvUkv=D|k&ayOVLI+8Ns8g%e`&NwkvEMI;wP6?y;=xx!D;?|czs)pTauBsJq3}3 z;dA(kZfQrm!8EW}J9q4SiC;*uj;PSaB?+9Q$Uz2S|JcC?nQ+!7WyBFv#u$#$1 zuUk^)Q?T*WExfP?ZivsC6t6ANlSZgBuYi}?G_rHtwg2QH;c2YPQPzLE0Jtj>UHwVi zuKCePy4H`~>fbLxBg!XwImi&>b;tJBTmY(D6o;D*s>g-5)}6aBOus*+-0RVlv`-ab z$Q$0%7GsdOsJzvkyW;b+qyo?@+S7YhdT=0U2RaJk8<;5B- zYZ1ohJ!H_;5N1&sK&#>;Aja2c&QaiYA*X)yp1DfYf*8K>*ttJAv*vb=RbCyY%)r4t z>S~)X{uZ#yvhkUxw1gU*&PgJ zJp8G^kEm^y+fI%T+n+ZJr43ySQ(Cn(|I!|oG`nWPf_t4Sj+}L6E$Dg(pI!AfX5Bj> z*L?{?UC`>oV6;&IsnYr)1YYUuf+xhUI-iDqD-!i}u-BPO}yED8ptH9~YO6>AxZ`QF|1xo?NbJU>V5Gm`faH?NLI&JQK z4_^^^FXH6p6tnAhU*L-jI3;w`e{7~Sy~vdr5+cpSoaJ7oP$3I`593Fnx?OyUGs(gl z9oL3&@)`8-6$@*hkq>WAqs<_l!)J4O+X)N*9{o}fI}k2Or~1$x*byZG{cRg-JTjO( zSFfo_%B0wrGCC}#ehiM`qm#1!I?sY$+LbbBIq{a+1eyxop4EX3Ir0lJ$;$3w9RGCs zbzP@0egzfexaQ5-L3g2`%k<<4hC@N+Ze#wriSatN#Gt?3O((jEnxXKHAdw

AjtuitFH26N|N26+TzqxqP5D6=HK8-2?VnqHuZVW zFP|e+DcvxPtghshkMEN?UA(HVbu+&V-6!TDx+g-N9)Tv$A|ed4#XXs&z@d6%gLa9o zsDm>+fh;{7wj5T>DFqA^gAy%Kulsz(8D;PXiKs*eEBXBUsNcW~6YPD0iD?o$pyMrw z&Ad{YKcbYEE~N@pBWR&NgRZ~%r?H*|%O#uN&K;(gOdCQs#eKT}N z<3dYAaMqJn)5{Ic_`5o!PLDs+tpzn5 z>P)qoUv6f`oImI=545P_w4pR-y-(PDvpVmsH_H%nZ-!tLzz{}UrE=k1t$)da@WZfl zJ0P@)+JiogKJHtC*cq8~KC{LT-XL^u?c!S#B(NSZ4eRQuMfoH~>P+qJwi1va;jZ!_M?EfM>OB+j&m&x2YF{(9clOxceq`A9OUn1V<7DM(V zFs74cS}U4lBm;@uyR=*vo02p^6wAV%C7$cCt)*o zopZEQbj5QxHPXIEp2RBt1^THxD>viCFVXZ$p2c%G8u#0jeyv$*l&^mI<3c>l+yD00D(|KfHtXY@Mp5PqYe;nobvPITn@u$z_xrUfR9Qd4vIdnfENapr+#m}~j z&@id5@@xaTP}0^?e!O^Zq_3LE*()C`h}fMzS;vqYn?Vz9plH^avOFtJ35}D~GIQgPT%|hZmpMRCnd+H*E{jT6O)%yF3K#X}fx~;^|}YOrDu= zQ0D*5sqsebSJ}}XjNt4f!>?LzGT$g=fL)-o zECrR5)>l2C2p@e|eG2IB7F+PMIZd=@?;_slJwmnnuC8&)fwq9CI+5HB{V$eMDc z{n~!ccB+cLMqEQ%;8<-)Z1E7(%eH~fI4cDT!dgvJ^ z>`$l)yQa;l7JUaW`W=o{wU3Ceet%=tdG6>Y)(Lpo9;{0X)6AsE_{0-656x%sQsYn* zk-1~DlO~r>ob^+S#B_|B$<(GT91rQb?7}ks#5*=K?gCl|rZ>nb<5%fbBACcP?slbV zx#vz2;TK24eH4BUVe(ccH`=PpUo}YuM>kHNKMeB#Ga-bohF-bvKwJJR^W)v#*H=We zo*9QJ1J%$`aQSGZiQ19>c-%Yp;*Hs7xtF%EZtAT(PX-#}G@T6r!&Sa%hvs4hgewF} z(mke_b9>we7)NqdfBTFVN`AbRlF@NXDTufxUDl z=MP%JEhH6_T`qT95S|h<|`Z6ygoj5@83!oyg7R!6copmTiG43$h5@YMw+F$@Ql* z`uUEw;|mF`aZNB|RNG*XMJEVW!-hT*RCd_z+7FHg;At->W@)3(lhdHlS0t4ymG*@Z zO_Sc-v`TO26RHX(ge!sX@|xuKw)3fAZ!>Y#5pezbFjkX3p*Lqvxifx_ae`!ZRew~$ zver`2B-DXE9y$3KhCmr5YwXDm2ApD%c03koA=~*qC|=Q<2xE$OVH?JAn;?i4xBDiN zHDX7eDnkqG+YoV53OE=R)&rl|)bFmK z%B)#R;>%H?ig){+H&y?@t68qxuW)tr5?UAGwMX&8qU-Bu=&c972G3k8T>l86+UdH- z8Hs35M5N#IRF4)qGNR92w!APwn2Be>xI_fnpegj>`rXrcMF!-gJ8eDbtnoi8$y8Fo zylQB(O?y+TJP{-H3>}uP}JBTHTZ zO$R*v@k(lrjj-57$$_kAPDNZ+Ml^s6~?9f9*mIIqYnV%LANlwJ0N#Mvl&#gj>srHChG*&1+53djC% z)Bclz*KVCBfc?tZQLA02#X0SvsIGogsS}(BZClsEk-B{O_@cpVPX*pjcV{t(PJ-;T9lU0&7(gZh? z?p~e2Bi_=~?&46#kHczu5V!M@jB;hA(-$deMcAyZ z=!Jdu>N_pUAzomC{n{+mjy_9@rhZr9`-r}LPrgtiKq?Q;<{2U5wdCJ(X*qhwg7rtl zk?dxCceJKU;v`BJOkGt=HGBsAs7z?{m`IYg0Nopu0z1^kVcAcK3KR z6;1nD^TQ)cF9N)e=(~}zoBAUUm7n6#hr;YKshNTL?)@cv`j%dZ zAh`&fj|mO7Hgl)dl+K>(c#^+$D`kn1npA>;5M=r(GFL)zL4zl|2?yQ%FJD+Wu;J`& zw-KEKjuF;H{vh*Sou~b2&YE0h=H86w;Hj}taTC9c;lGi$NM(4-CBr$kB2a5=s4;YK zq23e<4w*|*7$sDuHQ!&wBNBAcnbopWiZ6x~&0SVfU(TFT9x#%62p>g)qpYs4*bl*0jDqh$Cy7a@H!5l^ z8FDW^#AbcL*RPm&rG($AmgLB5kx;n(D7EFBo0O`J-EoIrd}d7a?siwqrseYcybVI= znA}RL_>wfzlE{ySy$z*)5k{JA#m>O>I}f?uf@FV34iIT(y*3V2?-ECZh7Pmk6<%$W zFM=on z!CkSvtY3z=V-oK8#_Y#)-eR!qyTzej=Y&@cp2*U-L8(R)Km9c3{JG=efGU%P)jv&D zu}T!A%a>Fm>$7qcXhufI{pG-kfs`bqVb5#1Q-h zF~G}oQHR3pD>*#E)X#(G#5%@;J+y{RM?rL`g5Zq#N>DGBL{BpRtmB#POCrP7W*ASj z@|hgLS|>D+=7gbWyIdu7mSSlYRNc9DPMD6V)r%5i*h8@*#K2!}+%L1Qzf`wsbStZXL|Y5U$Dl^Oy#JFL>`R^DazybJqA`Z3PB3ZxG0Pae+H9{WdMW=Wa~hSuBa|!Vw^?3j}>3;{dszW zBJ0Ev!Cpr;y;3O#Vg2lwTw{+2p8``YE9oKv$E#YFZC*-Vhi%#I(DBcg!#b3?LGHhx zbJQc6l_@1Hr^}Oxee?3f@nuQW3`CoeqeGuk1U?!QX;jE~_@@CEBFwO1Zw~RAdF{Sa zE}n|)06}7ZYlC$L{l98tiUg|(8=>A!fJZ4A#nN0qY0TmMK27sWl>+Y-Oj2!}K}w z`^MNJ2GE&k#ygC1yb^5Xa!>om#oJ!~ec&D5?n=8hA^oTjpi7gpn02>}oYAy5E1f@m zuVSmJ3d}fZFM$Yl*G6~;`~7|(Ks5b`iorR+`dB88o>E(w!V=gKszI0yc$Ac!%(PLF z9brOO3k2K5(rLT)MkmPND@O~wJCbL|otv{B(w7Gv9 z^FDbDeM)Gzv3}nT9Jx`xM5|7WU1-*V#gkl%FLX3Mwx+jV6}hv+sr2EV38Sl^m^9wyd^S|IG}c-9G>+CF^18-@D4`fxT{1aixx(_s?63M~W7%%2pkZbk3R+ z$b}EsnRfTb#?S@Kup2}5DWZR-8n zt4NOt{1e2)gP?SCvUp)3#bMix9vk^=5kvo{VFlfQm3qr13poc9U|hh?$7b9Em|16R z5p|(8tX6mT>0bc446{^yLFN$FpJdVqkIllAkxqvyx4SF-M-I)R1eF*&vF7^Mn~;$? zH$C(vPO(OVjO&aiMEAStaE}rKh`te)$V^p;b3zJxLWkph`}RJoCG}fd*!qGIPsD2C z)cH=l?V1?aO>1$|!=vk>j))XIvkOjLFYP$ZE`=Rb>-!|I7(C_YyL{^2M02#$?xxdzsY8BHmQpB*f~2nU6z!H zdZZbZg~c;5?>ToDmGCx^*g5?zM&E-RlB$zqn`DPI@VXc}|1c`&p7;ZV>rH*sGy30# z^$p6?YqTzU?5K?7;-z;j`}UV$_O8&+QMGg~meG5i(A}pp^QleuM&vtC7{k^^G~&0A zwaVfr#Bpd{AR1(PXf*Wed0#~Gvy5($=`^_YNjH+)338M0@$$E;GWt*tdK6+PAI+Fa znGB%mTV(hf?Kqft+T(MImK;3>aX1Zim<4>X%YcX(QC+-VTc^}iJYl1EHuoyXkDUV< z{p$jU@NqcsP&q#FKgL_v3;Y*TXB;B_uT7n>y-G%^RBVB!)Rh4Px`Lum_m`!fZ}+yxrNeWBNTD*%IYnqJb$>r<+!3ALz_8 zDasjA6b(7=O2IXh|K=WMTJ@!k%zM}GXVf_&d6Z%32dj}iP95?G)Hvsr`3wHY6r>QS zahO^DttNq(6qNMBu%cyp)CHh{#Ri|@aez5i2kkKr7tVkSI*;>ByB{l7XRIW`?taHs7H3n zbdIB_@h<%%sMyeGC+Kb^&u1$ijG>((8>SQB$Lk*AgOP%k1U3`9)?7PEQ*B!l(murm z%0S79iP1j;37=Qp_!EIq(6Id7PuPzDLnYs>o+8_Iy9r9{oS1x;^zJjub_~%ZFCK9$ zU|#?3W4aZ)A;_{fcCrh-uYdT;Qq)z`!a=Q)M52|{Wx)sXuq)f%k3h$H&4~YrN`je^ zi}WoapW&`;14^aM@Tu1jz}7BFB0!4s?k|#4JDQd|8g@)xt%6#^g+T-6lEQXjxi|S+_ zgReVqJ%(N4sfh;#0ouC<2%aw>Fh;5Y#2L4aYFNsw-J2wM3MVbD3Us?g|Agr4NXfG? zce5go?U-&V=*$;i)KU`7d(7k;*#Af_ojef;a3E{L^{_awo0^_`A7sf~G<9X^iU;2P z^yUoOsB58IkUIOYsOhEYhjnVU*9jBNs564}Rz-XO{LPfFdy^;ax@L*PLzLnNwS#h| zb#K*gg-z_3>sm<*_}8}XU`(l0WVz&|A!I%nT4-)w=gC40Xfx@m@FOX@gInf9SSS^( zn0H#_YkFnEkmf@D0IC`}&gVjg(v>PVe0~8HQvX*6=A7{OHZ8`V(T#tBa>A+5VNY*> zz$1pR7kQc)KI6{tZ&8nRp2kEjn}BY&Y9*8+-rvx`pX)sa|KAySL(wPhs;GW zDtN={jr-G{-qZ6^bxpG*G z7M(9#X>#TX-IHbaeJSa}wodj|t-MURBMKFKzR{q0D#SKchpPqPVOAEeWM=IF3!ZfK z-<0R-6p?H|Ukpt5q4?2j23x|nsz589OBd>%WqK{EX$v!Js_XfA9&1aj^GwqXir*J! zXsj?=0~FYbh6v)Cg;*z3BE@%bp9z==7DKiNxbw&>7r}!Jg~;yC$2~aPOKKLErVzv7 zH2Xze6nL3hqZ!$eb+mI*9dC%py?Qwv-Fftd{a+L;r3_bE z8$W8Ki$&Xk@2QsPYWmLK*is}8Of;#tp-oMV5G$C7SVndD!aHfQL4L^TrbIcsrSpI0 z(^CNpo;m?lwwTa)BF6Ij{FTv0zlw=?kkXpV-is924#Q|~gnHG;1(1<-J>2v?{E?j| zrG=P0ckt#S=%{nL)@G7Pc&*MUef^Kn$K)!y!x-_X6va*{T|#cj20bhLCw~FjR+e)7 zRJ~uHi`Q;mhV^;YF5mPs&&1prk_x=7zZo)FcBiyzW_zgCmIohQ#Of{8kINr`SCVxo zr*c?y@?>2U8gRAUOm@YZ>{zhuPi6aI53yZTYjy#U$`!1)klFL6Tyh1nII{QNs(A=O zm9;j3pzxyCbI8PT`WE~~u_8K*sn13si+FDr6e_=Gq^IGY@Uhb}z z-Ou%pUbwf)4mZ72@b-JJq=9v;&a<6@z?Gr zd8!+rt}h!`{*hGb99&Uc2-zgW23<1{T5l_~T*bwLf~&F?j+(oj<9x(e%j7)@;rKIJ zs`V4p%}?12IRb>|-PPl<1?M^SPtV|)4*(HKndk;}Z8;`jrW0ZfA5fMd*)a2u`D){p z`b&?{(54s(FTUsw*5w(&>5(HHTnTxG&xoJSuHN>-60s)~L@C0*(?-EJzXt66+6FjrgA2CqT0y;bCYkRwA}dU zGqT9;Ql61g13$;^br9llB5M{)C~~VoPlmzxsp(_n;!wI1m*2BMhbC2(vw)yKo_2M@ zGJ-#C#=~&F5teiX!~eAYi33lP6+LOiukaTGf9QW)eME|8=8;jDxKAIx7*820&yt! z4yFrC{VU6jM6kZ+yhMz}C6%O$KLngPzc!n#y8s6rYHWbi?l=WLk;)Sd0!`3AKmNvd zQ?(fUPvJb4{}j$+W@Z0x4-gXpD<><%f3N;`IFF5kgY*Av1yTc5LD6a})$T;Z5sXvrViRWI z&H?hzLSg@A?9KoY*hm?GK*27Hfs%i+4}*XJ1Q8(x6(I=}2p~wHaG)Q@;4T>eG>&Wp zJ%0pTK9Fy~0k~b*wK9PzH-GARr_ZbL!3^FbjGG*8nI8m`M-Gr$Ywx+gSrRU0@?+vU=IAG!U~{OYjB2d z9?K8M6VO)+M$k`wckALW`YQzz_yY&_cfDUnM^FJDVj0f>+z|}8`QP;vVFv;a0K)2X z3h@Xgyx>4Emmq?99P9Y5%KpZYnhZ<$QFM{ zN2gx_BzsTY7Yf0>9`<6@_su_k1rq8p=;K@SUvjS1txv1|+2NQyKxm7nzY@ydGhYV8 zfAeYpA^-vb0tFczJYXBZz#bd?M}OkkS7)G4Fi_u2GjugYYgm zm}dYWqzjy*|F#eKcMA~$0>Fll4I+Sb9S?}~jhlNCruDN)Ty_Wd0G0u?FoGNa;OFDZ z+cfSVl@{jW>ap$fcK^ZJ8WR(P@8oCuu8+{uGo8IZUL62p4;2NlupJ5oETRAn@OQcp zHt0(g^zK$ewHz0Q;J!>_nfANNV6Lxp?mdm69pHER86?bz2BZI-ePAYlNC0~|t^YUc zq)+&V-R*bs!5`s^|5EY6!R;s3=_lwH9Lgz>GLObOtLUpKbj|ELnO zHPoa1i@Y)lpn!z{yv6ybc^R01M%c zpW#oXO}0Wj7|zJpE&>K=raxWAo0{UkRJT{hPR?mD_k_wM+EZK*@E`F3$>Tpb4pDNKgOPlCRM^pxwj^hAofv$4Vrd`r0bmLEJ`gj91wcq z9pDH29g^fS^Sp`Oxa}R~=u^B?i5xkJvjK>CfzfQC3QJt+D} zRZ*9ewA-4^2VNw?pl>_Y@X?jOLmJRZG&%Drd&-2TG2&7sxDetQlz zwO*yLb!0D|i?U-kLiBOKTYo>^->;OH-6GzsQ@}`4ir|iI3U%M}Y7jj&M(ot~7^%_A z!z-tpN8fX11lOZ2OIgyhnCmX*$yrnSg(<42MD$`KD(W75Bz>!vyx+$d-l}^sIv!A{ z4HmzY5x;E2Z@gM0`4<|)(uO=T=<}I7ukHEo|UV z^s;w1c{Ok-^^MIA?25SQ7@&#qOGYi-Ma0_f8aEs?(GA6oQ}zI!TPrsj&0Jo>ht5D2 zT%3B?$DR!vZ#Nv~YNDTBKJa3~F(9B4&0;`Gn5vSX=and^J^7O}4m{Y{Z}0Zcvm7`@21`*hvg(r29ix{2=E?P=;rcFkAz;m~+V@M@mw!eIwry-NiC<@PM9M8h9T(V*KOpS%_cQG<1 zAG)Wp4DG>Yah@ok6t6A_{|bUcQ*MWrB2V4O5L}a6StO6r_dn9|{zF@yyUh1;1VXS| z!tA!TDwS7sjqsAT2Yrc$+nOpPIno>F1@Y*FMZKkz1X^q51k2i2*;8(o6bl~9ok^bsT9|(CHfMR@Ap;c=5B_k{J+fcw*ede%m zuvzR289Ar@2{o;<)lfbL(_nVVS|D_&NPMw1tx{Tr=q&0)5kSLfalmYiWOu z6i?{1pS$$;isMq(u4Ia~lXo4;W1Y3BQKq;0qufaJ%ffr4{c$EoGdke&`2YX zzrf}LMYPE8Kq;$&rrD1rb5p2k?Iq(EQ|IEcsHd+ZMT*TJ=vAh{I&~1XMwX=X!%qaM zw#%N}oty0R?BWcjuvwTiwHsb-?@_;=-EP3t#Lxo}bf^Ly*F-DX7FxNyvq(8KVp+#U zF4q!93R#8iPB^(lnNV$-Z6o&eO1PUBDkD){Ucqi84+H0L#flJC)7FOBLFUVXL9n;+eN;*B`H$aTUi}f>Kiyfrmrx|A;E^J!vVLg{MYMH@&zRu^81#y z-ds<#O+MPHQEcW_^i)QQbN7(^oHofoX`hPR~GWZG|(Ie z{-Z>=+5F9GnY?JI<>hR!*^vR4iHF&U$Ejy%=0~z95(#xHT4n#MpA8Ce287Sh8mFSq4+#e!ZJN9Fq;Z9n=PBN? z6iC9KHBDqFs}(KZ+WdTW4`EdJ$7L1obx|t(3FzJ$_QQFdN)W_L5g{FC<+>zKWG7yh zv*`8KbI4<&K@I%G71jK0fz+c{11&8m={vtp4)@OJ3)fN>4;f|I;JOp&%FNR;mcsWd z@)6D6bi>7hg)yTE9@yNY&{{Y>MV3gVbp1h}d-RI(S>|j~*|VGLlxL-^HBL1f3dIZh zYs<8eOU(L8YoZZ*zoc>qzklJb`=~w|Z!s`pzh7c&z?z>F#eWFMQZb*>88MlA@Hj~# zwu8)w#OsH}OY16@ZR(#3D&+Ib_&4S?cDR@=1MEmXZ~E|ox5vSts!IifJUl*Mxivw; z534Hfkfv+1r*=U}SK#-p9C~|$ze+$Xe$~a{$FF_DQYh0y*Od6=sM%sU3^*D;z(R;B z_p^po_8|9;b&VY!*OfiUJS`QNh8!Ksrokk8szt%cHRob&vc4$KO^Ha{z-5SuTCApY zE+QMYM($ZTLhfBnlrY{PATE=aA2pTmX@)u zgaage?6g^Df$ z;>ddPD#d)p46{EKMKx##S8cR6f@SVyD6MWEr*{5>G8Fd%(bENafEGch_QjwtOZw1* zEv2G6pYXT<6%*VwM1g%}871{XcY?w2x4?~ORs{m*!)1Ntvo~3*s54r~A0mxB`dqx! zQAvqWjMXf>NyK1r;A!nBBd51G*WOx~hdej54P!HT?7H-uQ1CA&!@=T3AbdR6p1$Vz z2KATSy)SbNk_jt@D>pChWJ4~e2(JoGRdJy-BSEZ9o_eYD)g_{})~<;54QVPe--$}b ziOE)Vo!bXyPK>-o-=36fFhU_RAyv0G>*;)uS;69x^+R0s4p&c%WgLWO!AMB%@xI9| z=Vb-T{r702Adf1^7`dvAhzz91M?>_*Uh3+z05jp|Or)S%Gwkm$`$8c8EcgX`gWV^; zIe*1VE|Ut~LPz(JY%HBx9o1sx;sR-lR<*em_$+EMHn($ao{=?_)XQ3*1GUEd< zKk^;)cx;lRE{~7w`*w|5(n4tVylddx&BVpNH}-kz7rDdlP(#JU=oL`gDy0_I)1Ri* z_)AGuG+@2UqOJ@1%kxZBz+!v1V?1VO{l7L-9`0w-e6WyFTWA=6CRapfK~r%N;8Ty= zQP9byh+x%Vk|{QlTCyOYWZPd~rr%Re?H6XSSva)3eH>P7n0>!(b4rk-K3r>hk!*h~TBoiwSL=r5O z%#h0(1uW73G^xpV`K?L%Tv-KDD*SDSlBUE%N6+136b;)yuR5lq$O|t;=1aVdOXjHJ z{{h*vkcr49WxHLS&6e#=J3D-1JweXIHBR3iJ)cKdb?K_tCS!I#wTnD?CGUSoZ z-TOv~Et8w99Fy2X-N7C6a-V2yI&#H4sF)e>*2ngSg@qnsJeU76Ppi-qIJUkXR_B;e znxhEKAlWzJxJ(|nNkZ*!zGWuU>SRk2t;fkC!Jm`ge=LHSgBV@X$R8dLO6 z;`Eb<8hcp*DC{VmyEAZIzrjVjFypR8fYic3N2XFht^{ItAqRz5Ix-Pzk zY_Z>_axAe(Ve|rOyVgeVJAiXsFRd&f{LGp1^Lfh?S(tXNoofwk6#Xv?4)EzE$j zr!zqO?<4T*Q#^Fm4dccb6ItoDSD-B%9&^11r-7wspYap(8beA#HfoPV@_1I}?YGu|!4i1=?pF$WTNs3fTPA_2MHgCHwvT}P&HyeJ@ zP-{H-U)QpLe|6UY{h?#{k|*X4c$4QCGke>aB+^no2CJM`^EGNBG)y$eB@8c?WoB#@ zNp2zFGp)68bz~F1Nwm_OwFc;B7%SV9?}LWdbf!aYvT2n?5`L|!pgKfH6^RocS*n;j zf?Y5Bq!b5TZ=YdgrRIsNJuJDDKYDpA6fK{g*>_6T9CM1BM z8#)e--C~UnA7vbqjf!3NbZzL8=d04%_`};u-p*yYN?p2>XZLM_rf1U&9z1IRjkm5R z>yr7rGt=51h4=5Ea+w|j$A+VvUeE8br$*hlax-+S#p@y$ZBINxfpc6o&8D+C$YAKG zJBZH^7|sdE7d?IJWVwD>hiyun2ObE7rOC@2$1pXdEjR0p)kAG*Dg}k=6E+!}q1upCIfi+v)pia148&q%})aSps|Yn5A-8o)LmeribNmN^mk zC#fK9s;m_aXdmC0juVqxB7HAK!yCYOw4GJ*)UL~wzBsjGe_29v&?p-X;&TcTpCa3& z5x6|@xb`Hep}%EsAGOr+HW8*pOV)h%F?Lrocx1_UT9HH?zGP<0+gjVD>Qrb?YHU2m zrCr?Ye47XHFzD*sR(}FydC0o0D6H)4gzH#4{X4CbcsCH~t;9}mB$I=A#{XuZa#XMc zGcdE_lW*3!ICojhbg|dblwr_@bS#uGR|G-90D1WI#^Ky^H)WEhkReDO8$gj z_J1DITn?btc)$`rs4|er(9yW&VR_@E3b`JJ?m2JmednL6!!i!#f_-EbW%;Fxc(~=k zy{Hs29`EF?l)AC{7^P9XqhYJ9-E%em7QoUCiFeu?t}_dV3oF%O_o3jm5ZA!FKpfzA z1D?Gb4wT8XdjLTro;w#X>A{o7T`kY2nh-~>D3%={1lrhnlAw?ezY)J|ouw6q zEU#d%;G-5qV!o>xbk5P030$1N%WpvH_y%Gu7u?40J6;Gql$M3NvsLv`T3DFXJu`I) zp7`!=I@N)-_7yVvyQ5Anl5KtY{T${N|C{&zv7?afo|mk!PyarcY0(JOY1!w@Y|u{| z{;@d~&c1!j;Bp@fPqq{Tm)}s)EXG%vqQ@GFcKC}gG7*waS|{53o2v7@VqbqtxvPqd zRx8-qd>n1NHDOh7Q5nnLFte_x=bR|mk38x(<#WA^9I|yHozIaIW?m?yc|BC5zBzok zdV4AZvird&!KL5FXmF{)88=g8p?~h;*eK~+1S{kw>^c~_jU5YLR|FMZDV2V1JQq!G zfqg!q5-W7^?QKI(xn0#QEH4O2drfI$<%4hTVcoEc_|j<2#eS;tUF;iS=E?s<8#3{Z zjcy4nt0TF-)#LrchC1mi`g(hoxn$$Ken@R@y3>pVMiR~9KZ8k^OMcErbsh2D$THtO zBwHrYlaAb-N9Hu1nm5ldM$a2lyRH~m05i%x;nAYAOn|qA=A|D>pne^AwUo}8R|=(<)QE68Sfm1Y`8|B_e%{Yt*N@NsB^$*kOckJ`qU zt6X_42~PIXbLS(AV@I!EnVD!P{l4dRh^OHGsKX6}zPlf-`wI;@E7&|_Ev{Mtu#Lqp z+a11m-^&tkN>XVDUB?c9RSQ0ZDia2)&6sGwbBj6<9oV{kxUdSehM5$Usg-fyDd+Gt zxT%{>eQFa82e&SJV^g>wm04V?qJkgN+r0%Ybfl6N&c_#utO-K9dF$eeethkpnan?W zo64;_23TdGoVmQRJA-wd3V?I6>LKb~=C0CGa^7~ntkW7>mehF2jV1<~0^e5K@zBj5 z3#8yURm?q|v){-C-pFPP2~KpecHS5EaRwi0XssPu8sEU0@cK+P3Rcfd$?+z6ZZd9g zaMD|Wd@0kmWRgMopvF4woIraf$U{#b3*(51yWb^W#;nFxCTAG^N9dJn;OT^mhc7>A z4cM5o#`KOY&r~^8r{c4}7{RA$hH`g<^`5Aq`XSlo9jB}YE?zR^*%b}p-if@Ln+1z#NhN*X2L+vl3NTHq2l`9~??o6AA?ma_Bpe<;tG%z#N1Dz$jQFfxDOab{_mKI2cHms8z=3q~gNC3CC zu@e#>5oI^@Y)^cCibC44^X3FwBwko)mTd2DU46 zsN2gsd%r-Q5B5#}39zyKC&0$S^gl%#OayGqoSgp&u(30(lqvdt%ZY<_?Q z1OYz-!wf)KtN)~bS8{Q#-*?!04xggfB*ym0Tm?y86*%Oh#&zZf9yfTBmmQT z@MXCC8SwdlA%dG>0n+v=bfAm9h~ce=SHyn9DM*Bb1cbx)Yd8gmK!W^M0}KJ|7?+TC z1G{EWZeW=GRt1Q~OMOC)V%$UtbxA)zd3kxh`e<%^oPC0+3E;aBB3wW)1b2u*U?cE1 zRXPFiE1-8>417iegChvnUtsLP>%?3G5Rd@C?1EN=bna0=(57Glfb=fFunR2!U3G}7 z_=Z({V7z|)8bF9U$S?9O{hdA_LBqbBf!0SRB09{pDJ`$`6V1S`3 zKg^(T zxin1M)gFU+o&U5ye475!vdVcP;_GeDZ;_HpND&}kcMt(UT|NZFzjH|lf-r>h^@A%4 z5A#h8JHQ`ex0@0r(qN0zAfm2DJAUzK2GDm_U0Xz4!m< zn(mMN)eq|Nui)M9tT^iN)tC0vz4W)g#Q>dxd0pQVMsHyP#*Ot5BR0UNy|VInp6g23 zx}YN6Z;h&W5F>X!fV0DoJaWNJr2@;a9DG!>>z8l}fBStMsB_pLftQ2(*+0D2PYnR{ zod(yW+A5bWK7>0owo3(JX8Ge=0yT|h_iEh*@~=O{00ihtGzODV3<>ZJ!eDhCF6jUB zHJG^Jb^wOscfhNChy(pc6o5Nw;q1gc{WE(3lwg4^g>=TRSO{r=H%9t3{zim=-4)E^ zAAEphZ2m>$AMGD?r&bCOpr*{eiQtJZ`}bFFfWUmh*5RdO2knY^a@7J^b5y8T9?vvz z)6sybQhH8L-%><;1%3(0WX`FjV01)ss0rTdw$t7U2b`%n2E7j(wq*o9Tc6tBpR(If z)u4g#2k(Qqq2(Omjx4AZ+$WJ&&)6e%ANp+{*`RC(?0RjM08KjzN2MN|DCRkNtFw!^ z!oNRv6Q^@XXYv{OKMZ#x zq>}xfu|wXPV|y?Ses}4x93&Hh(nImm6?nK!>u&@LB>|L)0vyKna>j@?e*Z)?hqFal z5Iw7|XjOyMm{aCj4F%nO!rvawj;6(C3GTw8sVe0FlqF&q#62{}-SqE?XEgF_4DW8U z=)!cm9q~xAn!?db`l(8BR5vEMBMfm{r#)U#zfB2y)5v?r0>p78$3GC9nsrGoOV@&- z)D-Hix0IG^O!rvvn~S41D#Az^+CHKjq>7Qy9T|-!8urG)wa9guE8QdNLwr$C^es=u zHEZH&l9v1TTrLOvIC{2_7szjtwf@sRJqMq{k-uEj)J>&%H>V!*L60?wr+G#xFDIZi z+Q5g+3PQk-CepVRDd6|^4vDf9uBcHAJ{Xd^Zus~MP>iLng^r#IKGG|;tK+?EF|OAZ zbuP>7u68AQ_4wC3%B7zutf6*tE(+R*uOnm$TSiNPpjQo6PvvKIS6;f+bRiJ>_;FKc zon8(8<_KPxPTwG0bL`%XVrwbC2zBy<{1=;h0kCIeR-{8>QY{kM!t&3EaknTXjf4yf z(kE0~fTP9uCNBr)cT;PqqMh??i2LN!CH9B-cOi8_Bh~Tx!?hY2lDEnnCRbT4I(Bd{ zTNRXEkc1l3(=ZU}<1lX0aeJ@i9)otZL=5sSbz@6`W!ge_T@~B?kIuweehW=_S+^7k#^ng&?Rs97V3CT$-VNN21bL5WJAxkEstx;zS3sPc6 zSm%f8rM(+43I~>aiOrM`9r(N*1Johrmn|cLI zX@7jNd5-0Lu7egAiHeP4dX&<8uvUU@|0Y*-ZtW>Hm}BX3xM-?#Kv5qRFSv`xWFe;^ z?*k8nU30*z?7JaIsp#9n9kcEfs1P>Mvd0Qj(TKE7j5W(*m^8SKD=SJZF#Fz)2p3kzIKFc` zt`L^nd4GbPkkrXob`_}!o4A+Wi}$tH=2Y>xG}t?pyN8p%R$cYSI4yvmvIjx!E{~-CJXku!6h^ znYfvO-$gq#5!=?+2-R5&hFKT%(2HOd4Tga5wY5LxtDER=WqN29W!(p7R~Dx16DGg6 z?VZnQdN}@TT*dQv0q^zGhw&RmhGZ63Mt*ZnLe4L5<+Y=&tj9txW78JtV@}zK@swq+ zgrw>r{m6A?sxu(v>Q$MOtTpbx>{)XSanK+RW%-%-8r0J-%!*0EqBgj_iT3jBI&YQw z;`$xJ0|oTGHvrY!9g)BWw7y-OB-aSYd_!+~M>j)jbAIbY=n8FX{OWV>Xe(ywYx>)6 zZMm0{nK>DDrUtg{_Fs(MQ?F=Im!RQo+qQAGb+&EWwr$(CZQHhO+qU|2cdAks-$ng| zm8{InI2!&5tXm7OmK708ReMELwSMk||!qCTh#ijx0^ z4Lqc)Wh-Vzd6AwWl*a3Bhf5!&W;oG&xFGB=yjZ)-jcOC{NFD^287q1t36QNBam*BYUceJkcLj7v4v*+m~~~`Nf;sP$3vZL&1|BrE$6$k z1|QpG-~Gr#6kM49Tv43x#F|MX!7;Tun0^xu$V+Y{$oXqJ2^VS~W)EFFSV?}tDf{i6 zBb$@?nD!sAQC{z|X$YPDO{CVut&y%n?hL#6OUA(|MJOynC>@hHi^e0?i)b|tIS3A%MTO|?Tb-|!Q(dq;L_YLeuy^x z??;TU1-?2SRF@rnS`Z-hX?ZDO?+ zAw!;MYK6UO?Y$8@nBv#`*IHUGBM2%6)ufSk%d4jC_7_3pklw;CSHGlR@$7?VnqM&~ zD~oo)Sa-Bdc?S?rwy`#sD%5qlmAU19%;CX399?}xmx~s_*TP4-O9O13E19z=J=7#$ z3-4D5?Nt*@B+E5y;k!F+`Qjr-GF|c@uD#q3=4^Vh1HglsuM>+KPWGt0bQHT*HxnX_ zxEPfpVp%0>v>GB)bZq$35Q)SV6dD?``f{%EaY2>cUR#aaQ@Bd!FI4;t#hN{haNkq^ zEn z4)JG4nKdpujY}LTf(}`Q&H(lR_?y+NjMawi6XaUE$fnywxSVRw!P4`YzQH8%ob>ln_C?0#wa@2a%)^VR z1?DBlCH{9F6Nti@)mAZxF7J8s+lC|MWpmP zr!c+9anj@6?2guanYrGc%g5$^@BuCIYMK?f=iI}Z~pD!p0F@Y*}Ay#Q6Ybq|_)OHIKY^ODm zKp~Sxf;U8kAYYVsWR>l69JYwWqXl#P*wK~3q5uw%-i^;_=6Q^|7_kZFnhMn4`i}1Q zJRJ4KO`27-!-Jk36=V8I78BDBm~*Jk<&O=$$~1$p%FNta?s8cIAkGq6N*&{qMj_}i zj6X_GGizUjt!gSIhvr|aF&S}nEY$5CQ7o)Zthd$na1;C4$dy`D{5wYdcTbk+g$|h~ z(dZOC-$|%wwG5ipO)|pQlijiJdWxjZrywfA)XL;Q9bnB{WpHXwcboD7*TTk)4o`1k zvy+V&;>^^6pMey3adIqGq)gd!U5O-d3~^tK*(>kjcK=VZDo(|K4Xy3d;vM*PgboBm z1>huF>`@uS=Wz_Pnla+QE(>02MT=Qe?K7n4)7KrSvDGNkL`a6|4MMsJ#2}1<)};Et zVay$r-9X#o8t?mb@7)fa)|4C9z`SAP5yOhsRAKd#Z>UpYsg5O*R(=r1DWkppAGUP= zOtiwXFOgxRftYJSLpah{87T`nVB%c`A?alWjA`sso0f zwTd~b{tmsF2E?1@; z$R;h&=w4`u3^`Zirt;S1cB)fkjUfC~zW-QORaNu-^rh{kS zrO&+H8J!Te8QvI1OR*&3<-o>Wjhrsgtj>GO5v}8sPTb$(m&Od2(tZ1Sas(cRkPVwG zYZ?WZpEnZMHa$^6^?P3Z6R8Ln7huH^lU^Z%Z{grBlsR4 zCu*}6onY9MX11*C64J=9m4>FD$Y8KNW3VYke$=_n*uE6S@{~NP)vp1P{w6g*=dVX- zCZeX=Pa($VX`gBx37o!4adIP=;b!#q^Vy&@yWDJD)Vg`yL?c8qtnI^@x^_9os34#B z;s?tE^Y4%H@f}dja}tHY;rBUmi2wtIoI|C6YRMrdP94~P1e72>{05MZLjwRqUZ?aK-!2>v_8H3%HoP_AUY8&bbb%MwLe9T#)Jm^GB0s*d zk8Dxu|Ikt;_yC{vZjg?6%xF&gFHxQko&Y9o~@Im|zsiU4nLshdo<9a(Bxk4Hd=Jk-=N_-b!)eUkjn8h16*<^0Lg_BfU=nXW#Jk{%n~ z_oxb%r6G+`(3XdQzwdi5pb?%)l;_$1eU|%$7laa;1Cty-y){P0e(~N4O;y^*C@+8i ze6Ty;(@_(n?JWs4_WWrhl>M`5w_Fka{oL^0#W$< zTxX>qR_wX$LNz95pGTCYDFPXY(tB^9MI4Aax+CN>qFKrXDu_*pO_EmHAFjG(QbZm6 z96G%@*u`zNVFNM18aCEB2jnWQCH+!rjNH^dy_+*%H{QVBDQgi$(-<*{N;RW)8uCY- zQtY7I=~Ufa3+NHUu+%*|)uCR54Sv#3n$NRH-7E+)6$3!J=S|_UbLsM|ZJ(r;C$`TB zQr=m{*@Q@?BuEzd%XW4*oDF{vnd8Z!3x;*WVoWd!c2_MiL7XW^k@0;_RN>A%VL`1+d}vJQsb9 zw3wY7ohBIb)s0p7wqUNMQezP+c`xpKRO(-aqex9TK72}@;$k(bwg>68=yUQ2mJ${^ zID-xN4P=O}{xqj7_m_U*yGmA|3g1C``0ekwWel-wa75*Esg)$;=fUDILOcW#m}r8Z zTw-66yJb$ZA$(9AqIcGO+U&tII3d;c$@=6rOy$NJ`}uVL9K$iKO+kR=6{u(hXvY{8 zAy~wY9@IJAq+Cxl_bj+m0;*wPl{6bjGDpD0pGV^eN!N%`4CZ}OOqnXoZC5Cbwjv_u z5bzveH7RA=21L09)SQN>pDG>V(tgw!(&x#0k+kvWt!sS_qxx;$nT|%@r-*v&x+r)Z z9q}l8?&nw+an1)Bx7OludEr7J4xo@tS?oWa8`++3C1%W~Alpxl~$uiXn^VA0hSsF%~_byuQf-0#cTSbTrvcu@U z3)lvdlBHY5Ex*a^P5T=#9-elE4^H>)p@ti?G>+zAg)(BvbOcUhD`Adt91yzthl8hd zKqXohl09RYWSeL(De1NeOm&%$M?0owyShN4TRdcX?1Hra3J3!eBt+(>4L!BBx+wTs z)#0&LX77!oJn7u&)9dXQL!P9WmlkfAcAG)R?${CvFM-|92$YS<24FZTLr3L{Sq_e4 zk-FkX(+C41Hei?OYqR|CYz|xcWJL4GFoKz{JgLbh$kZc2;jAw?R)hH7TdvS=Pi;yh z<5Q?|p?m3yQeB^Kl_WJXpYvDpIDpk8}B!SaFcS;JY zdjYmMfi(kGbkk}sEyNx5-CtVi=A)CwR(3Va)JD&SaPKSJAQxkLr$iYEF6bwhl*HtL zfy#~Wi?|3JSG4jH%-Nene-JCH{;qqAYUzQ<`P4xw%zpHV{h}McvAZnG0D*Mu#N^jY z&S+@0sGgM%HLrh9ts-SwCtp}Y3?6(Jp5G*WBesOUXGLb zQFU^89Z4VE5)!)gruij3VdB3>rbH-~n%{Zq4{=s+?ehMM{lun;MPalLkuw`yL(8HmAfi{0Qco(OGStFQ4w$ER(S*OqrA z$J}g}L2q_nZ6`mC=P6 zPCgQ}l578J?e0Bo8f*nSD1)gqzPQ?aUwFYI9YW}PJEj)%hTQD=x{U<+^;H%`noHOX zHtomu(2_53i$J9lBcC8fm(MEseR9CAOP@GlAA1>b%_%&aLZ4N=3Sn;%KE05)Jw~&% zAlD-)WD&n+UH}OPe1rxZsk=&~DX!NK_lL89b7f~C4cA8pGM@Mh^@VN~;m&3?@ZA9m z*n^ZC64EOMafz_~Je3I1{$Yx1!)iFIIz;kQXP)f}|^8TW8;Ql8@W&e+i%FOg%aQcr?S=j$$M1YNjmGytk zs4oAXQS*n)^5X?bA5D_3rNs365lms$< zmrmVte;<8zId)xLW?Xc8sc)!#R=r0Y2j_%@)*-JUR{09+h!EuKaO9L{)vzGIA|nI( z4FK@)6hT&if51WS(gqoJAebd?e9x5`>?qJ;%lYfwn7Emt%B~LqgTjCb6&w)EIp{Gc zz`!Pdtiwje0GIQ6AjtD_DCDrC13ZDqab0I z*Pe!julgQgA8#5o4s;SoVE;mc9>Eqg#A|4KfDb4e>|M~Wihxi5+gG4{j+ty8QxAw6 z{QzdnFW_ERevcgi+95Ff$hYlqFDU>Bkdr`P9iM0$G!W<;`Cq&c&foa^#8HATf7d>@ z1Af0f-Q3?StNSenfkG~zABJCUt+?>^`k3(Mx&Mc#^8BB`_Cy8?e25I<^awzR$iNbZ z@cq9r1`xtu$)Ioey0l45SQMY+>RzcoGHb83=a0Y57(oB>0Slssn9$%4zk>gGj|3y+ zH{i>6@vC+6H+s9b;ENaHXZPLg&CTs=<>6Q17hi({X&><}6>nA*|6g&(!|V$z?`Lxf z=*Lw1c~1rc|H#*}xlZm2j-pVD>t|6Ys19ZfufCY1N;7x zA25QiZ|`?uzZL2v#+SM4-s`J6;4t-MSGA&0&#Y8;la!1SG{}H{4gkPs$W0t6EO2ji z4)W$Vv!5@H0xEjA6X5k2X4IJ$Q`WsekAF(YJ-Ur5)7^#5|;pg~6 z6b(Fpi`%Q~7kJMUYM{el?>B9)5mf(suJ_ot82Yha?{4xVQ|3+MC&jlH#;%PQ2P_Ro zbkJtU(bMPlSU;MvGI#7D?+aqKK{&(@!UpMa;xsLTS$R)g<_+hBkE6LZ@#Qh$?{Cin z$|$By_dBS$l4OJYrTARAcfx(>u}a_2U306T>`L-w$NKoXkW{itz)V-b)ZkWlCgf(b z`$M;vQ5h^WCfxUq*~kBVBiS2^qsyw{PF5^vuW>I=vO_aNR^^mb+IN4CflLmm5|k|! z=QEmX;`FN*#AACFAjl~WfzX9WrxVqfgYN0ZjK;2LOm(u|KQ(PNJtWg5`}+e-Cu2-2 zoq3O3Q{~oTwlq>oBJ$-3?q6*(_D0nHR1F}MAXRNZcOQ+K8k~!LjUxR`p+9|gQQkyO zZ90(bTFD(wqN*a>|LNZCYTjyhc!l}|JIk>tn=4j{*E81DL4k@~G3^{EtmBhQ7iL5aPP;P`UqC=<&4Kiu9U#<-_UuM zv_+||wpr8g!$bW@x}QzBY1b*hw?{=xJSobr@__#=Fn?2XOe|yr=3`mQ<7tf$f7|v5 zMP9o`9b(eMdm9;|eJUkFiI)Tuqb@`aeMD9o&Aq30riW=n{)aHu^;SYNT-tdps?}#B zZ2@#cl0Lt*Knxj2PO6%`9U7YGJE6g9{yM-$azo-TwxPS~_trg&zzFJ%_nL~KP#}BH z>M9Xoo_w6s(B9_L4FUC1+=7>7`_+b!K`8kEclmg~wWrl-q@bwFx8<`06Cm^YN~=dC zE)*N8_bGU7DQ5-|%%{{LnV5zIkHB?%YwrS2@x`OOV+Rrk;m=&y6@hl}`o<7PpJ;#s zZR=F8V^5K>{!QS|eDz}&`xwaO=rGVE=&O?X2x9e>2`JvmV)I^nrypd`x$)u@wEsg~ z<(39lAiBw1>`)jWz7k_(zsV_@Rv%AeaonA~!ZgAR45Y{;WiIP5Hf z`dt&|#y30dI9Xf?nLrCdz?8HWrDhA@%OS>Rp85Qt*@w&VFD@73T0VmlT?Enq}EF9rj*vd=SIO?KtHnIJsQ zh7`lRwib5NQ>Or}u^Y?9wpxd6NdS%Re?h|B!huw4!^H;qN!|1^+tmZ%9pr_bLk7@a z%H^4e7w2*KR3e3!7TY(}s5Nit60Q!$`x3VSw%}a1+rXeYF?sf`$Ir?56(UCAIQyvu zk&Xkw=D&1ptCvkO9i#WjRz}W5pzp>;KNp#rd^g{-nD?tl(4fQfbm$dK1JxqIee8tZ z^M{Qeb2h>GXJ$O_Uv(pRwAaWjfBYJ+KPi-DY-N?)q9 zRR7Ar@ZDMIk_*kzRSDl`+1+j=Hq+KLp})tc8d0m++yLrmDfH098DsEC6XN22t=Hh4 z4_4GCGtCpb;AqAvC?DbnBwdiS8{3o~@=q~fnB^ecHGV*rdep;2lU?igOT4DCMcZyD z6>RIs*Y-qRGmhJdHPsjDw~zfrq-vQy4sp?Zz^v#fmNHME8Vm+#P}!P_AxDMH1q)SV zYAH8=;Hhrh*0Fy-@{(92CDG+auk%I>(Z2D`HO!>>dCnqQq;bRWR>(sU?ePrNa2#3b zEmKu^aaR$fA817B5cNp##Ta<6!DS!bTauPBwaxql%!#08mTr#Caltb(tjFIHr;0zg zu0zpZAE6muf-AwJ@+vRdkJ}?%yiyrL*#r?cPL(%(xq#~X{wtZ5z~gFM2B9yajHF+= z*#3U-s{0Aluy|_QRh9sJ=#}OSxY`L7np~SG(+PUmHAH)*1TpcBH+z@MK(CI9{M1p< zcZg;iwTdK#h63qz77J0bBbS3{U8L#ixWrr}LQaq%N0&0PGcMa>kuh;Qj-Vzxvh2y5 zs4KV;6dGLG@;T?eX5Mk}>L3+IkzF&TbBC=C zjBhV2-n!Iqkb3N_)al^E^oP8aEK#tH1sN%NQiV5c2LYGuMf5_FzO`+(`c9Yd&T!1; z1p)jLcU}dd^;Ei+W~~f)h;daP0NqlE?qrPdm3x*Iye<=v>4?VhOd2bg7=W^_aDolB1~1jAV>DyL4a?xC{x(pt!;Q zr{k&+wln7^LWA7aoqUpobZ2!JO+1N6yuF=jEPVa1l%-W{r#W#W?KyJ8zj8^8pqL_y zlFe;<2tp|jt)5%Z@r_54GgtzLHfE&}BTAD!eNt!^T0(6(z3-r1<`B`Yotw^==p3Yc z4>=?9)Vju&$q7mK#$9=I`)f?Q@r_G`8RW|{Q?#pfe_DNrpGjrhR{^@zjN)@`$f#S* ziwF*w!`1HUQYIS|X0or@T5mP$5&xaBZ0gKXB|Bjsbdqj)yi4@)(Vcl=EG`n z14nzk;hvtcjStMVMsIXcR#ovjc%CLry!}fSbm}#0e6XtbOpCLk`htR`*~+EQ(wJBe z)%{`fHNeakM#J-|jg|m+BzHG!`eECVe^Mu4c_nIj%V4b;44kA|$@kKJEZ6vytcz@b z-)w+PvsHC=g^FX}^Yd8?D!HSzP4PwEHTbHoFyn|kgb%f$`6S%kX1j}sq-c4fD3jBn z=spHZn}@abSKQjnwwYH=%bfN1G&Sm#Ua4+iRrQpFqp1q=^^}k4ci)$yGCKdyQH=83aoD zF8H=CtREcist*Gb;s8N)sUE>&G5gB1V@sJsvyOl4i2lj59~Y9Ct5a~n&xi8yE!R=L zBpp;>Ty^Lf9+uv%cO~m)Gs?k$Jb$(%TzG>(VwBCMzB=wf;3iA6V8E6szs{o}?zRjo=@YK1EH$0^XV$sTgQ*tsJ z=jB<{_wyZrC7Dx@|2@p=f}u@cSBadNQHDJUUKzG+Yec@5OZq#-ik|!nFzz%QB(y(a z89!=|ti>-5Pieb@tJP%)L#UHO3D~u|Gn;{>q`&K(tsiRsr~Z7)JM6c71Qf|nBLQ)W+qjVk zf%gE#nGoWg%BFx(-r11gd(`i>YD&@}zrQ$LtfEOtNM!LymF4`T$I_y-T6DQnYjXCb zlymNa+#_TUvCfpE;@}(DIkS!}ahY5I`D(%Z_KH#?+9v^21fw@RAIm_XEMFP#cntjb zw6N`8>ZUfs)wosN?#g;qmtp6AeY|1Qti_v40o6_z&Q=J~o)u+@4 zU~~sDzuT)sWb+ZKdy02(%~he(!c_LneHL}7u$HQ(w)9za@+B+E(9TqXP#k6yrN^9| z$MnOZm)xfb0%r5=VUH}0KK>NLcH*S6jJVuY-Y%Xu%t|c@Y^im#s&-9=QhPIn?s-Fv zAs;LtuAuJrS{EWq#?)=z_U{vNW0jdwti8OiIzZ4;bkk8MIF)wmP3d6$m)3X`4KF6ES5n)& zG^I2-f%Ofbgqcy_c*@9f`+NeQ-^w|EpazJ<_?rJNW`AuxiSEuJQ}>$;{mB$B#ts9oX^KJ*x1F=;Lm1&{EpC?kx-Bj6)C9 z(Cm15Zfs`me9D8xR$vQ8C&7~B_$6#9)P?#)gj-nw^5v!>xrRRVqt$UY?B~9b40Bix zt9V~i_xw*>#PO!~YXcf*=8VWjb;|-KXVK`@RG&Qe?laB?8Er86C)}KnKdJgr(&9%; zyzyzStXP?{vKwLYKqK@^UwKBfW15=y^mnv+RH9be! zFUecS%XoKfBr(z1sMNYYSfEOYc|{9#*gW3c{iZEBAFfH~M*;;gl3DGAvk>5)m?N_N zfkX$71y8tQ`AjxI31_qlrf=SD!=Wmh*~JnP3x`@u*`9TLX&JUM)j33{LIdQ5v>nvq zz4`Ypb+`L*gNP81i_5CuXX6Pae2h#)>;3Vx`$1~b@X8Wdg7#-wKPITnwC1qDtETC- zwoI(SRhCi7-pB0b`bqBFKXeWq9rn|V77(aK&knmTc~xV(&`lE{gpq%(??sZ%963Eo zf_x{OcS;7=|jsd}sHdmNQUS0B^oA{h47Z|m&Lefj4zEpG=nr6u2tG(Nc$bKiiv z6(#vW^c!rC#FJ+Kj3-1tL|6XR2oy7xoH3N^+Pc|JMhH>Ag}<*HkB9yNLS8-Rs%7RI zwOO-rv4iPsL1ev!Ey~oZL73GNR*X;lRFl1I)_zd-w$XKiV~iGp*F~;J7~Sp^)1KWIxv|sh{+L`;lmM$wUejMX>;3{@bI&VtIU@_8tOWXc<miga;x5wW4P^G?aXxQuofbrD7}`+jRIoT1E(z>P zsw{^`O`t3t^kU9*oH(s~w^(foAvh^(x2M{VwB-IeRfA3;zU^{*87b%C2{Sp+zHhgCgoI4*6OH-v4!M@OUqX?g}^W4;VPH4{VA=J z?j#mLPbId{QiN zSeP04BLN?VtBuA_uxPpKEt%Ta!Py=THiN!xCy*7IoCc#uWDlXWKv!-q;NeoFbu}yI z-l^*wanI(asr=G`W}jTXs?K1e6Y%w$<5+N@cI zv|031C&SSa-6KrMKa5NoUW4iP{HZawaSkvbMd&Si>eV24jOb^2~^{?UYKx7P-uswG)_ zQzkM>Q6i1AIJP7!{I-+XDy>?cQAW%_WPC30c5O}0f1VXf;yfi@kxeMJ0Vk+$i>n|V z1&92+SbjBjEo|4ZEF!EfnN$@Fcv|MlEy-+1mr#H7;>GNdhAZU09_dj2f!%&;y~+OSyUPZx8oDqLm7#eKyQM_C1rd;ZifaiK2hm$&bGB>i(_WW02oYX zVL%axfJ{DC@YY2^>$d0Yie5gJP)hN4O460darC|~?e*3aizc60{W~;3pfjH()uoxG zmMd`hBc>K}MNeqXvj;~`YHG<1rVctAE~7hpHYy#J6M5-SCq`b?al~~~F6rBD<2Bwd zCR&m*cw%R2NyV~+dDW4t3k}n)>`mxcyvL)=H#DT_XXVs8Ejid;2-`en(pk!lu&qA! z>B;)q4rykow8@Oq>dO5T1p$00%%Smt4(-xZl8d-B#?0}lpb{YkH-mgHb&Q4`6kV2< z!P_z9*6FnoAzwDA$hihWzxs-EzFsm-gQvb?>ii3%aVE`?xawZ6GdDCQ(JDMV_apOW z9VtomWE-WGrRoRAX>CPVbcQvt~hb@aF5+XT7M))?S)B+p|$_s^w{HrRI}_(r_0T(F|N+*yA#~Om$cm<-q^_# zkW*d-C0O4k#nyiiZ5|(I6vKpg&e*viI%#&BE6nV>f2R`|>0#5(jmRbzXE$lpGF7#P z?V}oJh@oA%_^jU%w7Z>8_SDvbh$)~&?AnF`c++#m5bBxMKu_?86lr)*o}*$6qlF1m zA6r(4LuBpSAeD_3t6`HXkJO?d)!Z-+q;}gxNFh)0LaoQD#{T<_-8w7R;k9i`@o6TN zwo&6xE5aWv;W*S@ocimxwJeg?`%{dXpXyaPn{q)6MbY?Hv60Yd;?qo#%9~FW{g;Vs z7w*ugV}W)UcPOzQM&g~q3Fxu|Wt@hcfTxn+_02Jo8vBoA@#`@jRoFM92U zzBqYh)esXDFUPu*oDzbQ59C zD*>(?23Ay_vlx%Zl_f+O#QWYC$spbOO0ppJU4*BTCsw(5GwX=*ch`Y}6E7y5 zmpV%Y0=rZTqRbUnSV)>Go@1+qV|!Stp4}AI_>+$%kDv1?J?eo9aIx&hkOHziU>q%~ zIZ5ie(6_^2F^(3tHhLRIqTE9wohkcUWF1oD(741dqcPdc_Ms@n54;*7ZkOjpFoTR3 z0#_<4QyOmu94;syV3V@jXgxe0eSmmAP8T|8V>{&oU=hFb{GY^DTSDg* z{kd94jnaH)GDdwJ%BatLH(`Z%;O=Ucn2hg^k^jbgGTL|ng}-X}8XJ*|>LO5PC^a<2 zE7b-Pakv2LX}_Yvz&Wv14(%y`RPoC^ter9>8GtZjWm~g86o#&OyCfR*D|2k_Z!98# zg;aom<1Mkun4iWWwjhS6J1!_mu}fOC*pJ$qh}}eQkxqGKG9$0!gbF%}7g2azPHE+R zN{hcv7=(nt_TNsa8ta!1Z? znDZEm>@5D#_%J#;eYtJ?YkgA7^tb(+iy{eUd#25D>al##w1@IRJz)t=iR=fAv~x*V zndPfK_sk1q(x80nyY^84a!e;GOw`QUoZ-j^MtsE#_}^y7MR;ZE&!9`H&3}VyM*Rqz zd^%aKwmM`5BH!22Xg+Hp@5PL1Q|!>jlYm}Pa7p57=)Cr0h# zG#o2l^wXLNqM_oKl7%YY`H#FJfHBVhL4jH5|C0i;$fqsJU1Ju}~}_uW^aZ~?(C!Ka2m0xUPrk^tt% zR}erD2f;vI3JG%z_a2Dkn86>nLl2^L;=8UKhd>V%Ssoy-#->w1;4ME;jYWd-<0Y7xo^Bc(cg+ot$!dpeziM;#ABLJY;g>ne&?W_Ud zw;_W-_T|9RuPgzcc?#_LW;y?`-vR%0VENVM-T9vVMEnSY1pdN-asDOZ;_ANxz`%jB z3uzYw__+8RK;etR3jpK#aSY+|Dx!DT-=mktxdwQ7$7xT`r#+4UFtYNh>bw&pmPS6I zIfs4nQz?+I%e*G363AIjz{N#im&A5o`=z8W7DoKC0vzPix(pk07YP2N&N;XzGt(#j$5;7d;d0*V0c&zG=31Q3P}aBzD@^c1;8(ue%8N$~|ea)OU@ z7Jdi9ZYb#oGMGiU#(ThLTSo`tC-A`+0Q}p!zsqT$ukVLEg$Qcr$ER<1;Ja2&KlDC} zx9LtYg|7!Y040k7@bUaPI{{WnOAfNdy@&t0JB_Nathh4Ia{Q@%=PNZa0pZJ+=U2we z$0vjXf&dmS0YFk8x#!!6;ivCw4ERB=f_xJNAoeSc<|*k*e)XyP>hB8+2EVtf9_>24CtN2Qn@*CRs%Zcxd@A|r{vPbv$s}Jhgw*~yuVEB9y zIAEcR?w<|t=G&Pe_!Cw6X9)7-@P1cC8U=$BSi-LC)AtYJNj2PKC_84KT+AQeq6cuc zZx+29diEiJeb~?EJOGd&{=DA?{nCkf*iSPz!{@h6kbb!7-dLqTPNFOy>C~_`5P&G5 z0N}8C+L4vX?2B(0xUln>jF@zXCeL;Y=hXBAC2$K6+A1Ff>V0%%2-+W&H1U|7{ zV4!dC_>m8Gg8mpAgsaK3s1I=TZ}^|mVP9;LIzR+Ed@J%_k)gVxoHcT=A37k0{oXm> z&`5oE?rraXXsl<6F7Qt1bNj2@RS1uS9sNNob2a_d{rf$`NAQCndXPQ~A-XQM+A-FW zh(!v<3;1-mZ7Q(aEnJfZnmAXsSDlN4yg^X_eR_x$Tn_0&d7u*0e+wQp2Cg#?!77ZaPP-BD2JbQy*DfG#51-tJgo z&hc61W^--TnJnAP+(m7(opm&)M`cVL##T*)T4@UZnRHEk#wp*k+|a4bI*Z14_@^h? z(I_JCmS(buL)0bS840Uwi{m->VXeeb+P`uwv^dUWhbhSBvMypj83Sfo;lF;Y;IcYp z!`9}oUoVrNE`buPtARIlN$ws?4s|TcG@Q~Q&8HfS8!=lkL3*cqpv?y%r2R8f)%aDn znloLz@^FoBK~u8(kiwGZ0%}S^Z$OE>pNol(cdS<6sJYXk?e|B_%Vj@XH@>n|6^v+~ z%qz^_v@FCu6}x-qKOz-#i8)R4Ye^9T;##?-BSfmAJ=M^I`kO_B^Ok^R_< zRVp0Bu_z#H*q@(~uA%f~c(u9|x^1=FoD(znN=(f$O$zX})QxOhPdIK`Q~{(t#x zDlJV=h^0Yy%!9QUhTaYHI1S`C&^nXZ5`j8R1gI}!6`2-oL~6us?6g?(;B(HYFLIL6 zskUaZhQJxmwj%mJ6;jf~-~5>1Z69Ji1?(kf!N89?z2@kYO+=NS;^^ z8rKX+uQfMM6urrw!=R&GX;FF~2Sz;K>AqP`8{D6R*A_U%Gs5Ht8gOp*fdy5w*ggTm zL33xh)}fQ$bwFgNd91iO^Y?vJHD4FT)>wPfT(}0n!9`5mp?^(mOl@$NxT6zS|9ensDHmMLGw#_KL3F<`$9BNKjm=T(P{=Dn+Vq^ zb~i^FQg#mmtkgLsls8stO`PErF?QqbWrw*b{`;1oi^|j~_DW;$siNb9G;L&M>h~1nVs!l6 zSZVNKtk&%W6Vz%5&+=2;&$xxJ$*{7X2A{a0Rk}5Mn4eq$_(fRB-xYCwEV^Sr^k#J^ z#?1h5%V0lP?owA!)^lcD@)F8}<=Tnc8?^DLeQBs91{x_YJ(G9>*_r&&z!^n*%$gN7 zbB*2E-TP^PZtLJzhBJ9dAX!B>Z#T{=wR|T*X~ER%1Dx%)!?4Bq42U9;~`!r9!-y&os`|o4@=DxKtMJ~zwffSwoM+Nn zc|X??#TZ&l@ce8KVZUR?V)zZ-`!e8cNz)X89C4NCMjYg9q?$3)N2g@KQu`3Gb6d<8 z#9^lm3HoL;idg1{vN=xEUdPz;AlBV)r8axopMoB?rh+$E`(AR+W{sc1>Y))f@pA|n zj4Q_L>Tncd{Z=|&a@D*c=1j6o|Jbf_&hs@%HW=H=>g|eY|ux* z_M=xT>p{oH911QY$vB0I>+k{bC|lj7o+5{O%QA-Cv{#MKHEwujy3HWt1Lj@C$;Y$B1eHv&U}W--|OYYmT3bkHD!d+9!=pbvL%Ax$o!kYYxiJ6l|>Gni}FCstYpI z?%)$E>w%sq4lT@b6Q_v&2?g0{NeP`U_t=SE!fPpr;G9Ezx*8-mSwvbhCU<($c#uy` z!w+@PYNb4A3HMS*R2o5yEn*JyT|^V*y|To}CkS3g9052b@%ekg4E5IjfvTV^_~-XAjq?o6MKH1W`emm)Q=Cs zrTJ$U{8$1_u5poYHBviR9M-WCL?|$~6t!V06JeL}1+gxF^l-bh0shDr7mC^PYw3eF z*Z7?Dx5`#fRF(vqdUwc_Ix|(Y50@4C%}|Za)OlzTY4S&~yR!n2w&3Nj6VF?Hfoq8d z*sQ50L;Y?AZmIFm;BF?sK#$ao17N3kh+j&8fD=X~Tw`7vJCAtr{GDFCL%>Mrkf|g# zZP6qPpf&B1qhUd*7T03s!J^eiNlrTdE%ya<(?#96Ee95la=K$eVhb)|gS)gN!*7sY zyp6mCqnnlMBh>A({k&#vfeHTLT37uWW>H+_%ox9Bm!HD4L2-b=kzL6ueaXqtl{LN{ za8&!qj|7$8`c+KU8aJL|3Ep%rr9!j~Y@m2Ie)J4Ie}m{C{N4MFF>ElJCX?DJkedD| z(S%?E|NB>)%WN*g(Qdv`K$*H?)52`X;ZM0cE<_ZE z8}$P%)ekXKofI3|YE7<`t;%@@z_RFVve`gEo`4Umg&S>8&x1FKmNGiVW+z}MtxUg3 z84C7oQLTiCl6jhq#}U}QC>|;jvd6paVn22k_cvz^(7xGUEEj|Y&nKiamTd7~hqP^? zV-JrV)fA>|t}*CB&84(s0o<^2gSX_1|I{Ew=&f30#I9aH&YoNzYUtCrGP+Z!#a$&l z{+X{n>&IOH?cG7^@jBRNHefUd>g7C`<<{&S0}sB$Y_&^I*47?trmx(yg6^U5?$2sh zpHIO=>)19+aca41m>9IJ5+Vi?S|sJSG)kB5u#c6*!a^3m6Zmlwaf2B7+UfdRD5|)x zEn=km-6x3{Qg+kiExGP@Z$}aE;#6`ZeXV}!yqcz2XFJV0oP1&$qPz|0f{WDJ{208u zPPwoJ-Si6oDH4C=t0rg#ULCk|yJ#gaeAQsIOg17M>G|Yv!jBOf$j6x-uTc$>MKUKGFX+JqV;E0_uz=pf{LFx#&+jerb({d$1urCt%BJH8qv0p-W^W^ z51#+im#deyz6L(uf_e09PYo5mZk!W?CY(>722wdz} z_!aJ6ey#g!q2Vlh;RBH2m<2`!-B za`HBDYDJ_=2vuBLWiSH2kSDBhoV-&-7S@8~tIXB+=Vl!V(BP`8hT+@js}`x3*Rxf^ zyuKZk-)A~1$+_&(>NkUauqgy2hd)7{*xVGygAA^x(_}MplJB{LCe(OBp471oJWi1bh3YJ2TS#8DPWS1o8{cN|P5<2y}$?}owi5^oL>Yk*#x62N61EZZ5 zR7sjjEuFrn;tmsfHS-yGQ2&Rra|p8p*w$>?c2(MywsF$7ZQHhOv(mP0+qP}%RZm{u z!5wrDV;-^Ni&%TFAIg_VR%%*BM&#Z9HHP7MyWG*y}6a^C0mDKn}H>#=zNY|ygV%+^>c-N*}BmPqa|Vv$~;>tiTuHPmr!A# zQU z!GyV7MXPEu;1JTnduRnd@z=rYnV6|0?x1#*Gn^89&WCH$GQvW9=OA`1*{v) zJF-gdN-w>q^EjI-cS|Km3#xL%S?eyQYpqS{}!wgnUvj@ju3b9n;fm4@1k{A z3TyF0BI6EU?_UoNFim5Rci2ICG%>Z-V?=+(Mp&qk33xxFS}5pQ4uFn!nE9^x9@;D? zzdR^Y*G>$8EOYlJqF)0cokJV%E4gRBsv2N1F$ddJxaiWa8>kZeCI8CW&2W?shH_{@ z5s4T98r-;vF1WK}K(QZr0^ zEXyUIOS%xiI%{5soib{;CF9BZBLuF{ofP41|XFC@m2Ho3I!isu{JNoVE4n!l9D1cODb(S&$8NY5rsR$yaOA-mk{)dhh#L zf1RGmiCAplG)NDt{4(S*a4)?H9%)uqqKh=f1s4EA^mW;|^{{s|Ih4HKg;r#}W@J|gej{dVpnWQp<1%HAhPUKN z#;2$8^PA3u6z>gQoX|Q{q97HOn~R)3Ll?9@QZSS87us2vE_a*4zSJmKpEhAoEcOwK zu<|df(TOpv{cA?^8`&gH@P|JGvzNdlF>V@Knl@Ctxolm6ba@NMY#7(2>J3;7b8mYJ zV=}jBb6?EzEm|fGf;CTIIlw2w~4 z@wh5VHn;4%ym{it!_bBQb7j&Cp41}>3Y`SDqZK(c0dli#ys&e? z{PM=m8X-*3X^=JGVkO0aTIQHu-3z998jvM`iFr-vpW_GMMarlcsx6e$$;iEFvt*n( z1ogRQMr^#FZVr?1dk!>I(xsQ1O1iyBk$?pXDiUo3jjv=;xOEcwLUO>W#;G3s6P(7d z3=yx%2X~NM<(yk|m~D&Ard+n-Rs=q9fD)sQB~t;$k383NJR4If(e%nSZ;cI)?N;r| z{m4tO+?O~;*Oen|kE>9}cXospMK-H{eI78D|3qo&^!k@*neL6TPHw?Q=VjTPo>t=9 z?A)Vz{BB+IP)qXa){;c6qM+m=N`cbmxIeD>Y7B|Vn>q8?W@$MvI+bo;KE{}8{2HB3 zqaz|fATK&TDgb@!H4pK|SlZWI&u{exi9#%GQ^w<23qO{1(KDtd?l`e3D`5WZu!nwk z#e{2SDl^N$Bo7v2FLXPi%#S%(5r4B*kl_nvE##pTIEV=iF=q%>MLe_Zc?U@eFAbH; zmw-!Fo-YZyr?);MMDIbHm}#R;r}nZ{NnkCAzgw#|dp00gCaQ;6BUf+!GKsOw?htJ6pT`qNgt703l8}+*hOaphxA{yCH2Tz!%49gxb+12q={m~~aam6s*z;#DP ztoDqTkMwwblEVCM^|a9BfLQRron`NA$(^!!2Tq-3MOetpOlt9syT`sp$MlyvHrf48g^RR1r)<~jHaUOVe*f7DpW1xWu zIRN|Y#rOA3^=E5fPM>7`;^P{^-%F9vaK;MD}2Uu6Ns$UEekqax*C)-L@g+Wu0#ww`d5#Eq5IA`!*{PW?Mmkt_gzL| z1NKElUxYEQtRe^gh)Ndr_&xGav%ZF(>UPn#Ye8GzT9GY;SuKqc_;28GUbl@(LWhOdGQR+;YOJSm^*y{VAd9MtH7L+j^Chk0MJ*$T zQ`&W(Xrh%9OF$VQTgjrQP?uzKCnB>?el(_SDVcKIT!NJkLk9feIR4t0Rx$>OpQs)w z2^KI;FJjUz22DhcAh8m3pz5O>$K`HIiR$8)74RGY=-v@>E=Ji{z=sPGIjR0J6AOSX z&;~lZg)DGHD#$tty}VV7t!cq{vaHsf7MlBT{y6)%J%7rLYtw#kjhb@zF;-!pBh|LA z*^n$3IrN@`Dmv|p+`HK+5g>1f(Gh|Q`DMEQ06$CN5Z@Cm-MzzQv5KFpC*#IkHFJs{-tKruYgIZBW7RTy_QdvP@j9`I~{$~z#BLvOO6}Cr5Qm5z1_|M2E z3n*=s5`klVXvCRQqE#Z{d4fL6NIT`SMOjwF{FAncU>s?69@a!}Mg&eYx{;AbD#9K5 zm*Nv46Qr(+g!wTI=_kZfO!LfOQCj=6+j5!4E+g`p%ch0iP7#`K-6popL$5@+IW|hiQ$isHC-JtHjvpqn&xle?s)%y1i^EByfLYbV%TCiq+x&SOmq2`vGI5`z_w}a-e;G+ri?#dV;A(GOKy+A??&WEdMhh;{oi5s^N5B zO`4lAw7WSXahU@_ST0p_t?n>5vRq(D3%7n}BkJy1%JZS6(amJTal?P5L(f?XGL~_~ zkjBSo)~M4a>^ar7g4OsiRpmK3;8?|);Ob<_m6km==iH>S{F)G-{*s1U?Fb+(?q2k^nD{U8+u*qx^Q%BtrQ176-4Q z@m3TEaFUQ`1Pu`dv9>XY#fC@N4|WF>T0TFiKH?eYDjyXC1W(r9lpZ~%O+Tsn zMu0Q>wfQN-AKH3Tg&DfB$ZtAh|L#qFm>Cm-(BM+U6kxob(A8 z*!r>dQF=Q4Bl<17-8%bekgSivO>)@76SxllvJ)^;iYSN0&AdTs{=-1IbFs39$U{qx z8|7#v>~WsH`zg2+yc#5Gr)O?iSFCw!n3m^!ea)E3!VvzO9# z+%R18KAm0y=Ci92(=zG`0c1lf0!5=DG6VyJY|D6hRNj`fADm(+6&!)8kpb2!zc#wC zQKhZn72=%G2{~0YgBH#(lXIY6TMIOSr;uBx5dpTs5%N$6o z?z=jsNHEOMpv+X0EZ2bBO(cIMu__B_b=%A@5QWdXLG%@h67e$t zkF027ZAB-sryfr+AEeA1vyLa+JSF5i%y@2aPw(8|A+!j4TV>NHZKSmDK5a|F*%yFa zm#y_T{s1x1GNss8HC_jH>JR9^6!FJ%<3h&MizgobkW0b0*gRrRD!8>6Ph!N&0`Xb5?fN{|^y0 zq+H_FGL4u#U%8)?j>k<`n84{gAsRnH9GHMO0d$u*YT=6xm@p@ia*|FV#lOL9VL46- z#X{)U5r^rw9><%>uEg|1?`NG39?vRQGHx7^Vxn@nBv2{T;K2y7um~y;0&hh{cRnpG z2_-G9grv|BIDhBBFP6mnw1HVHFqpE}9v}i{xPYOxMM5;#PXbL_76?p*} zc`ckcG)&c3Or&5Hutmacs6T({U{3Sn=;0_3p^o-KMc6qE?Tx>mpl-QffKXsy9Qu0( zfR$abe(yo?gS;bEGEL&D&LQtZq~+rv(^u{Q6mF@w4D0YB3=DXAdGnE6qyE5L6%rA^ zy%N+;`$5Bj3VIIw?XB?#1`Xr7oH5ETVO103+3YkwhO|B zqhDM^9eOti28Kd;hlR2q_-l8EWDC^~zwZb7d5r^NR{k3lY17YlWPm*%8BZShTwYzz!~iKaae~7pbn7fES&EZ2keVz2ZjRk!veNAAqW>G zhYnnx&`4C!(dLrK1Jn=MF-zD{5M&dp7mSt=E&?Gt~+m0KzSY2ZX~0 zMhyiVy5}PXN{?iVq@CaD5H^KUx`PJgZ+>cp{ zF=8(Zg7owB_OhUj)AjdHVdjqSZqExptUtOeh@uGiG@O(d~2 zWSGF$CkCp>Vxjd z4r554mwrs)O^IBL1Tw8Na@9yv`6Mq4unpcx=me;%3AcP|5gvs>=SDqy)TGeN8} z!J1~ypy>H=p^Q_vJ8>IaDW;-(6bx}8#E>npRkxNcG`l_2Oht`?k1%lfojl=HE7g^0 zH7Q|kD{VHFYQf-)L9s&9q|@;H+KJoXBf7`5i@?oMxId~lJY0d%=-Z8EIn?)s%w=RO zn9LX0Jbll&034g68zD@BQ`R)hkn>8TNp6HlLk)M>b^fpXYj|~>lvzD}Sw=N}x8r~h zP<%x>jk&i^VR7rQqzlTqD>wAZ7E*;gg;v~D!io}#RlKq2D*zT1y zl7e@v2Zp4aW3gCww(&i49VeLO6C9r@SJW8 z7bJ@=B(XpT&pa|0NSqgxa*g~gKrh5Gs-fQ4tGgr?RM=m?McUNgvkD?HqFwtZ3KvI(i9TdYG#DQ zl}TVMpW6PcR#c4B*DEJ<<0|>YT89N^5^{1m^IOyd)F139}JUm3sL!2bP*^RLOXm!7&<=G zsE7(<-1g!K#`x}wQ+`KE;UV_TUB0dGaj$|7*UdZJg)PN&0od7VBTvkEc&hC`0xG(~ zO_x8^{kW#>FS{nFX`2+@aq=d~{&@`=s1f)(Ws-gyAu71t7l~tOglE~p4GB|uRMZagP%mU_zn-l~diJjdWvr)^n9Il&2?coh>x zp^7;sstUy2i8YIwpWH6vR=?w(%zpJN0{op5W6TAu#caduNdkNWlAEC+JI`hE!9Csu zfGZmabS;^oxdd0&}u=@Hd0dj_t5;a!E^#197&{3n+rG$&6zaMs=U?>h>Dk!-fZY!YEI_d-EM5Sv_b!opFFqN&;RIeIntEZ4_ zJTO!a(m-`zo8E1_xG}r3`Zd~7u8^!Ls6=aUGSkZgiF~}CWDUQc3{8P^hjz}O=UA~)}nK|<94Pq z>?~EaJ4a@fkuqs9T4M*cTtJ%p=RiUEStd<*Qs&L~(oj?L%(#z^D#Lmz zr{m+C$ksXMZ{?7zg(mmuX&&>}V}9C_F1Byap+f$fH__`s(fhvY8yY(|;%KSE6j22n zU9y^4NE@_k+=CG&@6yaP&hupPhdP-h#Yk6pJ!>M5R^pzARI;QCHs!+eoUdx%T93op zD|Kl&YnhPSBS$S3n8Ha%0@1}@mnbj4vQu1#xf??q>7`d>5U<~tet`=evoXcl4$r>3(66i6NfEILvZ=?$I-e&41s{9|i7Fmj*9G2M;(=han3_zc zRa;UK{7^Pr4y~5=y~#}xHtU3|!b;mIt$}o(tE=>eaZ_yBDk0|;^ADlm%(xc(siRZ& z97T~S=7$tQ)dEB%m?ZFR<$9%T-jaBZdZtBI%OZS6cwK@~UR|j@n%jMp{ge1Y*alcG zlN~%aw~ADW=sHt&X?#w#%RD3e87m>5=({-~v(0N2sccL6qt27e&npdL?vH?1n)++B zLIs9BOwf<)T+b)VrZ5pg1q=(4oi~G=gTDLGv@*M}+^TO))Uy-aD2q-yN3`R#tT!M3 z!+wvLJ(WwR*i6=cB1C0L2X9TRh_r*XK=$d z@lc+a>wKLgz&kXz*H!P1s7v9=dG269ljyaif$(_TcK=mWWJ1yMmhK`6Z}YPkHpjet zz>W;GY`-7hV+0jSKbjO|5MViM^%}#9bB;>1hEq!SWpcPwIUTgs#TXfzYtt2c%g z4rjKcNJ;SAr#WC(r_$^I-p@s&QOjIRv|)1;UWecr?$%eoRnmWw>q7NJ5CKzvK*Hbt zIEg>1(k6_asxi8*!^Ca4-Vn0-Rx7GH@~B&nt{7$G8!J}7rbVH4$M1ElRCj{rwxtQ= z%>%7{!WE5P3p0Nw|Ip)qrE0l3jh*DIWoeMp>oOY;*I1Nm`eJfKWQn$<4wU-P zy82r^nOXGrsh|9V}3WD7A0n6J?4T2&#IUo7fpG!vrFcz z3gj47X=xUGKO-y2O!L4#ulu3b)*;CHSYO^{cT&zmcN`|IUa zmf-DzGneQ4^xd1LyqIhGgW;0#vWfCUd`Qr|;^ane;zn#*f9o2SLx;2_-q3VC)nj+n z+L%4Nc;fx|s%Tx+uzV^d3~5De!|I781f9w&yl-U^9IX*->vLoJoJ}V+aoM)=-fAKF zR{=j%ALbEh04XY$ZL;g82H>Ui7Dk|WlR^$p7vO4jYL~`^y;OIY(rz__$P{?vXpBj2 zo(MrcWXygU9V*y_HfbLFs3kExJiJ++eA7)9dt$X$`cPcqPxJ;KO!`nn!OGb#)QA#r zu3>T@^32Yy$i~#qZc4PCg8yggCZ}eUp4ZXFipi3iF--0(W@m>ZDk5vP3)|1aL-2em zb4-1tOGlVzh3cyxZot!(WcL$;T_Y)O+aJuVQ3l0)u?eR)QFdnX@SOx@8waAMPRWm^#`9u z>FFBqIxRXIB;+hdry1WlgZAcEovbgOBU5_$v%x$BbJ&yJB*@|nj~>eNK^uHHj?#as z9HX+&9w*!PQAn3Av)9%omv9q~C_IT=5sdUqHkyafK{ViZS=-(Fu}yFWFsI#$aDm4{ zq#PBtHe;Z5yC{3!Xt!0)+yiZ5cwvZn+cXV9b{5z`Iog(#wMO4S8FwG1c{_6q1fOQW z;TXZ-?Lv!Mo|f=Z{iiByG*9MVmpq@r)3{ZG)97+jIAF7N085`De+eVG&)TkPvIU!> zi>JTvY@KTGT@JTqFaCOJzt<1@&wt#}r*b|FRwcHHK;CBN;;9#qn450w;QOD$jEC*R z>x%IVgmJf!zEuYPNEc-bUAW}w_~tiIAX2#+ot;Fr)I}CIzL6MqwNo}X+Z>Wn2bm~; zWtNyosn*o%*WCVevR9x=+Mt_g@2Rxht3a=FJTk&GrDVmHCl*4_8ne=OBaw3LtOL`x zU7$=`E@84|&bf6>S&4$ClVw@wH9Sp72-sRXgw`Auws-%#T9+JI_}8Uv{oxu9zphP0 z4j2OZxFd@)e?NU+gskviMS$?0jvd#*7&9&K=;+jY-5)%jxaT}=L$(dAETToa*Za^? zXy;seGL@Qs=J%#MIcB(9*?2QVi&%^kl@^`81*(Bz=iPqujDstTFVdSF!nYv>1aEaP zCp1c{;qls_$1TbuTJ0(u&voK60DztQoY3zhCX23PS}2IEc%z<(&)Wgs9e|&|sAFKM z>}(`g^R)5wD#u2pI*eMvvykid$!(85UWbXhg>;I(_5DXRRbtew2z5g)8=adwQChAn zV`?3>EZhzqNn}kB8|Do%n`X&6o8vxnR5fR)-5(6U#}tVA9FUhIlngpEj8jeDMy+zy zYP6FdRv|iMvg=&)aOv~JTvnTMpzJimgte?a0e>I@IglhMV?*xcAEVIFgtfh9cv^3E zhxu)8bu3t^ehL^L4Hx%{a~xG^(gwg~R5!NiP|r_L^c6;Dpi~9iIs0CUKY?%?^P{y@ zwRggxp`{MNvuftO!HW&x$p3b?qPzH%X@ z$ci#exAAE5*4P;9O%bz?T~LCt&E}cal{6Q%6L-AcVsT04+!X=Hof8ON+d+~VU7|_0 z6dH*_4p<%SXHuAma))ods#WcHzr~OTxl#+kQq1o+-EF3bfMXlGW%$dLIn$rdL?p%I zmleB}5eCx>$7IIlkh(2&tiD4Cr6*KW&Q)gO2eh39r{@r1+8iRvT!d=3xVHMZD%ey8 zmd6YylFry)e@otilQAAsSK{Hz+<8_(V#zFv%W42TkEU2FHj!m??uuxhPsD}iu&W5J zR#^jZNZYxT$~^enWS+5;gd9VDDJAHJUe}Iu1lC^O^_f^AQk4dcwkJc1EHWFWD_It4 zq<3lriWh5QnM&!1c1LiPVKKi2xgayUy$qUrqFgDKM$!qh4zCI>{C#qKub2Xk>LfC@ z4n|%2PB5_wk{)%jO{;7p>@%re`p&z$$m>r{#Ls1xHD}bE#z$)%b?Jcg=xNO^56*I$NsAyh)yv zDbLsH)z6IJL)jQ}A?sM4h!-<6ChWJo|08lYWlhk>o(g>O8J2(C9tc_?Ay_R>{C>Lg z-1!$f0?AJAK&~UsXfkTs`>Df5vS3^P!tki-R5PF;?O3e*J`u3_&;$dqf?(aAw!qx7 zt!90?HQFNaltm%~8z=qDaOc&NtftuaLCHnF=RsjoZ1Di~2zrz6KIXHvQa2J+^%DR$CRo=}4zqB48%#H9}PXEP!#ipcvVfg8HL( zZ~iv;oGxv~s5l$1pz#{{LF5Q9KhUW$JF+6#UV-(VR%M5zam%80*=A;vquR9k$Wcu_ z(<8uZ+LUd&J~V_1zcqE4cOxE<+xS~?B-&Z?)#?(Qzw1E} zbX+iKhgJtZyvgw zOoaV7{jyTLZ0HB-M~K$VQ^)n@aN7-eB9^iibQ1RG5>7B0K7fNRp^OoWd^0+~%jXZ} z)U{lZ^0;)7?eJv^xzTCMbftRR6^0w$kzA?3J444!M{OHI@o>RNFa&Ywo&)wTBCz05 zk|uF^sK#acf;E%L1N_C)(@?y_ltyV1Z3@M!42?epeKuR9z*^xRRV@eMC2$yOFX7Iodu9ko4b1lCl=b8LO^`F1W@l$N=k8&lJ_P^QBGabt3=- zc2%2X{hGGeM%LmUCoA%JekcMaK82X;z#doFfggW?EX5m&&{6+h%rivkor_q#2g^ph zHEFX4pjldzho?g*%y=t5baNVALz8&9s6)C7Qo+z=ZZQ=peI&mPf1_~c+XK-{Z-K&Lx)2i|5Z%m2o>Lh4VWWJxvQW$tR68w}Q$Q5yt+3MPlF!8Z3kY+x! z%YOrD%>NCfu`>M!NMmRGzpMWQY5({d+yAqQxD{L}$r6(_$}dSQkXbObcb0T(i-rS^ zV-iWwwZtiqU~68Cn1G0oBAS4P0-k7;&4c^Id*qf3&kfQJrafu1q9;G;m?OhEh3`r$qx3(7Bf_e=;GWE$}jvq@lUU5 z1ud#qpJEr3_ZtpI&LtG6)g5>fglIE>h>ySz5(@2m1L>F&B(CYPwgsZp9wbR$t`-}k z0B&+^V`+OCA%^|rMidA(4850zn)>yzg^O<-`qBciJ_uxyde23Vd@!6q5{eHJq8@Uf z>jypHC>ft z3%K3o*~XW`NsrY|R#KH72$=7ZU#}Fqe+btC-UXaM2J-Yz83=P$-)v8m@(-gM%&glmq%SLrCU5&$PSY=%2MlgDPW33rvo9BfI&ZlLj)u^NKB%WC zw1{VL9!CF`%URN|GYO*?MSd^$eUq>HdD@OmhRt)d=69P$z=7k^6ZjyMu?fi~r0%}3NaV2p>^k}hq@A2~ikoTbcVQkkwrtLp2Z$E}_ zHGh6o^M7nb?yr$XZFweiA%5_?iV}GSKVrcH+OF*eF-rT8I)J`(6+v%xD=HwGn_XSs zb*oS|QR?6o{k?qmo^9@*b@VKyJ=sUE>6Sl(FTU2;fNGtbn;wS+CVvy&fqJzeYnsD9 zze}3{VUnXkh_(VDvAly?=~b)sKu{6D?IwJHf2Dwd18Z6QhzWoI(SG@o=o9!&yyAz4 z;`bV#U0%XGfONDHhrF;&!wa#itG9n+_67oJ(eUd*twMb3(%;~}(&c;x67Openm~Lb z28|*a-M|F+Wnbo9+x+x~#n=%Ve7D1V_aV*pM7O>HY0(dAKLZHgkerDeTtnKv&p&e? zf0k6^Ix47$?r*^Pn7{tz#zsRxc>43J!8XvxnWYH|s+~AzqXmZSHC>+y75M-0 zVPDv!(&bWqv5(TJs%G@^%fEKPtyU@TyViqbJEq;M|BqQW=GQI4}WGD6Oeaf z+SROQVTsjt)v71*2=U!QLPMzqi>icrj25`IVb{mIoxQR#Ff z1Q|PUXv5STNWeivK$;ZIStFF?1^K-s3sV^MSviE6V)mh?3ZFCdgD6%XPE=`7u`fJC zd+p=qIbr+Hovu&+ifJOM-%7<~pU0#+>OD#^Xw$=k91B-Fx==J}@Co@T%A>nItkd0z zld@|Z;}S!(P=8TC@tqwMZY*V~4xI{YR5uE&Il3e&3E$a= zJwN$^0TVGKUBaiOE?YRAvw<;-Zm!!HaQ9r%IHz=5w|gnk{V3bT=h%Pmck;$c=QF5# znZ@Qi!IoqZ#TX(~@+<{zlZF|s;QXs6wq(+a%YJreD69FPXw}Ox+(XKYrILVA3{wT9 z%tCzEHudc@hh1alu&c=8#GNX{a;H>!;?32{CXq_MdrHr=p=RoQC(Bo$}Iei1fNk1Ab8kfLYyPV6n@KgO|4yjAY!` zq~VG*8=_;DNc%;@yqLtL(si&#e`4;bw4eg4DD^P3@3YS$EW+G4vbk_3bG!oV>E-Qi z_*X`-D4QnLL&GC&DTO}T>pPIbnHW`o*jM(RTMivxeIw?BrO7L2N!)y@72rv7SU1^3 z@wd^aEEb$NYJR{30%P2UNhYJB*;j1g)E7MdFIZib&>Zek8n}h3ZKevRu+_eIJsqrK z*&UP`!eP598fKozw@td?{}wgW*^K&kcck zehovi2s2BIj+K%6r}^qfbba~tzYVpcIbWYEWr5H8IGZA#Nyk66l+ZLlG?1Rc?3=+R z#+VSfaU{lf-#-pfPh8|wWgeonmUh$@C#_~t#awuLFbdMX5C8NYFNVv6=Jl7UvZQR$ z?4W{CoPQ(M{ai&^BpPJwi+X4_3@yNvDr53)T$otW zA5WY~c87_1ZtX0&OgxM2TC%c;yEqD9+O|StO*{yf%b|ry2t0pP89qKgckILJxC?#PS0TIVXGV@?AtGZEs?oCKs?l z{WvwQkt&0|mig4<{^3J76Fm~5emv=E+%@fW`}Alju87nmC&81XH5<&4WcA@Mu}G6! z5VD#$kgJ@~;Nf?8Z#=p%lR@9MnoPbCGn!k!Y6r%kB`1YpK8H|kvmG_%o9%;e0mYDM z=r(}X;_PA(K?f!-x$1SWJdB31JdxbmZ8Mx9UD5GGJ9>Zj>t5q&u3zZjx42y@g0{a| z|4O5#D-%h!88yZC0yVHX!)K8I;;BN)HH3(?ioloKzY(27W$-)-%yrQiKHr_vu@}LF zw}rFIx}>#dcEoE+z7)gh*}S6Y;xjs??&R1dDuKA}HHLQYnoXW*P=cnZsxr*PAS)Z? z3p$$^_>gBc6{E}?-{ds+h-fc23vfEWLZkIPXp${UA@|4h)I9T>7*-habD&8%W<>L* ztQvYxREp|#E%0hiPhrX5(F;A#ojZ?dB^WM)&%?3g<|u_w%uU=yL`?L}?%82B+u%eJ;PDYgoETeN{^%h?&2iz4pM(4lCVp zL>m3Ha1#s4)$Yr*jo&^iNn=?aK(k3E!C%_naZR`Ky#lb_3h&ki< z@ULP5-nd;mefH}?sug*aqAY3d+P34clH*7h|1f`UB^R{wH_UAazP*|17JXqaxZ+}` zzR#&PA*y4T4o|rq|GM)VRcLXAl+ni(vo~z*KmwG=tv-eZ!tgRyRk`eE)Pmfk2Ki7x zN8&Mq?W}^LL_U=56pgb4?gLn;|B_U6?c^Smw-pkth0cT)Y*Gd^5MwYKXSnbz#=4xM zfqm9VBI4oaot&hzI%10PhTX)^5_Zf)$OO)0B9e1 zd?yoHV{9n;r4WCN&j_z%D`Hs$j#n^fKK$N!@FA~XSpIJ2IZDE{ z)lExZq%ZDj7_o>b9fY#fzp0c>EjDk{vKMyvNZnQUf{C-OPFPD-#ZhW8WmKJ^V`;_9 zStzbYAD*>hiA#7_jZRU9$>-?Fz8K{HXhMO;S$vz?DJu7L2YDj`^Eb|{#ms&H_vE11 zUwA^=Ze3#beNDZ~1aADYG@>;wXl5KR5;qm!Io@eD1t2}Uuhtb|lQy7?J|W=E<}k_-;I2VP?@@?(ua`BJ?tHbfM8W(fw6<4*0UzOMY*0_k~F(!B`e%P4scRSa2a%wR$ z^0Ac}m<2-{FN>{Fmu;qib%sTVm!PX^Q@)4Attb~U#NmZhK{t@&^XHYNMAuQQnrjv6 z5npYoq@P_keuT~>Q?@b7WTPgdyF3V{atGaU#+Kr$=i$-A2a0oW#)oXw8=}4*a|Wx9_oI zOf;?!{KJ(@XAen_lIUz8Pr26IBNJ>*w<=eJ=q}z9yk^?>YNZrm5s!}Q;l%M>YA@2l zgx&+7vKM!@LKk)a**L3Cuk?P)7C);C+h|CgsN(i+Bp0Ich-dTR5IcJ`+j)B$c(x{c zGI-Wv4*aUIDft|{KB!0TF@1k!`DFf>>uxuO%}tUY`LMMqs@0dT+u)Q0=c)2sr#e27 z8ybkEV?rZJb7Tn2{-o(@<}l1bp^I}&mF&(6FetSKQ%gfwnbx+91&@zd?Z(iu%fp;{teUC(vpYZtWsKUU# zyrJondLCqbgIgQMiYV?R0o3tsQhw5sVah9JWMGhqtInG8yzl)&tP3j=P@^qJP_MKb zo8`D75BmkInr95{TMYd0f>;=~mWz2UI^~V^Xpkw-YwvxJ|_E#=a1#)q6 zCrNm`j=i%huD@3q(Y3U(T0IoUI{rY(g6dQhBqf-WT%a~tZuVki_g{Gy zJc9pI1dPHmH&zDyDt2IPa4YX4Io6CLLAmBUqglu#>@lq{1ReUNy0w^i80rl6;t894 zSw@hR@i)a39C&+D2GVAx{?R2cINN-xBYvWh6O)cLU2@40Eu*`NXA*6MAMel4>vCUX zIFQG%<)3P;UE(?dPb`vRAKdT16EN>-=fO1-s8qxl_U+(=%{6sfg7~--UG6pd7Yr+6 z6Mlai%!Z=7N1*F-F05CIhxk{u(ZUBmmTSC@62e0z-wk;JG5=Z5ZaIF1J*~K0j_$Rk z^2Wf$#K0AMeKZZ0ju2!n2V`n=BK%ScbQ)WTZ@}-Qqhrc4C(vlBQD|&#$d|8L9uIHJ zn!#hv?aE)2wm(bBMH688;UEsq-2~ktUwjYp(LF6hxtTa5ezz(nN2FOja~c@bv2)5Q zGzYYt2Bk+IP7l$Gy#PO=eMcFPP2VNK3g!olgh#R18f_kTRz1^OTX)^AXXY3eEC<-n zwIqPlL^Uf$a;CzL9yXsZx!5!iYY*x09Q^)}wt32g_Hvk05e&W$RzV(s7YxKgeoKvO z(+cOY6xTtb%Av3&b?2PkhC6~oA%=f0Bjf3wg&cK7IDqOyR$AYGr)a?G&$6j*-$mC~Gyo;lVk(#5l<2P-Jgo>`Ir4=ylp`b6zwlY zBG~cAFa@1zqGCI{o@Zi>6TuT8;K}aN9m7CRWQi(DMfwk2r3AmC47E{mlPRz#aVJd| z&dTgt`VgsKk#@!%HXFt#vt2E7e^GxnG0fQs&SHY*rb6!3R6MY+qiN*yZ6<@e>q6{b zv1EHxUOi<&mQ(-wS4pL7ZY3s3J4@xbSiWct_{b!JZuk?iVp88`?X(~D)0m|hO`OsR z^+8IGGZIRLc&lve(fl6fu-OtolO%Z-rdIOC3=%^a0Qg&^4{Tl0&<^klfsvk(OCq(_ zV47opogmYAt^*L|#M+iI`O-A2Ate@UX7IQHJsC6j`AYC2+lVx?Qu-)C1NQNBTj*Xw z%2sdxBGYu`BD?KPi#Dv$y407&C2t;1e{*zq#X*}ToysFz?MkGSpw1ptf=1l@CCqK0 zt1y!e1s*#MDXAbEdJdG`bWueR?9v-AwscHxEXZjA`JK!0W%v-V`$6pg`8pE(enE^L zeYx~XYFlo(y{!N}%zWM!Y}Aue<#yB6!1758uFVFJ3Hed!TXNAxyu!u%`6DP`B!ZKu zt1aLt3n#+2ZW=s3<(}6W)ina%WM+YUEw!Eeh@sHIDoUjumDVRC=WVs z7yU+Z|A!oBx;6hb!%)gP@tPbpo&L!b;c){CkS^%5?d-6EG=0#C{#4S(gWy|@@ruGc zLBxnCQ<~Ze7rRQpJiT9_5?&uIRE71bv8h@YDEa4CYK3MtOqzakXQ822&Aw?~(f&`- z?Z9wZhn0|x1ar*KFU8p{E<*k3jK(QUH;N{sw;cM zHn`^6R{KMIo8Li4k|pk4l?#UfLh0);Ryq=Bnndj6at6I_c4xPhv>!k%Izc<6(H7Da zDh}`_JGNrFC?9xoOcPh|7j_y7_HlbDJ}57wh8-^oMw4KDRLsOMn94~h{)rfPLsD61 zJpTrZOmdUk9@MX=T>_LBQpxck?ssDAxG1gfu%IG03O`gkfp?{~dMr6kf<>E^wpuXR zl|+)BKjxBItaI^6rwxt}5z>)lD~4B(h)1xIk=W{|2VTK(!&QBYXPF@KsmK7L9vW9H z$FA2Z7st+O`DrgwI^e#BOb*|BBZ3|EqSnJ8sD*oC|HIfhMTru$S+;E3wr$(CZQC|) z*|u$0-Lh@lw)*zN%=E1FKlEe1M&`e{>sa5_S=ohozGTUZOadBPsH%Ask&B&8wUYI1c7CCNt!$3v=px)-F9=pAt`@2VoKwxdKo&l%wy?NVs={wwJZnPF zV89=z{qsrJf?11FC(e4Z*C`e^szPfDJqrwPLz9<9ySme@FB;`r7(FJV!&nBKELut;}nJ^1`_=ZYUpCS?t9xTU<| zMr7IZD0f;*OdoDniT^!Kp_W&1#QUgYcVl=vrq|qL-BE<~f-T81&d0F0sorgw z@#kmXqJ3uhg@bGw1*xPSa>_39SwVrwEsK4Y9Q;$m}x zj;ZfTL)4P>Pagj2xd6liE*KqPq{$KA8J>xR2esfOU`%!h72oV~B$Uyhn;m%K zo?XDRXX)MWQf@zlW+X>YieT`^ztM%#v1c?7GVS5;_M#KM;<^173(V#|sO9#qbeRL= z#k=?U8AvN$XMhqlOvde6y4l%yWHOwq$ZKe%Vypx+R$V=Rjva5RVR&3Mt(17l!-STfo=WVc)nCKi7R2-tI*^eH+IwpT57^8PU2q|=Qzgj#F=R&>H@?B>I z)8gPK1fG@_iVzor-tRG+)a0)2)aPY9^R7K+S4krn1emQWXN~WRVs~$j_zFu@xYi>1 zZ;u=HB2&o3R%uMH2}YRzK=(&l9z3R*MPn&8fIG$5eQkp|Z@u%qNA{lYTa@1D zo01j&#c5kOB=oShufp~>mv*hoxNcs@&=zGau3%REbE!)mHUCAxv$Sk#G_4vlo$+3| zfFVitvjGFV8DuM#auBV(G5Zu*l$zy;krY0}jy%g}XE`Ms=GS6~(_b|g>~MV6R+!4# zb;ikzSiRJRd``n$f~k8*E z@ej zwOboa$O};{!=1hctKye+@_tr*Zo$<6ReLvu8rei=DAmc`9)HN3ez`P>fr~yZ9swi` zu=wsc93YwLiuWu!P_y{Zd)ro=b@7LKVUOGILuJHxX_f&3`e;d#o7-k|ig&b=50P7t z4(cRq|FlmLw@$qU(s7iF2r`34_L1Z2nmCWWIb`^%1L#neuFLBU-JrJXGMx{Eky)wb z^-Cnf;lnNArug98k{0tVF48~7H#HPyL*99Fi~<6!DGI{HL;$CbzeT-bChHOL7Jqyc z@=Vkw8GK(5y%4}TWMzo4{z|qeMw0LfnF-rM%i(-8!E$)C8OLnf)_XTSGxey7{9xx0 zeZ(MZl^8nB_9=)fAEUZ1g$Xkt!YR9bW6$0{f?Rk^wJ|J>D4Pz^eTT|22 z;qG0ATosjL(N(5TVw1I%nmcB4pdNqUG&trqywDFZ@aYYut44~l&61Y0E0Hv0?BkNM zh9$Z%8NDn?n*3eT-OUSxrdja(kqA*>XpK|m0qIzH{ozWd>k_^2 zV9V4C>HZ!FfgD}*@k4o%lNg^#7cvP>0Q~Yxk8~itbn)jxdu|vpdj4#`$aT_hn*!9k zG-otOfBlMHKHCW>bmydaA<>RQKPi<^Ro{?~Pv)X_1zw?CiGhb(_Awq4b+p3m+i`i~ zBX&wSvyn(S!w)nE2u_1#uQBi1rZl)`4DHXrk7wX$dk5k)4S9=zRH{Ari;0=r$M5%W zV--kA$Mw87PB{arwz{#s>78{1U>s&rBU9ln1H!z1VNsBrfn+1n2&vPq*{*J;Z;%$( zhJk_xrpgq!wxQ%}ER)-`*IJ$Iq$56#74&v?kr%BB3VU#w+w_|HwY?_aP27WQQBj%m z(f62~U?uhJwMHXd@U$-KUE(o=ofwXj9)(yq#$!fZN+JCUb$yONh(E8at6 zf!|j8?G1`E;*3J5l2d3o* zT3f|zxKL&U>>7jD##QlzanIRb){MgXdD(w+?dj}ulxe%z_!^^mFslSsfT08G?B`r4$N}}-k_}$eFvx7tz z6z?jbJD+zZ&z@<(XEq`-xBo7f4Ttg&FMas&Otcz|sKS{i>+X~okHx@n*`vHlc(z8& zj)q93Q={F-p7Rt_1Um-H49+S)3!goE$_fPExJfq0poIkZ6mPf+t{2imaSWVFJzO~N zjYDRE1X2P+y=Pu1Gk!q9EdGrLA9v*e^Zuj!VYLU#HGGnSXXIGHb%K>g7+SFGQBUZ` z#nE`PnT~~2y!(gPZ6Cxw=E0h%lX(uI6Oc{$qssM=?eL8iBLjlT7VVH6dylqCCp#?V z_0-OhRY}8Ez6OC))0*ccr-Z_6NO-&I87Ae$nbS|t#s34DUhS${3Ou22khGxzKC;)LWEGP|f%k+zXpt6_T z;*)1w`31|$GB>L^H~)B{6Nm&h(tH1zeGa` zRoIuIPzflcZE!h|!4lUof=VV@3Ez!;u4pSg{wMp%kb_xqe;ub#_XZcltDr-XXUbY@ zD~he>88|_NIlm4B-5^e-!Ian}5R-5V&|K^a2A9>p=fY^wb?!Zo0!Au&Jv0qGQA6Fe5zFH!-u+0-0~f_~x>|hM=XF_eX?x34Q-u9(@Vqx2 z4EZEUR8jxrXm8f;dcN!X@ARS2>Mbkc&p?EGm`H&8sjxTgA1Pe-CiLgvsmhMF2#qd3 zV|aGkp==SawZX=$t+3W{Ww>akXKR~{X-><1SRN!EF|#LO63Ue2fE*+g?s6pDX-G~! zdS#;=-(m~=?gQ@^m8=eXh)0`c>50x_H`AiJmlE1On|hA6`WLBuk&JyOwz`l`P{+(srg&y06@_XnVqgW~>Aa1+~qf}2>F{%^DT zfA_5aKWD)Igqzq|S^oEy05@84L&%(&H1hFk>A9|AFGIQU-SxoY3TNeGpT342O~K!HsD$ci_O0I2okI8bw_U={^`7+5IVm?oA-ac}k_ z21?&Qk^7Tk6A!3tsv%1H9U!(h2tM@EBxM`Y1Fap75st!vG}!Oi4(GO8^+y0j97IC?2T0 z8{(<2+7O?hN8AwhPNSSa*Nn3QK>M!^*U&5Qv92J24Yqg<0R4V9?`}~kAwU8K2{8h2 zrvT$f{(((sVe7w|#_+qiH?Z|UMlIk#0RFtc?_L2Z=qRBs_wV69pFW~A$*L+cvYW^w1ojBY)*-1Aj9$bg)owf}hRGNI>IL0mSowT=LC5YX>r7%qJT^UH^TvFZCJ$dKG@ z-(w{aA;no8BXY_gkbv#&0ls2^>P!(*5&%DfD;^=koxV^Q1Vphy1`Tw8)=_`}-ie&2 z)dr~v01*{`!9H~Y$bbl3x1oBaU+h6Lw7`yjzv&Hs2E_n~!68s!_hGbq=udS~1bBCM zn)fz``s1ITA7AKxgB=El^D7i6qSwC_Cz6wvDMU?aa~BNz2Ts~1-JziaUtMLyJ1aSw@#spdPK+Fty!y#6ArGIkaNM{CZTaO{ zaJMB3M16BU(hLSAjV(m=ojE3Ku8362q^)`lFJFzYJ$95$umS*jILb|BOvXm2&Ks@w zg|urOsf@sAD@%^6+cgWkF|4vX`Uj#zhjPhUM(Hy?y&A)&FjKRyrahOE$lMfjH?_$$ z@I|JDkIP20m@-$Uh4NzyRsx526p}d9eNvI922?^J_cVLNR%8M+G&+v<837OijM0nv zL_9$3^SZ?H`zvwEp+eCUgNj1)!Ty_y*25bx$Et(ADp=)r^Fje zXhRF#tbZ#$oSeX;9r!fTh)6s4WBu!%f%xdhODQe<78Kv+TMmR%(h*~gx2xtPDGRH+ zQjwtQl&V`?7oV#qtn~6p_37-=CzV8FT6>crrm;+}d<#KqX*7yauh{P-60rd$gN zwH6E(H#c7|HJ17j6XDl*5?6q)!8ug#CAJ)Zw9|~d*e2>heXuP~IY*HVRx;Uw^1Iwd zaP(qq0e1hZu)1-r>wy%8SE8G22}oLgAE=ZvNAD}kcyt> zn7?^Pw6GkX>Knf$5-n&t6y))IN>LZ)P0#E++5X}gK${cd*P1QpuTF6 z^@8e^Gn(s?$>_1ySM^a8CnIN5ZP&#zm2zCpsT_}j@Ww0q zi+6Vo@*631@UCUv{Lfn6gazW|DO=fWqgSzFpk*ULcNcG2?ryowR2rlKizIT~P!+j<;VV$;>t*iDY4xqLF>`##nmT=pnpa5T zO6{KR(flYoH`rj}<5>4ZYOb1xBv;z;FQQ8m7=TD;(TX05^PXGG7t}wojC>@IAK2&* z)0_%@+QePargBC2+G9lBp*e6_B^V&*mM;s!*o|}XsWgU}MNi^s@T2{;n5RE!%u`V) zlnQdFyOYcRHGq(o_iyCdCeO)>oJ38e(%wOzi3dWaA~&v38+=3JEPMBkNxT=J+Rg67 z|F+0YFRGt->J=Z>S(c>IN_P@Aph#Ptsb)$g_DX%k99IL}Mo;7JKp}Aa`Z+)KgD}m7 zuR~oWIoP`)X@pGh@#{L>WrOnPU>UH*0C5?LgNeYWc&TcNr)cycx9wPGP5$1`lA1QS zA-B8_z{YWZkxIrRK4Q-=^Hv8OL^ITn)`bccoJZc6$e&Xlt_cO+`XiQFt$I)7m!9dV z@Q_3K*-qfdXKvY;d>@^B>E)=?s>H8XR>EH_MOV1o@SDN!OP7U{W2Swem6o#rh2{ZU^}v96 z*eg);Y+=PGL!@(JYQVR?R80Qch%4`ue`+zw-sEySF~k3d2tu8AekAy9dLY5Swh(ai zbX4y=q+AS_=#PT;P%I5??%M3N4)LzWo=aH!cHsNvB^DQQE^_SX{%8+xse5|OW*pm) zAjpb9kP{T*J3Jp2_fKN<@aq>-BmM5k7%QXS@b^`j*uapuFgyqxM1_O{?^VV5So#tE z=_=QrRdd1&AH@Mr2kD5^0th`^$&ICvfvy~joMNa?{ z$;6YkwVMO#jzebL!4?4@lzQ=LDZXC)%yqG8B)X{{#uwwH69qht*IqP|#X4U{x|M}3 z2%i7i-PtdtwX3S0Lu^R{pP;j(`>~EZWM5$;S7hs_>qU2`;A;Pg-A_{H2}Cqyy{2zS zR^Q8#b;Y49>jBe?^xja_9I9GJoFU#!Kx3XT@!!nh)bH7IxN>e|OlL~4P5Tg1H^F9e z7!_@4c<%_!iL77<6EtY>L2NY33Jy;r`R=hAcyM1}1*TW{Vt*Ko#=_;BqjJ~LiQ5nV ziSvlRteMQeB)z_@32uffvrePGE)FBcEZ@=R0}E&g&6t(twn`f`%N=eEU>iupMs`vHiV4@^70gN|P#Hw7%g5$!^M+XS5RU|wB4HG*3nuXa^miFIQ?9HS*ANy$z6x%l5(_aIs z7H7+WPY>shW}Imj7;H4c$qB@f?z&u@aYcUG2rKA2uN7CmKL@P5Hh7FCw0~f#h-mgJ z>r@rlsG+O7M+$UIzrLk+@x=7L&fGp(6dwYhQBH66_|9bYCk^mO&U4X=?pAl`=%z@I9pPa2StQ}p%>l*?@PLU zEJ)-+NZ~|{3 zuNc~FrTJfoH};|Bs98~h2;5jl;i}cA2x#K$xx;J$C1kZ@@gfy`jg@`?zUp9eXRZ4~ z)FktyWiGew9dybiMd6;^ZVXD4&Hl3MnwUo`s<{c_%8^n>*YX;7ccS^s^QUVYRmhE3 z)#K50cinJX>|cAZye*-g1RfEJ@{^En<&c}A;i@uV;p1WK%qPUtXG{!y9s>J;_MCb0 zV3@6w-)d2*()oE>W=4AFu`HRSsZuZ(BvAGsT{Q{OIzM?r8xQ@~H1g%n#7o?Ieq?Jq4fnMBl1oa& zxv1d)1jf)iyXtMDlzN? z?7@7^R%Y@~eo_znZo@vh2G5;ld2~hWrSL_{FR1-Tw_kg+8dx=p>aQsHvN(6(9sXQs zAjD(dnfwHMGbXW~ui9e+5!GsP_q0Q2O83pSlspI4-H-O|pHtxm=~aaTH{eHVXkS;8 zn=dxOK)KJoIVoSfpeL3RlHv5^69H$VxrF$}fUd87^E5*2h0Ev)P{56>FqeA1aeH0L z64JB`{8}|1cqJkU5_uWjD&4jVdwMZkr(Rv$6bx;Ms+Qhq{(l=c>BfUXv;+S+a%3+IhoxLF!J29SL;8ZH^ z9vhMQG`&9ysx7!m#n=OzhZacRwYJD|PS1dxud52kmfUI!jYdsVfQ#z&g`^CAYQi{U zcuE6|Tdh6@{p>q~mpHW(grXO6IRx6Lsz+R(I^8)7yIcwS-L?K9U)E+G)lwIoWtL3x zK#qsldLi`{&py#~fx$fIPN|~~+Ol(7Zcr9QGRed%UgUIx;%!t9p2P22>m72#l+W-| zlu1&sOhAHF>QpS*q<~1^X_P$W^7!4nU+ZzR2 zdWa-Vu*)q0=&xFtZSPf*aIVm}$tm6>!Q?~ykUbT2r;?kHUNVPbK!ia=Z!YLTpgO#7 z)Ma7uC2Mvb5q_zKkD(8}PJzB6knU zKWUK*+vOkwrcmN&$Lag9W$x-@Gqb#C^k_D8(^acUxhhuG@sNjhpQU%Yj3^u9R?@#} z`hRdF0>wI>A^ol*w3ZdcQOh5PMe(QrA5gW{En< zUV|5ee`J4=rt*I)N{pqx%8u<|{2$Wlo{csAY>@L^VA(E zO+C^LnJ_t+nxU_~q62BI!|1QJkzF&%+GYsN;I+6u9?z@#`>k|1dAE;PD9214!8}&i z8&B|SZ7{0v*M#zsufdEC$9hu@hM$>oDz2kkl98VPrp;Nk7iPE<;b;p>^0K*oXbMbc zfvv}gySQ{c-dLp%M1i8k`^~x9>5)n`A|A_dm|2&lWpzHbhY=E0_Me&2od4OX)`p^PG(e-_oPFFvB!A@_CH@nPHGxiZ08KlhV()g zt-~>TUVcEw3iApZq-g&-iaz~aX#Tmhs&KrwVPsf*CO=GtaHwB%My#bD#u4V`U#QVGf#eHfCTu#_n zE>34xWHoxbw2AUw7KLCiUqkjGu5?p5y7p#$vH6AgS%sPXeLVo%{%o1cDRFlN{mS5* zFvw!fjNry^OYCx!;fxcz#fL_a+Y+Dm+yUWvM0tGi`dEp!A;3B*EKI4qrf@9TF+=MY z(!?*L!7%Xs@Uc!Q6YwXy;YCf^a0l1-t+}f_EHnLVh-SgBE9Q{_mvSoC2N|9|XZVP9 zqLMN(5@XusX`I`Ot5REd&)4?Fm6Z|DtQh4B!JDJ&iu8+ve=AHf0U;o4NuGji>EJEe z_KH8Nr%`ls)MhNoxl(SjJA{S&dbT1^KSy7mc0@)4*5WC4G0xQmKWEw_YmukwYsyda%^O~G#oC(s z`Q^S_U&Ck6in_3Jaxjjpr|LM!?nVRpL)oM1fmtG4TaX7^VOoWU6At+SW=YDK0`ccd zu_r>3y_@1!S_9y#Z4qe>kD!bV!O$o@IG!m=+CK;GzWV5ni3#1R5+M=0V_P5Pgu_*Or?*)4*m=k0f=)#;+c<4<%Fz!sU{$Cg@CnrkayVAk2S8$Fgp z`YuM(2TBpfsY$;^O|}Q1ozogrNL%N{+X<%ZZZG$YWjCZGUHYBJVl-t8YzG|Mr>*63 zV{W}z%evy5`a0W`UQ?T1kJ;jrOZkdMG*|5rG>ck8$msHm1+ChGd+Vwh@E;D!FXLuu z_#`~oN5(lic@`do9NUwf6x<5vw$7L_E#*BgX2 zj&86@$zKHT++W>1;^E1mWXjd?k=(B2fL^b<_NHu~p}Zqj{wJ!ch_%eOEiNoOs7?`7|D6{Q1rr58S*xhP^aT$4rKF#$_RHJ%qZD_HchN5w`m1@$fLN$k%7-6v zM*6&jJum!&k%W-!4`pdpiBu2OR!bX+$S;z+4>W??T1l{Vq*Hucx+RUxpA}o2C+kIv zo{PwBZZ`TM7LkXN0p1Oy_1(T&R!{Bh0r@+piH---2_>24K#$Gw`xEB`+Tlv?3(u2f zrD3!0*9{1r5{xOy=3ClZVSRhK<-=4RM7S5*b1e!movdy%j{ecq5}o5QCS@nAnm5x( z6EUlRX}gdOFnv=7&FZI>ha)NDi{cbvi3q#++jS#iXZIQE5s*Q7n1V^5qLp*yG^wyl zGEz`qPhx$-2-Cw}K|k`ULA&zxN0TJRJhcxT%G`^%#wl_~^Y%zNF)T`!hAn9-r{jdm zKp%>lxUhKkZAhGWeM=ILsH&Z%E@?L@SyLE+$Z`x~QjuUrOHNu;`ideC7Ji*LT_QPr z#xO*9{18?<QgLD;&3*3J|IzojDBBN@{ds20Erdb3paf4NHm_ z(D3P*+7z-fXe@BK&!(7HE?BM~y5omyY``K2Bxgw;em>~vc9xjT=N@7G1IN5xoUNi5 z;)eD#5HQLTxApxDf^{26F@}YU!5fj3vY<&DsoV8XM^^=NFT|+Trme=%+M=W7rzLb& z?ZT%LxaOsAgb0R(P^L0!M}EPr$TIl2HX{WAAq+4~NxlpF0?-gcKLYdLIa(woAgMAXD%>Cm_cVg-oCOGqyI8Lo z&%Vc>U#;Ihvl{c<&yCfc*PT~iU3l=URJy!o)CHu{0FnGRfiEB=08Lk2V#R=f0EE7P z00Knta6Fu2fKO<$gSqgI_Q3>*$Y0Svu7QFI7BX-_LXS%c5CKtHzyKs50Fe>_BBUT7 z06{=N2mZ(jbVvZ45!_o)`7`hefuj+LU?YhCY2m*_Z~%C<+b{8T&@E#h0^0ilEcyZALJ4)|G3_9z z)1d)+I0e)-Ve`*Hgue)@z6rO$zg*b>5ctpXocv9HsX)ZPOVw7INFKk-x1s)wg8PH$^KgmukdFDOkfW9hc%aa3G^n!>DWD# z`wI*4tqSHN`4~~HQ9@iC1L#=lsfwSo9U3Nz&y9XBFRMkIfER(!pSF4*g8EWlSfhgz zFppqw#*V?XqmRNO;*38X76$a6^dmX~A{x+O1|Xe$3GJ<_J2wsa${pbeT1;`A_z51;McvC~pr+-3vicNf z^1mbRt3Ck`?{EH7d#AsP=8_uF?>{{E6SPs(hhJ-<`vW&H_wxSQ`v5_)aFI3(GVrgW zJ{tOOv;+VxxgZ0^9c6ik`4{wCuOJ1e zSp*+L>(XENEH;n8JGg*QoMUkM8D9Vaww*J7PwuSN&+yj@@#5qlXy&Je#O2q& z&fg#1fI%K3*}@73()Vtw_Q3PoGlQiFe0Kw2XHe-dTB9h=fg#G7XmeBzmS6Qgx+x}9 zl~GqeapmZ9F2PY>EZ6=tIJcDcT<|ecN|OTSJq|SkxR;$5eUz4s0gaj@c>0gULNw~b zH;3)XCK?$B*{dFA%r6Y0E$Rk^=4_9Z%QgerE+7Zc!|d1^5~kw(LPjjNMuM2lm2|lt zv2r5@6nc^gJMS^Mu)0RVUHUE4v*HuF9yJ*wWskG-_IVDjq>#A1>ZX)vlrZIaMYrl2 z)8|3gS;gUks+A5ShiSig<1Mn$?c6D6nA40gw^~eKdit92#yKbsAgGL+@4}tKln46s zCY7+N>of6pQ1&+bx}TT#zNxbW+*YOgy!2d%fncZT{;iJL0`W@>#C9!kXK#-h-Fmg>ki;o)i8fYd8e%jyEoFn8YvSENS@i~~K?mZY?*kuD!e-zL-2?x58zSVeTEy%f`jy};h23o zO+}VIRRw5$Un28*jE8;lm!? ziw+mr2+NGAS7G6EQqXJa%pG4Si2-6K&D?H@#twj(yu;f)4b?-)*ScHVv<_1Il5HNU zy^Znv!u*&|l@10kKoj>3*l~yJbXQC$^W~Ht0VlsgylWhaB*q)#^O%8X4V4Og!=+j7 zp6Qw;Wlz5g7)b*ezonS%4}+jTtYmDvH^^$kn?`I6=#)n_tgr3ey2T(0KQM;z4JIOe zI;LuQqNj9oFG2n zA7naDSqSsBp7pFWincUfrQLFKTZ?AESXM7`*HyROoCW1DE^UMmPi6(*xrd@K+iOj6 zbs?lvU?TQZ2>}Aqsx_sr%qu-K3zupzHlV8O+@QWv%KFdW|Lh^?xml| z1vg~aW(DDdU*hidbhQN>H*@k=kM7EL3nQ=i#X@82p>)`C&^|?!AxS*w^5|F+b{`CU z2&g>d{07@cK{{J{v0jX5%`rEM=Sd|oI88_yimuBmOXrd^R6H@0^xm-B2ko@8zSs`||j~c)AJi~z@}!&t%K)A~UsIIi_A|IqO0E&A1@ETdl$nD%n#H=>@_gI}BP)K#9i&ow)lfFS z2;Tv30OU#8)N%1tDl!s4%18Ucdyg;4YQ!s3(N$oPP+Hj&xSW40fTRxS?CdSVJ#4|u zoza4)B1GcBArtiEY(oU6@Px^4KB0X)>&rI^x1B1F(`=Y`QQwF!6KLaBZHDvbmmfik zyuqD1SgIYL;zv^LRfG8_o{6}_h41~h+MPHdEX6^p54=|}w4#Yh(NXhY8{jw;VcU7Y z1I?bsss5G{;V`3RzMsl|;rZz!_7LUNMyC!PDrTWSugp&>?#y%^ybC#$en}8)DKevAM>7?JAqz1`^K45z^@{b z&olXzb>-u*65-0lD3^)!%;KILy84^65T)3?tf;kkI7#aAC~ur~z3Q_y<&oOs8N`f$ zTujd^pmmw;M{E-1WH9NS3*XTF1}F@SlXb2c*CAUpa7Gx+OuKugkFJB%orXX&x+t&Q zpeTA>RN@~~zi2X^Wb;_>!{(LuJ%1#j0{b@yNN0BP?4KJ&s134Z8a z#ivHmcLEs>j!Dlh0<*uAJ#r|%Mj0N;=LSn|K{xG@$RiL2RqU7AE}6WV$d`W(D&$KtIl$n29#`R zHLtqLYzMNO>(tXNw+WYgtB(UuMTSxE@%z5W7GSZ~ZCPf0)fI(tqOZXgEe$#!3e!bh zk|ivDQjh+Ch4&bfz@!VQ!EcU94IVk|HB%@*&NX&p|L&3PeO5=b|9qv}w>3T}1A`Fi zXuf@Z1T8*eff!JBAh$SEZ}7FLz|JG!K>Ekkru7c4CW3JF*FlFpZe68kP3R}3zDFc9 zkKDifVB$O!J0kIe6^~Qk86VfdIo3Pgn8hZOg^@sLMw`ZR>)2_6{;I4>9&UEh-|6iG z1rE#P#5vBM$;=y@j9zPF=W@zF#U4{hmk`=TiZ>KDCp0akoC9ZMSH$@>R%$5a64I{1 zM&53Q&_=SxhU&dEV6TUvfpX+XB8E*pqjqfZNzSC&siBWGWBXtuUi8zmNaGT2i3KYW z4cTyq6<5joK6~TN-Z|1ncMFsTCAJx}M?-1n1RaK9LgDAdEY?gC2$LRPYUVs?4m9C3 z9)nfL+77kBjX&)W4_3u_W=n#EUM_JQemg1me|!f}yU{3=32bB%(UCzvN3O@+YaDzp zR|3^(wB0`6Z_3X+jF_MvJ**7cEeql@_ztmlLozRqxN8z!YrIiyj__s{v$4?LY+XY1 z9l8)^h~mh0G-_QQPp9&JfF+4k##$m<`kU2(C*d(1f42UH5QU-9=Z9y`#OkP#tTPo9 zx<$I~7W8GnJ>VjVcyP;lAdUd_{Cum-FIn(dI;p1A_bUA0zCTDlv%& z3mt3m5PAQl`_WdPd23vht?$HK3wqomvGKFIicvBVmKPASbMq03<=wckJ}?YmmpV# z4Cu&S;cAvCRBK8SJJFR(U)<_Q_v@Z1C1iD7MP zzF5a|Xw2vBG3^z22&5Hp_3QJG??7=*5B`?%O2wJ?7|>-rNJ}&*L_CGFo6V)s?8U!t zir+4V``~)n-DY%ViUgihT~Y`2?-VtdTk4^+L@5lk_*=lt{=6Kt-#k(s>|#K6DQbPa zo2?8ns$A9471o=b$=S+?`XCPR)y^kL!Z3`Or#u=}*|l&wocJI4Kd9lP^?aLiUs2UU zp2bA+i2sac`;m z^bp(Io2t9=y^usy`Bg*uN%H0wWFt-uiKz`8M3_$-g>06jlNrr zq13^FUs(~v(|(Ymf|yl~z^&lh{5dFfVVdy+6*rKh6$z-;~ThIp)sGVyfjmwjcjmLGnV z9`#sD>1$i4oo6KsOY~aFws^ z-sT%4+m5+|ddEK9okp)ehIolvDB2JGd*->)iXW~T$3xB+e4a>yaFDE$?3wmXA(s=- zWk9iz$AbKACYs!f>OEy$nQYLbqTz8sg{7MyTk0+tGBj3I8ijs-c{h7;CpAfTJwESv z11QN6MCAr9vG-VmV5o0hi0>C>y`F|kvH)#snGbG?7LN_e$?VJuQC|dDe^aav(W`z; ztzyLT>I#!jzXm5Vtm?N+xC^IkB3OKgvTa)MfH{sur8n`!xt!(cdvWw$=FV_|EZC+k z7!{^TUcbKK?AaKUwzuSaoy{xA#X_S-4X!%H!up@|{AJ zSbqp7S=SARHnXnDuZJ_~rn0Pk5PeQR?G;5b=H%ki1i{w0;ze4TDT6LoL+X_HF80Kb zD)l3HCT-J=Fds)C3ZQFon1}YgmKwhlgY`h=&JjC*n^;bu?}~0d&Ic=5?Z5`+LDsvF z3U!@+pW7F`HC1|}Ss}6ZxRXDBNVWk4y)NG3#iaxbmUxuW?bVD{AOc8!`mrbF#?=h? zf^j7#@}T5r%tESeL3Q=}G;=|(`nOX;Lc?%fDJXwQ53kR+Ucu{6nT@}4O8MWt7$;D{ z;UurJ);;P6ZcMU9GeA`G$}%Zfot#^^VyIQF{WCoc@&p|Nou!#}t=8!1OUq9S&c|E| zBUQXL9TA^b4)!bmqyj4#M6&bxTVI+M4_927uDDip_O!He@M_kSmNyyBSyhud#*Y=hsikQS|Cg)6Kr9vcsgR;r;?sk!T0$UDeItVz~!IwV#o0hYojBqWrS)@om(1KK4sK+ ztDe1F2^bA|*3Axz8c?_)MdIfbagrqK%G{SqQv)z7ny0>!VO%i)94#C2L3FUO)6z(< zH9%=3s971?x6RCoyrl)i;a(hB4of{b+#YjH%_RP+eW5RH z|1ZkUAx5-l-PYx*UAAr8wr$(CZQHhO+r}>2w*B_G$-Bu*PUm%2>(5$QotZi37~dG= z843+~=WUO8B%wnyY-R*cDJ8uKb5Rj}8>&m8({IwNso9lVoV9yd)mts@#~QVCuT9}d zR3n2HdFc_a==R=KJ>D4uvPp8l+Rgz{6?(P#Ywd{(@$=1II`QxWNco(PMLcBF%~QT9 zeb%?h&JpVbtM!U#od=hW--|~S>--OGcpKRUA_>+@@on3oB;^NBOQAwYY04_3Ir*AS z`xh0kIdsFk9Cd5zVI0BaC+2S!LEot1q;JNa9(k{AGi6)V-9HO|@_Hc+|Cm4iVrqZN z>pU6lDVw(qU9R*r5NHsrsz9qn`1VQng}N5_+R}mSNcF%O4!R_-iB$av;&>AN3s{A; z<;pIJ+d&joU2QbEPepXee)Qt^b2jSrBPwh zwsY2GIRG!cMNH;(U?6KD<@NAK{e&1q35c>x%I|DH6t8(>_xt|*&%Kg$l%Xu~HlSKx zk9-g^uJLpMFC<%r$*Z^U!w8c~HdrC(9$UfK^5Rf$ih5-CqbFm676#`fIMP6|VCG@i zA{ApEwx*c(iVn_=JS=WtZxoO!*tJ(5efrpds@NO3tznB0OC)mh5>VfwQ7J;tPpUio z46vPb+E(QNWUdPQ=5d9)P|G+$h3@oOILd~#BK_S7MXGtsVw3*fiaDDu0n(KV1APG) z=BuRd2 zF9!Oyr_~4@mGS+=0h3x`f6f8Lo4} z2wv~%xh5<{;m5S)Ywr9lFbkbVwdzDc4!57IzOTu^TE{-w$5kOO7K4fi<)a-?inYMu zIMS_m&|V(*pd61@hTA5ewSKEI;*Inl4qVpo?r&K8^=2<6uK4c#lOKUefth}yI0>mC z4kH-{-VK?%;Jc6KHmovmr-q$t;>na&kB-Ey$r;L&;b~!~F;2dvtff^L2MdoX3=4Wj zN%q1Cl#MYLezF}AVRsO{qfU}~^E4Yu!Z`2A=-98|+--Sr9bcsNyiI(98)X^J`Bokm z{O&y8DgSiJH_y$>POrV%S=BAF)?TW}!$ zf~vuwjq{{$Qx-K9P3|_{)}lt6@a@`k;gNGpq z2yk@K;}Vy)U?XuX(KfQV_id}K2n+1dm+>*$JrF$9^^b$Lyaz8%?g%sbs-y*BbY@}O zTo2;{Q&;YV9U4$>hsdZoV^;pQ`piPE$V?rhJuYVgC@3ojnSBC3=onjtYu&XHkLnhbH@FRhm$Rh@Eg z@J*|)u2xS;dP$sx*mJbH_|zgkjL4Q!zY;Rr;Nns|MJ1rJ>HH*x^0syuOEgjO&RjY* zi>Zu(XWl3zuory$>LIqz-ze6wCN{j9v7d(aU1MWwuwKtzWa08Z#bS*b&|;IXWv;zr z&Yq&y9zMv4Vpk8=W!75aIy9;$pgC{SgnR1Y343&J6aBrb$Q{Fm=ULsB&@RbIJZK?SvuuSq0y*iCNs#x zAM=c=lIQEnd4}ck8u4@FqOLv?ELrM@YVjj(x7+jYR|du4&4x7oHm&=vE2Xf?jdf-sB;A-c z*m2}$Di^JdP819fwt0CQ{yYhKUgMSpeIm84wdw21wI+$yQ0k__2W3re;2K34Pg30O zP5a_JydLABbu*a-+~W}TN=-MpB;;axIUr7^lAY=`@L-)igavgFnF)s$PtX8}i3BEW3%5`892y0<-)#{vp-6*YRZ7OmCb}^mI+SoYO#X{YE{W^Y zoH0Zf8SbTdtmWAhgFy4VU@w+*Yhu>vj9fZt$xX}R;fVE~$6d=4Qs=oKF14hkYKo!U z%r=dWOI9(4Ua|e*bXp=jos|6bpk=O1r>rwR_0gh0&1phQiZ+ja(VuI*(;fz`c^JWJ z3vC&)3)8~pLV$)xujtpZD%ty~Np9sI$osRhf%cX@LS;$rfIwf-$p7 z7A?N5uhFH35e!!u{s!@ZgY5@*Jt68G*eVEJqBf2$2= zrT=gGFcTa5|5b$l0m1a_|Em`NKl(5|)Bl$~ti1cdTC#_)xX4mmK0Ln-5$H@rFf`b}6ov(;Um|q+jzPKnZ4)uU{xbykDeXDi(xuS8I-L(7aVRd`D{ zq<{z-HY^Pt<;C$a36SepWIp}uN$5D=n*K7V}>RFQCSufTnXdLqEP zE+=|ob@qeR@WQ@Dc-MDS#L56iw=e<+_5Qja=6!VZ;QDLc z!hbX{%>U59I_v`p@@0BL{P*SxPQ+Wla7zncPz31!zYQEi_WTs_+0D(!5Ds#Z|E&7b6`SyIcSKF=daJXSbjQk$cVdlxUbju$V| zFQ)rGpNk7}yZpTRc5HcdSxHoKQc?<-gsb3!2Jio;G(6yspu7+#(l|9WDFsmC zmrip zvu!PL2*?j9vjfFNetIzA7eIdqXT-EbppOUykUt?Fzov}x${-Pg2!j5>7{LCrgcqm$dh8Aj+q4&Xdc; z9vV;FN&KRH`S(093*7cR< zD5oA^Y&1>HTleCYk!btu)G=`BV-d%3l;}#=OB?O)VjM}WPQ`Z6CgT~QKQ&Ov6C3)i zL|9+pd-eK?B6};Jlk8q}^SN=08Q^#5q|K))DKj|qiT$vOITc6iE-);>A#praff8gM;k1Qgtp<~ew2 z9$b{y>S~5&OqllUi>N#{4g__gX@}bVHFxckkZdm_`P}__D4bJB)ti2$gad$rtyt%^GTzLcmS0|0nqIw)%XZwxQ*xwItKR9C{*mi zv2RQ&Rw+||N3<7suYf8*m6;oX+B$ZS&b#<>RO^V$yh(+WEu7Xa^ zRcT%5v2QONtT-RtZ6}q-ImP^bx3unS+|=z#;5#&(8D1mGii-)$${DJ5b`L&~jTzuQ zKCCjyqpGSN8lSdYm=E9`z!$!NM=G4rWl+>qPQv;8xYFU(2Cs6yboB-x{_QR5)cZ0vD16$!$b4GPI zP`||%NrOohiwec#CMQz%H#d%CXVI6LKctW3Zw1%<0)(No>PpZ+a-A(3zfdi)E-=J` zyY-<-=?#w5A<06-pCT$@(W0ZS?H3^tS0^B(J@tgT4$h3r&^VUd0J01c7bv6{%g6RB zs$4q)?y!>G6t;>p#?W#UCm%JM7)w^3!$q{L8R`&_N}mwoSUe1~Q^5e1ug-nxGh06qy@qGe%%TGTdLFug;V!O3m^1wHF86PK*anrqP4R~>;WL*vaWUWUw#vr;F zI)V7O+@iPEl^sW&X{cY$_hq9BRvxlSd%g+R&pQk^DZqFZ@rk+ij+h1sAruAtB?Al+ zEM0R1H=+%Dq|00uwl4MKsbrtsQ+kSg`)I)dF{~Ae%Tko`tB9?b37_kC5l-Cef_e8< zywCEmTU;?on?`B2(~L)+b(fP{yK7UR?!6<7&0A^JygtJgSnZMd;WPP}rfXC%4^6o| zFsbXe=#A8?+362E=K@6%YaK2$j+tUy-gP8|&axjEsE`CS-0O zAamwbtcnKHYnz4D=)GB*=80uY``1p#IXzEJQsQDskHeW8;O*m-)c}+%RaJtM}{e9k&`(vBPpW2HK<( z&u@t(f-(!S5=}??Uz1chQ8^Ce1atTMnx7rzyX>`Nr;op|fAveQX|~9otu6gKFQ!~? zO03fIc>6?Nj~!iFrgt8nzE)RwJL9Wo5AMp)aE~r)_0$B@OH;UT(JC@Xp&5(+TnUax zCs)te4$)BN#Bzq7o2jMXwimh`Rd*&Pj@dd_`AcN$yPaQ&lM;XIoDYvzur8wGH1tR_ zQ!KgMG`kV?25r{>-&JRU5|X+xF}~pX@H&|GsMej~WJ^q$iD#oNE>wS7a7evyKD~g1 z1)GzaWF*%LN}>(XV8UL(gr0u9)~o)t%d4Qdgxr*3fCLAioTM=m9Cm!YWB6Wr7TRD|U62Ta;moC(1H1_IAv>O$PuxBF>fO&kxM3+|i&@hH1F6mm~+Vvsf zF|f~D&Eq%0HkW9B#O!UD@ zwdQRYOCBF?1@oYvy+`)}`6&OwzVN11iv@83E;hc@Br|o}z3Dn7>#1caU}LlEkHHb+ ze4XNBV=?VR5Ovw?mr)H()Jr5iY^nMxWGwHG{$PJLcT006$3OHqdIhR1%4ftIpvN{T zm@&W9!rNz5M5_~r{JI0JBU9?`y$u<35E^Nn4Ey>#9?E$_<)}DmTClYu(aZ>k!x`XG z3KV(Ow1(u#;`PFB%ZFtGBX_UreB?9X2c|U?TJJ6i`e9atiSCFRrA4 z;Y4m7EH8qcFR!(z#V-tUwa)Z0;v#uO{YDh7`L*cMb4p`Eq#^Y9`xr{xb@ULP((x&^ z4O<2s6>@t$@EU-bleQ{Jr=xEvBy}6s$F`(S2i4QmoqbZ%`MQ7>oQ>E zaK4aJAA&+lh6%>Xn_NOG60qKnmE0jnM^aCErU+$Kdc(2x|9#i`3 z%8H1#Du>ETw$3I-<$P6hTlVL>qsv9CyvQX=?@&4pa&jHRwT#^w=42@C zU*qw4nY3jBf+q44r_W|qS!oHVv)V1ZYlGbQKKO~hl_E;5jvlk9P$KlF8V)(qa~0B^ zD~8svkZt>P)ok?=IBd$T8(Lp9E-Ex=Yfhw(lTeT5%|;>*Hc zG2cs(`^f}(w2+TzlkBnt5vS!AL!<2h=G4{o<(CHYCgX)h+uh#!abgM|5%Ij@t|aUS z3`#P59`mu2?Kf3dHE0Cbd<35rYI0p#Tjpj0Ug~zo3mSF44q_p$;HATPjVgHEcgU>g zgCoAlZfx=r%PB`o#k|l793s?wZ}ARz;-M+*Lp=yKyM*a_+7xes28}GHnwy8y+$~sP zGW;236tWAE7IF?}6r8iIa#M-6AP&B9jYOE9{W_p7GouxPs)U!qtu-feE2PSLe$F!U z`38Kc0=hZ)N4QBO@jEf4!B(*;N5uI<(ruBo}V2T29F)f}W|FGn?!5nHy2) zXq1-D2raSmxa)B^iv%}nBFn2Jf2Bu@^%z?h_7Tbubj963FZ3;CcyvrlO59z?)QXWo za55%lM76X^up93mC9m-2>eZ5RyDX{^0juE?mG{589?WvCeGc?;%+TyHJ421uSx+U0 zUf@3m_VPQB9OK-S5<_cUqKBHucRqW;_eiax2F;w=>rx7-#Kyg((fG~*iyp*3od-I+ z!S3&2X)%%Wsb9aWvQ!nwN0_veYtCBbJc3&)O&5QVSKYjn819XWy~@7y?4U!hbQ_e8W6KPemDNu3OY3iV8WB10Gsw)*@6 z;yJ_|O4a*TIKpNs>KA|)b{iCwmg-Br9$ej|C~IMRJp&pS)KU>Q##CN(Le^M##LG}m zGIqz~wKioRD>#L%Rav2voJ*B;KIv950?#MQjD*E3acS@6E4W&UH9==Px=(6+RCzbZ zMLRvS_jNsQ-3!|kYXDXoy0-!>E69jzN|J=J>J=GT=uKWtRqwW73{hxfCTbn(%83{D!+0j($ots+SwSuW2 zGq}tzRVUPr-JPxtt{gW3)(xKIAn0;$LR=j#4jcL9JoC0sYP_G&3Hv?4+Bj*#*U>47 zx|XgsT>jg6*FKI@DGA zxjc8u^es&5c}X*UJBEeI`)O;jhvjG7BLZ))C6eqPERj4$McQ#OGG85>*Kplf;f+DX zZ)adTl-Z5o-IsSvLJEpnQ-SpYYf>q%`$XxegB-XHjRQT#T~P#!y0zI54aTKW*vivr zU*x```Sz$v;tm8B$rLY>d)X*L_lM!yPCuWuRp*EXLGA~WeVgP)C$>mB^`6jl_mDohH*B8!!{&D8 z48JbKR^++pONSrsuOV`89ipmcmN*MJ{{?I|^bINAoqtVdnJbdJvy^hF*W9f1#e|Nd zUp9YdU0yodnw6@tG3p@E~3N?zcgL+ zy!CD(h%p$g6m#meeOh@o?5nD+JmW2uWd2rrl59*ND9RlO#8C*4kLN(rB&7?%Mx`5? zI1$e_-*V-QB=e};iSW^y?aLKuxEnY{ME3lleY5?MQQ>*gfWXswtO8?uILj-0-CNCvkbXu$nf-&ZZY##7t51v z%*!x3(9=yrW54SO|AZ*mvCszeXJQziwJ!a2uPftNLj1)h1>^4QC`s7ny|8PRiaEIj z&7ekSv31#l73bN@Cv@!Y#M}9a-gfkq06OzLH^F)_THFE0t4Ie$hc9o*PbhVDGM_Wj#3R|Gz228U0*L)tgR_Etlvz6&> zDt$UAcwg1Lg}^I@%!O5$WEaFt3!h%IzXzNA0elL#zn<))lL zx!BCuxg^8pU)En&mdTaS!FR_CjPrb_M~TL)us+4|W=?+n__GY?hCf%rL=|@au~)6S zr*J^i)1em66Y)r1EHu|*1`{LaH8_8W8yU<7qYLMY9Yw>FU!0O8Js`mBmA%+e*j9M% zv2wHM-n$0M=C@?;&ku;-S;4cC)2ZO7Ki+COUB^N(JqbU@=*whku+x3krk8Ke1G2p> zWUtI`&W}NzsPUb@bP``%`~x%D#S9j5g@UJIXYZ9 z5q?ACq7m)6>Tz6bh~8h`9*!fKBG!?C!no=PCX<{}6TRy7-x;)EowlGNdJC`2C>fa*`Kl}N)T`3KiE$j^oO%rTq~qL)8{wBI06Y-gNy)5e`&NWsF0L5)>B@GI3*bA?6dKpn zwc4a;6s919o1k70RXBlSCV^fR$UtZczb;NAb4LTNCuLte5mD)yedV=AcKXn;LzmI<3^oN z%%%0+;NRrJ0<#?P%K%0d`}$HewmNRg^_@jI;{T!P-bdJk$``ba`CNPFVk2XKb(t6* zq<@}Hu$%aawp5%V-sx-t(@c2*BLAA%TuMB`ltO}WZJxHxrqmMtccD?hOoVLhurh8P zU7AC@u#V-2hI<%mg|m7+#gy$u+?HK~=4;H8(Ti~41@*B0P}xT0qOOp*D_@XI&M92a zdfG85oh!w-!CkPi^KO*G<x z#PnZ*PzDwj28RD3LLuoyEv%hQ9P#Nytqq(_giVa>j7=bUc_E#g9Zd{uAl)}&UO|;N zH(x*@i9j{Cdf>OV3);OJ1RbE@u@Sc-wH)YfZfTM~N*h&7hMTn?mRt7@8h{hf$VI*3|*4tFfo6tFOY9l`rtaS?>5; zg)8Ow#puUpQ-Adk4r2L<#;aroAs#Tx&CQ_Vof^UF9RSwa-`CyWG&BIOs;j+!|1>)t zfs3Pa1W5x%P6KdoY2l+MNN&yU%pe%s0($72^2GsYB5?v>;o-p@=A8p5VC55y509hf zn}aj}Y;@O}8ydsNH!%SM64?GK1-=AK)AE0|4WH!-CIQ_(^ASO+H-O7 z&#VUGU&l57RI4A<1B~|XV*~FWoqpMM^fUWafH3|vYfOlU$cgDmsKFXv!PW6@AMD$ zfan{X8i3Z;);IvU>)>>MwN8r=&g^i1CsSHjnt<=VMP6OlzWq`^^C*6Qm4C!ie$@(o^+XkAS62K!EPf&1e($l?{j0Zs zV%=40k&av-k*{^l23~$cErEV9bwu(h#wSjGJxvHi>z42>t$r%aNm*r0RcHII@avJs zQOrLOKo}a{q*(mcS$@*ltm0|zig3`M#$X;ZMq8^JOQV#un~UQ z)opnJqK@!N`4Hg7sxp5BvH?&#{NUmIMeh5;({TC=Kj1uPls>_GPAYzb+5xCBe?`3O zRHA#VyGsfG=JT=dD^%;*{Em9Rdf5728T&U+x#u^q3KZ}6;i&^l>=K_23K6*bm0-8_m1s z^o8zia{F8EjgOJZ!O_{f$LY5lPM75k@9Pv44x|%E20rcNS{ek1+6rjHwn{icJKc3` zokIbPcF?zPc`Jd~en;sZ>DS(EA_1$He1qka>B|=BF}&xjWI+-tZCTQ9h>0W{&#j^s zW_H>=YrzRo>Fx)jdT;ngskcdKGk$30FZOG*gv`h%>6BeSeqVJ4jz3*R%Sc{fSqmS7r^^3yIS`-SAEyCB7yM0GW2GGGyr&@@+H0Y~A3w@SDTWUs>$<;-~GSY#GY0VOe^ zB_0q=smBnNAHn+dt53XBwz=1i`EvgZ0{ooCcK^nii#8zEH3GJFAXKk;6DrE#`Nq8K z2-ct+7dlA}1o(60x!*lbD7WdAQ5SZdNWh~RKpC? z%rwvOEzNjBeA6xR{7X#=UGdk7aFalAH<&@bn0kPy*fqFo?DL;nOIo(3skFFm-f~GX7H`^u18LF97gP+}$NRC{SnGaP z@KQs_pFXc+H#}L)%03fnbO=j;VZ=wy6re)M2a0BYvJqe44N7-+=(EP|?jzg@67?7b z6s{3oo9^kgpCZ`C`XZJ`bRiC=&Ad|0tS@vc_=1C~Oe zk|@Evs(RdFac0UwDV2`C#1rEr&8OG*ifAO)FJ*1H*m_wkn>T0u+Fu~4 zsKixUrR#zb=xCAzIgRXQU-yc*ui>E}4FiFM6n=r^zQi^h>F^MOK8}RQ_qJ{xB9QP!(*t-s4<-@bW{_`=V|@uN z%o8{^wry*Eggi#&T;k3!EDz_-$nq(>)W-@Sc~pW!Z^fxL?Q$?%TiPFSgBH58Smdi1 zHTn5~TY5qa+UHoVk3O!$RM2JbZFbG8OWz;j^04ZF$gxWv&fX@J02uX-_G4($u+PC3 zvb!I|wkC~!M+dFh-;90NhIQH;YVW$@_*t4%jbGrE&5EJvGz}jol1sU-(=b3r@v7Hm zkG0ogrPSo<1vduu11k3+!KJp+ST1y(yryk0_Jc8Ei026j3%nJ{EyJh~DN41Qff9KE z{RjYWaZs{9Xbgee_t)1~ML`n2vioIUN25e_&jY=2R78!;bCrpxRWw2MaKytkdigdJ zS8|R${53gxH8{rR4~8Lw`fIm!@^?Z*&f9+v=uUk>^8qdgP(tQzye5;I@qZ7zZbvKET<}i|&p%y6pHFT`P_SG< zkS3A|2|T;SIZQGty z_Lz8YCAxqBy0w;kSQ!)|E@R9%7ekJBQJ0ML@XbGU&~*b}usKY{D$h4Y@H*O9 z`Nt{-=ISUGjdM~;x1#*jkm%IBKKazF@@#a<%PPT>)9)E`(SE3iT3i3Hj{Hq zS}+BlO1s(r{!~V;SxM(&kOAa}!f1MpT+|xUF8xv)Q&d1yAmEbmxMU8T4fy~;I`kwk z*c}4J)XF*h!ht1mQGge2z`b8tgG|EOkIR69(5V=sHrbY5PeNK5hjKk_H)$~s$LpK? zw8;-hmWd9ix;85TZ}$aV7Lm)u1GI}P*88wdk;J{{BL%xMlQH_v zgI#iS?z{LA7bOp%JNwBl@=A6H!_GL|%V zb2X)4cpDErYccMBCh=ZiF)&&x-`ibgEZo%e?VHh}f1=*P^7m-LWQV(^lD$v=uBY!! zK|D<@?#HAs>}bKz=9mUy{1qy`q38_S<#!jzy48B!{eIKS&0I4jnvcOUkSB(G%f0Is zErt#5g!~dK+ij zD=uy1s{R+EYf%0s0+#QFHP}NS*1SEY%CA*#^arZYA!1F)Q>#?2E+PfVPFX2A4;9gJ z)&2**^%<9i0C(miILE&>7Bk!>?r^SN9nF2o;3qo^Gw|sN(SA)p)krt&A!M{#ZLMIX zgax@Vo;0tB=M|u%qcAipaKiA5AMjcD_0Wm2$m>C;&+EMz^wK15xe4skC zas&TgU1C{;7=QPS9g&JyYhjGd*w`2)HNw5VCh_-^D6;s_N>nAUm4N(PIycDUU!z*2 z8SUzq0B_r(yA$QXt5j+Fq#Olx+kXNBacH?Iy(Mh=xC2#apBQmNDtmnQW-TB?V zH+_fivo&+-V36sUa`tFdY`PL@DXolXJ-ZzDqmsTyYGs>_AP+@4tzM|=B0ZPtN{A#rJKz{aB{0@%-y!s7ToG7F0mt91f2UE--e+C zyQ)(Fwlk^rbB5q~uR|z2Y}k&B&UkOm&cQbiP!Ss+Yr9oV({wBfRz1SAu%~q(7= zk>#J@knPEYJiEwqh{n0fDeZ7AGsw0Fve=!#r?xwTwHhOt5S?(jIvCem6X>%TiU%aR zPA>*qMFg_Jc7~JG5|?ES^ZYxOz2>|!K7LzRZiFX=Y&T&d{ij~a9}Lh~3SvB3=Pg^} z39`SgC=R)&yyEtB=_8N5y4-qEJl9iK;iR@`8Bykobc9s}2AD1*aDhgeo+1$W(*FaJNl`P*ba3;&k|1cfNX|h(b2iwMj!FW0f^l z2OF9gPXX44=o3WhW$gX|^J7O^uQpNJ!=AqlzD}oV4q1rX+a5lF zxZ8>m@$9(R6K=wV>bT6z9+1tH&P%}Ku<*9Gj z_L{}!^WKnRIgy z1PrIP45V|{L)enMZ`pPl2~D;wFqcXxz57FBn?0=E_d@9+S`pxnbIGvoaO%QLSy;Lg zt{b#A#CJ~Lt_np9FV1bhp6*n5&H?Vd4RJNna7gRE148^D(pH>`QX5ZZU*8?DO1XlbFElSmPVeMG(J9ZSIGX_9$yYlq1B8Oa!^R zouO0sb(ybM%*OTxvo~XKUk*f1BdbXMXICJ&R24UE?;Y8XsILUfO%bn$*lYy7p3h8E zG021osul%mRE!VCMk?JDRI zMe`@XvLp?NWo>9Wo3`-H5^g-7jVA?z?hjw%!lwJV3u_gV8mTImDma%c7tK7@g46OU zx8yQt42@g64Qz0&p1|GEjoP$%&&Jses#Y7I%;Vrm5`Ld{zAA+Mx4I!i*1U(^;xL)& zMS4NEU5HQfvcDw*I3{EH{4A}cZ^|xE>I%Gc<6RC(R7w#=L^mH0FjKH1?*dl! zGl8OCIgAp^SrR~hn~@gNG_@79aNa8Le`?doar-TDRRTFuujRDB6N`x3;}wOW7;cs{ zeWp%=Obl1+m;^@$eOVe!8YTm>UB@r`{K%(Ja<-3jR(Wql*hyz*#rs1az+oN|)miwO zpui8S%DOoWy45J&x?g2m-}mwJRiz&QWNU*q8e}%#aBf~HOXWXpv+h*f7TpBf&d6UG|mx;E6Pa%ZQuYMF!Nig zBT``if*5QV(z(odLq5b}i)9u|Xa=$%OjXXW(-;=;^<^Xg{_6Yf0D489c*zNS1Qc5a zA5idvM#5KHId226GcaK zeXD)z6z{LX#48%y2X4ffD!PZP?uzczFk<15Ek-8M*z!xEyXp0i;L3!gQM;08Hx_f+ zW`1~Y?K)A`y(3S#CSW$?wx`WJtV0qmCX7s<4!Jm-J`|{d0)z}37lK_LzGoktj>JN% zoEICwvsfzrUDcB17Z3@c=7Y_Ql?O&mbv+sX?EOvnQ;CX-_W&P=?w8r(0fY-#im={Pnv zWksb4PqHDtBfe>6GHt43XNCdMjCjM|GiDTkF7HOzvaEb&`$=L_0#(xEyjM2Lla*3TiEw!8XIt`!OtmnCSRBG{SG(8w{PmSAPX$B5Y9@;BfWKv8rx97joxF& zOG%4wQUH890|Mkd+7JgqEe|&GW%f^ePTZaOvZo)OOh8S#qIly2AT&H!S@f@ey&uZF zm1MlhQWhin!_J_{6p4OdMHM>I3Qk<<*33yXx;3Q}?#_>Jvjf)9OxM47OxR=-$3#Sh zyJ3P#Ybgvl)JZ1Ya|u6k!DAW7NzNL+_-CHTWiQjI!C;wD_N&HK>(Ov`WNbbgnkFZ> zri=yjviAFSAq{9pZqltAhS>nMuXhto{E&$;i9wrat_c5G47I0Chtz+hH-q&yo64C? zG)KgxFM6YNJotvl&PE$(!nXs9FZ%{<_0}vs3d^lmsd%weICD^~7!M+IbJ2v9fxq^T z@Vf1&{7UE?$bnMa37^AgGw- z7H8UmnMp^$=dGFm`jT8bva>!00qf|o?Im@S;(E7M!Cc?gA3r8M5M3AXIzQhHs-v^) zm5LZ6)!31V2DR#Eg573kQf5xG;0bp?dvuv-cCR*JfIb}hz)(NYD| z!S#PwLB=aB4%Z=nyN!S7k7O&16_sCW>ULlcu0$gqi6nk#L=rwvEaRea#hYt*vb@EC z55#@o+;_;5uu+Cdxh}=SK7Tgd1-WcrJn+NbY`%}56cm`K{EA63MTY_a)hMvonPxZk z#OQe)43(i~UN`^lpJUNTJY<7sPE9GbE$`QF(%Yt1>v@>tlsZOIfxCLsH>4oHx!d_jo9Op6k%3FQWSM^7iH8zIEriN#flHZ&D>sMIbkei*9TU41&uVA+}%)#@1DO76xD3gvD zO%9)vs`@`S`aAS@kmr*r@~v;%@G)gMn`5Y1`;nNhu!IFYysr||&3mc3PwDU|Uc@)3 zR7kQ$<=TV+rLw#Ko;FXHxcTa0B6xobW|-t}Nkh(b)J|bJF|?X!O!YhgM%YqP5L2pl zncH<3bi(mX?*SQ5;5ioWgYMaKN@)m96w3e$qP`@;1 z*Faa~cn^tb&+JtC+k}ZmQZ|DDSBC}MhD9Lt@fVkD${nx%lZy!3eJzYdlJ_pA=~DgF z*p=`FK-XW!1F>iVOWmpunf>j9+1Cl?H8SbYX)T@2sP*@BYga@K@1R8sy?cb&z@EYI zwEJCPJW}4$lUW@w-0Y)@qpJh5(!WCbro2--4=>}iV?aKWvbj#c)38y1`^vqgXr$Av zyufhcDv}JY5T6AbefHd4juUv8!9qjU%@Y~$ke$%7$ud+nz-wGz zSIcZdds9gi>L-yyqt`P}9s^XIGk6$zt^`%rTnL{j&OEa;&d8h&0`XbI8rl#>v!sNU z{BxzZe+h-QAJB;};AE`17C}tB!%-#G-w*wg#l5D|Sn8}{V6V)#;lh^=Wjs{kLOa@V zgt;yWWAb|Uobb8Nl?`_+S5+z;b#a^NUrtaNnfzbEH&TvKxv85bd?Io_ha>Htbkhes zQMQ_mSetNH(rB+}_&6xgv*2PqUL@Ntq^aLRz0-SP4^7Pk4+yIAG%QZOY?9V*l7@BRG0vAs)RO|ZY{$wCKr$`pG&r0CV|65(S zGyU5vQ9(x13bYtk$weQQ`w-rv~NPA(V314IM9T=XGA0>Ai zq8dP!rY<=6GkJCFBOG53kn;y#9{uNDxxiNPZ*OeS?73LOI5ao!8H;AqzbJu-4Bcw~dJD1k)wZK95XUNWHJ2S$yFT zsFLKI1P-N4b!nm9X&sF@MBN>6_U<*%23JR zQ%0{MacHrI1(>0`-%&*t2B*=j9+E_5`%N}`Ikr4OBm#g?3Eq5I>H~8LZ5$%4Gc_77 z{{p)Vv2?L61$zrAQkCua@Du@5^QBBeuB+v{d`wk`R;z>v`)*N(5g07-^fE{d)|h;v z-BMKq?Bks}s9llV^Cg)h{wZ8sfmOt0irB38fbOEgbRswv#v!zaJU7Zxj?Iqk{B*7h z(fK(|aq(AB%_wl@;3QGlgv`XIBBo|KY!n9fF;F$UFj`2$f@a=mqijOv%hrkBs9Ky8I(?ZWMX+D$<|l9^#<>Pp1X$Eg}dMLV63-Ry}p&XDa0QutgDee{a>u?%u_ zATRytu;#xsYj6`E=`J#WP@VQFe^LZt7&0uXM|YY6d-Z3_lB=qA-hqqtU*-ZTT%I+KI=^gPoE>@ghv&*Mx`*d!_Hzq4{|tQ z(r6IsZ%z=C8%)X;|BOW!^AMQWmEd>A_hn*PKB1PiGClYgN#;;)sd~kTjh*~yH}qLt zvf9#Vh_?STBk1AD)xO@#JX|^Qr22tvligHD33H^OdpoG4=u1mHf-nQB2 zE2-$$m?zQWr$GAi`WT%2FJRP{lPwVd1H+)qv4!9(UwvBbDYQ^=7ogMSCEuGKx`K=Y zL7viq%4B4f16KfL${$70o;Aa4D~bl&SwlbfLJftf2p;+ypxXy=1*|9EbDf*^w=AZo z`q%SLSUN|ZWyDmgSmDvU*#c&l_(ymrPAIqc{xL%)S|Cx1!29(mBI}%r2dV4Zu$I$! zUkG6Vj2^{R&wzGx%Wq0zSB<49KoXmG?=Rqu9!Fod(G*~E9OtLqeS0-9D39X9QZ&x} zTmAspl`R&cL(Snx({NV(&m8PbU$HA|>!Up*8Xi+`Y1^uR-?XZ1DnUZD9x>K^)xA%8%Kz)cfy42RU+N6Fi0Y^a#eILQRD`FyeX2ZVO z6iYe;z)>q;br4EJK?5V@7Ks+Tz*vWKg~I5cD^(uQ9?CpbEn(9$uMf&go1{TkF(fAk6>Z$X8ugy01YNfimd>wx8XnFqD?eAA@yM--^c)!a zXi`y9X)IhVFB3#b1+ojZ^=!Xmly#FaWP0KJAjHpSrwuad((fofOy!maTS+LJn%OqE zs%4N0d2G<1DAnYt(p?%U8=;*ccEqtnw<34@S9E~ybTz|3b1u>0I@=?t zzCe2mCzy?ance}j6kNo*-svxxYKmb_bR*x<;@v~oTWIE<*AXaqvR+U0*AP9Es}SO|RQNIA@FUa+zOO3B>eeh&^;N%H}%vf%ol$ zK~%vDb27Ka@Q(w*q)#Kq4Bqo}Z}}0eWFTA7L_MUI%e(3S_B!Ms{Tq#YY0p8@^L1W* zHxR$yoU)5&Yo9UnStEO)?AOXmR=Xz1fXeAdBKgoago!C(KA8<%a* z*(d3v^wvS19QoA4nPDY2(n7L*5!iq85*42jMN;79>HLu#%*!3hOT}q_XWHV{+5IkE z+L|=E0@U$8X#HxQA07nExB4fD6CjrIq4-PbFp&W4D)OUdMkbolG{ruQO)cwabM+>W zN%=9wAHaJTGT9JkpVwLPT_F)-6jLP#l+{|AKVDRUX0gb5MpK5x=SbRtdNqCCrI4K| z*X?`e7Hb@D;h|qa%Zh7GM5Q24kAE6wJFF0edCj(Ii0Ar8MQ(FRgeXF2H?RVY^qGmy z_gy+ck(h_?Waq0U2V6}{uk=nfr->=suRdbaonV0Os9U2{f+}Fby?VI#~dfx+Dc=hu*V!rVG=S`WG}sX*DV3J=iXFIMWK?5 zP+V%afe|rhQ@vIoV;5o=w=&Q_ID0uaVt(#n*|&H^_vcPpQ>Ug!b=tJ5SI!_@?VJ3Z zP8@!XMrgMkWa@?NcxJtKeoP?sjUhC3Kf@`$dePR;Z~h&Ay)8+=R#+_JnWktm)(yDbq-Cna z-zw+y*pQ*Sj2su(AIe4j`lI9T^~HQll8S+fFfs#q+mO}}#Ms`n<3PkaMQ_1zx3gGG z?EyjzeGFcv3fcF{$-~s`h3xaYA)~3i2dP#8b57a%M1Q$7ZGkthI8sV{dyCzvP*U;D zto225EbZC_Zmd1TzRAqiOjpOMbNK7b>lBMikwR=JKP1!JR>8*t&z+BB?se({vI8kV z1DWp%1mfrQPuEoZ+O+Fluy{vQ8j|u@kF2>ZPb`6x{NmMqb-JF}B~Q;V?Hc>=Ecd4u zxDJ)XfH!|?*2_BQmV8qRt;&r_S~g28p2aJ#Xm+3#={t8 zs2)NhYllpQgPe{Z%lV&>SOHsH11QuE)^hQ0ru?iBo1Yv;k>*@q@2(~R7=NmbymoG0 zGOsg8ymq$n#s?s56o6YF6G-}H%_tfAl~iZ5j{(fi0q`yf~1JIXUI^_ z)?&nFwPk$|Vwc76&e>g&WG_xtjK}VW(EXbxOtR!4_`>_ja$p)d7CaOC2Zof3IJ0!N z!a>v4!<^kt?2}f*P|zn^FUewM%l`0xOp;x?F`UqoXmdj|4rOUymY=3Z=LeIBV3!vX zy)cM2cVs=>wO}*-WpV#eHW)=sCG-JJNEWek5~MiS%6j|lA3>jajhuTa9@i}3G#z`W z!t)XkSmDjG&3HmM9kxv4A zIo!4#UohO~JsC7T-k>#&Ov&yPD+h03EU%)ssm^@*N}&eO`e~~D zj4ewKdm*ipQz2Q*QzSbQd98n#G1%{R`Ssv`JBM_Bj zF}&vmu|?WaTtu?VDvK{>{4CzQJ_+%h^y&Dc&3-Mt_98$6g`Jt-yTeuY&6^oTCu@i3(DFOG=;Ywd1LAAXTQ=yzi4^fPqgK!9-*%M z<69vjX*lxDF>SHoY2h;~0SRs`5O`)Z8M0V{I8JU9iR^r`f4X%q1U3|vkd$A;g3-VB z^9#qP^M(%&zRBZBV{EM7FF=`R8D?tpuzjX_ZXbFMe6mw|mYjpUiuzGN<>#otJ`` zjh#O>or5%`*&l2>lv135oS7`3C+R9=djYzm>jGlzNbZc7D@O9JDUNY$TSl1;lV^?@ zCvX%pO8>Q`7Rp*FrF#gK!47qWM)v+_kqI1?y(&5l#^}8PxZc^(A5N%0tTm>pbaT{N z{_>JOTdh;LF{SCa&dxBqv#hPJp9Qs=VGGp^Q|Z8>A&9Z_f#Q;z~R$s z9=fG>XB5?y<@L<+RBpSZJ7V{$S|q8Bbk}!d`Z!CA}j;D3j1>OgRhKf==yDJD?D8s={i@E5`Z}RfeV; zWeYFfeHLL!YxC&1!-+%88Sy{`ttBg|PdW1=MoU#>6BY6Y?bNHi-t9a*uh+4**5&LkjwsanYSnaiUY)O#iPJMh|lC%tC z97UFcJ?p+1mOps&Wve5Pv8B0gI_fOPu*W_$zl_zvLOB%o3Xit=^>Ma`{^0Ba5?RQ` zu{&gd*T49)POm$`fTE~YODeGzbsc;(Z%RX5dC_ldpxYKt6#Xvpw{1zjqTf^wq2>+5 z&Rd$v3PmS_eT~;XeS+oSL<`7F(8yL6tvCU$`=>V*oec~8JKa)E>TaO@}C%0}z zuib;53T3{DSJD7r)lexRuWxmdlz4}c_ajfyK=y2xHqmPF8Qn_>9m`04c>9V)WQvE` z>qhH2XW0yrq_6gNS5~`XMLDIOym)aTdPtaP8yHmkFwiR5!f(P$I6G zt}~`JtOQ&*;Nj=e8D6(65@4_4tszR%-`0StZ#rQydZOV?+b8`2m1dXi2c2D=1utJv z(>SqkKZ)#mSsfj7wRP6c2=C)~3LrE?ejVQO76g7*_a@o@{YXJOdiuUK1k z()a}Jmq)*28s!hV6ByLlYp=JdWn*6?MA=$A3-nn$N>9ur9XPD`H>`sWHfx`d9F;pg z(`k=$^VQN(oFaEz*@I3ef5skZOe0n}ZP1gRg5+EBC2Y~EQ*^u*Z!5^%-cgwb%9mRX zY78vaz1b~SOsS$&-`k~nMWT|X=+jEupxw5Uk;lmk>I-ZUB*nOj&LCbRxdlNlLex@H zQZ5roLJmA{AYlt*#I}FwngC-Ly?rT-H_+ ze1b`Mb53xYlyxa4RAQ4d!N;B+sC{)~kG(GIiAU#{<{CoBbK&KY$MnrX=8BA#^4MD446+Y&8^C9PaMC|LG)?w z?1}J{*cmKX>klZUA=n>+e?(fsSE(dmTvsX-NFR^2dWAByroC{KJuadZF$$Q$yykga zwMM+vM6liyII1q1bjNHGxGLbC(za11>Uwb}p^Ocx;9zmcRkr}rLr<3%Vtct zQK57nxp29LpX&S#T#xM=FipW8x(5+M3OB6+mFrV;tGK2luBe8mW@L zmbVkXT^3)p^~lL$p>2Rhm{UD2;swnHLR)K<<|Zl@h&>D&4*YBN@)?!dj4pD~$<-Zc zZ(x$9#*q}ow1_Uq%0 z!IrG6mv`joE>^_3pEt_4p8D2=pp88&K|IjnC z7$tndj>r=h2G<)^>zX*Dv+GoTV@h=KIPulWk_TA-uA-3_I;7~t-AlKhoEDyb4DF?5 z;UM2)>Bqz*Mq?ZHByQZ1i%EImRlYFEebTWiOMrNjNARp%QFj8*P8cHOch|&)BDpL~N4W1J{pq%iM#(N@r z9q+?j^HCMOZh5ArKYwv`b#?8Ha7LN#lsvvIzIwy|)R^zNH7)-Zb_GG!hjPk6zII%= zv0j8)OD>cws&KvL^O<4E)W}OSAd@>hFhqFXj$k4WyCkmN;4T-5@jRSQ!KpeL5e?+j zFu^MUD}&V5$YrMY-Vu#^wsB7a3*`*jCUjCAeI6l%^f31-XC-w%2M_GLEagw|P#R@O7`|d zZ0thjpI!XJQIt=ay;o1n;8PpIgxZfer%J>hKh>H;aD!Od=s!2)tx)Ysut@>eNa{6d zh#R1l6p29pGx@0lN(8t5<|O7nsVc~e^XD$XpXd(MYA%vnXLZ3y!^ERh;tlx_i1pv# zrVGXOv7!3!%bMX}TqU)<-7G5`=uUPY0?VGXb-IbPMob)y8T81x>X>_;6&h;ZB@3$i ziq3F+j_mxpmkEY0s?1qoNYT(@;|e&EKECR(MOsSG+E}i!22&h?5a*s1k4|KXYk>>S zmnzu^!+b#ja7 zAV?NHc-r0}m{RbhTel|9(S25LR@UlaouMczDJ>+Hm{ypng*AzWQjdmV4a1pELigWNt2KJ(LX2>%zBcK&RSt|?`#AzSIcMG(4yiC^ z-y5Djm{<)ig~K}l9pLkSz2Jd{V!~K?ddy<}MM%f>s+e{9;16u$Pk^^Ej;jNjqWou_ zHTjfZ_5%C@0`Rp%EJ! zum%?3XM1i&FJu2g>tO-GKfr|XAwdgkY@iGu=m>z|2o0tosI_%D1%{)mDE|H6T3YZBt*^gF;~Y=arVItKtXr?9*& z+*s%VV8FeDf^g>}tlb-^GfV^8c*4HraAD+=R6zsitG|`;C8Hvpgoxc28Nl^fp}dJY z@0f{lh~Vv?L4+154);AM2M`vht@*wpyfN!|a}2`XJikt0frV@QQUMBBY~Y89=rK4n+RW_}PYO{krz%@*|zVF@Wk# z$s+)KJ-@Fdy|)Y!K(q&s_3ihG)8xO2tY}E)oyt%AI!#UxZUgEe0q`L@XtgTH0(d0ECwcIa^pn5)xaphgV@HB=4c9`PlO?Xk1KCssZ_QPkWNN>+h2hUO*kkY- z898MQw{hkqCzkkIDFLk^lsiuL)Kl_SUpnsjWs!TlXx&zkN>I!x*LFPk87>;LyDkQO ze?=iXC$U>=Gs8_rB*qskp0%4cyBq&~?U+^1y}aI(txGcQ;#4lb)0whky^Bf@114{O zW~UZWvG=9OGmCDCVR)j?F_CMV!6)jDjz2RdGA{c(lH>F6W)ei@d=w>08y3E9POrqV zH)WzpabYv*+^{SFu_8GqW-l}r;w{6 zyXBX#opxk}i3cXja39A-5UVk=QHkvvC`%QKqckd(a@EJbVuT+yUQC-?=6aH?oFR|6 zi=sSrO;v*tRF76Z#|HA8-8_<*x>^)yG@B%>j#yCx& z+yWB@Eg+NU7|z`{l@Q}$x|+P@BVeyIHF5Z4LLABGiZ4zuxaMd(W_E``yeqo3BgB<^oGLeXock(T4}0D#5bXOStnRu*_f9W&N8;-awc7ehDZd*JTTVE^oo;05m1oMH`+w=<#NGW4Ni zy1CcZMMP-A4#21wr{Cl!@+AOpiuPSdzk}OaOPxPrR7L|WI@G3i?{~*DRTBcRSZ1puX(I6>xn!3oBOG@3T45P$TOve#zSc%hG zk_C2wlqbc*(Z=EL5N~jCf^GRYY~&O+D5D7n7Eu)}QDm@n#1D*`51Lditr>)@qL4cC za}S1#ZzlMclN?FCf+U&cj8>2Xyf3i-@r)XISs>rLMt2#iwA(|5AMIBDjH0jMP3uRB zrA*}sQ}|0T>@?P#@1A(gQaFoxq2l%el#mC|xFM0Nd~TgG8ckcUzE74zr?IrkE6Z!f z_4fSS+&1d8$*p>`0yObDFJvX_G)Bf)7TqUc`l&mI_qQo?mzyHuEzhY;iF=VJd*7u! z6X>5H*|p;Eksxu<7pbXA{pEElwo zzE*_p`#guAYm@)~rN6Q|*-j15A=H4=jN=aTjccGn^{u#KPUa9bn)3k;O7={dVleT6+}H zWT6!D5~N{#4YDfiH7ZR??LRQjeY8m*6Mi?s< z!4%boFZT?RfIu!XuP}vwkoJdp2bXgetTI!XK6FCh?BOSQ*bhR2P>^~kP>(Hl6Jgk0 zTYUT5nlXjdE|9Z)i)9D@j6`hPRUYc%leDiipakHbogmo=UoJY;sX4)>DdS3Y;)w;o z4?4StIm*h>e45EqJ}>d4SQA8Wu5dbqKO~6l5B5;e4W=Bi*O=w*FfPKQ(0;wcQfstP z-!r*Mq)7T`c98MdT18Or0b{eP+3{8gW(Y`3(QYQM$IF@!$pX7&T8iEN21k@czuR!K zvoKeB%!0etZVn~2V4!3_TqSZ*@SQ-V{CDe8{7Y}@LYY;%Gmx88#ODoaO$oY$I@!S|knU6$x3qWwk`k2F~Gkd&Ks3u{s? zFyffOY?3FWiG^MI86_;Pc?N& z(Up-IrI{*^8 z#8(ryP@-tQ84wp(Yr-U9co6*6An?;q?w4u>4`eRD=Fgd*zj(G>V@BCq1JIAZpBB$h55-qa>lp7@;l ziJY1;5ks)KTSe^k-Ae`f{a&A6#={TUE0>P7V)pidXD}pr4*0FZv2i6&M)_P+lyu?J zK7+{}h_ai+!EY@Z?EW>e7`pOxqkp+Q695ul^*;cXYJ8!gX$V$;O#lygW1FtfYAJE zmP(Dk0XBbK|G*2rD#>HCu@#vt$A9EODGif50j7wqxeJOw9Qalq!)wf8p~sinx?@lA z?@AU6M|XPciCbj0sl!G)-&ScD+2*Wjm@^n5s>EA_>)fC8kPdZs^L$D!0ViLJELfvY zoNlkJoZtKtnwr1ul@Ps7z$Q?gqQpJ7yB8{N1~kNp7sZ5F(^ilmqRhHFypcWpa!k-Dn^29cmY-1z*P(7+qwd<^kFq5O|LNnv1XI)elE6iB#Un zhY9=^k9DW-T?(N$f^@ow(>9t#A9 zErcgTtFN&|R)m|+m4yED4HVTl7TLGGvP*uk^F+_! zjUZH5q%QesOOHaP41@xXYGjjm+<1TdUea}8b7F1MMp;uf8}$AxiNd7rd}7fA`+|^z z1l=#&BuUS(6S!^uB}GX>|LbvXbcx(Ox(Hk6xX&}$o!TZM{4AYnyI^n^hMpYn*2-FO zkg!eCco&NNShETi+wXm~Lcqj(oz#`|&z;a&bdXNHYuNkIcaU8(u%Nar#3Q1Gh=VVO6$>bwy;eB#Wy_eC$fJ&eO%>4;> zFudIM+bS-{inbi#u9lbl*&shsrR3t|AA^YLJ_y67T~+FZeJq%`R9n9tD&s>)4kJ^_ zCi9IlvPhWPx(%-iMDDNo!{pSoIXMXP#a7t(e#=Tb7-BPsNmO;H-FG*AHq6E>hiwMV z#!Lq|;3eELH;pe2|2|RBZ`$fnnvkz1&Mqk_wKKW3 zS?9FYX7pFuZh;DWW^7~1Z?_}-;VqeUaMvcF^wU$Nk!xdvX|JvVZ1&WvqNrk11Ci)r z9i%Il)7R(SGbc#TRA|Mjq{Q6Qjel(9I_?wt&y|Fe$r|oQTiCI-#Dia%CbmM)(ucoJ zxfYpQBF0R}wl69xyQ2mfs}jt`11a@+ipm7;^j>_%SN5#H@pwj9c|4j%?J^=gC9j%HbmA zdCL~ddS@rc-LY-Lx&Ucre`QN3bHtfbVt$;Fj$I4tFs)CQU9v8GyFdq%md_y92#)l} zO{l(OQ>E7rsdmMkr!b@Bs65*Dw5Vv^G3@wqd0fkQ-1bY~=cgcH<%ALvrLU%Dv6|t=2Se@%3Z0K&SJeLGoO(5qX=LB@#=uF;wuZ zMj$)J(3rGDb}x>ny5vDO+?uG$@|$77dHzF-b@Z)R)2f9JLE>*+cuYwY)>?#Dl!jOuLYP>Kmn}UJ6LT+^gAp^?@llgOrQu{WT{l{%K5uJ4M33 z<%0F7+-Ewzl*yp{V!J@E$?@+(yt3+{!l-$95#Rjv<>KTA2cr!3Y~qM8ZGv3=meRXO4G`*G{%*l7iJ|5u=5`qGZOjsJ_5clp}caSa>GL1u>+CkN}* zw&AEv%S48tm-&{Q!z=h9XyGe!wZ&u>?L-GygIceN&j1zLAM zMkm`DvSsLAQIriSL)(9)JQB2b(YUxYbK2;Rq!HMTq{!2OiD`D=+1V_r-<|k;Bc{W>GE?>t+~?bCn9sbY;A$J~TT2!PdpeCNwwSG2>6 z=^$3`)7+T6yjs9J(}hQ6#Qw9A?<@7^3se=0<*Moi!7i+W3FuWZN_6+mgkis?!7zxh zYnSh{ay1di^EnQFTZ2VZBE0>^JFgQ=#R}|d%q~xR`z=GJ;H72x-w>{e#CW(EFy%4g zU1&xOiFOy@JwI$fH|(=+9F6J(oea1)<#THx+$m3ti%)~A3v#y-V~jc*#j!xnW08+V zLQU!YhY;~=U>-v8NX-xZ#X@WTAj#%-7Bbq%t7z^CCVf4ml8&v$uPDGPCCl9LulZI%3PI zbU+VoVBmp%hlSuD9>6=|Z$@SUO{8Ro{o{Mh#+n({y*d3B7I(g8PLlkT<86xdnQ<^* zQwmX@j}MMkpWEf50})}$0o)SOWmT;kb0)u-9|~cjvMDZb-JrIv*_A7XWcG%9 z$6avS{bF15MvOMZs24WC z4dm^kaCSLoQ(~C|Fcj~7s9G03qwF$T)KytHn?vHPk+(UuB=yJ9*7Z6a-($3X zq2+DNcGDGOp9X?s*Z$LNf6AjqWuv?{XA+2xNia_wreBC{qj2{`WKjT=vt7dUmD9an z=^XJTH+DHrHV%mDpnW3dL<|Btmsz{7LgFGXTftM)#?e9PEjnORZcmZP#%-_hNJ}+k z#Vs#3dmC>>2WL<%>xGEA{6f*V}p1D>6U#fEd^_fJ$t zU;d8J;g`$4@Mg7w8?v|7?tW_+**nvFZ$y%}eFib^QR+nsV#BXZG?!-E=x6k z{)myzr&0@A|H{o8pgb*D;d>H?cJ^SSoUnNd87O)jc9cjmcQt{_#anMTgnbw5LVW&V zC%d3i6fb62NHrC!ORPadrUCan*z->#L#+829&Jdjpfir)FN`$YdI)6d@^7p;-~T+1PkhdyqFj zPcS}-j06JUhiQUMn*}tEaw{geP22H(Ea{eVEX<=)%v&zINxdNLepj$dyTfcF zRseAi<|{1AA{#mKg|^r5a}0L|@QnE`muNquYPGxM!@iEIx3iCvd+-6{o|Tx0;B#(r zNejf}!hp=O(Y5hopTE9avU+Kv*lZiu>gbm8GWw z9rPCL3J4@`k5Qcw>lJ6*cWi^WM&*A027kcSlZCqQf=#&|UB?h-98RBT99m5EnIWk* zc7&(MDvwqZ)vRpws@wA_dpYj;{ED*ZD?-xSr>}fpV12#f6u()bSv{LW!%ieLgIQ9{884R`YRham*6mEW}ANzCNju6`ErAY_Dot4G_{K zmUbjpm3e$#Xe@wjR$IgbO^+E1N6{_i=CY8_U{uvYk@Dku{Tc}HUG=*KKHc3#eSne( z42ic^NnT*+A6w~~n@R-ud>e3)Sjt|i{d%?Bl#I4XyS<0a6um_{PL1q$SxJvk2|0Z? zDQ?Gj|3j^f|4Xx!aWZCvj?&?cb?T!`oTnCUR%o^erE%gD2@O~C8=*&4(#x=n_q&kB zNoC8z6yc=QSWcfao(pr15cB&26N_RWD%`Xy365@)5J_q(u{@dBlEOB8A3fH44}`0Q zn$g@@zLYli)|z5kVJfjHjsC0_7X`Sa9MZyYPnrj(>|*n{Kw=s3Cih*NpE0n!^PQ8Hs_vuh<_g5mm$Q;vyP*F0ss4Fxa^bH1Qi!Ow(EDK7TRbL{rz{sGzqAu4)yD-rdY3gzl2Z5%B+eF>9{rhP6thIhZU|Zd7;M1F z{3E+Nw3futDp5*?tF?zDN3a&>P3H7lqBB_)04PPhpHepjKT0&enM*e-jttU390ca- zl~0dT-$>1SVvovrvVeJfiteUX!MTv%__q1sbpe0l&d0*Z>ozY0 zqR9a$l;HIX+-2Xj_MX>SLf3p`1-j=S^BfWNdvygJxC(`W^2VfidPK z41rjL=G^-;dEc~E1=d0U4EZ3Hs=B$Us@ZW*h-(qnp2kYZXcig!1dA5y=DOGtzdZih z8AkaQMhbQjq#FAu%W4?y*1806uOrLY`KTw*Z0uBnV?iVvD;EnTQm=$YV5C?xxyGP1 zlHfuUvB=Y==yaJYL`vCnVVU`K{)i>E80H>=S5dH?Pa&?!U#pmw*865gY$aqB^LTstEn*?r7g;3{ zntRd(k5XBrrtFzY$<$Umr6iq0RNB;f)k3~dG7BRJMXcsX*+SaIAZuBduZ~J*8yC@FQkNM&l^9xYiHkO>OQd^Ji0=@iWmWEu1zh4C8 ztKi{DC3+-g7TImec+3#1m{%bp;@sh^^|`mZ2U5s+6%j56QCSs~dTe}D!~V0u9;!V8k#uG>m^EjG=YhBTM>EPossIkjZW z&56IIAM5;WzYm{%UXD$iHm{~n%F@V5H0Qet@?brvr zkj4Kj7>GwMH-dKx^H}yz;A%)}b4ZlVwJ(xa{Oi|DxP`)nT&d9bf@7leevwtvReXfxM6N}7csFs6ic9SRWSr{ZSz9Gh4IJoM1{CgbXLua zD~+D8xcBw*G)smWQy^ch&fAVZ3Af`vY85kCo^%_pjSFgG|BuGL0;Y~=>$*@1#ih6x zmjd@*oZ{|Qio?Y&aB+8vySo%A?(S~I-HW@s6qlcuPxA7=mwYdoWX?IWk4$DVdu7i) zYgw6G?(L|{$^eBw+oW5-ld#5l6}cfCv+lzJZa!#e$~LP z+6aT?`%ENQb80oUnFmH96b|KLR9kFHnht!TqZFX=rKHLa(pd;9C90cwsVj2Nj0t3l zdyDnt#zPJ29~XbAna^#~CahM_x4lZ`Iai~zEM1>|uH)Om^!+I)t%QFVE7B6`RlO`Nia&eOni-zIh@C@DeT)bPK}`)2?Eww| zwt#6bZ$zsVjT=z3RBDB$_8TsEN2;Ct1Nm!DKIUoXz7>z_pp!U3U0xNu_Mt{ z-S~tNs!6nED@ecK;e(@o&3|**(RqykM7VJQ^M{Dg>ErnGzH*qRxdwI)6+)(rh(SBU zlExQItc)%`Lap*XHt&YD-!UFG47Q*Volv>*=Zz50b1g?F2jqqpRuc^5wdx$XAG#}! zkaba&Nlj48zz@~Xpw?A~Uj2a*6sg9$fOqoylox3@fcA)>kUx%l>8xk;kCrptV4Vqr>RQ8aqaf#Hl$DbQO0R_KS7()zI8P zB(BoKRAf}sKB~>y+frNn*W=_{_^tEOw%iO zKl@Kj7CncHjU;?*08^rBiNzn@OFR!7BUY-i&H*Q7c$T~q4sa>K0{;aw9MPvQWCt9W ze(J$4Ox**7VsjJ;xK8cnJLPKzHz25(V`C0GXxG{2QRvDaC<8?=F5Gl zKPs!2)x3vQ5T3{4*V3#4a5kje+9j#3n?JSHsh8*BObhNVVavhg+$*_9;Tu#|#QNcf z)om8l)oEGR$pESY&`TiYP&g=R(eHJ{(7!Q@@z+$p%*^GTYARk0x*x#3i7Ir&<)x}* zSSo?~TNt0Wv42wLD^rb;3&dTT;!b@GLYUL4*TK>=t#DxvaA8h;2UCkVr?D|`SYMHu z(Z>G78H<}CG}vrxE=dt)PTkulD^_1NVYElpX@Dm^2AD2~LKll6O<5-!24RLB#5UCq zKS4)2>Z4!iBX#-o$aUot;NDdk8i5$^?sUt zbvO{%jo95_LHo*_`^w@5LJ5_v=C{WztEr28fo8^dJcnUiB@&L2_6u}`LY5f==by7l z_Zvm#)D7dja;zm%@Q^>dx$!#fi?P9)BylgZR(%W=3zEJug@(j$gg@6!(u*yAD;DfIWp z^`oxY)P0@4?=^UQbdgu3v#4X~|2y4sFyDKNygXt@y?L-Od3>6`7q z1MG=QFde{^fQtzE7+0G=f@xUZ8e|wzN%g%16MS?k)0Z8b#pT$45ij->jKynZMY%v= z>(`iW(jXfsGNIquO6ifEzWN$5{KA{Jr4f} zvO263JC%x>APnPg>47nv_XQ!B7z6*LHc1G`J)7u4uDN{quoolbNmI&)hHe zLG_(@%fswu9rTlpyFuMf#ufxqy6skO%DkVyjwNo*N_w@;Y9k&uPJmAXD?CQOaP9kA zdFIl})S;+Yj;f`&*U_6Eu{a5|6&(R}hAI>0q|d|KlN6oHypmMS6B$$L54OK%F@t-o z59=PS-M&2q`3iXmxbZ``g%sRR9fgZxR|J}+NNTwC!; zgKuzYR-F$aCy<>Us@h9_KM=|iKHj;^b5lPD@;@;S^5$#moHgG?=&7m!5>tgmhE_$l z(>k^Y>IG@n?FRVW1$kEtWnt4fhQ(9 z*3Aw_SJ^%HEavub0Y!?Lu(2;Hx!WN|KQ>%l5c?{YozzjDeh?!J)?lyjx)_)26JA%N zaW>a=UxeT;@5GgPAsR(P^T`r~R+25rm7A^)@@tPWqA={-GIUq9QQ@A&Qt7D-8#Nc+ z`u=T~$UQgK59$68vKp1s(pItTQzm5;lcwse@rg?kF~C@Zu&Bh4emi&mvco{Ph>Pw7vLf?X3MHkX0td{PBj5 zK@3eeX70B%%qsegX4U8wqMqcY_;|4gtVb#%F#xv@WUEiVX@Bv&p3g|H zox}zi{DC_BWvhE>f;D!kypaNt^i&fT94y>JKuP5BCZ|e!jNP%5XkUxfYOb>`Y-ndt zB&!`G+LjU#U2V~=p}>pu8ab+1#4E}#6Btg+=f>g1%*f%IvBfVX844bjt@N`(!JYuZexWM~A zwRO#A_pm7R9Sx~lCZl=IRUefT#Rz=8(7T1+l_DP6rYYGh@QKaIqh`uEQA!Ep?35XVG%N{R8Eequ^N!i)Vt znnUu;n>slpX`I=4l~{SX>U!M6t&QA_gWd57O)66>P2MPyr#~~7+lV@(lk7uP`lk|( z3Go+4e{eTqKjkZ%khpTUJO~^$#I+TK(4SVsOOGrIP}?IB6OG9&RVv}I-e+YN~< z;ujqPn1nki30kE|N5@Zh?wEMPisxJKxalTC0dfptO09Svpqh2#@pr3u%ih(6e~KzS z&X2iN;cneaXn)0QssBAR{Jno@+J;v86sR%Iny7dgxd8qlW5jJ*sa=ao42RGz#7lPb141R*-MBs>H{60;XfLlX^TSjPi*%e)(Co zg^%BhKZVq*pdY(l^NXKzhgs{gPPjt8MATTM0u5@GfV!;w+GeV2i6@vQrYTW|NE_if z=Xpwgad2V&qWAWu^?CB;jHNmuo&NJg^KFuJL(GlGnZVbeufnMWyVs1_^UgT>afNp7q%{S_%BZ1wy1VDDy8p(oex#2CR zpEGA`C&;QobnE($k@4q+e5vUfks6p;fore)ul(F4wHF?s%&~S{$JS$eL&~`8v)iCE zw9l0a2xVn3oOYe4;r%3q8dW_-sYJy*T0;l$e>OJBzqXI`OT?Xp9o)|^c#X@`tl>V# zaPO7|GLJu!C+#tM3(z39K7sg7`EGROf6OR^U7dzhsj%+2PP%K4?ntD1M0QB*&y|u5 zO=Fp#g^=#mR3u4+RZNFn#a*nOym69#eR2CmbZ35PD0I4KfW&-*?nbHgczp761wF`P z;=QJYUP`sX)9swv*n-86vB_tF%qvt`{?*_pB8|J-#|qMpRcijz6Eym8_Vjz316+Gk zYfw-}_n&1mk&OEBL8qtHc8Vh*r>)1@YLd9##%Hn{*xwnw4jz||4<}kCyf0J&Xx<$I zVo#pbt+QcBqE*2`QC>sc9vY?2f`?y-LW|7=1B|fQj6X1`54af0(Zfmo#?=kse^47*@X|nKRJn)J&IPW#v_C&@~?7+r>$wX z^`eYvYibsgrLY18D!yi2Z!a}KhhJZ^jUZ0kX9&{KG>C~~`SDE-_rp^rDlge_%~x^5 z$e>U!-7(y_3a~tWu{(y~k631kim<^06%JS6eVA%n@=IeZ@$+oRr5lPBXLaScZoAvf zA$R7D;HGIhRU~&_5cjdZU#$!#wNQ01`S5#G?JpC zVdwl|^oboyxuip6+awf9%xO15eH z&~ZBRES|VO`Lki1R7eONZR#%yqRx)^hjKM^R=6l<%%cs8e*MhY2-(rFlPHDEws+KI z@Za2cw8r+8RzoK%B(wZpn%4V^h(PgeHp=;Exs~`Gd zXt%-R`+A7G@pINYP$zzFMnV5m4-W9Tm&dHhA947To|`yY>orhM;865$<|hf`xpf5I z4VXVW*3$b(t}@Lm3UnuY2Wpzn;vAN*Cvht$A~d#i53~nkbi9Nn!hf=bYS93(8i zr)K-SV&feQ+mgET)6TXMX|6*`?}rC^M32zr^Y;fKADzlF9Wb=#=pk@fgBwFc6Skg z#YUwy+Y*k0>Kw&{?WOjf_VGDGc zC#1|UJVIELtYJP<3Zzjg|C*~4qkOn8pDXz%Kw3=dqmKV{qT&>DgANzE32L)x<{tN6 z%AUs6>)LJm+N;j0f>%gO5HKw0zQ+QkHv(!@{K4j`(l$p4CSi#DTaiO-dpoT!@`i#_ z>2rDqmWeHy7Yj@GeH4 zixD+VPODZakCO9AZywPbGuZ;|R}3_>N3J@-2g4x^ z#kMI~5+w@>4)vXf=tn-fh!A1w>>*t{xBq z-jw9c0E#ZqpFt}ukz`4*1q=W!Sp|M{IUH?W?_H4H2kf2q8Aw3h(_H#dQPd5616h6%eD2MRX<0CyA)V1~FMYW~_+t<$ae z*L*uj{44#nHLJm}f46N%7u>q_4@v)zIG;Ycr(h&{AfE@);?AM⪚i8=+Y8XIC%%a ze-vmykExDPOx}xJ*Y5I{?K=Tvy%cG?$A?|Sn+uzy!b(#3U{f( zdOu_b`(?h6G}%g^u87uTv*-)1Jmx+7MwkCps#g_xqnZm*(BLHe`YGro`EOtbw<>n6 zEh)R{(G>|a1otWxNjm@Pc`3qaW>k~!N&Ju@$GKU%qkS;S=Mr|ejd6E50lgFoNVCRX zUb>)ruJfB^>1`ro{UqM9&CVpxjgUL0 z=rlvZSZhJeoHgwy?5D-UQ_pP{X>QY(9|Dix&BNkfJ=m1BX0aDY_Z}h_(wfTT6I4jI z|J0TUVuDw}sk2UX)dx3iMk}p5$A^yvhBiI#(~l^KGx=VJmlSaNahLD*f4XY_Y5c%= zdmHM&O2%cVIc*QRV`kdip01*+$E9U&aeOzlboHon5?BvaqOjwz^<3{3kTW-10b8#6b39mQldZ-}f zVcW`{Gt#ActE_uq*VtU~a(Hu;A&s@>o2+jJykgnukJsjSoFYYQ6)J5YBA#>MhfYql z+ABv-Ph8?LV+)OMYD^6Bhpx~R7Syo)@I}uym(qjhn1$__XE%vc7gYqM?wX^Mz@=TD zsF%kJ)(WKNTUP|}m-g;7Zf0HUP=u_NzjGk7`?^s)9D6@rbEzgCW7-@_T-py3%?=Um zRACNbF69F0-vllTXAh%rZchccisN>8tZglv8~?7d%b<}Eq7)tMIz*TF=WJ*M86?3M zWH##IN<{rVOih^bG8_&yzRkYXkCw>kf{YKNS&C@VO7}kdon@R1*!)RVyC27sy79&0 z1AmXY?Js5Rc6wf9_fn$k1~#Ue?rt8mG}#cq;Z_xHh9$D*Ur zO!jqKv)q7;c{E38$YItCMfQP}*x@%6nIfFQ53~BuK0P6nZs$d0bStOC(B@ zZflorsPy2cAJRvLH8cPB#i>-}*>*WKNGw^dxuyr7RaFEFaN?J9ivAtGLE22h=C?+h zwcAOA58oRZD>tt0@s}LF0PLuxmO6$0XOA?2b2`vNxY$?=*~;i5{3E(r4eo7vD2LZl zv_{+KWDRH$U)pN)kFwoPpOb=JT<1!o>Xu80efu$RCNE3W$)nN6dD};U({RnPe}jEE{~7xTIXakH+tJaps6ZVoAaCbyjs|8BLx;DL z$eUuc!`n4keHDm0xii$kl-%?!SHjK?VoYwMZ)mP>0-G66Vg0RY-J zJ2`8k|I0+hPT$4`V)UkOt#4ruL1Ix<5mRRtceJoD(6_RB)4irsF@@Tbza9Uzo-gF8 z5Ig&~smWQHfowo_ZV(4M6Ns7Pf7bbC|8{S(P$vjE2moYf5rr5)^{wd1&297@Ozk21 z=bwP*TW;6kzfDQjY}v>xmQmauPA{-K`?lR=0uZrbA66u+}_M7Q#R(dz>T&FjUG$2-yW6MXd2_wUwS-6WA2}6(IeSBb- z9@F0s@%nVCfVYr{M}QukVLbWLZ+&7hSvp^?Cuy)NT&tcmRweEe1)&gL85IcEM&Ck| z*wD1z@S`7kDA#nK2mGX7KDvaqfsH!i-LJ*R>p}DI7k4?uoEi<26QhPd`4tPsM+=uC zPwzD|7IUBz&l6Fap1xW7I4sV=dwiN@qYBqMIT-tt1sI-v1ef$LhwP~>V%1~buzY@Z zf0?C{SO{VlZwcWI7xk(EVQL52O}gb+-@>c6`{9<)32UC;F%yJ)g)}I|W|j1v^Xxe( z;|uB`0twwR1v2koKDBucTTH58RZNCDhd_lQR-X=-J)SVGwOEhj1}#O&t&E4nX;)4` zJ!0)Qgtr&%f^^BOavdftUlkQlpLAY}SP!>d4m-oX@!ra~D0e<4ZTX#FG|e`+9Q-Ol zYCGorQ6RFZje<^=z3O4HF$8n_iho)%yiqoHweM=W@dHPG&^obgox6>A^Kr zTGt+W%W?CV8SMn`aT7p!OEB`q|aXVj*KJ_cBi@}4X!iM^9Qq= zbQjwjUT*0&@fiiO9|ilNiw;Uw&HIg8V^8=jaU`uL9M-!j`|NH9w&+OTD_O!XHgXQkW;YWIcqGWtHdrU)=t@2MSlzsEE-HTn>^ z9Bm%Iwj^D5O}I0UAUYn8k^r$N%UZM%usGDDOEfaM!N_I2pN+v{haoEiL zM6m@V-BPYO*W&tIl6WoV5K&y^=H$WxwFY6X1#*vq>;Ij<Py7$_U~@ zt_2_ma&qY)v3!HNLHkYNF&? zyxbshA#N@aEPg{bMg$o;4FEU zgf(Ghvd{?iaY_T-#MqiILF!{{tHynhp*{F>WX)X~IuT?Gf7A(Sp9Ctxow`mLT81ljlx#A=TNS=N^fN^Z{dzzbV;V#> zQai#A7^8mdbn+f|psi(We$;MyUoS-K=NY_GiR{!vy6@9Af$Uj{&M;9?*y_;s4EQKw z^A4^1Gkzc@7m9=)c4Rk@3ypT2D$RG=27Zj;fvjbcyLa1n+O@Z4PaY5ZEHIs!fuD&- zNBQaL)Ir1S;n+cpu$W6HfrcloTuMQgJ3^{rjVnTiZ0)N~(vMN@6~*GmUA8PXzD>5G z>wUjzxx9ut#+JNVt}_R%gMP9C`n-+}2MIAP%hTG>t^#>hhJ54n(_$B{QwN3KFa-JA z?<4c7fRat;lZ7 0: + rel_diff = (chi2_prev - self._chi2) / (chi2_prev + np.finfo(float).eps) + print("{:9d} {:20.4f} {:18.6f}".format(i, self._chi2, -rel_diff)) + if self._chi2 < chi2_prev and rel_diff < tol: + return + else: + print("{:9d} {:20.4f}".format(i, self._chi2)) + + # Update the previous iteration's chi^2 error + chi2_prev = self._chi2 + + # Hold the first pose fixed + if fix_first_pose: + self._hessian[:dim, :] = 0. + self._hessian[:, :dim] = 0. + self._hessian[:dim, :dim] += np.eye(dim) + self._gradient[:dim] = 0. + + # Solve for the updates + dx = spsolve(self._hessian, -self._gradient) # pylint: disable=invalid-unary-operand-type + + # Apply the updates + for v, dx_i in zip(self._vertices, np.split(dx, n)): + v.pose += dx_i + + # If we reached the maximum number of iterations, print out the final iteration's results + self.calc_chi2() + rel_diff = (chi2_prev - self._chi2) / (chi2_prev + np.finfo(float).eps) + print("{:9d} {:20.4f} {:18.6f}".format(max_iter, self._chi2, -rel_diff)) + + def to_g2o(self, outfile): + """Save the graph in .g2o format. + + Parameters + ---------- + outfile : str + The path where the graph will be saved + + """ + with open(outfile, 'w') as f: + for v in self._vertices: + f.write(v.to_g2o()) + + for e in self._edges: + f.write(e.to_g2o()) + + def plot(self, vertex_color='r', vertex_marker='o', vertex_markersize=3, edge_color='b', title=None): + """Plot the graph. + + Parameters + ---------- + vertex_color : str + The color that will be used to plot the vertices + vertex_marker : str + The marker that will be used to plot the vertices + vertex_markersize : int + The size of the plotted vertices + edge_color : str + The color that will be used to plot the edges + title : str, None + The title that will be used for the plot + + """ + plt.figure() + + for e in self._edges: + e.plot(edge_color) + + for v in self._vertices: + v.plot(vertex_color, vertex_marker, vertex_markersize) + + if title: + plt.title(title) + + plt.show() diff --git a/SLAM/GraphBasedSLAM/graphslam/load.py b/SLAM/GraphBasedSLAM/graphslam/load.py new file mode 100644 index 0000000000..b0dd023d93 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/load.py @@ -0,0 +1,66 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""Functions for loading graphs. + +""" + + +import logging + +import numpy as np + +from .edge.edge_odometry import EdgeOdometry +from .graph import Graph +from .pose.se2 import PoseSE2 +from .util import upper_triangular_matrix_to_full_matrix +from .vertex import Vertex + + +_LOGGER = logging.getLogger(__name__) + + +def load_g2o_se2(infile): + """Load an :math:`SE(2)` graph from a .g2o file. + + Parameters + ---------- + infile : str + The path to the .g2o file + + Returns + ------- + Graph + The loaded graph + + """ + edges = [] + vertices = [] + + with open(infile) as f: + for line in f.readlines(): + if line.startswith("VERTEX_SE2"): + numbers = line[10:].split() + arr = np.array([float(number) for number in numbers[1:]], dtype=np.float64) + p = PoseSE2(arr[:2], arr[2]) + v = Vertex(int(numbers[0]), p) + vertices.append(v) + continue + + if line.startswith("EDGE_SE2"): + numbers = line[9:].split() + arr = np.array([float(number) for number in numbers[2:]], dtype=np.float64) + vertex_ids = [int(numbers[0]), int(numbers[1])] + estimate = PoseSE2(arr[:2], arr[2]) + information = upper_triangular_matrix_to_full_matrix(arr[3:], 3) + e = EdgeOdometry(vertex_ids, information, estimate) + edges.append(e) + continue + + if line.strip(): + _LOGGER.warning("Line not supported -- '%s'", line.rstrip()) + + return Graph(edges, vertices) diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py new file mode 100644 index 0000000000..afb8549087 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py @@ -0,0 +1,5 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/se2.py b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py new file mode 100644 index 0000000000..88518510e7 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py @@ -0,0 +1,171 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +r"""Representation of a pose in :math:`SE(2)`. + +""" + +import math + +import numpy as np + +from ..util import neg_pi_to_pi + + +class PoseSE2(np.ndarray): + r"""A representation of a pose in :math:`SE(2)`. + + Parameters + ---------- + position : np.ndarray, list + The position in :math:`\mathbb{R}^2` + orientation : float + The angle of the pose (in radians) + + """ + def __new__(cls, position, orientation): + obj = np.array([position[0], position[1], neg_pi_to_pi(orientation)], dtype=np.float64).view(cls) + return obj + + # pylint: disable=arguments-differ + def copy(self): + """Return a copy of the pose. + + Returns + ------- + PoseSE2 + A copy of the pose + + """ + return PoseSE2(self[:2], self[2]) + + def to_array(self): + """Return the pose as a numpy array. + + Returns + ------- + np.ndarray + The pose as a numpy array + + """ + return np.array(self) + + def to_compact(self): + """Return the pose as a compact numpy array. + + Returns + ------- + np.ndarray + The pose as a compact numpy array + + """ + return np.array(self) + + def to_matrix(self): + """Return the pose as an :math:`SE(2)` matrix. + + Returns + ------- + np.ndarray + The pose as an :math:`SE(2)` matrix + + """ + return np.array([[np.cos(self[2]), -np.sin(self[2]), self[0]], [np.sin(self[2]), np.cos(self[2]), self[1]], [0., 0., 1.]], dtype=np.float64) + + @classmethod + def from_matrix(cls, matrix): + """Return the pose as an :math:`SE(2)` matrix. + + Parameters + ---------- + matrix : np.ndarray + The :math:`SE(2)` matrix that will be converted to a `PoseSE2` instance + + Returns + ------- + PoseSE2 + The matrix as a `PoseSE2` object + + """ + return cls([matrix[0, 2], matrix[1, 2]], math.atan2(matrix[1, 0], matrix[0, 0])) + + # ======================================================================= # + # # + # Properties # + # # + # ======================================================================= # + @property + def position(self): + """Return the pose's position. + + Returns + ------- + np.ndarray + The position portion of the pose + + """ + return np.array(self[:2]) + + @property + def orientation(self): + """Return the pose's orientation. + + Returns + ------- + float + The angle of the pose + + """ + return self[2] + + @property + def inverse(self): + """Return the pose's inverse. + + Returns + ------- + PoseSE2 + The pose's inverse + + """ + return PoseSE2([-self[0] * np.cos(self[2]) - self[1] * np.sin(self[2]), self[0] * np.sin(self[2]) - self[1] * np.cos([self[2]])], -self[2]) + + # ======================================================================= # + # # + # Magic Methods # + # # + # ======================================================================= # + def __add__(self, other): + r"""Add poses (i.e., pose composition): :math:`p_1 \oplus p_2`. + + Parameters + ---------- + other : PoseSE2 + The other pose + + Returns + ------- + PoseSE2 + The result of pose composition + + """ + return PoseSE2([self[0] + other[0] * np.cos(self[2]) - other[1] * np.sin(self[2]), self[1] + other[0] * np.sin(self[2]) + other[1] * np.cos(self[2])], neg_pi_to_pi(self[2] + other[2])) + + def __sub__(self, other): + r"""Subtract poses (i.e., inverse pose composition): :math:`p_1 \ominus p_2`. + + Parameters + ---------- + other : PoseSE2 + The other pose + + Returns + ------- + PoseSE2 + The result of inverse pose composition + + """ + return PoseSE2([(self[0] - other[0]) * np.cos(other[2]) + (self[1] - other[1]) * np.sin(other[2]), (other[0] - self[0]) * np.sin(other[2]) + (self[1] - other[1]) * np.cos(other[2])], neg_pi_to_pi(self[2] - other[2])) diff --git a/SLAM/GraphBasedSLAM/graphslam/util.py b/SLAM/GraphBasedSLAM/graphslam/util.py new file mode 100644 index 0000000000..070dc1aa06 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/util.py @@ -0,0 +1,78 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""Utility functions used throughout the package. + +""" + +import numpy as np + + +TWO_PI = 2 * np.pi + + +def neg_pi_to_pi(angle): + r"""Normalize ``angle`` to be in :math:`[-\pi, \pi)`. + + Parameters + ---------- + angle : float + An angle (in radians) + + Returns + ------- + float + The angle normalized to :math:`[-\pi, \pi)` + + """ + return (angle + np.pi) % (TWO_PI) - np.pi + + +def solve_for_edge_dimensionality(n): + r"""Solve for the dimensionality of an edge. + + In a .g2o file, an edge is specified as `` ``, where only the upper triangular portion of the matrix is provided. + + This solves the problem: + + .. math:: + + d + \frac{d (d + 1)}{2} = n + + Returns + ------- + int + The dimensionality of the edge + + """ + return int(round(np.sqrt(2 * n + 2.25) - 1.5)) + + +def upper_triangular_matrix_to_full_matrix(arr, n): + """Given an upper triangular matrix, return the full matrix. + + Parameters + ---------- + arr : np.ndarray + The upper triangular portion of the matrix + n : int + The size of the matrix + + Returns + ------- + mat : np.ndarray + The full matrix + + """ + triu0 = np.triu_indices(n, 0) + triu1 = np.triu_indices(n, 1) + tril1 = np.tril_indices(n, -1) + + mat = np.zeros((n, n), dtype=np.float64) + mat[triu0] = arr + mat[tril1] = mat[triu1] + + return mat diff --git a/SLAM/GraphBasedSLAM/graphslam/vertex.py b/SLAM/GraphBasedSLAM/graphslam/vertex.py new file mode 100644 index 0000000000..6fb1f0d098 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/vertex.py @@ -0,0 +1,67 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""A ``Vertex`` class. + +""" + +import matplotlib.pyplot as plt + + +# pylint: disable=too-few-public-methods +class Vertex: + """A class for representing a vertex in Graph SLAM. + + Parameters + ---------- + vertex_id : int + The vertex's unique ID + pose : graphslam.pose.se2.PoseSE2 + The pose associated with the vertex + vertex_index : int, None + The vertex's index in the graph's ``vertices`` list + + Attributes + ---------- + id : int + The vertex's unique ID + index : int, None + The vertex's index in the graph's ``vertices`` list + pose : graphslam.pose.se2.PoseSE2 + The pose associated with the vertex + + """ + def __init__(self, vertex_id, pose, vertex_index=None): + self.id = vertex_id + self.pose = pose + self.index = vertex_index + + def to_g2o(self): + """Export the vertex to the .g2o format. + + Returns + ------- + str + The vertex in .g2o format + + """ + return "VERTEX_SE2 {} {} {} {}\n".format(self.id, self.pose[0], self.pose[1], self.pose[2]) + + def plot(self, color='r', marker='o', markersize=3): + """Plot the vertex. + + Parameters + ---------- + color : str + The color that will be used to plot the vertex + marker : str + The marker that will be used to plot the vertex + markersize : int + The size of the plotted vertex + + """ + x, y = self.pose.position + plt.plot(x, y, color=color, marker=marker, markersize=markersize) diff --git a/SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif b/SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif new file mode 100644 index 0000000000000000000000000000000000000000..2fabeaafc9cd4ad4b71bbf451637bf2560f1be5e GIT binary patch literal 114966 zcmdp-`#;nF|NnP*ZgxOBI83Nv=FCW<)O(xb80HXiYD6ij5v5XXvyC~_oX?t5A!fU?vKay;lXfsbc#*~tAc-m zKoAH-RaI3(Lu1{#btDqW($aFnh7Hcn&aSSmUS3|2k&%IcfxC9?N=QgZPft%xP3;41 z`w3F{1A=@9A^(LTSCPmCi1s(M#tIIonzzYkNL6_g!@K8sD^U#m#*+Jp7M;;78ApY0rc2g7&V)$Nv`_zjFBSr})E1!J=4D zc>=sVS*<(`U+x4R0)to4=v6#^RabYFL|V19T(!4fb#`8LMGv{4hM4%Fz_ml$^@buz zL$MbB=ZPDJQk;iUorlt0hFn}$natIopw)^A#*4zP`1!wWFis`t|FpBGGDj`LCk#51Hk?8ABNvt2sHVMMbMsRjc*&tF5i8 z9UZHGM-Ai*jTa70Rt-IE7@EH@^s;4W@ygJ*>;LBi0|R4YV^5zxefaR<>d@cj>iGET zg9ocmo~*ul^=ff(@#V|a#l_Wc|7WXz4fOx18T!4P;T60zfl|emZ25K%wR_rFshXz%c>1&g$IkPj~Dv$K#;Y=hECKE@=$22 zc~B}bsoXXSyV2#325=+mbOzpYLJ4P-{Zkgr|h(m zSwR-T5UA+jt4GsavxabVf6r0 zvG37jY&pWa3Z!J-IobGmtOrKv*~s<>gYJ%bsma(pDDTGPktqn@tl*!x8(0C?2#RG< zk6Zv`URKCu<9s8i<-B}1R$U-J1>N7I1b@|Z1(6_IL3&~ptLbMsrZoO~8p_py3yyeN z5Nrjt4;V87am%z$IF1HT#b;7}dV-!BJ4!&!sw6$5s|00<5k!vz%7EsJrb>}|DWEK* zIL$i~Vu0D5RcQclc~E;I!D#znfII|bNvBqcHZFm3xdnn~+8QEtr}-%A9^L$Y@O zoaQ5I!#TXaon3)&tANsUYH-j z#EA{gnbQE`=9V(8_s5i=h;0GXHvUoO&fDwH@3p;Q8bZ?D->J#o-XZ?7P@hYLH$q9tDg+wRS;#fI!X{%hvRNi<1{xQwiL%LPH4^Rotfu+Vw)#CAiF#=3c{HI6yl zCUwHe?pa{+J{Oe!@dW58Iwb@RO&K#|CB$W(EC5IB8z?#O!i-YmakabE|NZqH8l?*z zrv#{wT*@#1+Ah-q>f%)uo8MNsj^WK8-aV~Dfgh`X`u$buVe{wP!;pi2zO#^Q`Hz_+ zpZ@%u&9qrro-aMP@@wJzrImjdyFRV_w{+X4Zy6#Bviz}}k$TGOzc-&&1OMngU4DjM-Uyz|`z`eUW1cNEDQo%J*G0tUF ziIl!QJ1rcUxhF?Af~z9y<^hLI!MG|qaivuPScE!i;JxOtQ%Qooh?oKDTTZ6gtic)+ ziqL{d6xPYyFqxjNHTGCTPv<+h4ZA?@Fh8hsFIVH}vS{NX1>!RmJ%s*sw7a94xDYm@x4sLmz*h*0}=`lfmCyr}FYv?TMvVA&q|H(?icN)VI`VjIpCPz7 zXq<1X#zPzk0BKxY;R;Q|ni zeEu4jnHQvF3X-cXkZRJ*8Rm0idcAg~dE>?~h{1!MCA$jo*SJ(RXy%|Z zpy~;Nu4u$~{BKlX+Z{t(w;!fcz(I$XZ8*(9xWazC^Yjd!)oA3-Z{0WtH;YO-=h9^E znkV-$yQpmPs`iX^QJ{8eO%naSL$&u+j9Rh_A@$R@bl-qf*45D3tE#zc)yHnRl47bo zJy#(3ZdPW%G{0Er2{9x^XOU!=yVl=$t#^Oa&Ho`7<1@Rs_J|qmKrl$-a9X`tvzhN! zUkAgfKUuURrbtn@;WcLWZhg@LiaOAaF2N-34D5dP#=I!=L2*os*^UR5hS7~~G7=6F zeUEO+D{YUY8wwUs%=Bnv;vWb(f|s?iW)8L9jjm%k=hf#+mj&n@uoIU(%}nVwDvq%`)-kr6u*or_t$|YFHQ``3@hsY9<Nh7WXuJO^TKbZg6l$9}QiXS3l3j=Rzf@m?zTNij%grCE`z&^1 z;l?B|swxyg=A(s_VTbOhvO$Z2EwctE!N@e_RpWvsR0JJ&9xFSz#h42(S4;o_z!mF8 z>D_RXezZUiRoh1u%w8-)xC|?5wk*$y9v(M3=6Gn`%kYdu4>{(bbiOl_C3Ff?Xf{e* z%_1zrnaUT$&ZX}jSZ7f%@UyH{b)i6NU|i4K=> z0g2!>*L`*-evu$Nvoeg+%sxgs(D2`OfAzqk7^nL}w1$s_i~u=eI*D8_ZX5#xUl(_1@>^0T<**m~RJ81HzZ)!#ir790v10rE zDyG-`@MkY^e&PAb27JB=vKj>2zVRr)i~IT$V-<=5cez+eclu#qx`)vf5<&8j#AxZh z^XHK=(BbvPryz5vl}nr8-ZDUa8EBKh16;wLRQO5=H*q7nYZm6c1nW=Dl%xbcehqDv z|4rb~6CeccP1drDXhRX+z#Uw-33ksU1{R(4AOzbT%djS<9@0RyYM|ci-t$8Rw#Ea^ zAi}+gNuo4#`xGGKpvQh3$DIeH++CU&SpOvOU>bE%3iwdb|Czw6X1R436}u20FDlF- zHE`xONA1YgR!=X-e1y9Q_N~n8f2>GI^x^e`NrVX$NCZrYVA+GowM17JHbZ~u@>kpz|&7k8A|DYgDN!P`m1T0Nyl(Ukhc+VFDkk_)^8itXC27TLfZp9yf=(;!tN-hl5!%2=oY3E z6~)0Agd{fIKI1)$Z0L5`Ms%&ua^ErlzNsDI#eryGApa6JA30j8){n~Ej_fY?au31$ z?&cG06K_8Pd}OCq95I!WL+?|)TuNf`Y}l8SglL(cy#wYzCh#!UCw4^&_<_oRq?mpo z(r*@~Ws=0loJfBgw`BlYz68^Ko1jm0yTWj|T8=+S39~Uhir@(jreVJvi5uB|n87Mn zdUBx#L9SO%;5mprQr>R%-ku^Dm*UaDVKy!Sx-xex3vj`}o`=RfdYpOt5z+@#YR&~a zEcsK;705b0@p88-O5`pjY}(9i4;y*3%Y}onGKCs`Od7}v#L;=j?;H|Pu;t0UPxVUnd+m6og83u-UQ?Z=eOHa6(t8l(Xj3X9%_8TYJ$FKXW;QhcUOs z(S*{7^{_yu9NPJ72}#Gt-w*dd0#Hr_XqU=P+B&|s96$xGATa#x*G1E z|9)-wP6_9o8JH$xl*@qLSXelGg&`(k63XdLL~on!3kQRmEZ3^7FWmmve zh;sv&C0Fdo}?4bXoK z_z^J)rH5g>Vb1>tRqsbpG2)zSE(ck?O>bbk zB*+@B_(6xu5Icebqsx`B zCO6=4&drNKDlbI4V_Fr~Nj*3voOl(eecy3YE2=pJORDO{U*`^W=62|%J1!r8Gc@L! z*3_hu-{qm$#lDMacb6w(lHIa=D2TJukn^1`2{O6UmcSx;7sYPK#z5s^k;-kYP6#$R z*EDH#3%1iVseB1&J`xj4J+57Os+xUD8jdMvpVB^pe1<#{?hXH_hfN5I>{PBGqnD0F za*^-RFi+5h9+JxbM+cZ3WTmdFiF51bcjHz`7oF!-<|8JcU^rsvT$UGh*9b7OvAu$w z6rfui9TL*_7?|8Maq~@rEhE2t>6jPj{@TwsG%1)Xl<{yhyh4VIVYN!KLfvP}F1>+O zu{w}X9+V~Gf5Feq{Pd5Mj6$$UCmav|9>)x&B_@XTUXee1oNzdDiF1*vU{h~gVT)-q zz~z}3To*9;5B6j#`XUwn%^6<7Me=|9?_?i$y8wT-+sBs(AK4yTtg7T4pR#YS#LZsc zFo@FFBt2XbH#Z5p8GK*WfP3S1Y8eRTCEL>>OM=)Y;!1~H7i6@R-`6Z1;N>?Sugkx0 zvGqhL7a1+f?^A(qbwVx;!1s$%{XL<263F{l8A;fMJMpd^I&J{(VBbcIisrqZu#Xf~v9%r}PZ(@!-qCfs3*M zCg>@14Ef|wLNo?0SjY=R!mHS?%icg8wZMs-I9r)}s$<|i5|8|z?o*#=?VEz7+`RfcR1m)heewK!`hLuPtGwH$q8j3`k9>jGjEtfbM`7UC zF3$UL*_s#cVv>3^WILD`Xuvsd8)^AA%%~ry_senYIw;8B5Cc!vLbSgqi;F#|0kinw zzim39%Ja>g1Fg9BfzlBm^fhWO5xv_ZKGNMm%9BK&U`j`rEZD@{!`y^V_sNuc9t+L2qxOtgkrB51~IsVd`Wf z8#ao&BoWn|&u9Op<@HgDJWQ^|sm9;_mF)KA%=t7C`^XB4l(>*%jj5z6{AQQ%wNEd- z0isx3FC{Dn1SeejOrYI7KY;3Bzw)7=8)fOApP+7(#FbONgU5vOw7M;Nd|NS# zJGg@kFOxm$`w5G?i+%FbozFoVbbVLranV&mG1?PzR%8FxV~^Ni)a1shp!H?#TX&Q2 zn;Zg9H_zV+u9Dvs&x&8FtxPPY*ED$CnZC%53r$R9N%slL=c7RA4h~Ws0qb6m#XQe! z-}ZK=6j?=qU&{QqEDDS8Wc2S&4C5C30HX6xU}zGs{cM8oEC-b2Jxk@o)YiF{vF7L^ zgql4mODZ1_p8?i+8q0V_JXOne=?MRM&x}^GrI%M{kP0fpKBE21K&yg-nY;U7y zJ{4%v3toY5P**0KA)8bTr;`p$Ol0{J|~c zVMh(WJ?OBnk4GAW@%G4PP1_+44vxo_2cW zB7^;C#vz3^6$##AYdfABF=Uvv9Uly<5*FI_E?|d@tI}Q|O`1a2O!XLg){Y>;92sMz zPFIMyI4dh3X(C;MsM_8nzDE+jnlIY$LVwMv1d~4(gcZ~km+YxVuEY%9GfLmjKx#(v zr_K7~`Az8Fuq5%d)Z5h2TbMmh_g}EiqQ5)O)jbBo+g*PYr0O@jwyf1!RsEorpY<<= zC1GN}0%`JE6D7uR+NNWyXrg>XoeiLe)DDYBinTDMF~&x93)e?bCq=`1_E?>-lAyj4 z9vk--E_I?sh123%*A3TRxg~84L7_mkqNLG^ySSI{h0dQ3d~dLC-@3ng`gCqda8a+W zdqvnTL*>gV_O7kykJm%_NM=^=MX!jxgN4416S2d!FPhK-9cLL;WSFiw)A7xCx|^YG zc`oORh~igxvie@r1ra;%)Lt`k)>^0wd+t)W5|U8k%}-o8Fo$npHYRi=Xwl=_#U~;c zkb4b=Erw@->ev@-BWw*>fw6cw@;<)(xI&vUhYX%mJxOX(U?g(DqICe0TAuMio~&yT zBs~^sM=RuqYU|mLs0_ZlKR@4v`A@%De1G4%|5%jn78VS3$6&Nv<3$HI`kmwHy@PKC zu4>L_8Svpq-SS6`)ob=iG8(>0Jq2Az+Z0;vbteN7OOU}jDaj)FJ6A*8kV?Dk<^63{Nn(NB`RXM4Di(p^z6@>s)yjn}Rq?FK$@>Ax0w zq!_qQnxX<7EgVn$EJihg8o6^QH~zEV3#QPX?PuGqkS zp`O~Fp>HlyS=pi#Leem>qc;b#Q9yE`%0yt{Yi~>#C+3Py6odITVf4Y;$uOLRcWip9 z03F>{YCTa$yXdLqVMa?uG-%`Pz}le^bvL|i-_R5gQD?m4^%;Ho;3yZ4*^_{nuI3t8 z(!i+2?%O9zQ)2rcuYW=* z;YYS_BG%ombp3JehQ1%AyiPsBaTZr2v7@BX4qQy(Yb&VmvnkogD&oj~5j9HJqlftK zew~=zqO}#Yu-O5-Yc^zkXl$@ zT=A2$7*doy?@Z8xbw(DBr8b<4(`%oxY`0atm_B7aXhG+xusAXJ3OPU?riduqIdmjf zfxlSj!MmrHu=*cF$G%_OdxVakoO8;pP{Js=2Kbt4p;ei(MCYLp`lDp8Nx_y2YE{RD zvf+Us1?PTvDEe9LYIbA2$-{k{d&)qTY|R5s8)`#yEe?^+Vm2u94b%^{S|Ll8&0Af^ z9NqtOsMke?PdA3hYd$;{Fy#VoBGeWHHI2U%-?HtPIKSuG>B)?Ze`<4nqC4pEr7ssC zwx-Q-mthC}A$Daw<<}gEOH@$R*`t-`A&Z~_2H%^AZAemooUp=gPUG*8HXBIzgCK`< zF=rCRP?z@`+#Yl%c+-C+!StI^wiH@tnD#A~wVLTh*RP!ho)lY)K?Tte8v@j4!6=^# zYh?3Nu3uXR+G?yyCF?bsd?kp!=xNNYHw}dtQosaag*w{d!7Smet&94+qnmTqj@hE8 z%aCU}H8yfx(`i9S)(u;Xby%A4`=JUGiFE``?UX@=Z+x#HUO33%TjCK3BRqQzw+xKj z&C=@76RpQNEiYN;t#$a0yVj`dLRg5wT_mwgZr^wf8>Y+)`KO|vn5B&@wTt*}+dllMQ)4+u#ep=%Bb?-_0BNP+iLpLW1-mhT(2XDx>dds!`r7L#f8#@X&P$6|} z$O+ZFjrQtfQ1*2v?Z1Uc^?i+PC{&L(B-Ko?zQQJa31D*bo-RP_*tH@#@MjAlxXk_+ z-;*3OV0_GOD@T1}og(Bv!j}bILiZKb9E(D|>Q& zh-*P_23P2V$dDyN3NCwONQF;Wd~Ys#tC(9y_mVU*ejyY*-_Py+T@pIAxd6)VU!iPhm;zQuCw?p$P{zZ0{`A;h!qugI>WGQvdf6>Qeg4zZpK(m2EC zo*oi%JfRKb|z-fX6@ee(W=lH(4e;mF(8ijC$E^n3`CCG`)I% zCXdYJ+h8)h9s7dQgn1y|*0?WJQ|v{Gq|aH`!~1Bd`HOEJ)g zSQNS*tt?Zr!2K(mC}qM&rgq8^fklEk`E5a2*sb;*6BLTmtLANm27MIFgU8-Oo4ahSg#2nW{;ulw0m&udU|No3bqn~{KQ&&^Fzjk`DI7N8a`PQJdUnUw*VVPUH40EVS}?7 z!LWROJRlCSUtbJqKyS;UBR1wa=e4c<9ArXlD8t+hKcT91O~4IwZf!vlC;j@oqVLYdPyed0Cj5E+MWRTwuJy!D4VJHi5lful$5P|^$%NO(GWI~wUJ zY*9ZJd+*V%DUd&Eo&P$A{|Grdpg)thRe$*#Y;Krzp)WCGa$2nrJUsL718e1ug~~Dm z_V$IfPPTI3-a9ve68!g0rbaw{R*cCj=lzU6>pXZ19;V&ae_5h-=3~=86$^pUZP#MU z^=;)f%xSMv$u1#W)bAWq({8|z3k#WF_bTCL+cgDR%-X=|Zwd9cn+E}o6Hw8u+w^k}0=R(*Jy(1+dC_rz$W z5Qlp?U47RG5$GoS34=dSF2zGa8|@?P+x z>yl0XpgS}{=B&4*mXk8tFt@aHolXu{To-m^PIc8ZQNac z?VYGS_{Vbg+e&_GnabovhAM>(u{0|y^@g99USqqnZm!I z$y$H@bH{5hsXDb*&AzjyOCPS;E@xP`^IQ{5IQ5r&g1zha{m=4;&5-8*jMIcoEvGN! z&>y`bju}6^+T@~&GgXg)tU*?P5B$5wsV{#hAZ?2cSr9OZ83ilo-OXN%!SG;F*~8ma zr3p{*6gYLS`_O&!I^D$rLqbtA%q&lUd`an^4M0(p(QX|uUl4Q>L=eefXQ#J^Ei~F9 zvgw8>W@tOPmKz}5b6hLXsmNT@N9WpgK~Lr5cO1SA2>RxU)4o(lq)!d-ATCjJu;Dle zV#Z66I{zGR*Cm9l~ww{9b&NK|M{@fz`6-OVi{c8Q+L9Jm3VimR|3{C;D`6 zQG66ormp|h>0OrXS1UXfmP=DBG+yRMJl$?fcz2;n_{l9;Gi;=LLEx*CeNUKGdkZ|J z^^z|^WSfGvjO03AgJJt%XJ+TgiRL82r$e`RRvNnI zY*6tT8=G=A5-04apY$%df7<+sja>*iIQjV2`|x|Zmi?Ob|LxfxQM!05`%T_~8XPhh z#CKJ_(YQ+hl_lPpRlV1}=&o9VY06P6%P3jetue`v`}4ahw!Z#iy;uignF?Juz|L22 zO)&zRx85gnC;6yR6)ZeS8IS*z*?R&_OPv-^aAr&V==>UM4Z&uj zFtGv9B|==XGTiPDSRkN|gpiLFkS|iM1bf_jK|qz%lDQMCS!lpg6e%skER^s2eCH3I z0(X>u_KAQR@icf?pzq2keagugUa;6T_|>h`|5ZnW5f@yR1!uq8eDs&`z8-{35RQPT z6HI#I!7F=iSw)=H?c21@L#sOk*S82A2z)Dm;s9Yr@oP@3ojiyapItu?ccnea{MJRA zIjA1JouaDM@nGOng=0=Lk9D%YXv6<-Exi>(7@Vpe`jH>N|haZWm5u zf&SMGYx*TvSD#cAkNgCjApGK6{A>C?t7n>5wqX}PKaBd9)afvPa?k(;>k~c!VNO61 z#(omj_JZah7*f+csT{+DSOjYtGKr>hFC-)vYcIlOtWg0HXUfrgoUv<&WWL=z`f_X> z&X`h2;Xz*CKNo!Ez>R-M@N8zWpCUFn?!DIihORJP{$t>QZ=>gq{9I*5@x#`zuH+9Z zJ(JuiSxnz)tAxY*=*YqYd5oBx?d4i};T_Q%zkVDqP1|!g`tqiQNaJJ0j(h7iiSaf& zd#O(8T_fbi&WN~okSj=n9bE)1 z7W-7&W1n^W)GpF^`v*mhSpS3E2so0?zejEE#2z7L%a6bn@bt87pNWEL#h39ct^#hSU*FLwf2?ip9$8rzi)en1#^|Gg94 zt^cdutL*hZqZXx!Gl%fN#|1ZSUq^VLw~yoJZ$no8zmf>PP2b#1&P&g;t}WJFy*L%d z)Bh1%L(G4s<)ciV*6yP6gd|-KX_Na}@SBN)`X@Aa9;U+iPtP@B)>&E}aA%rUFs8~V zU(a6vXb7ikg*>KYVw4=49(|S1%Hmm)ZLIE8F}<@Uyn;t3?7Z*U8-v|Ux)yo3{h|$- z2KXp$^jo%N+~$4ENcR2FcWtpaQIT&!*snbt&bJllcdu3ah^aoq-i9 zAh)GXagMV=sP}Q_nG1J-R!le7pNRE94(c@#TUR6I)K22X0E;Tv#G*yhFVppKpRAzu*k_dVFF-<6q?GFqGh!3WFp z4@uZ?i?AeA@P=v4KDoHQS5cPxuWs*B5bj%2ASVYsqfsX9J5bP`6Sz$7Z;(J%z{tW| z5$p%lUpjvTG}RaxM#nlyY%AzTk51qSlzwDLH(g^pm_D`mZCH>DD~UQ3Kdm5M-ZuOx zbt40!Gb9y+FW^vK2CQtRshJ6}Q4^OpviGL6_q5gSMoVyp$*2JNnP`qW`ttd+*XO%_ zg3qf(b6&d5&Tjj+|I>=+*O%cx77pj@nHi|*UCSUlBst&xWxcmH_Vj(Wu#}wDkGDu> z<7%iP-!v18&IP1SFQ~Un^%cgxJL}l}jmXon(#+OzlCSB9BZe3FG zr-PcFt_DiR-PEW7K>Y6-Y>D)&P1YPPMy}3uF17Wy%0q_!Pyxji~07m=aH0J~B%xChex%mo3-C+2w0^s|DLD4bNRE z!aN9{u0yVj#ElRJsJD*T?Q!?49V7>tTWVvX5n)V-0Vz7$mkajyW;YNzxXf~Zfn*U} z_1(c}Q%nQOHqz8`b99yi6D(nP_QL}xg>%c^4e&1%!eMQVm&srFezOt9dN1dW8y=)v zBBdsh=3tzE!^P;F;M{T2Xz~owV`nFd}%pqhbaZpR+5t>)T5tpPID!rB=Kb`m3 z!BXeY$9RyIj{C^0$7y6&JFw;+Loc?Ica7x)y39UR$CRBwkC_Duu71h|#&`VN2 zhEl3EAC!M+z@Pt|bKrS7*>?}ZJX7sfMlb}%l(uNf6Vx+$mI_Sf0lZx82xmjWBcElY zZFKkDm{n@qXgHCVcaIEWzrG7KYV>IdLRtJ^Bkf}QIn6~}bk>P{ z-SO{+h3r9u^_R%lGa-*t%rAkh^1Dz>-lh7>xxlUhjdIgy6J~@j3lzv}HQ4ZKCPq#Avji1l-!7zEaa{SZ2=Ts3&xl z4U$2&BRL)1y%$l?FD+LC$SDSAqgmhcngx29_kaymS*Y#qUy>)Q_#}-odi(OpeUv}!^nV&&CTQ6HZ!9Q*F0&EmqZSz#75;y`1_(^3;m3@X0r>A zAyBDfa3W>1IP2k@F&17Vf0__TmV5f5?u2XHISw{gVsJt^RF4&PhThdc)p zawp>?G~gO!yN-7C+d+IcpWLd+Ues(gfIaIE$0vbQgVu&x@w6qh<);u6jVjS1$O8oS z*rA4}j6_C6`;XIA^LW~hYt_Fqq5GLbI@&MqxTN7BoLbxnuD!#b+Ws^-Jz6U`SZW1+ zq&G+&1|)w%MZJ6zfd+mUq|yL7?Z_jL6#7|o3&g0KoO?Q5ojg-fn74hS7!Ibd2}o2l zIrcZl(>tEJiR0<#`sw7f{)JHQB1hiJ7m8NYc%_A$Zo#3G1#ms5yAIKE-JACp^4DFD zUmY0-zL%03CU~tX= z%ynYTZ|XHiHi0x)EK}qY>08L)Q%yj5gio+Q!^GYVKLbHPM3+nva^xU04csEKE91^fAvR8debpDgJAJKZJ?WduodH1nzN?pn>(eq?O@K2N$jo2xDh2NFH>U znC|{fTMzWBVfw}2!8ih6<8+QGanL(A&H|xNF$Q~+g;?9#Ef>|~k&p)wC57o=%W1{< zQn8h#KA~Gd`l!oG@84thvM|O>1+&45oZ!@4O-&Vrw|NPw0XAZ_TOcguA zf&dzW1qu>f=!TeEY{jWn$;TSq)`7qmPd@VVa=&o*e&s9EO4x{T8c9_EHdu>|At8Ex z!E`i&vpMI7?+(13J#R8JKv2?2`uLY16%@uJV`HfK=M|rt5&%U6Ux|chH|cSDLAX%$ zf~%12d9)onUU>@meYLEXb;5EfgAnv`tY)xdohS;!D|t1{&GlG=XaQ!yO8AF`ybB?Y z><{e_Jz{@2bKriI0G2p7w#-;tz%Po(8b0x^Eo2==h?EzC{Igxs;U_9qN;knhdos|fQx~}epAdi#DyEW zmV`zHJ`CFPI_6l!CoKwhj8H z@#8TJ+;Ny?L}U)}PL)-n`9YWkMpZv$;aG3Ad?>e419F<6e@-bnI3O~X^WQfQ9F}U(_D${y>c?@wVKru8>#Z=xz>q=(5m6zh?~86)t~-51c7XK+g5q7FC-0l6)7+t~hO@Xlk6 z%9Y#e#<`U#^+nM_@W0+KHR95QDHcyBwatamIwrc`EMd+AFA*`ph-%B~HLksUuc}Xs z$9KA=;8UUQEN=gJ)=)J>Pg-^cZ6i}jX)>k!g~h+3GhD46xa%g;n26`WDT=<0zAE!C zar(9#!P+P;kCx|6HnL3bP%y=mf1*pxmN#^l4ALJf3ig|MP_dq$lD~aR4tO|cCFd*l z2d<%@4x7PlbmS#ZKkQ}?7NrF#eZ-1X`N_Nw+795y`mZ=F?@jIW zV)OJhcxRSX+rK3^;`5fN6%PrDbMjW@QG5iZjkbR%mKY8Jd<>7EU=d*=)0#mCe|;whfye z_dPuK^Stlp_tVR@;1d?bQQ|-psncU|E_{E0Yc)K?B4U| z@Ph+Nd+s5lH+gLXR!k}nQhmjVeU|8)jzbHr;cb-M?2eh)@U-Q_JIntoEG403FKFx4-jFH!W~)ybmnrl+*F% zG`9toc799%Nj)HcFvNVAgfd1@%L(_PnD)?hU4u3~9uzvvRQ%m;1mZ0mPr`4;NO^iS z5Zv@wCSgF2;}N_2hr@07078K2KJDBpyzmm%7%@?kPxKX*jq8jiiJ;w^E^MRkuI6Y~ z7W1COr0I0$&jdhTLu!w1Mftk7nLXvdH|~D<6r3&{SzH`_v~ueFw+D3EYxJW5=9qR* z;xhmW-?p%b2_Nu%$5T2FWU)_flgminG)*4tl&#S7^k==@?M#faV~S5r#?Ey!}^^4waXr=YQrHmoBRpAn_Wv* z*Txn=O|Mln953PIL^3*OF}YeNyGtDQo3#nC$-x|t@?9Zkw+&?B% zB^W&5pyjTL4j*4e_{dzDdu!3D3+x~Q1!xEiVGR5HQ_|pF5-P2-*c+7n_Tg%a-8Y|< z1;k*izyrY|ROF2Kc$~(&S}~jfWYTSX_fF}?loXlo3cf*FjB* zYD#%#r;Dl*__;=n@J*lr%?$dAp+HMJY z+nxurQ=$QdB^^v~c@624uV~97N5i5(S$HW=uq2qu5oIxFnlByWa(AkYkuEisDI1ID zDtyhJM3bIh6Ac=YSkgkt8q^_mY_P^x086@sXsBPEBK`s|z_( z45zT*uL7fB&Tpc)O-vma$?S-&%QT&6=a-Oc5uc5$DO^`<#go9CMk*Eg7r4n@(Phkx zEPg#!9<$rq5452=n3CSW4&SsDkaENXgXlwzTf|j~+%Pa@`9HkPP;G3Zw_VA&7Sn`( zcJlCoaksOIGKF^rV9g--z0urZh?26bvel{V^PJOnQtr-#kS|90Q0j|A zOgnuNjI8=EZ%5bMEO#t^_qb`W_Y=tWdp83o(u^nqA|{t7dVXM#rnL#<{|RZ*068MS zkbJrMr=z-Jo*Ab_kLRo$HmS;eSHN4G2|L2|=Q;oL4$pr-0X;p~dps7hk5dh=kNzq& zS%mI!9g|HZKvgXk>f+b$g^sM8ExX+9ii)8L_DlD5*hTL$JVseTq;b~>K0=m<-Uc3q zlb~wPW^tzDFWjp_im5%`q;7&+l2$bO&2qzY?GFV^5$<0?vaLgH=g_B8X9ad2hgCTD zgEJn=Gp#Z1`+*iH{qrc!ugo2cG!t+TUr!+M;vz1eur+X?*uz4$5rLRo^+yM*#x{Y4 zN`}-aP<+;z9b^UtP@f-0@5!+g;`og7W|MB9eKg`=qMH_13;OfZuyTi_PAlHu&YMam zW9md`8|fNlhcV1*tyP<3`&Gk|-+~)ehZ3_Ml2^x*4&nH)XCdnSr6WsrQ<@<43+goE|~D1Qsz`!(Lal)j^pJQ z0K|l4;`qG~(pYIegQlJ}&sS)CN5DB6nFOHm(5fcxTH%k&WPxH|++$mOY| zbY-iFZevbg9CGW3Q>~cyFwV(km}WslVPYtFKng4LkwRDcWMY4RxQWjk#OwWpWzM_0wN7W6_FhZ7daPA6{ zi&_;`d|kJ5I8*y*HEVPoMrWk>T40gUChDTWazXoGsQQ8|WmsQ1hzylycC87qT?ZB`cV4ZaWNN0F@R6cyGfzVV$W-{~ zEzU&V!YvJu(jhCqzB{PuPUWMgCvwNX*=p6=1C6byjk`lfZ`dA#HR>ec+%CInH7KdA z%%=htWo*Og!|JZ|&1)(~Xm!aIv~|XlN)D)K!(Fkcw7U*Cldd_{gLT~E_ey!XiJWqb zjtk0Fl9BSFfIw!?qmbyAYq9d1$Ped3*!*oNib4}hh!LuH5P70uI^3DFEBxtul?6+! zQe?Gjh2C9>o&9?cYsb=U2w1jh(bsT|z6o^l;D@Y_b3o_%N9!zQrA{jT?dx?-q~F^8 zc8^9+IUgJ`rw+dU5uaqDwUiKcF6N4|2SmBU<=*)Zmp<*uZjAp{<34CiQ+yiSdD$X5m6QylfR}m5S%jtbL#Amh07c_{zItC!y_eTeV>=3Qg~^ZL{)2UDp&GSJ=LZ zhol(O&lz))7Yv~8TH=9f@noVPnK0$1?LC^e!J&10$0?V52GTJim2u(tMr(hk$ zb|ny`(~ObrEZ&AsltJ)RzG)3d-5lnK9LA6Fh@^Uumtk(^bvwGv3|4HiU2Nu9L`XuR zKV+yZWaxb{rc!vY2?mTV!!jdZ4cC)w(CX+{=IxVS9WCZIsz#V0qu-}7F|HJz(ASx( zM&++8Rnd4ySuGG4+s$cMvouUwG@y4^eagjsCtPf9Hy^y|NM+s}^aTbt=^akI*}kB6 zROZ2wz0|0~>G|C3734C_k1~runLxjMLcyK23K*ns=dY>Z5Mqe<5LZwL5S{9*+u;YR zIH7)t_(M@3mET$>(pHp0x;_qTRJ&gAYfQ6wXP$7&gCg5YxqDNq(+pZ@!W=+@gVREk zmTi%lEqpUEkC@wO&J>u6@0wp60;`AcSs9?d=TyB={jt#3ekSC7^BO_4mrbM9x=4I_ zlWMLB`O7dKVpGGe(@gd&vfHD3&=qJ6Sm+4Qvy7aja#Zd!cuc-cnkdHAWwD8C+$4y@ zyfU}>fHQX`w{Y#pzTyj+;H@OHW|8p;f-%KajZ}uhH$&Fb7TFK90!|hEsM2U7{bi?!Swezv!TEAOdK0GJ6k0= zuk5C=p(?3F6&k~g(;(ou<@NIIq42@3xCbnWP19-8dq=EGp}TN$&Qu*Dj^e&I^AX;;bm$w>Uu&q zm(jC!dr4R8*GVMMp+Ri00KBNiIJ97HXXtQ+)>l7{cZ@^^&8k)rd+ZaE$~bDU$*u8G z8;{-7Xr2zYSo9;7bd}uaHSfFmvty3b>2NBLhm2HD;i@BD+*db)D0lL#4_QNzxtcNy zT;*cdcN(RCFz2|$)=Ge5)3{g{-=INoYNTU(9l3&|7SA{si1DL%XbR4-Xzv&*Yb}V~ zR_Xhl+fV6!BCW@{s&@!bwUSM4YxcPt-zAT#$^yaZV)McY?NPVbL79G$324jjm~XKIO7OtqbB~oqk2j+E%U$S?I%%OZaW+^69~B!cOV&i5%D=nceU# zPP99cRlg9VIdh396-EPT=t( zG%JbPe@k}$9iedwY=@|{G{hUrU_V>6de3h#cct~unTijX#q)hG%W}#P_RSO{<^@xm zN8R=3H+Q*ztXgwG_OCu1WwU*d*#Tre+WlI)@E8V{=ZEI3D|99zN@V@whu=)gHtVy_F1 zy?3zJ>Par%0-BG(y`@ODuDj$*;Kl)3B<@1kTpse434lnXGga zw!)l%=7zu`AjyZ=q9D@FWghl9kewvHzpE}k+a081_L0)h&ryy(SFIiw;$*#+Co37|?^ zcC{0gT`(7KJCf=Su09{u&(Y*&Z>|h|X0^p8+Yw!vd}b&mWc(sQf6$RK!!xlucXRDyjHtSCROD?-U*BcX}h@4sXEn0*pXO;cjSzbul7%b6CJxfys za=Rns@bAFGy^Yvb1Cr8L&UQ1Jk{+<#VHVp^&3i_%s;;L z)=l$9g5j?{3dB6^lRZfNE`tN#@aG#2Ke*{=#y3frbc`UV&2x&&LN6bX_Wl$0dw!b! z0l?e(!pKRth=iD^*=>7|8M(jPbSmjK?+JWj9Z+H|yBa1P3>z96JY`G+y3c5)Taw>P zTr|4PWKk%U@GGYRpUI50mb}egJ{}5t=!ajnBHvqLvh#P>5;gNoY8*Ay;?4bL)Wg*o zrw4act@*09LbPW_7yLcC@Xe14g(7HpOqa!LyEh7WEcKxDfZS8)22&xT6a#| zy}ega>AaG^NqKr3>p@gSk$gx2k~9{D5cqPjggOZg`n<=?pymW^04|+4GxcUX81sV1ZX={xB!*WTxDNU2+3v zRaRcMR-Aov_^q52c1w6?ox*(Z($HIj;XA+m$WV9p^tpwtueP2j+P->^bp7L~m9Eg= zZxkPl>Tdn5XBhImB&hPvGj%iuhS*>{A z^P=)}`iK4#ANDCej9iJhl>YH%MA~)5#|O^w_tHN-R~#Nve0m)*5BG*>y!pJ~{N-Ev z@&#E^e1UG1qdn!|Rk_MbIr`|Af1DR||9sZIy0GHUg5jzK#yjZ2wFmvUD1tg3@R2z#~o5CjB+5N*3V_~V;0rs^pAXUn#`u6wj-5UqK9H1s-} zb{)4}@$1s6pK)6wxib*OwVzi{LIziD>$nU-NYDu`Xz8|}1&49LGZ4gf98!XZ5b^vl zKvmC4M4fR_$5G*ovz*}c3KGN6*1V0viU+L&H^L8mEA*ZhHH zPTNXbryrQ88`VH?-wn{VnN_3`U1M=j71~;-dDP~J2nluZpr3Tsm)&V~3$g%*FB-GV zT|0o|xxQ6|k`SrVZ9Sh|56?X7L*&~fx{C)+^;v>i9C6TRBW1u~?ewn6vrtdb_zMgR z_4OIs0;j&Tg5A*y?IFEH$`0(aR7r;#Ie$XC@E^4O{lbhXPl$Nr6Lii>KEKOb0Z&uW zcFzB4{4P7nbU%WxaAy@Hpp&m}1; zsGyTP7pkfTkwNmu1k2xuCO<4@*mOlfH%w$AA#J)4hJ~;5yWk4A4hupGiul2;+1W9^ z{aC^ka7S&@Eyj-HDKBz%oH+D(e8Eot*ye@dC}JSGsXVte{jzi z|ATvOfQ9vGZ2nK^d0BbRQ%b49q?}TVZN*xDQn33>qbKI|(*k$qgPfE(C?f=6)r=b5Y>sep_kCD+IbMybPo;}pAd1L;y zo`Vgpg&X}h^t}H6f}S^TUY4c*L`D4zJ@4E1=kVcwq3101tbFYMD9;tv|0>U|Hd)g3 zxy!h75372_C+o)MtOwy)LtCq#MQ2UKR8Q^u*LQxkGwW0Gzr^#mw5*x5e~IV3fNSO9 z|KiRKyZ-f^mvQHw|HhqbYHF5o=Z1!cwzjr&=guwT&Wfz8uld#g={vs@{_8sng@5w% z|CE;g>pM3z{6Br?`^Wwzo}Zoimv~;j{*!qA-v3|3^Rn-}tUNCh&qG8163@%p^Rs9F zMLf^V{r`e^URIp{&(AXE9P|Gf=FC{eoFT0b+SoB&n0bi*!?T=9JWJ~?zb;era+Ytb z2-D1khrKu6TAn$w@}UYNTcqcCI+6P8@rP|txw1cQsoYydGHpmqEp?@ae! zYe^%~o_m8SRKN6nzD0(4$H4dRG++NXhlYUu=k1|2RK)dK)qJ5ycG& z=nLYm%(D}cwys-lJFdWptCilMyPI4D8jCcg3?0cGN(DwpOYA@fB48>w^E^X=dIOzz z-Y-{dx(09ikrp{of`E)oxSBUl=bCk-LbU8^PV^ZB$YLRcYpq1l(nL_=h38DM(p`=F zO*D~Hm4T<4zP&+x7sU*9N=4T~br7&7ob33aXG=eK785@Qg%PB*#N%12t(6fIHb|)Q zbNoC7rpsfG)tjld(JrWC7L?gpw|GY+Iv+w#}`(xVs$|;X_U#yi@nrb@V69dVi~b;{c(V zYj-A%DYi|Xxh8||+q1)+dvZ`?cCQ$ z*5i^E8|`XHSx=H-RGhQq*XJ(6>~ zvz^fNuo))kp(!2!15-5Se%#`Y(Wdx%tvHNFVc_0egu@8Y&jn?fw3iU^aTeb>FE+nb zl&`rkjCU~1_G{o`wU)ILf3P|U{(nUg&g38~RjxLCgG$iVN6@l*4 z#YwgT)NcyZP=5wdx_HXiS{J%ZAD32_(R7K$Io4JsgzY!zW*PIj&H*JQiIeX7=94)= z?JzBzmCS;|qPiNIphQ7JbaC5dx@{aH*YP8?^z6rI>XA4m z-|615=Zi50`H6rHD*!QJOR~isWKyk4HBUguMkjc;EIGqCx`Ms~?mVN+%pFiYig=4Y z9f}q>veXr6BWo@tGDz*S#7?>ZJq$r^ds6}nO&zpxSnwt2B@5(%6HZgw)RKsSS8&z3Utjcpv6Cz!-s1ZCdF9_P2|)t#oq)7J?G0y}-tZ#@}>5u|t*r@dtMRZWK7(wFieV6DKmr zKro?<{f=aT$?{H_X}PG?qjThdO0elBPE!Re)I32{U@~MqHlFv$e#j4KNJL1@&j;KnvC%zN45Gm?gBvSF)9iy+Q;3 z7UZ2aBg%r=h8xw_EodE-2x6?)qo1$j%aj=K9YxYi*!pOkH+io+K0MQ#In#9WpE5rs z(FuO+1YyOk+orQRe4nW$!z%Vy1)5?lW|!f>mMW3?p~DYNi|*h`?T50@;RDz@GV^T_ zhAv3-K!EOoMtZv}aLrewReLhX#ElsTKY^R9nZtQco$>Hn7z5=qH-3Pou$4_w&~G~B zUdbcn%MQ4Av#uKdlX*axS}|L#yiwaBQzu{S_a^JZDb?7T3s$v}f#;Gy`V%#(x_y{fQ8n?rm~SE{x4?!0b%uqD9Wc86b3m9UqF)3@;TgALQQSWg108HAB9c|O;e7FnVD_n2A9rMrVj z(#!J&W8Is=i|2@u=)N+DK6hoJ%86Nx0N$ErH)2ltO6ZfCt#RXq0XgMe2Z?RH4Y;JZ zfQ=R_ENr}dA$PXq#4DxIgbZXdwXrk6W!U`DB!(*zZNTENjoz`Sw!Ua|jt3yFA*d_+E=)|uhO z*{Z=m;6;d0sspe02)z6SwtJC=a%Q@%%8pTi@rZv^Hxls{_#BL_m^{)S6V^GI6yhZW zBcnOIJ?b72kOCY+h?)tz{ygAy z$rBY$Qz(}5=I?-KWlR8v#q+q6WnG+=n3`=i1MZ*#_Up1DQTz}SFslkvE(Yk3LtjJo z)5|jvor%qFQHMuE8%KRlQv-O9w8{|JA~|!F9O^KQh}Kr|M_>ff@B(VSQYUisQRqu! ztjYnv7saP@z_!UuwO&*!LWDkz>XZW1OyH?KYLyAp@Pby~JZ29Y>L3l;B2?Cu?KCz7 zpOMiAWA}&2a;;pJ*Arm>X?Pn?bkt)P0=MM(-#N%rO;ulEA5oa|roTj@DKOi+2( zbkDTV0l(wrJ!=Mi~v30la-ryIu6kp>P-gK zIuEElI0~Rs%&N2EIhB646_zvLS@&Z24CpnFu9FmpKztH@pw2={f=A&?shCdb0VYJu zpn-cw0nO^@Ci-sGI|bh2xCg-~v<^}`2Jn%UyWS}^xPw@iSb^Zj=HL%wAEQTN>0SrX ztsE{)tm3e2R$-LK< zIFxG339FP)v>2{$SadwOn6i+$uMa4h%r-)+HZ}sq@||0!fSWl-%^##9(WQqgfssc^ zbV%A+9{hri*2NZd41=L9Mpa8-PEx@Z0O2WBt`3bzO@w>#;8o+8v&${FZ-EL)mG0gn zUUE2X6kvivIG6zj$ zZBj2*Dl1cRm_c$NxjYIedxBm!1$>(d-Pr^;I+)QPl)=eNyY&#@wYXPyO$maA#Xwh78FS0tc8*!WmY)({3=tELbElzy!x;>{HatgZ_T=V#_ z{S@ma9i{mwOnnE+x*EC06xEqnzNS@djDv%_PUsr8!6G~6cg7o`8^yUfFBX|W6DTpY z4!IY(N3H-^;`$9})lzCDhuKP4$oAzS_hz?;p?Hmr*^uoh=iCE#n&8hz19!Ei(GDGU zuFC4RV8&zb)~O?%IjBwosF~7bgAUMN(X6w*?SffQGNkM@PidKY&HIVk zV-Jlbux^(jqr|aae`2XwiAP^=Ae0IST&29Y^NH6=eFCVa0>Mao0v&|e(^WlsW}nx}P^0P@FD%M`Mc z+I2;A8VKy#e|!76E>y&!W+3QsP;ny1OMZlr80g0XEHf*jcK}}xU~x6*0$R_x`-qqC zz3`GAof#!RHk^TCrn^JyQ0F%mBO_SneZJQl_?Lu9k&AEpErQbGnt(2juA4 zNjO7((Mxt}nuJuX1o*PkCjM7-tc#0SC&|-7!3S<01X&Boww{I`m=hjr(<<9?K>anG zdkAf$a-n51Gx#*{9PBjAFIQTApq><5(cV&smwZ`~7M$27OwJdb72nh1BLgK}=FcYK)``Vsed#2XHrlb4n2Bu- zDwV0w0y(lZ5fsRjL!^M`Bm+wYu4}=A#L9-b967T^pD;n7u`b^>`Gu`D~* z3C|k*@VLF``_T-lM`O^Wh?6M9^%wxZ6}le+CQPbqU7jVf;Cf5ovD0)d3Fx?lY~g?< za(EbRG~JTxGYK!JPI)O7kZZgL&Wwyj(VJR0(ZQp@UVJO(Vs4l8z{}BnDi2fXtjE|p zyKwL)pZmLJ~xZ<~hi*C;NtM*@n2V9l)zHxLLf1`td9(!GGR;fGGp~WN?@PSjqt_Su@DB-ZWHDA|2|k z94$^vWAdit9~e#qM6u+Vuk0Cfa(Ov`7qh@h>6dHNtmg zJOC7}^7JD&-)4_RquJmabJdRd*vRRNE@{C^^fO>R6!l!6}Cq9vdKKySG29;LSwH-z(nyQBE< z!n|}jIHH2~mRdK_-w&j;SF61SG-IUZ#tQ?lfplDH`9IseB*qC(bc6l#4!l6%tU6Jg6fT%{}rt@(MgEVeZQd_*U9t zoyJ>cq8vPlJxc>=X_8;>P&-wtI;LC9jlr#t0H?~hN^t=v_tO)r&f{>;Bn~k2?UR|m z`yL8(Um}>*j_ja)L8BW#uq#G~J+9%PX4D%@3DD;7m-)!UVj--o4CW{Q@-^Xa%nY(6 z5$sO*0KW=E-2P(z`O(@hi^xrww#0i0dOyP;w^a=;LV%cB3VY7<(HgiDtX95ETw$fmvS#?o+1V5BzYK2<&?=o zJEh3T)o;A1OLYyfFY{iykheAm=LU-2l<}4~s%4LkPJ>sz=+pn=7YzVk`k4|q;^mK( zd%+*)qsF!nAZdmxprc~@F)silUN06DHrz6Ihk&b1u8 z)lL#!M2LK;Qw;)4q)>zhezuR)&x0n=qH#$$7T4K?dH1f6F%%_}qWah5W z{2t%?DJFOp$Zrg?Hdvp&HV2#$GG)!&KIBZr==`SpE{157MAfbL06vX8_V`_$M! z9$ZfIbGEasT^p8>(%#?v8|K_f%1QaDI%BhU@U^!Nvnue;oB8rUt7?+k>hm1#m7h~d zbZc*!+2_tcQi-MEP?e~`x}2=rjL9G*dACrtxX=v-+@ZO~A0<;n<1SJaqzti7DdF0S zoq?u!qbd9GYi07@T-Y-^$3_jKR?3jbiZw7?vYNb}*lE>EY0WV%BfvH+`i*@)^SNe{ zn`d=-YV~q0s-?lq%`J+7aB{Se+X>Ve zY1#UyG9wraoJrv{>~5fP7$S#`an#)4kBI`yktY5vbfa#_B&$3z5JwL7cg!S}Zh76@ zRC4H9bFs!my-Z|Dcs_<>klh4%-u6ginB_Z36cA%7SIS@AWIMt9flrPFe>dH&f4cK* zpf~H&<>4aLi-RJ7BCBDso(;=-qss$VopKSZ5EMk`e6sKnsd~RDkGV%GEQoPGZ)b__ z_h5xHwh3(mTS|m}EZL8Sgok=KoTydZ*<4?E(PnZ8xq==Z|7BPG&W0z)pX4ml zmAyu&8y72$0xzw7pOq3=XG@|9|1kL2@~mZAgK-~B9$Oi>r(|U+cm6+4Qcl zm;cnqnj-{BoYP7$%-858llIC#El&)HixUSu+jma@~M{Iw`3l$~;3VoLx1H%H0=l!+p z85bl&qI;&E-b=Z=dU+h*C6pvy-a->pdJp+0zaMecYnJ7%%y|vxO}0MkAFOmUdSWJ4 zoXVYRa5eE698Tiw$g%z5j-mNSt!TM#X(F23slVJR^Pa6UG2OX2J-SXcSSld0tdLx) z>+h1#Vyeg(|9OQVROdjsAql{xei#cdTR8r#od^c>4q5KDWxgZ{Ab`&BwTjqMvs=yR zd27ZvV3t=h&f#zQNgE+yuwIJ`W|z{q^f;VqNJBkF`L3&AcF}hcg06+kLC``}=IY)e zuw{yFeB(elj!A=qp@N@Qrg@%MW)a1c>Lw_Y2@{M=tBXQ2O?g$tLdcohzT_BZ(IyTvYQ;nN{kO9-9Y zttG?_q*kNL^{R|{b?iCW_$(@Lorojz)VKpF)EZpQKj1}i_qRP7Y*nej!kKejC7Wvp z5S|ooc=F>2w~-1=u{{b~CUF|9l^&zLcGWRkST!n~w%Ev8{Vo0av&sY+&xa$hXe9`V zGDBpz+;?1&2>j@oxYP$dn>zk9wD5V>)t*QW-sc)xvFs-q*DOaJIn_PT9u;m-suz+T zuATmw=oNNtvnUpEPiW;%jCi)8>;z?jL`q#WlUN3gSkWRAH6oW^Bm#6aZ>7r(k!^a_ z0_{t7=*^__MyJBRv>)~VPiFk1Z9h3 z-?UOwVQS&=Vk7#X(OL-&%%|~@V-5`pV_R*-+{5#PNYHOy@Lq60LYA3=tF+WMmr3Ez zzdkgAm7Ecm-;CYsFhCCJll{YdhzL?t=xvCB52}QFKi+y<^q|O^;)>J5(hx45yw3>2 z4OhNH;0>G?Wz3W7pRp)k-X!Cav;!tSZeQ)9dgp|@vBlnZPq;|XM}jP`<(ZP>T?Se> zn%m6onB=r2TPing!d&6$=AJMH>dK{;ZYDtkZin^bL^5Ea{f)y=bzP6$huZ-Jb3e8X zI}AcRykxL zicA;0G1w~&CH#I;;s8@}+;}~1-)0+g{Q5YF}XX&*j&Zi<)rrReX!Lm=~SnXicr%D+!*@{#*hfTB?f0pg-VZI zG9k{F=x}dP>B$Pk6)Fw>IT!9jlNm{EK$){!A7IIYEQ+C4Jc1SW@-sS|EI;>iZ@wnU zag-`pi*O5KwB0xAwn7=`^qtkewAye?pV7ME&pB0})DvZdmiyR2sE4*C4>bMWi`*a zd7v_N<5jt!co*``3?4mLc3x`#oGXPaT)ete+C=vdN+gIe1dD?zS%dvcd zUd7|W+oIFw*q#+j>(wNb;yB>ga>x%-a%>0@p(g3SuKwX?{%R3?MxOE6)pL}6`PrD; z&0P-L_aVMClXrnyBx&KNr=|xTl}xFEb<(O8mxcP#F#Ej-$0R)?w=R!60`FSeLi_&v zVH?b!X^>xOI^8*b=(1NbX&rg0<^{&eN9tAUbcxJXU3luS<;VJsxebu7LZ%#c5o(f~ z4+btTt5b%Bv=Tv?+wkVq$EbEiOP%+l9Ae#V6ReR?@9}R>FDCr1R!`+$nXM&LVKI+A z0me8JaQFwc(kc<#B)QrE;GvxWWS2)1rO&8axIa86P%NCZS9{YrXe<{nCEW@)MkZrk zurIneIc}nfV+tZXS1g!ExM*Uf;tD5z$mQI=@Eo=XXoo7bgrCi-xl)*{=ECByoCYr0 zZY;^qdwz`ka$nw#dl#8BcgilOc7%jTgKa!UO1)9Edb!A1Yv99fyU}n7XamYtFdwL@ z?aDac;Nx4->k?eM{xJl5uQ}g}=3Bo2r%prg8i*FPzy{lebRTq{K5mX>odY1f0U z7p#ZWOU}WP+BU?VEB%y4G@EZ}lR`~WbGgS>`t^E%RT)cbn2+QFhREQX1@os`|9aE1 z(W(IW2Ej?KT!UH>qj!A<4bG4tE*#5yVx#uxsSEU8Vcu7V*QZY84iK;Y9MrZ~wRb9` zvQWnNV6V(^b~*y5-XZ7LW6>7p&)F+k+27aOz1m>1Bs5a#TysWg4fNa?&yd$<peXS+h8Y;rlwkIQ=)p&r&GM@B19Rh^lNrN+&R&4YU5owyX zy^NK=1D!gHeuKeHVDyAyFS4-ncv-#^j_iXhWv zIp>b#Z~vOb1ZBm+=)@acVaj}fDHd=S(n zSIc+&cX8X?s%0~cu%35{pp7;H@3~wOLMccNdn^JV5g>)0K}`;RxkNKVZoO(5N}Y5W zPBb@`2=ZWlWPu>BKZAe{zNj^`uUp(ZHaaqvm(nj@%^GCNAM;0~1CtWcvGA6Uh>$Vu z$FZTtrPn+_C5C;srZ3{<;whxgt7!M4m2#1Z20_0HmKh7vPJcc-Y=(-+S?zocad2C~ zH}w$KCh1U3Su||tall>QKa*eXu_PR)o!czM)omXB)Dz`d_-uj}sT`Qen1;cveQk4u z)&JO|xmv{T$4(o{ysM^sj=jiDjW(99*WIq_u@k9P#XJA4Z54g?#dNFPb}K8!2$h|S z3c>-~!61dz^sMyl^v3|k*dsTkEA(Df_s@u*YxBZ!6Xp>8!S#ZTY$1!VT^ZVUznLuy)Y^^QDydL{sl6&|+`UBn|gBqi$l_H{|VyUTFS%IR0 zBhEPEn3k5BV`Ty2JcRR*6`HeFR;FgQHxQbom6@8h8?sL*W$zd`CRYobve8Fqg{NU8%$gwrbOK1*BhHlsPT%Y1sr#6*d$0(Oz-hUEX_7 z_%0vP$JK699e&A)fAkuDanQCf5YPsB`MU}5wxM|qAY;&@_wa+DOsHXEX zW0T4XQd7@=)-@FIeg;bzX!a3>IOpeZb`=$QI-c*tFer);HndbjnC&I>*&FRYqjA={ zh`bm2*V13NHM333aAr%lAWsBLT26&kf$7laXQkyw6V$3gi(VtbHfe_GxNpi93BS)H zw@NykiPbh?XeV39r_7w%L#G2VnyWMA{&!XP9`4vHg8DAK_+_N8#YLhcQ+WU&u8ygQX0IFUCuvWQ)J@8 z_E;*xHmQEr)I9xcFF9T7K7|F}7F+DhSzgN0()NL)E1=l{D0KL_Qi)Ix*7RD^<#^oR>f_Gd#7Tq-JRq7K4Ux6O+^;|T#u-o|-6F2S2es}dV7~7I*pP3mD%d?+_!)U_a{>FT6O({Xt z>2Q-kO?)e{;IZSw2T;iM=Im`mC6UZsOGg`poGGf;n%6QPHB>lEGRGub5}D5i?luP~yf-J; zWi>g!Z}=&#S^vE2(ie-$EQ8J2zah11KzL52r-wsnZ1fk3_)jarn8pfrR?ToWKxQ82 zIwv@}0QU!FUkRvWO3uuj)NuyEO`Tv^Do2FCX1i9ZFv$xU>;mI$%~*>?&Stj{BzsnM`?{B!#oNdk z$aAr7FTaKNN1mF-`o-^@e6{t^Y40#UQ>4`nH-H&kWegg_gByP5UmEWf+&=i49vM>D z-11VSy8S2jXmmwhd_}A=_P8AZ*ka^!-o?KI=^9B6^Lm)_>eUqo=UhGgDZzp1P$i@A zI{G33pKI^r8pXzyAu5IH%yt1X%6Zfd!DvCmdXgR6(PvpE`IB(?LV;a@!~0i#qb$OJ z`gF2HmqY_Wh$1|A9UwO~6dJ#`mKsD}z8y^MV!s>~Adk{noSo)^87SEoBy_=PTxM*n zk;_P|^if$05W1#;(l5jG=IC2pNY;sV^&yR!z_l+!v$R-vF&)4*J0#!CRrC{pkx&;L`QpSg<^XAfG6#qXCU3{ z08XW@q8+Sf`}QJXmOV*I@9;vDV@(lehe~SkvZB2wj9V@irC_1H`;J?b=@e~l@TOJ- zyI?fFOgB5}1IxeZBR=iN1v3SAuOMH@XV8bbcUq}!pmPG-Ee!* zcCE@G6B}!Ym*x6Oo{-7YS8N&ejs&+5&6zDX?L>`N*crfY_TL!R`4~BQ{X=xzE#t0d zH@-S{K4VN@c*!~5<8ss45q7{_Ut|BTJ{LTBt6$ZL6u>~6ejQto>*_jb?RI+O6g0Mr z_hH!hvqgP#hipIW6GQ{v)VP(=inyegPnJysK4h{=M~|D+6W_9jK0>SttGt`mcCmD- zi+E={Lei{*4ePViLDe(^z%Cx#zw7*ty9N#CpeKJkFBB%8ACXKAXUc5?T4fga7T z;_}J@JV0WvC(zGvZ!b2OLa?#FarY|XSv2OVAZ*4`w5|Ikp*$miNx^j7=0@;Dd@cmH zSi9BL4b{~S->5jW*B`PYl+k4$HS7xLAyK5TrTptKEUb#N-bC!(l#d~D`RbLhFvkqA z95#JT50AiAuG(+xwbEN{0^4v@I|`c;>z(!t(;#=lhVw2Z(s z5bJ=8HCIQtYR4_(^ynfG>~~8Oa#&)Hac*m)srY4})}V^93ZCdXwbcVszTrlw6rJi8 zV}1g1OZk*pf#ceKqSry@>MrcX?H7`W7>jUL=jXx{H~BW}BnM-vZo#(raD;{HYiwwa zbAuu~>fcT(j?e7Z6BMXAR<=t7Ry)iJ5P9SPhJJaaX{7d}5*A$P@sk!;|6n^J6BNv( zdTuu$x}nm%CIq5+q(3^AUQsZfOVd%XumiKk0>^3c<9 z`6@Z=^35rL1Edk~i)ci8>~@q3H!bc)bqPt2~%-nGRYCTiu}lt z?M#ZR11W-%8xKqAsC|PmGq1y3Y%*_g5p1NT3s)M5P=n=HMh)z;jy`2^6)0OB2Hf;= zq^le`h78S#aM69XAGNV$t2^YfbA53O&Lsn~X&nvK)o3)SBNpm20yX}eHb9ioh9?@h z2$c{6Go?=gurjuwN&ho^JupA#&|gzRrse@Q6Yg@a9<6>ve}Pmca<~C#Vog*2f^(rP zT=9O*yIA15lIEQQBpP^+C>`+z_l~SFuzN9~rfT*~*E35C=uX>>H$IN(x)Z~VOibxj z(uN==;)>8YzOx8lz|api9`q#}U7x)ow=y|sE|9Cmv5MYbkD>=m_*ki&uHT>Fy7{7z zDMN_gC;GE+7op}tH`v#0bnBi=@OJS?gFvWtR*_Af=j3JNTz+P`fJ4si9GnT#aSH|K zl4GmL2WGum7P&a*A=fzaaW+}IOUN98NEnaU8i(q8YqF#z6%yPu#lq^0=G*kZ!423$ z21PGSDcG)cQT)K#fMI|y2X$Iy`@5(4wy)~|h<^Co^i0laP@O`mOa>Tj}E zE7S`dJ^KaQjKsHtpv4lX=hW8?zT`(^_(x?f#g2*^{v}*K6*aZcMsj85^t=y1C#P!c z`}^kjmbjyU;b_F!3ihxd%DV30H4}mg-3}M*c{j>}e{^H-JtvrK;Uup4p`z;p6S0%O zp)nek3_5g*;i<1j)>ReZCPP4H_SBiU_RQQ|b4#2n^G(zxoqk>^YIV%f{z=3Kh@FY8 zM(=JJFQASs3&t50u9H4w>{7C;A{YK>E`eDFB;{PiTKG8xn(F2jI^3Wc7HlQcTUhAz zKS4T^WE)j8Dyq}4;om6W3O$10OT3hsU!oqjEeRtAWotN-@;DitkUJx)_nxU|MxV3O za}kpkP7RnKe}d54{*&j-k6v95I_HDu2Y7rboWEd2+;$sTcZk3 zepD{d)J1K*u03A2{X6f%i-dO2>pzoDAT>pD=R-(j4T+ey@0;-UX?B3fRJzBCKXm6& z-@M=SLw`PAh!bmJ$pzBG%ZeaTGdqEBa810eTs8W3#S!$*syw`&>D`CQ`$IxBr!NzdnDYWz15<=r2#SS{-EW?NzZ3@O+UeMn|XASVN9Nq8w>Tay3N*Lv5G7`q+ z&b4EdmcWl&_$o5VkX-NVqMGLbWaIpLFk0G6s*}*6n$~2z{bB3Tg}1c`ctd^75k!h~M0IYI}x3oRVR#>(`~2yLNi9 zo6yHW==_Hj33p8Z^1I_wT*C{_@#1AwA+86ny|d8NqHsnu5=!P*18(PjmSKIK4u=b! zEq$POWKrXcn?82uIQdkv?~U;yV-@&ijhQJ$3r0yUrjo|`2Fk(?n*ea9t)5jr(x=1I z$#&0=BtLGm@i_2ubM1ODjnxBs$0+KZ_2XY$bSim4T|kjJtpZE*dryPo@h)^V#>Ow6 z70cRK%cok36=_cG#9f9{&s{hEbSMLvN~D`VmmjytKe-dU*ZGbi@X~kntV3|+CW@|O zbnJKnCA~w1X(l!NGW}ih)aWVSpqI{S&jn(6gVHp7%varo}Smn0`wTMFWl*UEj8HUS=8Sat@H!ehfeOB#^U5lLdYk1gYg{FFibs{CA{&R=Er?AkOr{N>t*w7rw zU~HT}vpy5gH<8P-#QOyzCw&S(ZVvS|<%fWUYjq!&_(=8*=lU6YLX<5Ox`v^fAr;oR3MHK|-)2BM@U zl5(mh9ly#`wS92T#?5yN1(rL);L*>CF&hWwqS+fhVq75q#@LtTT~|Tlh(N`Nw>$fM zRKXi;C3p@5wJbFmqk{LkOSFUiQ@%$3epjGm14_d4sI@ZCw|Bp%F$_g+p|Eka4@EFJ zV`K2r_(0k1XHqf}jOT#=YTylDDb30+QvU`W?0NHX$Q9{FXi@=2X76O5SzmGH#%)A5 z(QHso=wXn9{Pev7jGWh(%HT5d#tywgn% zlpdASI!L)9o24VLFDr}GT7Kh5#Sg$W;nhrtcVs$3w>qRsM1!sU5sPN zb>a(kYoQ6_F4jk0vX|pIe}+EFb+_goVzj%Czq@up2eSV3Ao%!dspUmTiu|uM;TJpq zwN8d%J5ROQ*pDj{pj#+C?MRiFy<1caDjn%1o}s;knIfIfv&P?VHa_4u#@>;MV&Ms8Tc_HjtlvCnHm@}?4-uHp&?bhB*da0`*Mn^oDU_d%fJ#lFKQ0e z5{hi=p%#Ztt&Qpj1Hbi3Z*#G%RY{vG0=~!#kpvrv=$Tb~m0Ag!!v6wQU9P_f2;1`7 zc^IZlD`4biCIe!m;rl57Wz-b`tmSVyoHuPl{_O6P!tx&Q=OlGTumrMvbNvRTY1!3cZSn zU|B+LTJgu>G6EL(jRx*dJu{L}s2WkyJyn$83mp2oys1UTBT4nC3`i#5Jme`5Uc^tK zKUiLI_TkXQb{g&I?oRpYP%?W32IUDh|E&*JktlDM{HB&*zW>s5HovvcNgvOLPMt$n z0MKzMcMYtg5{UV7PUXJjz_=uOw)JXSm@D~#IG{Us>GR+odC5u4$J!=0tDdQ@^Qmk;&^RT%REb`s_BXbLThzGfIkuU>V>NmU0~# zoZmP+J1Rz#wOQlqlG$$(9Vbkn3Vn%+Qm$uH>x9czu)W8G*Uh9k^>uWK6J6?ZBbL!R zGZsrsby5*!5lrYqEJ#9%JEsl{0y}^4eZTVA&Byz5YfnwYOaCswP$jUlPbIU*GBBUQ z`XbT!<8JWnJ`uhb)&L-*J`XMz+%CB{du6|B=}1@?<77C>_)EjZt@N8fSX)R{kwE>jif64gRj!=Nc zAOBL)@NMIWr3}gip~sWbPRF^Ev4r*!n2J;=LwIS)_aMOs|8jPncvX9-OrF~6B!6>D zmrjcd)_F-`cmJB-aw%(^wh!#Hst;h_2sF%b(}_a#wR6xAhE1 zL$2dd?(@&xxxrT$+BBJVaN})L+16)&w;kVfLFskC<_M?mOqLmiHA-aJx~@xmXsCj} z56U4#ai7>DXkzQJEcoG22$LcHW@UlHHT_>53fmcBkg93Tl+#z&FX|2eI^wO|0e&)@U8e6?DcM zq%{DXsjAVil^Pf45NPzXPbAP@o}is^gU#PCrSlt;)faRpu-%n9`+4x=1-IBWqgMH$ zs1KNL^nVPb+U?^Phk#3C*T-(8Z7Eti8f5DNxDeqU_ePazI_uk_cS=nfAled8Y1YsH z)h44-p64&on_Ug65hA#U6n2>w^+9Q)MDnPaI)uhI$T#uqLY9XxKVNh1YBepbH2XL# z>qgG}d~GBI!Gxd_kE~jTu3z;YDk|I46(+@eq5qRBteJCbKD=_V;pM3W=jP2m2kuK* z#dJ!$iXyd8DLirZ?>+P90N58gCYE>56XtMlyKUt@!)&aYL`~uCoPkxgEa6 zIZKyDprV`0%ERCOm^8LM{ZG_}rGbA-%H$gwf_zYO_kvHJev;$3dKuu+{`SY{v`c1t z(KO3?Vz`|mNNUVvxA#DVIVgHVx&FH`OcAp(wr*hE6H!yZE$x0{lf2j=#GJ6Su#x7Q z1SneSNjr~3wQ9n2_BLOy*za*}U%D1(SLG6;(V@)1Vesx9j4o1->h)uL6}G6#I=3*q zN5BZUSk1xjUSrmBuDCzsXh?JA{=ud3h}22s9cQO<4Gc+ts>!?ki&lZ)O=W2Vj=H$A z3-gG>a@tzrlPWCl=CEwnZKIV8r?%t#0~!>wQ-Y0l>iE?T)?a%#({<{%YPY{CU(|Kh zb9_jY1;FG|%;D|~#@Jjz6U^`10^v1=9Cb>A|Iq$r2OpK`>PqmNls^%ag05UZoz$41$%UZuFVxQBwkJPnkOF2z$AvNntxRU# zJY~hG4|#GBeQRckJ8BZZ4!7IkG86=q>nZwh`+Uk1OXVeux^Uf&2u-y?y$*tK|yt_pxt}Gf+E;p zdbF&MZy>RAD0c@p3J^QGA6e}-l~-7~Y5$yOGHd-wp1Tn z*hVg9)1i7zkE&a?L&$KL)5S=>>ZQG9*%dCthkm-qV&){`Pb%i!SP3QbfUd>;w33KpF{|?+!ZRp$?~`pJRdW|d*A$V?v-!4{d+ff#-FE%; z_LZV|C2$F-x5;QOjartyZ{C_Q`e#8inuIn>-u>jmt$@8x6PH+|e{?O#%O;5ulP7lg z)0t1c!?zxFbWtOyckxpkIY1ZA#9V+QH5LfP#Yc0p6w(!k^hBW+&wKCYG^iLU8SA zqZezJ-AZt}(7UlQQa>~QStuXaHZFImxihY5lE~MNlJ3mXSWsQoxQ&BVP$ml{FWVCV z%4`q$gJ6+qW`2F>;RwtyBOh5F3DdO=XU=5iZ!WL2K?vuwGHM?%LoWm5&2A9SQB?wB zwuL+-!(F1X-doGg#T_E6cP?(&P-fTaxCXXyCmZxGa@vI2_>&35>~&1#M2-e^Q8n?d z(zZMM>r6RvR30E(S39CO$&wy$nb(>lnE|>QQdHY2dpqB%yu{IP=h6K88jxHd*s67R z^h8 z-ht1nHP*`JF`T49EGVKcRG}!`YsR(O^FzvptSNG%;yS*}ZVdv1zPg`_+SOh~U zAPC3242Bkin&g1gs zp*RD&fC;v`hY#L-haq5<#jl=V>AsY+Q(liY{Rk_K#$0frfcSHA$&Ax#!~`ul z`h{1Kd)ja_z56|QV$oBKp}KGW0)r5dt+OZ@srW9t---x1ORXW7?BsfeUVgae=jW$O zYNbXuZZ^#xha7OJq_2kQo{)fNTc16qNCpv{ zztV2}u{M6S)w)zv4&|A@m*tztC-$0ixj#(7B-iS%?zMM9dTO)8 zPg|0|t4#jsB-^pBv**RDh}M0}{uzS%Y{>{&`V#ZxFxdvS$|R}RigPJE{d`G?tuEg0 zZZV975H;IW$`I9D!+P1*&{K%<_v=k<>$Vd!>U>Ppd@Y%$)Wr0xU9>%Fw`@K7n>xRy z)DhlbD0>-WpsmEJK1?xCN@!?5SIQfkc&S=mfFSZ;*-Z#nwjunpBmH2LP!y^a|cmMAkyI%B_&g_*g_!@##re-g)mxt z9%#Se6Z;QZIH3L#AV)(W{5=dcwK$UcEXYs}a`J=VL2Ww)B66<%$9$4{R2=EJcn-F{ z4K>K!P->JedIkN&{;RqNUm+`4bvjjlkJQOCiQm6+bX0Y*)NN+?>6BtlhM{G-1X*Qw zE{cxti^Vm0Kt{O;M^DIeE}>VIaQY+uj3?kBg>EW9{*b_SfsBP>#JBmVU5&VPCK^V9 zus=fmn&1?W?hu4rJ1?LX`wgiYgYUWymyWhWkveKf*6%xO;=4|Ml zkL`)`I$)1$poNoY@Md@2&yoUzKj9ORh(iS*X>LZAbod&P>I&0&kH-A^)baB&nf1UL z%hZjbp(oh|>N40bz7Bt`0Ymfvzu zHVRVu(BQ86dS1EuR<8l?$XiDRdTeOORa?*BS1Ga4R&c32dCDdx8tI=E8rJfa;?3ZaAiUIrIpVaWWoqmW-lEaU!S1C`9tncYKf|+rNNtRXoJbZk96*n8@ zysHemi~p(~w|8M_Po97VwbXetzspwqBR0Y!ce_R;Ws*!&m5DX#ywx}KnkHf&Z4$WljxPY=mcW%fz;Y1;wEufoXj7?iOt{y4}mF#+;~3z>Q- zhEzIkaCXd+G2`$jcj>BBigS1AZK^xKEU26k`Fv?ju~)gPmP}F>tvWAXa?X~y)IdKB z+BpyR-jjTJeIM_!vZVId(s9QZw^w*a(<5k*{M&4j&Iy-vny_t9qT&fpz$`nJFZ(dJ*9wnV-l4fE`yy&UB9wj{MHo>UO-?FHh zw)XXKBDvXr^|h+Ba{gaFCl|!wgVA8GTX?^$RHMd6o;WbrbvzM5n-N(BRHX*gT~pja z4OW3IR)LMFffv38c6|-JHXU#^HRz^Qz>Tj#zgqm~6F^D} zFz^d7_Vd`P?qMgw%In0#OLD_wXbNZpkWGK)fwrs+NPQ-7Ie5Ax->jI+&w zglH-HZZZ2`zXOIcu+L1wg5M#NX1p`sJDQ&Km%2TCeg!GUuSDUQy04?8;O;cEPoEt} zdV|XcIZKa3gHt-3z=zhJb*FjzTG?oe5Baa9Vu)$k_F$&e^Fguyjwm#vJ3VfzS4|q& z>v3Ar4jZ-kX&5-uBnm&%m-z{JZO{a|Qbf?`cjx%uyK8;y;d`(OH}hHQYsFdd^&;@z zZt!UO`fGt6#>{uxhmdRp#CW?sf7!o3S`R$onq}B@+?;XzcK^xr)VMKMbv3$tMR+t? z7i2Bqzmwwukort2X)`Bas>BD^2x7#iE6t9>GK{xoJVQ%gZx)Y#^H*1&&#oc~FQ72) zzUp38&pFvSsQGMPfA3d2jAAo*%DV4&&7P#!`c$NmK;MM?3~RMUUPZ>yo&5sCZ--U6 z{^!0GKn=lx{jZxhrs>$czVa>2D9Z2PSHB>7#&!S0k)_22{?-wyi8pLA_bc)K_?GFi zlJQAMu&FtAx!)ZvKJ;n!SkMUinH`lOhU%it7TOEg+sf$Vq>uX^8H z)_20tE}8JXB<%emRGppiMs*d?5nSyNPybZ&C@^~9$i5vZ8Lk zG^p+%tS%kI=s#q$ z_t;2Z)<|w{Zc$Ou|8h3FySvYyKmWg+&0h*aQC&e#whQ?p2N`oXy8)N1ip0D3Hxp-T&ikejOSa9UYyXp8h|P&9Sln z3)y`4?%n@KkWGcEdHDY|RnvRR|6kP{=}aA?pYP`0+G+|iT2yjG=^Q7Vp5PhxC7P;H zcKaU+C`Q2m%IcDs3J%6yv_O}Yfk7&;nFt#9a2OvB0^l@aBNeKcI)EK8rh~wW9T}RI zSr!ciS)wYdh+ks_T@WgIw*A13;m#>dPxX<6mQ}ymD4s<(h;m!G~^P7O-t?MrMp0e z9KP^UUx|w%??*RP0d~pH1TZ< zNu_c$eqE`Tg$_e~9*H!Ds7y7}fT7oVcJQA}G-&zRXPQz0I`?7w+P}5Vrq_6LPn#|v zdq=@!h6V`KdT+PC-rcmS zhQs4;>p`u+otduRUfzPX)qdT5oLxPTIaRaL$_n;SPH)f0{x?qZ?IO*EWR&5Z{SSX2dRp#-;W(GSg z?GR+Q#S+#oA_~N}^5W4|gfZyyerh85azIdn=1|xR0k7NSAOD(relgvl$86dtPuEG` zp4+A07fspG>h?o6e>GLvOtYjbHY6a>&wpP_GL-b)d#LHGptXgMnQbpYz!mG$)Y3$U z;4oC8`?Wj>P14{!u-WBP$r{%-TL!`d)~s+njofOW6FoBF@0n%NLD z9@2kQrariuV^-X#vY&ZN>&a@a&3L0)`sgj~AFB#gQzb&>$hGnlXIAr*%t_9b`ErAp zoB{)W6RvFuZ&WTX^cg34^-!=|4}2=J`$S^O;UgBGg~i(R^O}!iaaPtn1@u)K8YwGe z_Q;6cqf%u9sbj-HlHN%bE}Bf_!@m%5brL|AMC2n>UScD7%|tkhxp(cd0e_rna3me< zTnIvlH$(LEKzG?*UJ#oBvO&O=I|F=PIZ+HXjpr946+~zHX1Ixa9Lx7^bCo){buf)J z8jNf%9hqv;KDIno3$GwOU??IUiP=%sILgCHrge+F5Wy5fW`<%s`Vg4pABNbXTE%mwFMlagCLJ&oOQY7_Bq!hP}Uv=y9Pv{ z%!yJ&GdBt-WedHrSX59xReea4Pfd}c!oJBixwH6oQFge~OAJF5dY-2wLjCH{u-9_C ze@LHSL+tQ+oJT%u^w?dYy5i_%W4yVtb3GVdTE)|BSQQ#J(3@joA-L)u0BciS*`jh# z?-cr3yL%(TEm45Gi1wv1EO6C{Mhca*;By}Yl}O1k-L(vUtd=Ice68GL?>whmCMUSi zWCpPq7^!y}zSWehd-KP$q1R^#m$!d0v8Ft{NSqH#(|!k?d)Wg z7QDW0V-c|IE`e0`f;Rq~cSCYyxQjffsn0)w=n;S7j-pN4^kT{i=}K`we|IBgeEf?v3GEl_8=v z>XZ`%Ww_Lb$onccWh~s=rUQoV5q~f}vGUGzT%dp9o1pfz2oab8M!2;Lw#4oB((?Fz z7t%OvvO;6o9G9XtTPxMO)B(nfDs(;X6E)`FrPld5LmTm;a_A&NpDcasGApMIB?@=; zG~xYQK3qK`7P^w@h%+>VsRek2e7unWxej1eOmg{ht|a?H|ABRB!mGpOGTdniLt}2zu?9w!mZ5Pyh6<7w!RLi9_raC=!ob)-t^iR3%dSAYEIetr7s2>ws(TQfUep8G zkevacRDo99YMOA#Hqjdn{9AGCuSMm`pJ12Zqyyv>usV!xs5^ZfFjiTBe^2;g8rvu| zgv)W??=hTgA41uCb>G42phxyU6`I23>R#xBRrK`;l>2er-}7!V3>l|{rud(wXSoN* zEgW7gXsc`9?P`ba7E>L_6^!G|HiQjY(T5 z=rA#GwGSG}4%%*}gx0|Hh!DXbXO;w7zZwsOqaKey3-frjAm{G{SYKks7LHSsC<~Lw z-P@SGQ;JNA4kLx5_&xawh$@+@L>h+GeT7smLJD7Tw)a4XTMo6v0HxFWRXlUMI42r- zIS45t*a_`20qyTe&0)v$D44!^L^vpurVcyHErozl5`zR?%2^5#%r$VVmfTNkr;z1b6cgR7oTXjH=03 zRO4awv+L-pzX9*Rk;<{Cu3RJ~QR(yJgsOH#ILuj~UZMODvEdD(hjz4v7}He?g!S{8 zJ?YRHrap%ui?Ju#>YMA&by%fluR#{M%Sr zWHnN_L-892oZ0(%;-IojoID?Q939M%0R9qKb`RpB8LCCB%vlSJdV_3w3}F1z^z(eL zP9W>wa5hRHg$^OGo#8(f{h(Od3_?pe{#9neOddK{F{{|d-9HYOiuO0H0h{JQoVXEF*ZdBy zLBq}9FQLdwW`~=5V3Hl8sJ7F$@!T_xEDQ}03wcm5ikVydxF50j78ybGGCojfhG-5wL03@rHTm%S^;H0&`|g&_9n@$5SGk9`pCXinemjBQRb!YK|Of z!|e%B8fP*U-k_%gQ2T^g|Ad*41F8H1iKewwHbY{>P(HWzQp*`SnyciOf6y%2o()8c zT>8X_#W&Dl7G`M)s@$05DgpYq$SkLji!;nX+6m`*sF4lkq~D2Nkm&3(*Hr`rWfUE2 zOLA#Lr^Df*CwaTVv$1R?eQ~o8fP{`9+r`RzX{>}*<%2!dIY5i}ZF40d1IGp`3Aq>% z1pkD|F@x@3RX!|XZhei&qOoixNMH6P?7R}WBk*M^kS$V9FH}tHMjl&2SG@s_e+RCQ zLVX8e7bg%-v5nh0P7)p-+_ZlkWnT?Q{6ZD9nenkAhVm7rS$(eod{aNJB@Wlf?Rm^( zX062rTRrQC5(N69Bk%BXGz{8HD1z42p zDw^jA-xTDh`w4DW~iejSeRDalsZp|4{(5Ps=9%9#<9;_V9_O2o}jv6)RP z&QnA2_?3=AQ4NWRAoj79*T8{{E#bg^tOPUX z!+bOYQ`m>N^UxqJ?7UEdq2)VshwwCb828j+hmhEvT%u%<*Pam~zN$<|bt#4v)d4j< z(PLFXgR$sv5pb3gb7l$M_Psp;z;>)!Zm_%lxeE8)k*UjuTuX(A_dt)t_Pee^Popau z%{m!0R=Nb?W>)C@cba`Yx{9V$ZX?AKA)09Lb<}MV(a(hKe4yvLHw)YjLaqPCVnuUf zOr0V?g@E4*r(F!&PK@qPEPDNqg7eMff--}}1zqq=jRWX|#%LE&P|y+@N(BLD- z%5a;NgT;Uo=ynk&pLC70-2^(rVQ!^{V7ZNx(JfnpTbi4}($s64GnFq%;@egSVC}&5 zVLrn_JG;H)p z{%{T8uf|+7LmvIAh|3# z01S0su~};C>M;*dAVLatOGE`p4!9@sgJ!rrAk?K*?u7~DSuXU`tdEYa&1aY2PgLM4 zk4p8?%Jys|G8~yOf9Zx(TAv7r?U~bDU*RM^OZE}N>|L0fxIJw)X%~Et?09_J3_Zy7 zd*pKf_*M@MP7I(rF%?~#@ovnYJNv+$53y`uJZA(e0;_8cZOF^Vtttx=m3FKuziAB* zmW2QM=kVFgI2W_4MKS%@y$jJ@@}Yk*r)VI1-wDq3eAqvTJeqQ=S!#Ep66|0t5*%Ou zuh&)3XgV<;&jpgEU*N_Yb;5f&U9j^9A`VDkLJ2}lJbh_*6~T-tltX^sk(Xc?v*yNR zh!iIoQ0GI}rm0YAVTk-Iu>IY^;B_c>^;I|#R+fUORVPLQzIu7nq_`>LENcgbtBYmWF!Ync^=#SNiHVgUf+^JY|LP+7=Vx zD~2X;;rZ;qtBJ_3noe{s>S7|IDLww@u8h;Gr+ug}j#rhwpJ@=!|(TRwz-RM#{ zj5VLCx^QL927+TNbrNcRGxjb!`e*ugF~a;QmY5H51m`_3zUbWeRcr43Oa$Ky-sW>R z>qOR>d1%HTOmB9?^a^KT3(kIh>Do1zIBQh=T#Dn+J zA+Yf>4m;}lA`mPAf_WE^;i%ISwM-E7FH>-32Eu6`mT=bb?>Y=Ngy~PXJh~NK#9$_| zAv#>Z(QF-3IWb5eUg}SAp-GUfW;gN@5hgpFqpBea{xnFj<6cA5_7t9fr(DfGcX1w8 zDFnAMPHqqHCFhBRmdbS?RsxL`HxIZH%k+vR*L<0ZQ5)@CR2Kz$@c@|3hHMhU`a~%h z32eYWi^)T*9p|4lD^=KoKm9))_F37C$$4-Mpx7cAf5$42i+zc;(so#A+AM|*}mgdbKKvCjbB0wXM7yNjq{2G5rP!oF>_FgO>BAU z%G`m57Wx9YXs&|@2sDHF@&NX2C~N`g=d=*z$UL};RE<+M`}A4^^Ja6VOVYXoX6)hY zD(=Pep5}#uAFPiMR!6X_Le7Q2z4H*NnNoe0N8Fo3`YXy2_hJ6qvY))+oPB{M?fBIj z$4%AYR<0)V?$@L;Ti7bnD84ZDNB6>z9 zLhznt9IO9SP3LOUkmnYwUawv2%;TOj>arsX^z8FBifMF86a8Q)yx2?*IBmj^eU{91 zWkM3ns6mdnyDTA=?ac}xB^BxJ;T*pFgwyC_;ub!cDEvq1P4Hmq`-@T077u7TaqM^p z^M!d#;btev7LLJ`$o{H?(LnjcB1&;rg0X+?cdIgr6cg8Xk~ntfj07gNH%~u_IWXNF za^+?ITY{mDlBdc}Y@i*`Mu?D9S-f&mm13eM?iL+2=r&K>&v2cL#$Bks z_}R_24_B`-M|zteE#Ga*@+F9OnEp$yHp$pgdze~*tvRA%J2S6GlT!ZiZD4}rG}2O3 zrE|gzb)k)&l+(u#*7!637R(|XuHL7`+*$9ec^>|MaCe_UO*L-2=u=iIplLv;h88*k z(iGGrw9rGZLO?)3)F53^lMo;jF%*$*fPko|hzKaCNd!btpP;Cys6kP&Jc=C~?)=~L z&faIwoH^h2m%Sz*^C8J()|z#%`}$qefZ4Nh|MWJcVU8K&tifs(o{a|r)-J9+=j(mF zE=%;)O^)r43LSkOt@*iNpunCr`*B6$(%F^;x0RVO8U z_SQb*t7PsCm&Usd0VAf!)oIL?Lwvm`VcVf$=GM=KFb#`!GO$5@4LN!PxC8aL*oAvl zLcVdc(D6B(JSucFVk9e|hSA0`(DA+*enW7x#cjBfY-%NLNKe&At#Og*ZN0x= zPLC|v6?+|r1QKTLqo1v??!Szl{{$*L^!0IWVp@Z$Nwt1Till${jt7uZ|IvO<$Lqrie*2YO@tSiVMp{Xg z8@nR7Y6OHb@vM?y)8M~RPi4$Pt%&KZLaar@Yb8T#({p&)yV;++qW$WGA0!4pprvFB z4Vp^BzX?T$oWfL1cBE+4#mwa7Zgnrm!ghHn8;+XPsIDs`c4XbzUS$5oM4ofGGq^`{ zqHqmsi1Ph$&Hl@JU5_bT_z|4pPm8#kL`5oIzPC$SDFM9y_m; zKI@I#^a5q*63>b2@ZhKZUZEvTqo%#7*K zB6V|4--d@8LVT1d<(Nm1WdRbl_c&q*mZ% ztF5BqXf;tEb@1Uq!bmSFIGqRaOriBGwNw2yZFVnh)hy9xYeqZip-y4$nhRdHGwW)s zsF>SWt|8|A+%v*{q1doF&JS3I*VFFE3*?fPz$hR`D>p)L>{)m5QoMiF)5!0 zkV|Xpbc`rqB1!46#ea}WF*I8rqv?C*q_JYuC1#j!MixUZm7WMW$6pC8y}QfVEFt^9IgDtAW`QzOL|2DCyApha5%QM?uoFRA*y+S;wjLad@VqZPGQ%m}$ zR>lBrkL)OXU!-ILy?zkAA5^Ax&%t9Ok*^|Pn!fnZhghbZRG|#`fkux&9)Q$t49gb;(!h;!o;IAT$PFZ@l{LL0S2ENj zv3Kl0;rVYCrRY$J(Ip)5szrAZvbru;vj5zeu~{KxWhfD37nGm8->@3^Y0W|T3Ai(E zV{OMpOd6>`hAP2=}Eh>ovH_aYiXU_@f>Ww};!M+&7_%FC3reZ z3TYUF*9zm|s#nG=nq@S@W!!^*tcJ4x$-!tU8G8M!5o6dp!B2Rf4n+jvbexXp`CIWv7_-5aO||G5rzQrXG9-cZOfQ1pkb%WciD zu`I@f(XWb+Y^pi8^~1kiY?yAHli=FpguZCGfoZ8V+;mpI*W|SuPI2RHBq~q}?fv?F z_x_VGKYd&c$R?*s$Q$=sp#YJKT=is@!`apJm@P%OpB#tnL5cQ0ZrO~lYmEIxnwUqT z?Sc!-J{Lc2aNp-&4^ywUp40JB5a?U^&DDm9NH64!>JduN~D~ zzcG-(#R)NMbieO$G@hNDu02Khnv_tr<=vVuSNeZldD8CQ`0|R;?cs*SwquM9ANP`c zoV0#3xVA*3W6C;;9I4DdI1Db_?n4rvwQXLf-Zxyi%ci_uv;N#8F-Q~opw#4|tGKDH zup9;RU4#raf-EP1*hb!|Aq>YFdhjBwE)eo2LUd2d`A<1EI)bCL$i^*!XYxiim~eD^ zLEx;W;SDMwvnv->zciI=@#_^~!g{DBvV8gx_fh;|4x4-O0xZeZHJS}^BvQCbS&g}=Bbs>mwJCegeB zTWryR3_LDEHFi#gr8HVAH!IF}NnU7t)Lyl1y2=`P)q+)vOwqY7G0nXw{rz@)ZT=@(b37~6fg1GgQ{AL2k9^I{_y$aS)S{9 z$nDar`zx?rsdyFZB0n}{t@AHR_i{Lc!M!J+o~t&^tPK>k4C}YjXVD3O4@zno=0sRa zhg2+a@foEcLbYE$dQI;^d&*d+$mhU9Q!z_%If80dK@FLZ*gf9*GSCWA2;PRT$?m6p z-*6-IY-gp6J01eTf3&J4NjOetLFU&UcXI`zbv5Y*|1#7pSYBZ)SouQ}GuE1hbb76v zSM_^xHnG%M3nG}}`N?_yOS~{v5qj79{if2wcdsn}#TyX&jQ^#5IgCMo~B=Cg30b00r zNx{H+OP#pe8`x$;5dY&4BT5}~%Vv&{_xE+Bhsg>EM2FSV0SJk`zxp&0tE*-tI!@so z1{J9gkvziT_34KrOF>uD1BvVVEJf=7%0NUStP@h`Kq<2U9VCNQD#fe+NFct%PT27- z{UBH7~T78-FXlmt4$|EF=Gp=SBKBOfqJfgDD{Jmc@Y7Zgfe%J*--b7!6}9WIZ6 z`iDnwjghpmW|)6(H+dN{$+MHmG2M?0FETrzj2SmNub4h#nZ0qQly~1n1=xTs`>i^( zJb5v}kV>BnJb&2nrp}%W!bbb!zD|%6>3m<|p%K)ks61FeH&nBYYbZOa*9*~XE8P+r z0%!4xnQRY}ljpq6;bmSfJ2azL=vT%oDqZE6`d>IB8P{i;yQ*5zWgq;Ztz2va<9b8L zrbYDz-Ik2AN0zFe?m6;K5O9&yBQ*ouh`a3DhG780UEW*>1G{4E#;R2l?INrBG&QNZlWt4T<|? z2s-XMDMv#C7+lMV!Q_uE{>}sbu!mRjEn9Z**HNmCQ%s%r4tM>#s(J^~<5E%RP!O;S{#Cf%$6xT#XzThJf7XRm>3yv>HMi}vdbJA$g2MV)YNDr zRh>A>d3|!))ne<`@Wp`L=8A{693!_<8j*XWf6L~CI&EPi{lVaqKMdz{Xj@gJF4A)A zM~Hb_ks(9>uQG|F6g__GNpaOCJxs^?=dsVeR604~&i*SI3WC&nyDshX49p){54!vP zW_wl@TZ4r|v*H5ZK5=qa*3X03fR2S@IxKswzt+;IHZZ+&MXx!2(EUO(p07%Wm=L)e zx*xB4bmIfbmp=v4B=Q=xE?LQVKJv3ZONBkkm%*=rH!kH4PTcBlf2{w(o@pv&`N6Am zaXA_*M>sAjQF5SHz$f>1o96kiy!4rJtBJ}4aji*I3YpXaMnH9$EB!U4q-hgv^F+PN3(8R18h_WfcmC!irFs9&Lk4nw z&TYR+87TU(ikn=fx=AU`9u=s%@bNiDf$zG>64jCuh^bYM#2^9^IB*UY1!8)s9c`g- z(U%w|bl)r&e00i~*F~6VM4{`-!UYpvnj&4Fr)%f2@V*x|W5F@av-AF4h##V49QZh%DuU4xhM$;!MpNS-sAr7U{{D zC^jeP^r+gmO22(*EfUv-bPX-$8s9I%hS77`?m>MK2WiR>nWS*ZQp~XC9-+ zUUS&LG*F30khQI{dc2XrjdVkK5&2q6p4+6t*%NFhBG&}E{mS~GB$wxiE}i2xvd1R8 z8du%gUSCcpe|-70>K3i>C7bQFq&^oD-=r89ODEHn&dCiS>!(5JjW0Xj z70*ZOBi|e!Z@8hWN^GkLJL_%F;t(h>?n8h~Z;s}7<7%tuEDO2+zi0pWp%%-EimwK* ztRjoKK7lbJCz#Eru!@x(_g8R4;mcYE}|BmGk)UFC7>c+pO_f6;-cAx>n9M(0DI zGFW=1mWOXje_x5!6N8?}1=;ze*<#fFjw!uB z>CER1-&c{cSM}7gZ85hJ-&eY-+#B9<>V+=m!gw7_#1EY&|De<?a#o4W%6^0tepgK7}gnU9?pE*VJ zj+>!GcNZmntMn3sy@vo3Yn=DcfFA~GQ>OeKgIrzDTXo7&Z4V@}#BMDTx;C%;3XEE| zRtoQA5g79|CgSfO0h=i9p)*e}v_#d4zaO?zwL1u+4#T3Bpqt#e_nu^oSeI62K}Z$6 zAWX;FUd6LS(3&BT^eu;Ava72E>pDSIi<>yyy~j{dBLT|4nR&1#*J{M*WZp|>?d2a8 zuNkrT3Imq_|9WVpfXmObTlqoxWw;$>oW?D8M@92bl4rMSS6$wl&oy!?xO@y1dF1?5 zsAEHF(TPB=Pu?HBh0iztor@OS-iO{&y1(>6qAGeBx^@Ec?SGH=r~OsU)MK)=%51c}LA|Q(sj|`<_D`z~6wX{RLv`XRGUJ8taFSQGoARk>{W#M| zTOY&8+QF0zs`Q1(yDGYFw(LKuX7h&JPw!rTHkJvU9;MV`IMUT&rWu60^^ogWRb|tH z_7`PSReFUqG;AeJXdY1;mm8ZBl|i3IMXvask_lAJwM-1%gWjA#&DeFc#<&I149d!* z1tyY2rF%G|GwJ?P8&ne6(8uM$7akBid!x}Y^ZoCdy9aT~bXhN@}Iu$C($;;0LvS#-=qy zoW1F-xzXg(SM;v>MzcYaz@xu5{$BnVd9ac#MP5a}2oCFG)N)NSMcJcir>HOBTYlva zG!@v`@PjeBKpW0HyKS^AT9vdLMNB2;RS|k_7LVc!lZ04=55?Y%)NH61X{;($^)lL- zcnk|$!9PiuQl~qC%e_yLGQ0{E8S}(|f%?E1WyKE5yk&1XZd`3`dlF`qcf1KWsHBIN#GtCH8?Fj{;jT@ObzE)KFJb(|hPCV)!4jI>k zbV^l=o|r=}_?b)Og9wkXJ-Z#8%I z|7khY8cBl_j*1u%L~d+95ARptO(eKtY5nnr83X4`Vz{?rH*G;O7{%(2hnfxc3|Pg z6t2zpC)U2U0JE)aMUzUQ+jRy ze-m(nw0pT0zk#Y0z?3SL7NXIyGX475WL(ED-Q~-w7Y#~%A!?X8z*mU1FVIuw$f^4mhL>EDe)u?Pc*%s;N@-i%XR2S@XD~{Dwa(gAy3_jH4Fy zXkf@X$iWJ+L7z03Lngt(HAMRRj&rqERTb$mz^FgNdYbdkiy(m{^kTUf{ZsXd{+{;Y zDj7YsmbmH4B?v}S1F(ny1H>7h0JseYPNqPjzOI0<3VV^7Oo9<8>5Ky#Xu99-blL63 zne?y=-GM-LH)Rg2uYrrJWn63G(?W;~k8snYjzJS`Xf-WA-Q0fZ+a8d;<`UkWFYdYL zCp_YD7UT(RJKAU}K?hgynsV-6PYp`ZSEW8Mi3skdXF*U6;!-sRh!-y1eQ3VXT`h4d zGB}Y=?eCUi6lq@9o9D7Ura{e(Qb>OwuNtmF4MS%GX9Ago_YVy1cXcBUR!|MMPrL$@ zGn7(LAJn>8FI2W(*EqPdSar|R)pyE4ni`=ggy23d-=Ep7#Sk*4Dz*gMf+XQBmihPy z`tF%dz<5ML@^VX|ZAmUS=hIg(J-vlCMi?HQ2}ZT{R*=(gyIQ@teL(x}jnJ#R-O51R z78Nkf#6b^kIb(rJlJU`ujx{&!7gmP|!avP?FAMVxg}6pYRl8C!`FBf_c|j^6=G->ReD#BXnYvpVb9sYF<}sU~zk1THjOujY4g+N9v}Z z?L@mtkWRPn-WDb*1%MKiJ((OB2~=dvY{#9stq`}VCj%1ONqhgjb5x{iZiZV7EtI(# z$5PR$XEPrNs-aqbgLJy2-he^8M=L?Ro}gvY@Z?;!c<$k%aB;#mwJVZ)bsyV zkjooT=o^?H~$wttXG$c0ro)r!Wz1y)TGq~-P(aB8=meloibj@9I{YCwc0O8!D z8ns6f|2GL-b*W<2@{5z?UO!)HMl~MwyEFUjZqu74)m(#-BR*+MT=mOKh$xK&d<(^m zys?=PjroG1BgZs-f7I2dKv4HhKUn&60_~FRE%y1BVytA)0i=^i{}Sv_wt|diwNF~T zzg|bSMz0}^p+9KW>bYc8ue;7yYZTK0odd%ywNfVcoZlAsY5AI)A& zk5^py3bK5~Oj~mIHjK#&-6|gB6J-wt9s zzPBExf7|+uDG!{)Rcv-{pelylYyy8p;)c9it7kZ`tgK4ty0M#w(J%yPtj2R!?>@Ud z6RC8j-R*XG^^nmV_fd)e^P|JnU!&O|ds^{7VIPI`pc(l&gG7%Hl6!YjnLm46_s;p7H;L}xQ)g)wi?{fY1Kd|j03cwh^|Pm zK@{Fb^EMdLN@(z-mli^ky*sBc+cC{gjC)?;%$f5jYmFB(F54j98D4rRw0{b?IwoaAHt-XF_L52oQ^-94}IOg>6DU`C3B@b@(R8DkG6+-w+^v8 zVl0N&GZL|<2xiFVL0!a_-8Arw)C|M^5gJ~;QTg-_o@R>MpX{+eHcwat8Zl2&a9$^5 zv_gHOo;yK89Kv3j*9xfss}+FB>0EODVtT&^}mH9@L!GzlkK>WIhwv9mrkOX%>l36(fjP&pwHGYWNeQZr2^K&_rk}f zH@N1r97U}VnaAnrk*F7dAK4edEA-sy9DE8`n?y5bhlh28F#@k^Gmo^AIK)J*-U8Un z*#0+;vHwBO= z;N}IdoDLFP-yzMwQU6(qDj1OkYN%MK#845wx=%?2bC-MWE)ol(*GB`;Tb@Wk%QkWqICN2&;bHw9kv_k5IlkB0m&LDWIlh%^jPYvR-2Q+C*RX$USSC*vAQr$DEOU--}0wLIB5A6z& zkwwCqRfou$Jf(?Z0%QD;{xr6>0(*mvk%5l`9V9-VVDchXn6B>C#JEP8{_HY0b48G4Gp_9Q`zZHdmjP45VJgz;tkik`NZCOj~=jbFC|dBxzVr5uI;fZB`F5m zW|<`|_k9qoNC(-&U?I{|ZZuOO1i=&F1TV*m%g5i3-tm97FKHaH(5Yg%MXSO~H(T1S zxZ@g?Rd~$k*-hZN8wmEoOK&$NWb6nXES@9QUmjhaWf~&1*SWH>siTwe#c(%f&`~|0uqe=5w$| zZ*f8N`}Cn03C6-am43pc!sFX(3amg}@ou{-a~Jr@`} z@r9fc+#xRn5DhsV9yC4Dhr#|cxB|(g2Nb^?rN4n7WpsC)(?LWC1vyg^h?xYI!XM@P zHC{&icryOOW66KCojOCQcnDYs5o&xx?Uk4%(FpCC`~#8z#w~NSFdSVW1XuCklIA?i zm#bUw#wU=XEe5|Ox@qvJ#@%(x`)>_;TVvwrZQazghdj%rMKz)XnaN#4$oTYamAmZ{ zAw+WKuGQuC$BNm#M&g4&me;Gv@_ieu-@!A0nv<|u%6uBPGi=oG0b4Z}PNsXT%vDpx zZ2b0d@<&O%5OgU-a_S&wjf`Wsz((Xzus@eXF4h|639?gb0(v^BV!xM{GPdP z)(llEQIcw3WXLTtD<4}iTWf1B6L~n<253t$0`9KYeak%R?}{CP4BPTB{YwqD^(#v@ zO>2jLcrZYbt1IA+=PJtU!-9XW9qRvtVBRGj$V~Vn-&ZW%@Kk30F8-69^^klL^j5q) ze$M6Us~I>9cI2(f$Ct-dK0B(PqdR?}Ohv3d2~?y3$gH3?2F1_fG#AH6BJbYeqClfjf7p$F_E%5ApUNg=HB;U)G_ z$Lwu#Js>g9%_u8h!P@PP+zzJ`=eIol8hOOfyDM?oh)th?EO$ylqn&<8kdv-Mg7H9t z!8ee_z}C$UiJk+Ajta_QASupa%hrM9T>}Zh4%-emB=2=dIh2!F{!Jk^B##)yA9IVj z=IQzBd_LrS`qf!cZ?c7uxBWC1G}IMwCnx=v!^e>Ue~R56O$xYYn?bV(Tzho;uXvWT zqdhIxZLL%#a8M=k`(NhZ-xSA>EXUXbj(H`6d50YHj|}D?{qAe*2%0!gs$7#fd;==l z1|Aula*;0Ie6ch!$m$q{ASvNbxfUc4m;~BY;&b3{Zh^XZw`aduH*Nb7FNC13OSjVMlJsRAspv zNH|*e)``3BLd~_)UhmI)YhG}$Vtac`)^{Wt484T9U6`U=pj$u=ul{Gp6b;;)JC*pu zGV6z>aNtP!=#Fjn&8xG@pE_-MlP~=2chKPCU(EWaOY6bQL;Mfx1?9j|&o6~nyLiJl zgys;RPdAIU4V8cQvm8ybB!a^B{ygAJDLUfx6#2tad4mD(r=z131Y(0`^Y#uKKeZ5h zk;Oj3&jD5|fk4pJ)%~AB!p4moJv=-V zHbQW4@c+Xj?Ay05J3IRdXww{M&36#u4+#7fg!&0X{Y9Z(K{WoT5tpE=AAt<+fK2C* zrvK$6tiQY3=`F$duc6@|Q}Y#j`<0EG{xx<~I0?hh|2PREX!Lnx;2!x5W?4zuDOyW&&M2QRr5_xk)dm2fAjSh}TQZfo&$dc(W_LK2>5 zR49am|H&gXC5(%moBuZ(;cD4`+X(ks#^*Zz10%dVHU745{LAq8@|E$W!ST`2(W$Aa|9>Ij?c2X! zzkdDl<*(uZ{au+C3J#Eji^3l8dBV6Y#^%G5%Md)$$;DcY3xW_0V-iUeE(ZYuW_<)$&ZX|1 zHht*9{;A>IfA3xDHtRJ5A6F(v2^se|q1foBLH49?JMUkD>C+iLVc>p*#`*+Sq#Qg7 ztbrXGJ6{Ki>^gT+)C6L`bQ?@qF~wMeez4tOpgEdoP<;RW(_N24vq|hO#9+`9 zt~f!kqnJWf&I_j;a8*mC94N!6Pwi8W>TUxCorZ(-0k?Z=psOlUj?ugC7EOYndb=Nh zXipNv;l_>2NCk3GOMwEL7TJxkjh{qR(2x-Ws%%Gz@aXo{Y$<~rPhjV2=r2%;j{{xE zL-QJ_1+ao}`n1^6zo+&Xr6Q&HMO~3uP-NA<2lQ}*rpdJUG$MHvv>PxjeY>qLxgT^6 z>Srzk1x&V6db(&o^`iPfOC*D)+mUZCXg=PfWCjpxqbxu?a!Op$?V|4XiYIxg$6=PF zNGj50=uwmM#(@WtXx)V~RHc$~Lj#yeZ4VX6HhwyUjn*)^sJ%HWyacK$;BPcMwGt!$>El0>s|9U_2{r#^GV#M0tOHNyMia$;mpZWdihU16d zpJkqF|9qJV-}UF~?6zGL@Wb2>f4>_ z-oUQX-{tFNm^LxK?k5A1o!;T|%mllsH4$MyCke1(d14ihnj9*QuF>n8sHSr(H)}|A z^2K<v4YCU_|~qlzBk}c-@+{J+;k0 zqRKtt8&A!T?ds!0LZ@rm)&KqCWgLcq9)2>a>}x%0ZOZ1kEccf?K1R`uFoo+_&y1a0 zB!Q{6O5_R&&PVRL#@d=wg`RHTh@z=%6$4~Du<~J6k$*&EP^*B0I=9T#i~yI`1EW=abd2yn{><}1BSoFQfdn#_0`;5NZ-Ysa88yZT{lY5bz+{8FB^g-?aDV` zKe1rzDaTFd!{8aEzA0Q>4yMQwc{`@8!d9>WRftc?P}X#IO5eaqn9s`rO$WXi587#K6Y!xIB_ z5<*)s=?M5OF>4n$~r9PnKNI$of`5tt6fcH&2L9SGj`6_)ubwSOSn zo(Fbw%rISmJ249PAma~`OB@HXJ?Ok#JFu4+Ldo%5!3uWkzl3K{kPULwUNKrEPRq(p zo>W(BHrxxL?j?8P8$JD7$jI?)m@`7SQWv&gfHJ7xA0-dTS=zT&T zh5sKprxt|TPX<$Em>w1)gbB;cJ*Y8{K5Pw33We?FCo0naK}<~6T_}m|wPj#etb#S_ zjY)i&;?)ajdX;j}0sP!Pu`~siB6r0LfkJqqqtl_{98WkZem%2Pzt0=k#(JEB?_|Rx zNf<6Ol}d>`R1_;B?b59(+sashd9bQB86uLthUiYmbqGpKM|qakzF0Y`1B9vq3A&G^ zU(2agm4g{!u-Aitt#yT$kX4LGYyqKZy^$+cI1VR1C1c`^Z+=D5%Y1j z!d?WgUtyv}8rYsCuze!EDSsQWs{Bz-tds~YlA~R(R}ErN`pkVfvY-c{m{)X|zZhke zj|*o4=}e$ao}aLU8#0aKQQ%BQyp{USmv>{CB=~+%t@$93!U9$^T&*y$Bq8d?eZV!x zlOTYR-2KnwV@}CopCj6hBn>COG?)VZPZcP99bo?jJfIfjo{adKh<@h|7Gdy=^&ty~ zId+^T=nIqrjH#CwnF5Gl5G)mw`L!h0M-I`TK#wqx`SQ$NV?bGP;%cE{1Pkmj1?Q5m z17cLXbtVRm06XF>-WSFH&WqN|SjIR3couzg$f?mLfff)OOUim!8T04)LP6iT5 z{-?WY#|A2eVpOA8Wc9t);Dlfy2}ULJAnssKR-unItVPxWiC1du?V5ktHXQ~IkpV@N z6UNwMCfNG>_tUuy=q3VWPyk~ocEM%rl?bGt@c3j``x@|(=ij>Au)Au9Dyzk@SjOSk z+4;C$$n`~6^+uXC1@>yJ^7vxGd>w2DE9ppYOow%oO=-vY8?0h9=w@2KNd!H1Jl)1R zu)8ES##-suaYfgu|Fai}sIxKJ_Q2k-7$@(Y+23;?CFcNb%}d0c3>N$VyCV(+|E{*v z!Z>cb5VdytwEaA4H4|(l1~M3~>tv^1&DPm{1mZv|sI1=ncSzM^FW`)PQKIaq`L+_g ztk5(Bif~5elaTT1I|Jl^1)}(y8a!Eu>R=sC+4E zVZim&&RKxb9xP;|Y&IyiX-sxI^~m_O_OkR3S;R4saug}}k{XDlRP2Fb9xmx!c1)kC5_w4^|CtYX1F zZ`l*{{Cf8f1C#_x)&a@LOGTCR?;0 ze6KY;*$D2#3~6Ft8f3tIL9pvesxA$U_-T0VmzdlTpWaE#v89Y3uPz}9E)=L1hD{z? zYonw&2W+D#ZDGTsL*OBx9>_HMgVq(F`G6}6af|L?!zFl)SG$HD@^d%M{Grrb5~#xj zYt|K5Q0<$2`zW;TU5l$2dM!t(j@h5U*arOw6NDlS_a>%Bk891L zeKUM}HbvecZ8tn-#7NVMEsNAKF-=RLuAeav(QL_bq z)a!=kM|6ZhP$fo8*t&O$+ceQq!Ty(X9iOos`=N_iU!JQCHr$TCOZ1cEGNGbGq(Q z{AlocES|BymYEtyg4&b(>wzPftbL@fDf#GS&8+s_iSO?&| zn-W6~3=}-N?16udL`*I|wVFnQRxpR$9{^Ty`w{U9AwtLZ*@J`lqvl{w5EA14#QE%O zsI?3uLHP*NF1m)N%U$ISG-L5u^%=Q=B+!GRe)ybidC+_LiRU#v(_3D) zLITm7*)3)Jl|-y##Y~h@x%aESm@_O?0vjfKc;e)CSdc8^wqe|zR_v)PGUv(bO`~(& zp*W>?u4`o_kwSnhPO%?a+{;8J$N_^lE3UQ{`bSxVx2(WBtl`_(s1{jtofufHfGv;1 zcY@}~ZC=cC$kxor^%*bpyQEL8aF55tdk5Y<%>@q%%8rJHT`NMhi{JdJSLOBJ`i4Ta z$qM{sySFpphv<`2*NWpQXwR3B6KcqaTXNkh(7Qqq6JKo?uTYja`>%`}9ENHxAgeXZy7#jW__EB&x;jIZj{<5D-QZoe+pTn^qWTZ%J$0nhkiyao&USi%LkP@@oLw$D7RSVdV`CDPm9ib*V61&CWDhKj3!wEb zTrT?MaJ!PO6nV2b`pEp2usx(0448{N=^R$y+yI-ZX$d&xwBw-&Fo6*q^u}KNBxHKs z+(i|yh$Kf|*Ya7Yg?Z}ZD z!L?|s->bd5(#j}@j_5D)45MtZR|oXsZRZ`MW2Z%<_?C46Wj43OqOo#%19U_EbbGkzAPP-PQYI?c}^y5WV|hE3MDhBkjQH)Wvs_5Bg@%M@2+ z;f5@J4XME?;S{Q%S$J2+Qgu~y*M>-?wzcHU@*3OZO9wlwH^lb|@OF#$9`czF7OEqz zzd)jzBKY7E(p+{5qKszkz#NK*EQgRi8{I3pVb+{>Tpwonx_4pWC<&V8WYXRD-Vd#|^?~3*(CD@$dPnqLnQPrOsKEyA$LQ zr8^-)vS7d&r5|AqnVG#P>H6>t7Y5N4K7)4Yq`@DFj?N}^)P#@QdFF9LKy4Z04hvD+x zJMQd>B2`D!z=5Hi*KTj$y{VI1YJHU;5W-I~a#@>6nnRu&t&8&4N~s$0JeTB3Z=0JR zODe>V^$Z0gUUmBI|0o38M-3UOB=Ec0eKg}CJ0j!3|1<(RMYu+?7PG|&mWhPg>lIe}Jt!V@`1(AEcTnmypU zRmfXk%W>Lvl>t3T@%r&`7ulK~Z>tbDB=>zcAD+SVXHtf4nFRHw#-UPMzlbAtZ0F)K z=^V$bp)^pC7~F@_-Brqf)t)`0MvQ}7`V8(H#Up_6_i}95@&6$9!1T143EPKv;7+5s zmN5&en+wK@Ev|s&gYY~^BoJEwC|y*@1!awe`S#7Ktc5l3XCAwyH>!&|g2acD6y}Nz z`GhDJ7X%Fj*0@8-^-YMUZ|?wmkm#&d^e`$x!eUQc**<1I0FRx0{`XCi&dlRP<(i}s zt=e6~@3g%^{jzS7&pKMqTRf)uV;)3f~$|L?@7l|sNN|i zOoc^QDsl$l8?AZnzS#ZHpOk#;47nJ0PJA5I0>N4gprZ9hRjY9@C_pFMTqOr;_a-Ui z^7J}5@2k+Tn(h9O*6FniuEU8|jQ;vHw@G4eiPhpY|M-y=M=gK{()RuA*v|^T zJd(whqv;M-#wB)%xE5{%9rMis6W{*COJSAx{`&sXmU7b=oyM%G`0;}NNyXi|tFxC@ zs6{$^Xs(79R8>zE0HB2m(}j^4+uakcwx^l9z#LlI6>&HC?av_}O{D(XHDG+?n9Qh< zos#CE+DZbPJWzuG&%~=jRu0U&BCrqlkM0b2BBmEp{9RNERL?gjyV8P8*XKb=S78#O zE~*9v5rTC8j1_WQSzAM}qzJxqDBob3j-UD5wT?lSS3xAIe7P$pHXB zJXzk zvB8Up=;?!R=e5<9PVFy6^_x%)(q`Y<9XS5w6LRm0t;>Q?+v-KtR=Gd>ho=-uA3wY! zdcL2e{|_VE+w3mNZ_Q0MK1$yBz+pau>pwQxBS!Ry<+d|YwS+M#{=XIC{N#_X$C3&ztIBw~yYWULl&)E@ZKE zR5lvy++y+VxI1fDetFsNsMFolG|p5--pYcPXuoNpHA~aN9e;bsOr#=Qyr-5w98jJa2 z=U&F@n7CfVHE3q5iMjW+Z3>^_+SEj+lan6M*(4mwPbr zAC%b-P@Uq0^Ck!?4(_TzgfItgTQovUU5#wun#*L(pi+^LQm1tK7U z!eRk9z7j~_EZBRU0eP@@m~y-~{b{i;6{Jxs<4;GUz1oasA#sa&zxp(=|`tQD_ABYU`^IKT^qE?zD~S;A11Ff_EgO9%sL zeY))2wrwc3Ew9a16YMGihx8QJ+uW6spn4Qm>)W<*m1_MMTyjMLMR2?5iO=&Gn6sYe zvy=((ylI}0UWvsLC(0TDM?a8>| zv0TlqW8g|D^PvXGbecFH!<7yXkqeX%R3OhKcVjaE%~PyIaSU&g9KF1q7u8kSJu0KO?W-i4q!4Z1pLvo#>hq?9L!=^(0bN5y3%{qg$PmCL5|D%*NT!PZeS4m_ zG^8Hq>BF@7h3DGLf?OE6+Je?nZ3{}Kk(1(pms7Q^gtd)a5#9_T(v^r5Wh=_26czX+ zadU{jvo1=Z<4x^#6f|HA;tPZPsd3LEc{usI9rf85-h+Iu>lCx0Fu4L?Dh}#i0nN?A zt-XZ)fQRsxmrBR-m7WcAXA9vlP;k;luXPfXy3BD{fsBno+yn*Na9|=IWCqYITyYT2 zY3<7bKdD!uZslRun9+W>sv^~uW(^5=u>Y)LbPp#oleOX3^c{TehBLCknPI~~P{J3S z9+77wswa|BhmS#{$eQdRFBT05W8}gZK(*!ar3zFujYY<>7}!VC6$^)UbYrdgz zhR68z(fp))XGXNxqVO#QoDY%XyzN2?ViatbRz3=S@f7WI+8%U`wI;Uu=jg z5j5E!-3;Tp#sJkN43v-^FajBxiTzHMfrtoc7MS zqno@JV1zZ6y@c)D1FXY=Hh2NONiVMP*zIH`B5zD&AC}!SSXXw(bRHDd46F?e7LYuU zghGC5T;c3}$Ie>CJf-x0TDBOZSfG?hSUx_99M&i$Ho z#62HaG(M~wMztokYM|K0IMdq2QLTWy+fl5Hm-i}x@wq@P_%4D>dJ{4b^dcEV_5#;c z!lTS%e`RnD8C&IDYsy6r+C_1jpM#cdK})}P!G=c}^N?dYu$1_h7o(Xblrl=s&Qc+i zkim-VLAp@d_7`x9u3Tf(BRB8PbCJxu+ATh7sF?qTOYS8EE|0zgvJFvBxiGLHotwSJ zwxP$ewI|B-UzYw;)KQ`T*O$Z+0@#o|%xzxu-OVHNKtU(-%_Q@&->0+8%T1HmCe&?T z&0t?_;eMv<96C307t9z2PI{GRC+^5oYoKINc*HB@&v_=F$I*rj zE=vIN^8hs}a8<}iIK*6F08Cq3+;b=4Fpi&;vmQZ!-gMsRMdU_`jrYePeP$sO285~Z ztqpw-s^wm>*&J6oXmua#V*|%i#|I{fn_@DqmNOhHWApg)xDkR817yx)YD$1EJrF+$ zB!CX33ZT8`awBDmP$F33*zLaRu=L>lpBl~sV(f7?*Bbxo)v?!4_9J%X11td0$(DB! zc&fb5J0&^_&A$$|0IE8tj8ypyba5H6P@1NMLjmR8;>S%@w_%u8Z}P@R=NxbZf1E- z-W$LIqX^uyK(01^gWRL)6DjL++WrUo?IQ#$8mR^*`b5Nr6^P%*@Yfw-Y!TCiDA~F{ zXjZ9eqD#?;Z>aLezy|T&=qYe3zw!PVz!tt?g#nC2V*BwIUt>;(Q(3mOE73%@euepB zOG@0XR3siWsUws1a2+YZp3_V(<^9_~RF~Jgrydk00TDQXf};ee-5gp)wmWzNi1lJU zB6XXg*ggbE<&Jh3wOmqgq6;n;^l(O3RWM^5Z0I=UbGYFvOq#jd(P_QpoTg z13S4F8f`jkez;OU@UD0JQBW^XD+4&53#binYRs%0-<^-~O36Gx00%su6R}v9kne&= zJOS5-*K9@ShV#dX!p^1Ww5-F+^|Ww25lq?!GFo%*R5`>GL2+kCdE!<$Ju#{|kvR5j zN(mmP#R{Qw9V93h68QN9&_~Ky(+YFubMk`&^2Qj8EAPNf<=*!ZhfZlS9AIPsczv_E zU|SC)f^Hqs39;^p{LD~0x*O)75kVaLSA|>6@VZW)qJ1XFi>#r|+?2V?>zYBA_!^3o zAKDaNTTwnmpq8i(_n|TIB9O%xc!=7TTK~X%y-m;*rXyfh=N!b{Lr_mpqY))5_y9AE#G@nFs{hLEk^!x|{I5~@D4S-Rv?T_6%xL9zJd1*qw zSjrz0^Dsui?MbV;qXlTiq?xrOAz1!esA_Xpp4g*sg9D4cEMedFGTjqwbCm^#S8Rwg zZ*kkh;=pT?Fx6uSjA`!n(!DV+gF#SqacWnm%FC7^4HZ#%^Ex2xzP9=Hn7#DgcsL~o zTTaw?M;tG+I&jdd)#Metv_E(v0mDtF)i^x{ z1lmWtJKo*b$1GFL$$DKJ4v!(|D}n0K(=V60H2Z6QGARj%NVDW;m9wlbHam zAGq2W#Ix|AF!yab3FE5GLK{ZRd~~{owd-e@s-f%KiOg_H>MCg<(xI^{e1}EBEq8dJ zOVeD`wpQ-b5HxaLe`8$q>zKN=DS)^-tN}u6&Q(+yA7q$; zby%?E#<0-$qM->X>cWZV9UQ#b9e(`PO8=+GsSOxhs(f%N~$NkIY`a-eIwgb>G$N8a< zf1J+@hL{|m&uVn=6sg{(|Ly#K{nqr?yv**fvXFBO@X(i?9yh;%r#yz$LTDhvR698f z;XI-Kx;D0vF4qq*_57>KBfWeDS`R4Pay|G0IZLL?(KjGkR-A><0ogVM{;2Xbw{|sK zsC5!ZdtOD!m!PNX2SwQjJ2Yey#cWmDXq4H4xVnkcy+AqGe!E z>8deMb&v)RTx5iJ(pfk}hrGuxPd@VV65fF21;<(Ca*&PvZ$*$mSWTu{g+5kE#{wZ5 zfThNfl}XpSRlx-00)b-^u8$i`WW-T7Z6!)UP0YfTX}_b|(#R49()!je}<7_jfH4(*uYOGOuXu$w-^an1<_HB@HQ-&y(FmK%iw2_C+CD<9l#4YzA)fIDM< zMnyAehGuKY`;wWgG-zm>NrH~A?8&R3YlLDHP}zB|Qxxyfp*i2W|7`w!fkng>?#tA~ z9|q4pD!F624vxWg59;K6?Y{o*jCrOtc*os4k52XGUrwDhj%EGK?_d99KsdS7_7s5a zAu#3!GLA`fKEJZN4lSHxY%+^`%)3T7+}V00a4T!ox#yI$bT>jkQm>Vj_^&-HCz zP`#3&hu&{lu*+=M>3ZCt^-asdw3wHL?@70u*H`nIutgo&aLwu7SaE*)qQS982fTM% zmDQ!b9E1bh!f#rYUuj=b*w=e|$GVlE%aK7W?Y)z@@k+&X`);$k%)9&T4pqG{+e5td z_%;Z?T6($fq2u(?`zMyZ;DP_dZA%H0X#8!>S3Di>3J#mJPWxKNZ0B_aM75ofd)uH> zne6Y|JAHoLrrFK>ZBS|7Orx5u9syYpadC3TO3pqWhWAGmQhtgH&q(c{roh08zkNb44ie}p5a+hnL) zyB`U=_6Ntj7Hz`3s)!@qA(;T(sWb@d_lsAJy#>nWKSkfss=ym9+&HTgbo5mJi$6*v zw7he1({0j{e(#7kEBULtK3*{Q@%uG)WPa4sS~a=mINQnFCq7D=9X^6J{;rC@!vo5y zx@$^z+t?L=>pJ4)?$K{IAC;x(8ZthCDI8I*)8|2B@oFCKI8cSQ7INt3m-Bxdm)$o1 znk>EfwQ-x%+mOq@9$dNk?b0cy_q#U#{rHD1{{MoIfx%z}1%>|;A(KUReSCZ(BO_%9 zS!!zP$&)Al6Cr!{FG42w-x0D`K-{`IZdDFF2h^Vim^_A<$PlvIK$~HR^8*Fj_iF!> zBKtSEOR)PNwcUD9beBA(Pd!>jkyV0|F2Mf{?w*DoIjj6{aJLnkbXhyK+i?GwiuVHo z<(-|^ZQJB^PtPA@&oyt#e+GAdghjt|kC<~$n)W;LE;Q+Vc=Er^-K3-+w13OHANTw> zoJ^r2OZ9)^WLWGUZEYFd_P@t>eKG&CWZ@hB#mRP={1;1h%XO{Ygpr zlb-%ZR^DYJvSs)GEbpGt{;%?Gu71T?s|s0mx6vxE-#xp-uR>Pa9SzQx)pnm8uDG+O zVktHIKS8o@$FpCa{I|AS81`>!_e{*_f3jq<&TiN7e_68Z|F^SST3Y&l1<5}A2S~=@ z{Q2*Z-L|$rSFip@WVc{c*4e#N`oDB`U$%~ZxcXl#+5ZNT4G;ghbLY?W^q;3s|12#n z$x^#7U;cUj{?FHcZ~y-U$z%xGq5rQUyA*><{{tbbKWuuIy*+9u&m#&S>?MC%&5oWv z1!(J_*C-Jk9>vF=ZU<3qy;8`JI9C+h704t2Kn|p;AUjK&6oUaUENYqH^7OXfI}9;; zb-yPhOxYqzxbl#B4SN78EvP)h2m>jT3^RPiW_Nmu_J;%TpKD{TU|=}D-6Mtv6tEcV zF0)^B_n*+(a{Db{mlwE5UGn!?+LGKcR3DpV7JSO?i$SDL7#iS z$X|T-n9Pp3h+EDJuE&T-2egX?X{7T!K}C$1mGgBexjhaeJYHVoOLFVpZ>~5KM~OH zB}hE))L9)@xUW1`zo^W(iG1|17s_-?_M3S!KDZkvP%}OVa7C(YM}bBxrQ~Yi^LmZq zQq}YbQ(&{Mgg33Ixm30ucJSd6IUhpQj>}d`e?e{stjxK>RKjr}Ios?vMOA9oQkw5f zgsQiJR7GA9?cyU5mk(Hi7`r6hJ`6Uh_Q<1loqO?@z;H>tBnfN}VD#ZyFyy0G9j8<| zvy+(dD)g)1xqWx#-j@jZX5Z(`5dCAjGT++^>%iYswZ#VxhaHvW5-ff!lk+|=MN|PZ zc29yfPQ_Orx-uEhxQKimTp=djdiwDy)TUNkV%lr)PF!`ErbcJpsDp%E7+3*{0netQ^m^uxDDv>fyAvk7PSeSe(Pbn*L>)N3EU&(Tkr zC*BKxbo#-RwjzbR4$OExb?q5L@7qyNu=ton$~3Z2Sx`sQdRz)jE$jn}kCxlsYYVva zlX4~`y^7n481{PTxqp9FV0FYVQsxFYxQ|qw->BJZ7p}rQ$VXQ)-W1Y5jGS)s70I8qxHWQLz;o)Lg*2{1@ ze!TC3qh+QUYRG`b%-6EAI_s$6rjoGA+3Gh~F{Q6*E8lr9FD3+J-waX_%9b27T{Y4= zP|xJhX9OW;0qe8I(Kqw*F!wxYROh9K**5^Uro^2O#=9A=R5;kPLX6`1Ad_?UaPW@M zy&t~L1wsZ`+PomOD#DP;D{rWEYONY^U<5PPESnnYU@>Lxx>PbJUCF#&=L}49dj=Z; z&{69^d2IC4$#2YB!0ez5Vuh06fOD=GyL4zcvNr639Y>|wZ->fZ7SfagRKG-S(vd{k z3V+o@o|ZD8<>CpLkO2*eZGadO!wAcVK~y12^`>|N4%1aUOLA8-^J0c5)VE>Ly1HqD za6+oCdOghr;2$j69aKI}9y!o~h#8Lpz>Cfd!%T>*i-Yc1igeg?89(Poz$gV0!AbHhSXCdX z+|#OI2V(%j4+ervTw$u5r-9xW1{OZqun#iW+7Fj>T}_rXh&yHTMgKnPNAt#U*t z=qd`vh7AXaIU(sGc=1Tb2}@SKG45>l>Cgif6ZSAd{XlQcjayZ7W}w(rE$P{6 zRxTWADhfrMyfL&swRMn824clXxIS#f+~PTaQF zDQNR$>V~q4XKn+&IiHKwNXobzYxlu1G9^07C=edR1MQvs9kID!K!HuOFg}iqiAiuh zPvNsJw5>o5%7{&g43;5T69cMm0hCQ>2ae_D9BrM%cS#|d!~Eo|Jm6^a#adHg%wXtK z7p1)!t}0^;m^Xoxx$%-Yikt?6?98|`QzeUp<*=|Jm%*P42mQ|6;uvvyuljji0lqk% zZ8I~^qc;z#IBGE;uiK&`#?n>SYfTRLg}P?y(l$rm;=gFlq^J%@6|(m~Ds>|;RT`W3 zDSzLS-&7da@b&7ThMh}LpnDur)hlbOQ=FVI-vt|S7-}S5p~Lxust|*HkVO&@d-Nwf zke8xqsc^)A)E-KBp*0js{&DlXgm@2o4vN}jeETj{(=U6HNSwMEJMCKFYwHq zK#_IUj-}bwA?*+r_&EmN&Nkq zI!J+ZPoP+i13>oDd}Kw+K-7VgVe)4Hr&P%x_CxT5H9YEprz#Qty2;VMJT^)SwGziC z9XVzujW83&qUed^*yD#IsB7OL!6K*)EojH#Ef0?Ddu$lI)dk^0lm8wbZG-o3Ain7QoUhazxG#(eBK}-puXT9S>w(|X8z{prz_#xim@hcz;z>&iq$BuPDg1OY*0=o&em^$^`Hf-mUjj=O;?452FD(Dvact{sWm)E!+f-tqqM$>()BGhYA!_%MnT zG_eari(qxi$4^+pa_H^}1d?|nIz%6GN}MP23ajGbc0b~VY*8Ju@r{164ii~Uck#vt z2H{yoH97hT$ZC4pHM_uQaZHWuytaE!MzeepF^fDJ5lV;KQdnJwBTB|V*S0|LOt31& z8<2ilBh4em?#QxjQdV}3t2pNMu+y>tS&f25NrN6_ppTGGPpU!B3o-VFMRlTec(Qos z4;(ZcAlG*WCIbd80}z=E#54Vqu|f!oaG?HL(9=?2Q(_ra?4(RN8jq(KWuk<_y;`Bz z``^&&w7BS75kCcv_H)f}HE-j*WbS zma}uMwXej87RG_`+K#SQh zYf|>Gz%gY71Xn|t5g}Z9lsg3ZYAwvx$`tksV0Y0CONI!z85MV6nae_#dSOfS$70B+!W8=1g=Hw`QlDrIK z0_F}&`n^y%76mN)iue{uAu`J_G+%*b zXyajMJ^f@o5w=efF#@k1=R)ZKxf4Etyxx@k8BiHi^|U@m_mvR7Tyr%F>lF#i1crajC&RN8$k?X_g+lx=@`$_%1-w z`{Z+otW!(h)2i{vuURNe8P@?1nqXhjt+|vj9>nEBdx+rD2biiAN`$m(d>ULqt2ql* zr_Eee(m{gr{L_}!K{9rsY010TqfWl%sGduQ6rS?J5sJ)xA&UOdum zEwYCW43?xyoHXt3hIJ`KG0AEIdKak zVq}L1;g2eiT-0tXAV7o<+)e3?h(q*nDwx9PP7<(?i{_|B1YSqSnmTQF2dC0#n*p+J zI5L5s>N6466$Yy3An$rZFAG)cg+MC@^b!^r)9UE90@*34Q4T7cmG9Xz6jN z4Bdp^UL%A)F-TC9(Rjq_@gcciS%VMru`T(sbVE?|*}rtqv30hcLRE2L}-k=d`pf$M?Bg~LmZYszm_#&$q0+I8|#aQT$+VYGgSBs0>)B1 z!iXPRrwU8rQ|~~_R+kV}v>mcMZ`(0X_H}d?K@dwLqs5S`zJ≻MieUHv{SR=GG|% zu~~87I5@lOO!;PoA$Tgg$7Xb@L9U{)b;6T+Istx^PxIC(a^ZwkGoXD-d*cmI%?uef zlf_#*eM%jAXl^1{8+!y5&ayu@&IWgx4SwG}^!;Jhj8|fln3}_v+f9_?Wt;;0dOLtS zF(}Bz1en+nNaMrL?Yj~hv#}hsUV$V^p!QMlUOhOx%u$yg)|+{79GV=el1 zZuaZF$eFOoa<~<6>_=}wtO!maHh%gW<4RixZsZ5>!@P9(Tb&g zOW@Q8_FfeUG@9;XyL!T?8l|gpkB+Xyh)>yZWLW_@X~kWl3u2%NVmeo0Q!|OOyj3z` zqgd@YT;=E}3R?@4qrRCK?4zp)WwbDR*tQ{va4EFUx|Dci6DmRofX0h&ZXTHa5EAVx zoeZFXj?l0oX#@&^?mGngMitNV3y$ zq4SX*G5wb47W5lb#D)^b_35x0v6C?!v{~3Tc;fM^4nUC}b4!qy9|M`4bV7{_X99+=Y?0SRQG-#r*D`E%T+E0F^=y!Z0>%pk zS~+~}Fn{QYEfD+@5<-U_KMvO7g9|s9I3f|rsDsV6@(0CEkJ88XY`_fZ&4oJNwih1t zGDpdUgK8=r9K@-d9@@XrlFhXz_A5vf=pD0V`wmK?rB*t=)9ent4vjf=jm|zJ6 zU<7ocxnNN*C122hD=@9PeWaR>Zz-pyV$u20QM8;me}3Gn_Y%^PlQn#~cyR>=1p=|l zI=?sVr9syd7;-su`FhD73grq$I+!kooD?oCd_f~bTiy&VkR~B(jnDx6kz>E`} z*T!PhA|4J=SSu}G^wWh>`JL5^&E687<+iJ(~-5>acfd zA(C_VKSQrQ0M3-Ynz)jz9txlIaXQFI4WjRV8i7(Qd>b_x)E|QErXx<$5obhTZ%N}0 zKDglP)Eys`Hxjx_czGuv^Hb<6SuWyMs`#rmaGxpAK)BR^54&*Au?&T*BExL);LH)e zuUL+T3cHpAdVCaqneteG9zu~{U%VOLdJLtf1qEz?&4fUH?t6UQ0{u_jJ4L4K;rgeu zO6c*ez-E4~pT+(NK+?K;eES`${)dal%v}yBOI&qfp!M+`~thG@U~h_>`dEJRjQnodQ5H=Nh9JP!QKTeLgQR&_#E@>8xwqUr#%fs|{y zI~%-Sp!Tc-)zj+JByyXQpKHhvGRHy@1HQO>|Btf1EWCA(U(Y)A#*4QI;}gKGQmG?S zF6%^=uTn)f1z8vkFDdj5R{r#9Kf2~8Xa|28>(XLD{tH6~#WCRLr7K5o%UgJ4j^s~F3`^vS5C^9re6q6#?n)xX4ZrAjI7brD&;D+_TP(1*zf^&`s z@%%8FoZ!|kdEo7ErENV@coHKum?F115%qEILD-kMPE}|q|I1+p-17TES|Tt&^eyD~ zYDm!%UK^MxMPW<=0ILZygbZrnHIdjBQfV11B=Fn;eahSALbY`<}bM*-PWH98I-lhs;6_yv{;%)r&uRubfmpWwR2x zceFWVXWwVGfzo|=ppy6Ayw72prpkAZ=*UKUF6D&8eXfTR^;L}Hr|7NRN!8%m6r=?+ zc*)Nw+NM}!i+T7qe)RN)I)$OpFoc4$o!!W{JW7>O`t8*9tsVm}<aE0moZc;@W3|(8{>f^eE8Cd|jAo5~IrxF?`o*E}uocQcZ$u3d1TTGfrITY-o z-*)4ayfW5L%jatBlP95uN3qz=G_38W^Ig9M7lYdLNwqmo@Fx^b1TEweuEHn^0rWHj z5F*c4BAiZ|Fe|lcW`Lk<-L-|12zsVZ4$ED**&TgxYP?Q9j@7_t8d4WHEGlKN2OZma zU{rI%A#PK>+~@oeCP7rEbLa=4O?lwyp30K%o9Vp9_CpX!|Ttj?{(-Nz52!np5ELUxGjjO$Q|B$(BO6# zfgcA~JLx_WSa7did1~Zf3>@XwF(VTkm39K|R~k;<4{=qjoem0dJHC{Q|9EvAqvp&w z6vUqCsV8nXP*jeL&L^hyzRy3m)@~!iZQ=eyI0^$bPXrC~C{(#D%ObmLf0pjFKKgaKlC()L3$5nUQ89 zA`U1vefWt52>7c${3Khx{z{AUq^CU#ZD^cPu4~`(Y8DfNfId z6IAy&H9BtHf~+-e?TJ^gx<`Il;%E0}QPmkyvgo5k5iyMr2n}}rXbok-!_*M7v}+V_ z;d!98$?UvpfKr89p{fJB7R>hKf6r#Er8@mn;A-qu6d=29m)b~(yA&+jg|2zMcQji~ z&BM)Pl74_Qfy5;3Y#zj}XK|o4;!&kVpVQ0DSJ^Cqct5lSh;Sy?KkzVB+7P-Ec6U1} ze|}J{gTXZ-4M4PJfr`<~B?{&0*Udx&NZnjlMMS6Et8cQY0BJ~vM)hH-3z5Y0=Z!nlKXVeQr zp+emOzoGN4vRJSUt<~RJ>o$K7>E~n}Wrx>7J3j|dT|)?_Rp z!qgxYCo~N*NUIRFF)5UpJ_8$2^Uqq)w<^zYWk~q>VQE-B-SH=(yN#J2$MmZM?VFF1 zR}EPzGeOBZJmt6cL9VL=5L!T%IS1~?)B_QfGzE;SRPu{BiiQHjCKk0Y5DJeWdN1$& z-h-JrArFC$>v|mC+pzm!JY1Xn)MG0UYE3GzY^RL?Lo1QtDpIwJcz|E-!$53>3H<5f zZt?%f~NKG*Et*beM^=>q2iuH&NbW-($TmSt=F$U=E z-B;d`vM z1@CDk2UX)JH?@%&wOvEj3_xs3AijU>0i_>q%haW3TLAmo}w1#aCjFK zIoROx!N_8aCTHHkGV;za3DpYS^><5K`v+)_A%qFNAh311z7iQBbtO#xTs;SL+**_* zeYmQ6mnG7FpKyQd48{whA`qi_oS;0dTUB+UF){~&nf6^~3 zMl(~-&OQ5TSqV8W%syWA==Qd`(5r8DMfb*! zl?UdUNFgM$BTQu%O@%`XIesa_pzUTXfkni8Q#uU`91$i_vYWvojx;%ZV&hQ z{<(gE(Kybc30J>p{N0lG?gxL!bLZKj-y!a4&8o}mPOC5GNdeN2#o-aj%0`kQ>D`A6YvI#DgJ_ucrl(zOu~5pwI&i32aRm29Ka`D-KOC2VFpYQA5-T2}^Hh2l(Vh|V`nQY>P&_8r!bK1>+ ztoNcdGgPl!;ra7z0!U6gU=NDakT0z&5N~6P`kd_{KKWgL>duqHV50MiGz(p$nUpIKn3c-YwYpl^w>SLUr z#03b<<(7LsNlKfd&m&8!3O<*8g#te`jYOv0ywP7z88w)Hbq9BKBP}f_DLaIWdNU67=YfoqE}nL{+)xSC zcLemrZ$4l>a+>F|tHPyn4LCb#+ZU&0Do`{_E;~Eh9Q(z6TV|twByy7u!l4HoB7r$C zgK9NhW`=UXf{Ur`7h`%ZMhm$yR4%XwI?-u%r&T>PiK!$4C^7&@JX5m{?)s#rFH_k< z#5z`{!=kWWKZcMcK;!imSsa+b!e7|+zSMnI#j{SZF^;8L3^rJ1;T5W1yXMZh!lhSo zA57O*)0pPXxy%yA?ow{WUa(%i60rwlNHb)KwFnu?_EuviaP}DmP25+wk9fq+zWkCD z=Q9rJ&fW! z?*l`FjVQI~{&7QHSfsJJ9MFej)dIuhgTX zAXa!%cT%%Rr8uDspu}f)&mg_=Tt67ZF3GvzAhVvYikM|%ngO{7Z?Ee0CAQ<;B(|Dm z@b#O;E@*dlBHSt`B)d_L_(gHIyHm z3Nqk<&qgcWPSby9Wjz~n+KQn$(hLnCu{$$(COB~KSd~Ai?KUwmMxRHqx;Bk%c?(f{ zDR67YLjz^4TomV1@fNn2u_+lOiyfK7Y46eqcxU5gz|iz&K;bp05-+xY4+K%nvKCed zL>_D$Wf*%mUzS2dfr6LWAq1#14!WwF=ROAU>w&nC$~KEH{P|guBe69g+w`^o>;y6v z4*bMdV1%prrbl`CyO_menBg?6#1QIOffWvJD&g#{hex28_siB11@(wZF~I-veOB%n zbvS>cF3%3dwi1B<8e>z*s7vH377yqY%HKT8x?hF%rGOk5)0@62IlTd>Ewgf)p-LTG zzh)4RPiblUOTga_7X$9b6es>>5y!fn=svABf!+XU-sG)zGoCtyCGFQkzv;s<{2USs zI^6{M8BhZ*$nfx#>pz1Pd>8!{nK}yUQ){wC$U45)S*CcjV6e$}PAZm5ZRVC~RRw#w z>6|Wvqh$CAhk|42CFO=)2b_&m*tTXK^sO+2q3Qf{ntU2$&G%Y09XQLs_v82N_(@D8 z%4#bPY$^Z+<}vKDct>?*?Pk^wJ>GyGPi>vTiZRDomXd??M}8FKQl*e=0ccu>oO+^w zp$Bs!vJLi4Wz|e=cR9WGHMiwXH)R&$-@~z#@e_FP-Ggovzq~{Uc9zE`I zD#$kw75YkQ_U)Sen+QW?u%E#qvRY>Ir9FPb)Y@4VRSNX1_x3b{8AxoIdR;6O-#CLU z`(QV`89sLyF>1-P7~_PUDHnFZI=H!~aWX6uWSFaImI=OZD$o=H&Wiy~Jz$41I~N#) zodh-^`JFfp^F2{?ZtBVC7zb>t)oBo2!GjtTh4oT~5e-aX$lyG%8sPleZ=8d1A(b*4 zJH+*&HVhmtFeLu9ep6d>*r1XsVX*`Ntbm~eC{?2abhTTQ9l9*2didE}(VHAxh)J6)?o|mu5dQTw4Ip#_bqg_F3Edbm8gsPnl1+ zhx6W!z+wc?3&>!??2b_e^JvhyMT5#Q5lM48xC`gmglnyR+xVL)v}|U5@5&1%#5xq* zOlvs1DmEfTvJ7OzCKY4?m=o}2@2Bl0k9Vb(HGq-UuJYPt?a6Q55D*YC zQ~^;#Q@{o&f;}oK)*B0ow~8nC^Souhdp~=hebzer%UNfweB={rW|En?e%Ie#HAoD% zWPxU6#1}&o|8ig%!;lLU#O@Q^ii24?aDBz*35MZOBPSP*Gwg2)tMWJDzA8sIw4(sX z<|x7tshVHLtGrLZlmW^DWx`z1oRp=O&88X&6a^ehG0fo}S6=xfNjblENNGt4O}(t= z`{NN`>D~^!0R1Q5Iv{*fq;ubG_|@M3FEDT( zrC$Wmu$y``z4Z294nA7B=CRblg?(U`%H{o_xkysDNqfsF9PeC*j48C@S_}tNXS0kC&4#uTP;g z5Pr=5z>z>j?bG=Vd;^Er{aLo*4sfgH6(_72t?=YO%MjWUZXxlWLpm~s%UwN=NWZ%_ z&bxGF2H%x+?jo_qp%=CcfZ<63Z7JN1$or5KX##gg0tL+lfZ7OXAy8HaRLm1Nb~7AH z)-pXQtD*Mp>U_R!IPD>;gB4;F|L< z3c8h4`(mO<-0B8aY^%5EXr;QK7==w)@<(s=-$FhjgSFjx!EA#3=5OZIV*JZY9bTsT z)C=hv9QkgjgA)1*a@vsbOodExtV+G*efg$)10*l_^+WwPT3EV*ke*S%{rHM~Nw13i zQ#n$W_RMitBu9_T52xtSkf1(E{x&C8ey_&iY#FBTBX@2e7QH?{$}`VKntO5iLXNKt ztD-z=_U3J)7l<8UryPwm1K#b)+g>i=+w-23jTax4@)zpBxk_Q1lA6ZDv@`oJTgk7x zM_CjNUfvaaeCdkQhlf$DRWRfHZNyiE$b zlfKI25_%>a^c8t*=?ga?!p!btnvD`1rv>TTP}3dT)Q_>07&RS)cN}&vhnB3-x@rIQ z(|;TW>>EIH)@ogRnq4=z+AA^i8Nxy}nyR z?^Y%idAa%H8uBo3|HU;g_;OHSLknvL2YH4$v)7=r6$Z;Y~&ma|xdc|3}oq-UwI*Z*3s zdiTD)?5{{s)KRYE41B#;BnJy~E`zT-%%Mnn4k7u7c&^>-$~W_ZXdmwH_~SeuU}WrU zw8$c}&*BbqK~RA+t3s`x$HWFz{YcC(UA!0VrLuwe5!egH-bN-(DsaZDrbVj;8t59*OIt4-4RPD3CtRR zb46@ZMwXGr)~v(RX1duEk4roX`2s%2n(@;+xnOJ{vn$g)Vkl>?&+VlHllJ4Fe>Qm1 zVnyLP!muZ$Km_l4aK3gX0X>&z)38JSO}3f@4b}T>Ojez)1*kG+4QZ#Pf5eeF=^PVA z>sZUlk{|O2W|Ne>NUT$St3pl=(^BWl(YL2A)yfy`07z0rCT^#liz{S+SJNuA z9Tnihdg4<8i-v=(qAPnz6Pcr-F5Y<5%S@x9#L;4e$!kjHWC)*6bxj#-rMc!B(Zm)# zJ=ozQ=fovN{#i}IebkNx?3uYnk@bfSAm&jrYOaY;aBLbsMp)Fgc z+g^;lO6C_v#{|xsHd;RJGsNlC5^c9>k^HT3B|C2mo^%Jn-Edrtdc7&f&V4Fpsy4bT zJ#cs|_{(5LO^xT1pM_^`mzww>r`q0WrQV<3lW?u&?Cv`*sNxx|T=QxB^yuI|?F>E7 zI!#ijSZun7EI)KFC)x4a8r3RDw3eM<%U#vOmAmbpR8ddZ?nSB93UKtWfnuB1zH9aV zE5H8w8NSXrBk=jR(AoWx$^&hhH9Xz@qx@?cfdw#k%^vNVA=938*um&y?-KbYNlZ@# z3n)HGgdh~yj{18Mh7?uOc;{(;ue}+A8ZlK88e++Zx!GOMOxRtze?twSR`ks%9##Mx z4(HJb*l@$B(_f5qeY(SO?wJW`pAajHonHA^UUP}d)u2%`JW^?)d;xyrNRURs?iXM_ zf!_Ce5Lz!FSp?sun!~0VDGXva?O5c=&nlh`WV&?NgMTF`9YR z-^2;WSLgePhXT$VSo^weLuizF>6;chu`+CC5yJMvDSv( zt&*KiEQ&xx~Xx|o#TiYrO0DK zeV^th6Xd9cyRLe(?&_`^2bv=gu>q+eCJ&q^IJ6I(2HOzB0Fk)5_UGD_`-`4^8q*%# zo8jTV#?(63xRVkcHTmtuvMzd7T9suf<6CHdK0ZCN)R6P6)gUB zDw#mg_aJQiX~9+xn%~*FH793t?{mYojmL&D-ZwJd5{9Z}p_>SiP0xdIHvPBcJK1|g zgU_DbbG3RmyC+a%`k>{Teb<_o!cc1p0sA|6me>X5o^Bqpa?Ml8#peeemdHoh4n{Vc zcMoxznc1sPu8TVRwtgB~6GQA~x+|8gFq#i@f9Cq-o8|H0IpeV$|IZI!ZD==)L70t1|Zh!#V==<3>w-5u4-7khdK9*Yw(qfSYIBivblZ8 zBD2u^Q35imIlN!&zR%b;=k;}F&<;5ZGPW1)xe-EvW&{Ga;DtF3WxPFmQIn z9Txu70W2$7+TIlI?xQ0Lba!ASc>2E%SZ8{>b>3DTN#j$`pzTA53=7Q{4}iR}^P#mR zK>G+}nK@?NhBs`gqDuWV=aC!>Db6Q&C`^qQn&%h~L+s&&FM0q+->4*~-Ed!n!UKb@ zcIR^34M3@W#D$mfO+6y>7}Na55uYyLFsTXt6Wx9Z&%?2y2N5ZOK(pCM(1yZxyb3M5QPaHnI6pF}GN@?&YvIweDOTxuksJ$G7~``k zjgRh%dZ@2{o@qLx{1!N2Q`(AfOtotA_4ZT(0C3(i;yP##v5a7Id`-hK{KLCGS(lv% z!7KnE10I5s+9PL6!TakNf2m0?A@`Gc1{P0I!QBIDm&m!Ro1ZS*(LJcUL>9PNJi`@t z4;e27QhYqMHUYVlP>2e~Jnwt6_m8pM4gfxHS@xNB+d{V^!w@PRfT=O>( zQYHNznj)FWLsN1h^vTrj@6Z(Z@1d#xfe6V%Q)Sq!ntu=>iB9STBW9af)~Jg2lv&Vw zd(Uh3De}tHxBnnQ^r#P1x||5z@ymMd&y*{n&(X{u|0quV?-L{}I3@r54Tbjq_e!Xy zrl!5U{lbL{zjJf{nVXU;p$nWV|5QTq+*D=d@7mhm|5QSKeZPkau3Rhnn+Q!+{hgbd zJ#$4)gxp~1m_O@#ix+M1I4pk4pxd{CQBI^&;-san48F|OA?d=NwK zgN~@JW$m1#{HG5pKmrIPMaHm%#i;bI#TNFn00qNk`w{{9tydv(KBf*+G}T>p?CwS1 z!uDbKVS;_U7(2~AzdXY+z0NlXxLayuo$Zu935<0xUk?~jcE5b$f$|FiDBBHUI@IJ) zD0G_T0ReOIJG+6XXIG9_Zrw$sz=pw-OX^4oah@`c#<8Z{#jFpZu*dr3sEM^MinX^6 zS~ci)|E{i_IGqnuo_m&;{;p?Q)v(tc&)QZsL;OX%J169A}9DR%)S z`l6I-RZ5(p-q$rWFb5?G15n!3YkasPrIG^Jy0U;}h`UnwZ`JR?EU;ByN-1!%XB|ZB zKmCZZ<7`_k1w)v7xOe&N8mxKe+%x211dLS?w#nceLa{=WZih0$o-)rlHbfx@_v7|vSHdOQHr4pZO#xHY6DtoLp_ zAjbW$ql7ghWcR2oa|^HbDigx0j`rFD@uJe0-1(bMIh|W!M@ZvueYP#6eYv@uDBn`= zvr_JZj7&%Gvk$p$U6=~r{O>+U8^w_R4?gIs<+q1Br?-B4l>O@L`K9||O?0~%mfON^ zPdI@lm4SM?i_g4GTPA>Sy0Z??OP1R?dLXFV#$S}~eys8;>yY!-XD5zr+vC+c5hNAF zA9iNFmi$Jn^(fE|8-LgO>I41*{?~=5_)2y60fZX8CTF_Ob2jg(nNL6oN`<TnKU&` z$5MYe!@zIv)~Ngn8Dg33;Ungzi&v(d%R%r^poxu3iDcv6k~tyNwV8d=P;akccr;{S z<62B2?^Oe20l6m5$WOD}NsOM%XA!GaL{+u)g5l}i#ozrYxl7JC*mrRAU@pPh@LU7s zOLn)4uUI5p%Z~fvK^a@PEPgWSvTqnR4K%2356$@dZSK^o$Sa2Zfxyt^cE321g z)gr|SI?MNTIv5WXYnwhtSo9P-ryVJ_^M(_gupScjQalsdj?mrV6a(+oacsSATrEZjVi_X|3xKAMM8Juik4< zVr!svtQt#)I0ZAH1ig8VXUQnS82e?Khy@&D(o;_#iyFwI`}9QkTCt_oIOr&)U=#H) zL9(ZWb_w5-QYc&{?=%E9fLcy$w9ov!YO*CVvb0weB$+I5>H$@ET6@MB51iPPU>0ly zI)92`p(^}bFw&-LC>qcl$O3gtC494Jm{PtGPs^qs*#BKUw+#}(r&h>^%lH*#_9%-iT8Gz61{dT6JKv#wE_Ud$t7-E&4KqQjkpXy|1 zrq3Fz{7ano;*x9o&POkxB2k2oND3M$YRllt zp{^xrQl7CAj*}GNg6Usq5yY9Z&-)w!UzbYdWAuCrNj1t;^jM`y#-IPxhAkf-GG1#f za1?WngZ8`~YuBHy@fi>+G!8Ai z2nXJ7VY?thYKVmhm@(p-?)uI?q`#NZPN|}8vDzhsFiOrNmigK5-=&_h!wOscgr0S#3tH;mYB%5 zVSrfm!@7CDG}Hx@6ZS4 zIk7JOV#H?NYqUiQ=hH5oP}yv%|LH)j(y;H zM6$C)${2lnHRe?4;^xP(Xxno5I++V0l*Q5g;5%E#sr?9MAZBxxT8gJXXXf-9yBSle zqj@`39;p`cwQBZ5)HLkp1X|j_ZC{v{^y{TW554bx*OOOll%DU|9p3gLU4K`FhsFI>aIou^NoEzNfSl@F{0s4fybzijQrZd*~Na$17OqM#OPz3f;%O%z2M85y*jFAs`TvY^~h@@}MfW*O$KuntZnLX{fM zcEFZkGRDi0v0p0m6~(GbkagG{)+W1h2w4x{u#NM(t%%MhtgOy@u;;Ybix6bqd~keg zOlF6(8>`^iEN93Kwc%K7uqU={T;VJoe_n!okp%OZ-xwt2nBcNZcVbS?XH2MUjwa^U z&_WlUA54Y>IikH;q(4*vC`5#^pN}+47g$P!DyGiv0Di5!sY9m(ci|Y+^$8}hJ>!b` z9*HamM2>y#ix3V7LkEeV)UqYK+dMT1OOuEwV5pxO16DhZ+QMS|(x8Q675X}mCjhj3 zkae##v6qM`mqCMzA>v%9)oc9ah`WKSxufF`!z-qXyL!3>{St(DF>yJDTpQmY`B73aPSG*6#3N z8nlU+AH_K6GXt6toh@jJr$iWmI^@3?87G0v?)t{PMtxLF{e!Bq`5rEa>Lk&uRFNvc zkkKZ|P9YI6|Maa2)o2VIwlIuOF+>1KI~;LLVIu4_5hD>RP6jJ7X$l##vLh&nEQL8r zHrFkQ6=0?1=U%{QtG4sEN<#BcU`%B;>bA-fX@b_ zYQ{loIu7Rz^ zdNdI8?aFFQV2b8lr>L!=R8?nJiGr8I=0H(Ch2*?pEmk5{Xi}ufdq+!LN%$rj^dY(Y zqMGwg+KD)Hy}dQs6f6G$pV7udUH*=4l^$+XRjC(yH#w+HBA_rDIw%aylPUCF5u96q zO_f3!SOuXL?WlK}HXqt7MZG0tVS1|Ziw&gKFic@3ua4O(hHCl9KjZMO{JUI+4Li?m7MHb3?QK2_y06$Cpl>8VaspF_UEbRb+4pBRB=Ct_Zba ztT8w=pLh?=lC!KcAJega_cQ#z8}+h!Bm^!hujPmDFdxd5#usk@agqxD0zFfewnp+;yK)D9?lNOXI<;b`AT0W zfqBz9IgA-C=tBB6_B1{j>Okg zqPTS3D6fZHMhDQkD+r2quoZBveJ{6TP+3ofgp8J7y7Bj)Mv zp|D;tdN&2xq%KsWpiZLD_}Wp6IK}OqB1+?B3$xq+i`*T8ZHpS{DiMk)xiu)iBn!zm zy-%m*BSlH!aZ*(6`CQwp0}IVpOwV}P0#Fhl!Q6rG+=pW>RNUiLrOqu~oP^)3&+K}P z;#XCqe68F1E$aH$W_$_{jGd3Lk=`QrD{7C!EPl20%91q6cP#x;jp;p;28zKJ*c2>O zE-louTpu3_+a!Uy=qj()^eb9#h&@C;=Lj>E_&V8^F~?7Y=&01CC;QH~Z=tGeqtUT0 z?WBjRl?|Qmt#Ec0g(8v_468;{Zv@v|36IXdV_JxbZKB6GPi8z#B2w0C8q?U8GlfG} zDuxgbzamT+iuN#!(7gzofe9ibogS_}M^W^XOphIeO1IwAehS1J7?mcgsMBG-08<>P zQi&DgKJFNLXty5`MPv=rAK{c4>rR%a#40HEiag?u<8_uCq$s@|^5^K2J5UaBZk=#X z$3l;7V$9&9#?`pnsxnsyGrfDOZK@G^_LThjH2lgI75iC$KL}Ku+IZd4*$+roR)3`M zKsdpLZ($*Gz9!sj!r0xF9(GpiA)=>-|5!yv_w9QqPbOVYa8PKyyk`t#KI12 z>3Yx(PxC-5YrzB&z%l^cmX7w6CPii;a%hTsl%gILqyIdO+`>}0J?df>YnfV#X_cVj zXfgU`e~4Zq&WB!7lN|Lwv0>%Y6^F#DAMRFJ`l{}1&qx4taVb5LW;0kvee7d*cehZq z?Nr^835Z<%@Iw8GiFSoBnnH>gnN36U)S%^>&Yq(C{*0mI?>IEW0VR3@&zQwLMVNO% z8!1O;FXDQ}Z_AG5kjUBRhT+T>RHC?*PE)9)pi4y4Dzuls18;6ghuS+8!dVJ=^LI@9 z2G-Mau>p@PR_{+frnzM0Pn9TS>Wi;|zu?arR>Msp&TB z=uw`0z~-}(4-n>*Gfv)__Fz6nZDuuCZgh&@XO?B*Z0)~Zm8g)=GXDDRxjl9&l~5AtdsIR&Fu zl)&zx1^c=~-O^#2Qn=|7nuS$3b3S;C+q zYwEmCvRMDhOQ7qViERj>DO@`;_{0LcG4flu2*rKdC%O9rsP>gnIM6a(Y8mYxi7De+ zTbE};Lf_hO;p*1I#{QLAw5sfi*$Nnc0~tvC19$uW&z{XUFCU0vGKbjR=Z z*zDM9YsOdav~FB)PWf7YPt6)9}xhyI+|L z$g?=giZ2Mr+{2fKQ7f4}Rd)xk!}AP@RP&?RWlRKm_bko~ZAeK4)m8Fdh|ZH3AYT|6 zUL)02Y@5GK8qRBMF(@ZaoGpLX?MBcsb_G52s`fP~=82HLokFucZ8vnSt0*0P8l0te zzM7#(N+!J|wqG^<@nf|`FQv%Z78O}G=c)F#f_39qY&rAhF` z#u8b-W|^0A3!Qvca)Z*}WE13aphkcU*Q}f4tY5ho5(W%%cKXx*C|#yT;!$o@(;|WX z`dPIkw?k1@F(F;dl~bKXLp4p*vtg2DHbEl8;V<~*4#fUI#;qyyz7dKJUN6Gl)F5BM zbdgzu9+Ue{>M>h3ddFa&+<@~;0tEKGm`(ep0 zZh3!t)XzV;RPy+v8Y$F4WyW_Ozh}$FBeibg=(H=2=;M1n_^C%>>r36;DZ)A|{;G82 zSkb1?#ED$?R4qzdyKC*AyhM=z?CM?G`-HnKjuV;}DR8}pst|zr8^NPrw-!GFe4g5$ zba265T(gl>>V8aIQ{cZhxxt~^EG435`OyN-vOLyp{J>0^aemfIPys@VL+jI*H#sWC z5}nnco7Scc5-{KTx`V+XIUE{N3IB_U3s@c`b*V=y>v1u8M+NahqjL`2;y|X_wXa_u z+^Gh2W)7Rc?TWxi{th9 z))ap7*(NE@RA0~P#9LJd8RZ3e;h8yvt%1^( zE(pKv)7zvIELTi2z>Vwj&ONktv#XBl3O@>)nlcWx8rp1Rvl_Nqc)vs}7GK+T!kl0c zKjHDn7NPcwQf;yjST#>&7g@Llv;?{l9Q2MF3MjSc2_r)^0E8;>a0sH*5I=Bj1`8v} z-UK3zKY5hccM?m`c~(ySyybH&o0Eb8&FtE1p&icvXSwb|voK*;M#HLN=73cl@0Y{W zS@1gndaTb5nsX&&S&Uj(;g{^sAA(?vB!mHi!wMnt8YC`5fj3N7L`jL@n*FK4@6$nJ zCm7^M;#z&7;CyBW(81)m$&pVXY+E88i~|hO&ya8p2C%9a?&T^8zelWr?8RFX*Mu2i zv^>;mrRF2+pKdJH76VtETMQAdkuhazolSh@p}kPiLom&+cdHrQNP<``Z`SFK^qU8i z3lF#Pde}N?ai@Ne8$71`OWL%vrkO{bgdSjwz!flRJ4h1s`%{xz!bi7+4pyWQmYF@T ztIwx@*9|5_L=LDGcqrzj!%hy#?+5>mEE!UW8q$qNwVW$EuTC{P+(85NLY+M&TvIsDxJNQrUx01+my3C zyRqpM<)9fVf&4PoYQrnZ>xxq09$sG1p@>_1^G{Lbf$pK!@0a-p@OQFK%c$J%6QQRF zIt6Ou1T6dJUdJzL6Gljnz%Tx0KfWwe-D;92!3o`D#@c`zXiPX{YSqV5 zFzRu&+$Cs?URQgMaZeO4e63)Dt%hnezG_{Tfe&BSnB;%jxyd`X<+TqFe%08x`GEd~ zw51&Z*Yj!m_q27YH-GyaUEAP$;`i;x>E|mi5+dM-i~w+d{@ojweaxFr60V}Dx1W6I zQYYLM&-<>_4)J8rFPFP166hTJfddXlGF?Jert6^v6v>rkhf;J)FH~*a%U7T*@Ell9 zvxH~dNY)O4TCJ?^da~n@igdQHR;Fx!lFnr9``lETgW5#CiS7vhn31E>udA`#+C|l{ zboE95^dgpnAFEq*LRXD7O+YJ4O5h?y+?d{@{Fy!}&7 zg3J64ag=rlb!E=AFt^1^Zc5Kzo)Dk`_Ll|C*nT1m_9DU+6_<7Kg4X zKmB>UoijDCccJqFgE*>^JR#Wn>?ue<+$X3uK9W?S_m-x+hzU%Ou zIx^_(8n7elr_`+eA+ZD_iqq@(Q;|Z~B;+};?{}9_DJ69mHqgEChrHEX-y%%QI051d z)3QrpSlA{lLEJmcpm966T95Z+E>w&vk+i^$uWlfxLq_lM0^aLImhGae8!qO~QTIPdV=juxK zh-*C8ep#=NU_CQn&E=mVuHwS;TjH(4NI*{hq0HMbvtp!mH^-h_HF6ss_nZ>#g6V({ zF3ocY#7n|w)izA+ei)%`@eC<#aQ4D+rH+!&jFQlvK~=hZ@R@~^8qlOXMNKGbuE5zA zxqhCdO1ikgNw^Y@UOxw?Q*d7<_{b{xrl|80hE-(Q0GxJi0lhkW=%_BC{y~(WpaPK5 z?A5*UOeLH*P^h=KS~O3}(jK%Nh>Vz|Bp$P#_zOB`e3Ii`W7CIb%=uY`?2QDie=I=rg7 z)o}N^LQyYOn8Mt9aExg&OmC>@}4itt3PAiQb6rOHj z!byu{fAqKbQanl{tr5Vm467|vF}=!x(ZZ_x zWEcgA8E*v1zzZ|-PIk?y8hH6LNTNdh_6!WU~fk@u~x z5*r*of~#g+M=Ay1kvAOf1?Sx3hVDc6HEV99!EMAG*WPuzUZ{S40FPY=(Ws^GeT#uT z3hSOcAzx${Fv4>v6*!RK+P2zr%@_n99A?99NN`&Xgw_n(MR2Q@0cwlj{v!dtvop1o z0xXLwDi7O<3g(FVfra4#85l)Y8T>fvqhyq1ekC$rh2)@Ht^>OJ-Y@lnMDv_Y`^y{n z_{`wTrebhhT#9CK66w`qye*>#j!{7NkpE5S8&n1d&Q`lU;O0K+cAElquCWzj0uTQyT5G2U$wZ9ZwXYZ zh=J?N8q^ymO=-O1&KqG3CT0}K5Xj3_Z?%0b#Vg!bT1~))5*E&POK1qdpi3q9qL+l2)PWlUxCNmF<(g!-V@} z$G0j5D2LKgso7aGK~w{1MxokBIDaLff|-woYNr{_$AFZEo_Nq$#!_Z*%*0Q4axT;j zYW$R8bp>?{hQphq9Pa(k%i6D20{(-3A`XZ@Ac*b;$9<3+N6gN;)TyjT`MieRWXH_J zAb&Mc@r{n`{@ACH0$b6NsagSu{_^yo27icKuIF(qdLCgB{sdJ93qCFwFJWm&I5tGY zTM{InRV+ewtga1@A#zD9NXKfzG#P2ljM2NNZLw4uR0hX2fmCe$R<_(A0zq1bOpB01 zn$>Riz*pWp1ozAknPHaxOu6g%vXT|Z!!qM{g;C_9@{!&KFAfJM@S&M`^spYpln^Av znkj4z;%#{r+f>HUk`UJe{Eb)~{2}Gt!qbj1)~mBx>th{!ybzJ`Pc|t$)_QT@h2FR> zZARFA5217+AIVk3@%Qg}-hKnp@YpD`P9CmAk%>^}OlbrXa(VNtE~dl@hFVu0Ask8A zd$f|UM42jaoEqB0Rt!XJ6hL?8UUniNOaEYJwRkn2T_DWH##XFZc9G7f0;&H>qwXb!uw`vfD5i;giSDK3$dJa z6rL+_Qwu+!;t(M30=AU^>SD2b2D=h!G-hxu7bn!FfEL>@(_+Yuk|z^@f0iRxvO>~J zWYZ&j-vRIX^;|zG;z?b&zo@%V#MLAw8y$eO3w((epw;7e3H zh~#EUgTvnU&*{cs=3$*!pFHBJZ2QYWdL=%65zoh2I;<0JSdN?sMJ!g+NPh-*^M#gd zrJ05^S%>Jzm}%Ar!<;bncOiCwrYUnn4DhPoIBnwrl#yJ?j3jSq0f$ad8QTO=61Sf( z@(|Y`lNQdqACK$;#(XGXoEC^EW^tXb$#s^SjM>eM9gN^C@Y&CEkGs319y%^Ra-%Cn z@_4H6pu~iCT)0XKTCmo3Yar}qc4`raObh*)GbQc@)2MS3`w3O#RP7ZPqkbF1VBs8FPy_Htn(eQdHT;ex?K;%sJ zWkd)Y%x@~;Nex*lBygQZDvH68pO(wJ0o865VfqWrLO>&&u*YNPK@JW#f)f{=LVw5kB6#3LMWCP~)+(5#+RI82Y3VxbRF*L)_~lcDtPuNghPwvDxg0Ru{^cqw$I+VHybZ5!jve1obw%RqA9e9YbV(y zWpGWHY%Ofmk|_Y)w7vTo$g>yBvz@=#OEr^D$=MNipbF3?a>-(WrkJy36Ij~v>iwJe z{as&gx8w)wX=(oW+4t1Q(}A_?;qLx7-(m>C{DIr)M}yXkfB`J9Hf`-&QSr^w?i>;K z!goU4C-gc#=lV0tR(E)?!@YA(Nnd3Cm~fu_8a%nQO+@P-Plr_;FOC{PRP}&X7voz2 zq&LKTZ8p;cScM_bHfc<;-q61#rk=z#meM(B~+p5w{+j~PYTJThC%EApiAHEu|DK>v?=c^%pX4GG2qdYPXaFJ%0}RHt{amjw=E>{*)&ImGno>P>kT{Rj7jz6kOlBvRu%tjua^^3|6z!s~<)q0;zV zLSRXpUS4;dT8I(C_$hs5Ku0w^Nom`VtL7%LBoOjNq`2#`3&IWEG;2u4WtEor{@tb* zGkG4WRpBq)8)k-rlA#xwe8Stpk0`=kdi-tku7|3_nl?V{D;DXl9V2*}VN?F@@?jfD zRk+0JUycrS_Du{y!mQ1RP-bvfi6=jK;q%$=KE*6CzH`x;wah5RU zBHJu`6f{gYyQfggcQ?XuI3}1pWljyIJk9m~SeQ6jTk3&06C6`&i_x_>4!9FGVY?^r z$r&(abLS-btWV1Rh>5d12Ubj2M%I3%?!}I}LaJ3386TDqDjuy#Tff=Yjuf_0S`oC8 z^>1*^ijk~5la!%}BB*R12dQk)Qz*1}nETC&MKX^LG_ov|9aBnaQF@|HE79j+^5}$o zLMSxzyS8Ckqn-u|cIXn%`4L)2993ajG^V-wPzF4^WuUOrRwU0pV{H?rL`Yu)?N9NV5v z#uEC#^}7Kgm?H7#ERJaLntblz`|TYrD&x~zKAQK8;6Fq?G9UXj#yNjnn#eNJEGyql zf^TSIUd2Bi^be49NR?f-uCbWVO$53xDn?QdKxjXFcw23$DRQ+*kBh`%1WWIJkr`8* z|8Coj@~&{q~DT; z2u{;q_WR(l<$7aPG!=zy33oF;d?a5Z^O)vsLDA@(p^-ka27NGlyYQ#I5_vFDmLYH2%ySU7OrieB$S< zAqF)TSQJ!LNgXxyZ5#{f^38AFXJp}6=Hq&$?PyokJ&PmRavwBVnvQ3|IREB@v|0b~ zK{oB>BWcFAr%Z1!*6*me+h=TjMtEbZPjKbKpD%4LHu}MsHhX&LRo`y*xZG-NPkrxK z<9J(hV^-6r!9ZI;xfTlc=jvLJ(l7 zDtY_CG}>(xf!lyq$c&-FAhHKn5B%yt!VxqU=MD%%P$-rkN+(O-aByY|Op~aIJa{-= zUD12Q)&9QxZ>3ABy(EfxuRW_wYpZIr_%+;POrZGiTBFM@Da~^4Nb`|DKAAoa5zhU0TJiZO>gZR<`DNl{e@ zixIUGVKfW56a)r;h8#kYl#&;k^3T2*Xvv;RE4RwO2U0l1-gFiisy4%MsF8RWAT81I z0e#D^)`F1mw1`NNBC@M^r{$Tj&Fk8SLra_O-ZwpztZjezCjM+M(>zhn^`T$pS7I-1 zBoi|!xYN?y;OYP7dO8~uBYOs{yr{n8RAg{d&9VCWtwZ2i6iWUN0j~I8k58^=4H!y0 z+|k9nc#&_^b+kq-1`7ZPnc(Q9j<&qD=^UNbP4F*kYW^oaXuWk_@ZX84?qO9F^8XwZ z()gc2p}WiEQ0N~mp?`-$A4&fYpisLuvsNdo@87M^9n+xqYrOs!R%rIWTA_bY6k7IQ zib4d!e-?%QTP`Fo3ei{m{rS5nWd3hOq5l;Z!sN1%|5gZiOD~ zD!;M0TyBMCQ~y_1=+u_~_o2|E+W#9U^dBvuN00tXOX&ZHLf&n)qs64)rs&bOx@*VC z31d~>?e#Y*9d^8VINE;t)=3H%t>e?tFmcMO*eqtOqw)4>n$iCR3XRA^LjM&CJt`kj1BJZd;je4luQ3c1&>1?}Kd{H(VZDZsJUvrnsBlD)qvju} zZUw7bjalQvC<5i=u(qy~B4v4kinfzy@+Y2xX-7;pMxCEx0}x@!^Q11rMaEXtHgy6* z)!ATO6qKDWO>=*T&=Gr_yF}!C9fUOQB!7J!&w}@MyRzc{%m|4}DMZk;Ht)hokygdm z)sDkD?gUZ(fWxFn7~D4fF$EO7jN02vkP55{k?GPu5Jp%E06x@^m%S%IAQf~JRZ{ee zm^GATPDEMJ1{`VJ46ZbU+yZBL(XxAK4yY3OA``~Z_s)`&l=Ycj*I=9QU!GHxZDlN& zmfkqU#Z{SZoWfLaG%Vitj2?aTt4opg;dS6zTI?E7{P^UAKOR-(@?m$_arjhC14Tsf zq2<9{GBreMmQsV`Zjtw6>%GkGy=t-#VLmZiLTKzfW)Az3B;Fg@B3Dc3eU7hBFybRw zF1BcS!6?O&N2ytRcLxWmc5b08M#S z6tzx0<_jD-H|aI$vF5$4PcsszsfRDD>&>%~nZOFGoL7d{MHVg% zw_4Wu_4wM#=fE}Z6iJJ)I%HGe+Q4621#Lh^XE)l zfK9)dc#6<=-tezek72t(-k<#KZ0kKls%?1DV&DWWuFR|eL2*>Lx8clH;>wW~nx?6hnwpiBHm$3xsH=UI z?+?8{=X<{2pT7S9KX7=R^E@w}x5wS_+*lI`^DAG2X6{(O&dXAxsQzG;u-|HoYf0Au z;HQ0AZ_h~6J=weEuWn&?dhrV!*U!uSmXnbe7hmXOw|=~Dw>{r(5As>wlw)EFF%;Q|k zTaKzV)(N$bW4Isci?uE<#C#F0&6bV%sILAuk|` zKd_c!D0Ff?U$2eMl@GxqQ%P+rr-IQb5$Y8N+76mg#f9~bbaDIvEE}i7vGSj&eYTxe zVD=ugipwW6MkB;?JOM{6`|cQkoeo9&KoK2VEHe~)sb>!VTYh5X%lk9TO90*VJyYN z4qL|4)R0?bslDhwXn3Z>(M`ugiAI9=iC>F;r4jH!EB8$!Ldnq>5G6WRlU`JG?Clv+O6j;6)yax`(NV6Q6s zM6C^`96b`ck~l$XrGwtOl7>V1K)k+yOI-)`B!_c%9SA86qXAKw9KGNnK=APU`5x;x z<4MzxAXBIAit9mfG`|hdM4&gwi1PlMFD2srlir=DDA2S6AA`pZe*(FS^fbscAja{V zMqL$4ixw&I+$<7XU6&)XED9+M>CLhv9ngq62=qv3LaWf?WQQs1A8Rr%W2zFrXm3Oy z^eRxH^cz@T%2n+!pyb|P5m3qE{P_$PI-TTX1zkFzy63y=)v3#&5t{+sf09H!Lc2N(DnqPS&Jn{J7t0;aZNQTmLbXV7-jU8!2p6wu6hE04} z;ihDQIpng1W!q#mmxS{Ux&;TF-DbZ;I@3{*7HNB#tqSh1u1nT$rjShC-@0G{sP;vl66u`W!f>mDS$y z4MJ!?UhIuCkRgy@rh?5KE45&`?QT+%0jUBV0vH^ebBB6{HHjbg#E2j9Flf-SS{F@G zEyDj!gLab`3OSuUO&5kSzDQarCCDuc5$v}h8UHO7yd#kpmTfPU-@sBZFAfaIjFOZ; zPa+f?kCI1)Aq^M4Kw4-|J^+1dFtiicCIJZjVzt-e<_)cwNTjwKA002|nIV*jvF9~^ zGtV^cPN827qx_5g0!FBR#pYWeUZlggO43&!1-P>|yxRZpL-W?*I zgjmZVPi%ZBKC^vu;?{vDpN603|NT4+Y8>+nd)JAq^8Ju>upshtFnMxW)+cvba~-kk z!g$h;&^TO^_f+!DL(6Jm!fEQDmilSqs`l09K>p@p{6 zvbMH^J!y#+TcIRDXtkNN7(3)@LXR-uy?hjl7^;JZCiAGr7|6&NpoTDEKgFh87pWv~r zw*g8DqE1Xly^M{(EI{vnfjw1&MG+-}bECZYi83NKcr9ba80@eRn*)6OHIKnM!>#y$uKru!b-_8{0n{0EZ#04N=w zn3(uKP$+4E25^N^iLmA7q6QH{fJUBJ2>wuope;bWgeiUTgi<{sAAtIAvW5^Fw9taEgj68-HeD$*yxEn2Rzi-eNZ19HF^O$gv$dLqZ%lu z1z(-_9E?;t>NN4WMqmLvOkqq8M%{8KmlZ({Q=B?P$A3;?luaPu6@+72Ou_#uA%Vn7 zs>C5WEOmn>`6I&@0N%w1&)tN9x6`YcFM)%yDPG^uBMXS-uZhf7i7tevN-sn~kaGme zrsK{mKZgRD?luz(yVSJ{4z)N@+EczhI)MG)=mNkGF+-> zpnfEn)(AS4+5jm}IIwWKs2tiXDt~LyL|8oV1(rAX*+yL$e^Pj=hcDr~05x!`*`-pv z>?h%_l3;0>Ucm<%1X6hc*%Pg9M%p!XX=nm28JwQ~s|_*2M>2@WLW)E*4f^%+#J;cjE{h7a!BS#x&N{;Bw5H#GlMozZK^XR+9gm)=o4TLG!eiW zmV*Ut94>p1xV;=Lv3aXTY$}?0AQd4{_E=%1=y(qr^-xOSD zMSOryt2whae=uQG2<<3``-#)m zA%7sxRV`pTBTL)>T5g6rYyQDOguEh8Q8tlLbak2vb`m2Ss3|o`h5>KDqvmyJJ#-Wo z5Ui$+CNY2{5+=kAt2`hPgz%?{GGgeclgBYbLa~p6KK+Mht{@+2;*J#KAR3Gxcs@_Q zvG2{{uP#8g2$3D!CiX#o@wqlc&JA4`#YCtcP}C-SW%tH;tn_}&HlS@K8sdwG;U1xXyV~qu0F!834a1?( z+4!M$u#y1ckcjD{qz2&m62)gXspx)EavbjzMLOgJDn!*0xJtI!C-yTSL0BhH-?-`d+q+6%qlf7!t1$c(mFk*ZQ;Un$d*K(zdj*P&2W+{w+ z`i{<+qz3Vjk5QN%zcAbdNH!pGS_8_$k4UP7E~|l$(-6t6rKuYbec@%e3Mw}j_OrHm z3p@#CA}utL;rxi}5751QSTf!-c_D8k_5I z1fj%YdEp4UDo}*@ts}F2*aWz1(=G$huTO(N4n-aVz#vYrUB{3P&#&w?4DZ~4l42@V zRVJC7IIWDNTQ}od011nVs35#x8A~HeJ6G0959&Z^8^^qbry#|w;{3z{I%-H%)*`~} zTgUve0w%*J)O-*)y0tqcPEK^_m`TJ@V#=g5CF!^eSBS6>*~Fk^VuofFKL(x`K<8wI zTHUBlz61w-f_33+JpwtVc55$FLYY)g3cjuhWV=YxGjU`qg+DUr5c)19-&VQ9c;3~< z3GXS(gO_s>qXmfWed(Q)RQ0ht(POO~C$KLa_5(?_72fRjKwNs@VwL5w_E(OxLxzm7 ze)--u=yg)ZVgYQu!tUKVMwtzwkwT2{ca0YR_@MhmmqziS3JdqTCIUOqQBNHtJgm`) zL})b;d$n$VbRaNt;g1jcD}G$k&ULqv{3Qz@T-%|B2$gxYZ1@<{D$4d0_A^bebH?V_AQjd+s*23xSASnAxsdSS9}^x%^Pw<$x2d^z;?UZekx4#N;4ChVEy3Hck3b zz3_Y=Iw7n z(!UDQ`-kQt9LkwckdMcz@}exDQc!3yN4lL`aD$D=MVm|xl;*%XO*%h1hIq$(sUi3eNEw^hBQf217MCqP8=!^h2g zsc`6J*tMX;FBBW?#~0z1n@o$w)8hZozyB@%sszbez-`$v_x^Gx=Rl-IY%9nds45_K zY#ci?7@5POwKRAf^=_HmSpoXKN(LW{>i&6W2 z+g$%w<2KZs}{AyRFC;Rg64P-K!YWaS<#gb%Cbtke)Eq+4=Pwi_L1 zFq2o&p|uw??!01FU%ol?`s5CW9Qs9rg zCIm0ZEHApDzjdXb)P_w20edH(FGZ|Mf1KWFxL^}%qe3cplmy{wz;5~@M$o82A=q>S zTCPw|TY!oeM8!7fx<1~1H}LE9HX~UC?WneuP?_-OkAdvqPfHC}_2VZHFD z*bMUnmt)&b(jl+v7kq$;oMWG39zMId;@7d|2aFNC1SDTir^2H2(ErJF$!8!gv70izUQ~UC=?l`I+Jz7b5yOsMjX8pPJW(^S!tKAV|@fEaD2achi zQaKu@+_;AH^5=K)rE0F#0#%{&71sA02oWOS`u-JoDg5fGlTMK=PFJ+-N}1|q5TVF5 z#Y>Q3}RlMQE|5`Xev;Oj-6HYH^fz9)g|k?dgC?u1wDL2w}46w z%-%iN?KIz)l3Jl!m6F{&^}ixkFNUAi_~%tQQi@a-cN>b7-c9i9LtU?I@-aahbtqtt<26Uq@tsz{TtO45a`8<(vg!*bth+It))Xv@{7UVdbibe zrNjEd{&Q-3^ro=a@zN)wzE-SBCmLCRrQz=MPOJWPq~(?BWP<%_cMXHRCqfZ~cA7^Q z6zJFRn#52Dk=Pv+@xw#w;vM(9IV^SU7@eLh{C}a4PnS$%EnwtajGdz%vW~>$e}lb~ zZqd|T{veA-87(0&_i7j*>(B65308@)7q98_sgbY#*76MBts$o0Q}QTFq$U}fux$sb zXyG-TH9SASo3QJ3 z?bKUzk~3kuMa$VfdROUbQWEBWpSUO8{M9HiyHQZ2b8QW2Vs2PnrVzR9q%Vd-J~;)1 z1zziPS$OE^bZ86lyL-xBAHTS+D{epcQQs4GR(DmVuHP#dRQtZu_ zw7qcbBX?chrl`7i)+S#RvupV*w}^~)V2uk2&HN{VZvLYloeQXM_qU-=1$9Xmc;`Cz zYc(|6#01Sp=n58^ij0@2YT{ArACR*BXKyUz$fV%AK#ud@oA{b-3HG=2mNsH!Y6&hQ zx0Up^R4Tk>I&yZXov58iXOZzi5-hxa1i;V;$r1r&8aCLP+vr}HiMZzzJj{|Us<77c zVW2+DE{%mSt`i(1@iI8DT#HBnnPzwN#(2(~l>67TuD*j5s?A9G0ziAE_6DU08Ucl` zuQUCp)kcP=^rDWEv}fX_4)C#3la*rx`lb|38!X#S2eSs4*+Iny!iz%P=a9`ypLKKQ9mx$f;*MuLaeowBa4?eMd}NkHc?t5MO5k2pYPN_=iZd3i9U zjaVZ){1_;!)dRYm4okvnh>WFKq$T zQJC-ATV=0M64me5>Xi>IMiX~^E!a&5q&9*k4J&_)#DRFay*?aIvO4OxC#@7W!jZki z(<`%fH|^n)&A-H&dXpQW#*FbE^{E?(?v(nSf0L7lDp1VTr6BOgYo}T9=JrBsHFoCi zUJ0FkO7<&bl`}HZwqOYNa+*4!59_Yi$IXvrOZja;A}a8pvQv)7c-jB}l_~9vW&lb> zT=j52Nb*IW{VI64Qn+QnS@T(^2Kt0VhM>mVLq*DSDO@+?D5LRhlPpxo(S`H;yTU)y zN}@og+AV_^n`{j|0>{9yciW|Ko`no6`yyY~ce>jRI__T3 zRJQ?C8fz-AMr(yPB~mAKR!5EcI}24`w$G;@tM?u4ioPaJic03~^dmaZ+~;bx8cZ)H zhIh|9FXBxP2Q_|8@6f)q4B1Ow+yVUv+F$ywEcwr@CRyktKCNB8`3@Zuiqo<{gYxWg zXRkKfq2MYq+s4`{_|ufYtn^kS>b$OYqfTZ(N z&yDgx*ldg2=XJy2<|GN7q$s3f>4&=Ub-|%mlXrjHaW1fbz4nev2Kf@-!}sid1++?n z9*OKrG-~y5JH6zS!E3Vfqp&H)o{PnblU+t`v4_h?mx3%f¨k!z_aNFW=6G#yxJ? z-Vp=8czN*BHE|}Hs*bwyF0wsae<>w-t2a5zX?GKmEyq=TFejOV%BV%v4z$nL+deQ? zn_$LmyS#NV?|3|vo*C!l5sC7dGaem(OFVCpb?tT8F@Vwv%+p;sclA_y?RrR}S!^e0 zRWcLMUu#L2^r}a^zB_QGi5*mLWuHm1)3}MRwD&$X@~rjq)46mPz+~I{BVmy888&>{Bd>iD`zr zX+rc~ukIWB1Q`b#U2x3$@*I)wxfxtt-tW8QP8!ek9w&H#)m**bcahY? z7~Q=9+U-{FD1uPUp-JNvLB)XWe<}<8#>tCdJ42A>El%wy>ul5hQGib4=(d;)0bU&f zbcgP6AzX2c5(G6eRvs1TxKB`2a)|TBR0i_%(!L&a*H#J#^nLIpV^m4lhrs9P5u5u) z#%zX1W-3LKs- zORCB$;O^srNC0KL0Dz%Nx%Y8Hg?*DgM&jSaQ(Oge2GF4B_8-3+-QOz@KCoy_+t~}a z^w4#RI8nIcUm|1y$`@ybs4kJ}@;Xa$)(bc7-@)x1=cwAP%wdQZ30$blecLtnLg>7c zpMze9w`z-%ub0D9bNwm1ao}-Yq+lw?+Fnq>S((PsY^`bSx7s+}5cZFgr6k^Gq7VufR za4AZmb^^#g6SLeg^JV>95FISjEVe@I3-Dqi8rXY=&F6zm$u&<+y#97XY&~}?=5{gh zEMEY`p9tNLhx#z~IfCn zrC1HJK2EtI?qZN)M$>#p& zxt$oW5o5>}?LM&X?Iwg&C~!3s=9mnoX2NY|yE-ybx`GE>^6-CWDZ?A*8kpAT3B5nw z@ZSt$)jt{uB60T9yUYckf{@$#fE)`v+kr9U!{dZ*<#Z7_*6Q%&^;P=?wilYCDxO%| zDw0IkjG`g$M_2BXpfWjSp=%H~{l#L)D)=+^9}mRuZg}T5X|7NJ)$0Nq&xpGhmp@7u zuodA%Kn`&?yg7U4;WWwpPExiaaL9a6a5cw^3O1&$vP8GjPj&=sf=#wo4(Q9vrI)PY z7ouJkzDIDpHrO8gd(5gF;|;t0MN>l*inYQH3o#cWgYEf1WjtH23a>Q-v|M0|9Q}E% zC>MlymaEc)f4}slSGUUT^4plbRUD&_4$Utn{W+K2!EVz$kdA;=tHIix@^F;Q;R3*= zX0K$rHh;M*T^QxFaX7V`0b_Q&{)nJcjvlw8#4G%vI(mxs9aVT_b z4I=e&*A-dW>SB%#gEb@qi0eg^D%Q4r71-<|JZhjiX}mx?S-Nlr+PPRU`xvE-D{D)~ z-Clt{Rzd`Cv65|oNO1)wi>Y^!oJUfaXVT9p1db)KQJ3_DOO@W@ zGo;9^EIP=%o)I^RLC{@IXCTuBW@wK&_{1~p`)G!RjMS42LQz?$c8T5_%T_9jIl^^g zbOwz8Hj|5G_}Fh;rg1$0&Ij#n2X4FtQ@=x`BS~I6UY?BXk9gr)WbD>e=+l;vcPL_fUE@lF(IT#g)@F+ifhzH1{P)f|f8X&-_K z+m1whYcK5szF@9xvdF-IWVe}emOLQLNyMgVpGk4P^H&wfOe!Y*=JI`>|2~RlK!PL^ z0B&YpwnB4~ZvkYvbNKw12so2oU+Fl*&PtI@o`2BC1acc<0s;cmKCbRj=gdDxg#=6a zo3lEvNKr2LQ7JivOhsbctMpd|ZfihmVohy1xSes?f|Bz&^1|pUSzAAJFCJSI7)92+|?4V`oF&1&@_+6EtvG{&oH?$yJ{J@ z@9ULYAcAk-!KFu>+a<&WkUnozj{q@SU^|fx-!ePr1=ubo2w5InPHhd#bmKzM@Z&uU zwa3Q+ATfj+o|O)rms=ss2;*J|*j%v^O5oYgD~bo%j;gzqPgU&6Y>s~*=h^*FWI=o( z@lKug6}dfJDMk*9TxV=%l~3OpU@BMe>D4|VOOIr-PkTvciDj~O$Z_y&4fUMqe~A#p z4t%eg;}#!kcN5jJ#E}r6r<)uGpG}OSfdu1sMHIH2h+%7$zi!FWCYD?(IXn(SG6c)aB~O9 zG@&+Z3(`*8bw2Zsdb+I=OWl}Jxm1l(EdCX{B536&9 z1CfEq+_fRlS@p67$cKDF!d#%KcAM^JCe2-^`meJC#|da(Q=1Z%lOW6{D0hY7li=9% zEc$M+B7|n3ALJs9GJNBE@qCW~@hJ)~1jxQ5U0V`yfw#=K={~7B+F}`G9;zdVx`yBB zzxA4#nPY20-A*_GhA_>nNaFj5^N1OsF)oM2XX<8t)np_fw&F#W&k?u;X!$`FK(@(H z(HH=&pGJv&(D9aUH~PNOJRamd^sAnfG2a4t@jxBfmV=qR{(4aOB;0bQ*2BWNdq!rQ zlvBny+aE4&X1+hQB0fQ(o)0jbM6+tHe~S#b@YBdPIrz=s1}77X!BO~toSY&!ng{Xu@MN+;>E{Tp zgNA8r6OG?A&U!@IR<3Z|%$?=U&XV=4;4#rRy8Be`30vQ0;Ml ztDq*%JlvSb+4|}4Tu|$9Il=foXL#i1>xByr>R*o9x0YxrHMcdG-Tg;T&HLF!C7RN#5TFrn1Ks4^`~@oL8BK zeHE*cJLURuLh7+=3?BX@0loq>H=9+K9G+Xf*_HP!K-#UWda}M7y<%7s zM^H_hlMQHxIeQQ|0Z=(zrSe4k05UL->|m=|*ivL08{tdkn7Av;*W;&TXpuk&%CM=*2>3_ z5c5hZfk|i(7)rRw(LTAVT7=2CX!Z>}d^(D)NTNHI^BqAEW>kOm*`8$;CxXK;pX}I6 zVLGYq@!{E{Hr`I}nQipcjFumzppHhV?V^I^`8R{@aD2_AzEP*=D^*Ua^NQHoPoplt z^R-T&5waoVO;D%rul6r~vSbo)k8P#z-)Wa$f@YPTuo_`OffeKV`f8yWeaE;r>e0$^ z&tA4){ABsI#i`h8649;|2AO##*|EgNDu*sR%VMI;X;5yN9Y^Lrxjr1K?!C6}X#;z0 zW1x|hF}IvXjpwY$X?)#cT+`2oKkT>^q9Qb$dSZL@_{guLi>Sy!FS)t$2T#_&hB#cS zM97z;`(qU70G5{`FlBMaheJx-An&SETa!I6RNaRTDK(gW!UE4djxeGZOY-M^hMQ*6 z^%k!`{Dq3^OHn**P;zxD?MMcy4E{@Js8SJ!@ok<0~7TYcVjhBhtJW`QDqmJzgpHP&tKySaq0W)0p$dC3T%# z?!#tPIc#&m;%;wMQdJYWRr{Kr?-nP<`nlt3P-zL5pC|uo69VTtmrxfusbkTSx1BLN zEbnk_w(!c$(Kkt$CAwO$JYw=E_k-ET%%V*KefaC%0`O1c%Fio^S@9CtgUJE zCnRL_Pt~80P&2|K-mSl8b+@KzPsi|P_ORRd`3l{QucXVq~>NEUb zYZt%1qtlSm&`=g{eK+6R&k}U}_q+A|z_)jq@B73dq5lho(*JiQ2_Hj*5{t%nZ&VgG zC1FlRLe|X=-7O}P08n$XzW5F~WSJGNVbft?5&{6z%1SOKOaZk!QB3qCULhH>4&OkA z%kZ~lLw1qe3oj!Bg`a`=*h%o(pnsJmpuKUvgGTB^LAsw^2nmIP`m&Z=V;6(#q{St-LQvWYEkC?F>gC|W9QIcr z<918f)ac4;lU}c{RF?s+F<^Lng*G4}gsjZ2hW+@8zul@H2W={3@%0AI;4Y4{-Ta%I zB;|+2w}p04{4z9FJI2rGT#4&K{bhhJ<>AB(2(Ugb1B*p|cL&+)?sY}S4U;alcAu^u n1bp8i9={4d81rZV00i)b-%LrT_UQcoLPCF_P*NiU0I>QW)2;|X literal 0 HcmV?d00001