From a440106330ac5659b8455afef709d901712b6f6d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 4 Jun 2012 22:57:01 +0000 Subject: [PATCH] Moved docs to gtsam --- doc/LieGroups.lyx | 4065 ++++++++++++++++++++ doc/LieGroups.pdf | Bin 0 -> 319029 bytes doc/cholesky.lyx | 170 + doc/images/circular.pdf | Bin 0 -> 62900 bytes doc/images/circular.png | Bin 0 -> 1493 bytes doc/images/gtsam-structure.graffle | 1302 +++++++ doc/images/gtsam-structure.pdf | Bin 0 -> 29463 bytes doc/images/n-steps.pdf | Bin 0 -> 62899 bytes doc/images/n-steps.png | Bin 0 -> 1427 bytes doc/macros.lyx | 294 ++ doc/math.lyx | 5746 ++++++++++++++++++++++++++++ doc/math.pdf | Bin 0 -> 118509 bytes 12 files changed, 11577 insertions(+) create mode 100644 doc/LieGroups.lyx create mode 100644 doc/LieGroups.pdf create mode 100644 doc/cholesky.lyx create mode 100644 doc/images/circular.pdf create mode 100644 doc/images/circular.png create mode 100644 doc/images/gtsam-structure.graffle create mode 100644 doc/images/gtsam-structure.pdf create mode 100644 doc/images/n-steps.pdf create mode 100644 doc/images/n-steps.png create mode 100644 doc/macros.lyx create mode 100644 doc/math.lyx create mode 100644 doc/math.pdf diff --git a/doc/LieGroups.lyx b/doc/LieGroups.lyx new file mode 100644 index 000000000..03116dbc9 --- /dev/null +++ b/doc/LieGroups.lyx @@ -0,0 +1,4065 @@ +#LyX 2.0 created this file. For more info see http://www.lyx.org/ +\lyxformat 413 +\begin_document +\begin_header +\textclass article +\use_default_options false +\begin_modules +theorems-std +\end_modules +\maintain_unincluded_children false +\language english +\language_package default +\inputencoding auto +\fontencoding global +\font_roman times +\font_sans default +\font_typewriter default +\font_default_family rmdefault +\use_non_tex_fonts false +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\default_output_format default +\output_sync 0 +\bibtex_command default +\index_command default +\paperfontsize 12 +\spacing single +\use_hyperref false +\papersize default +\use_geometry true +\use_amsmath 1 +\use_esint 0 +\use_mhchem 1 +\use_mathdots 1 +\cite_engine basic +\use_bibtopic false +\use_indices false +\paperorientation portrait +\suppress_date false +\use_refstyle 0 +\index Index +\shortcut idx +\color #008000 +\end_index +\leftmargin 1in +\topmargin 1in +\rightmargin 1in +\bottommargin 1in +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\paragraph_indentation default +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\html_math_output 0 +\html_css_as_file 0 +\html_be_strict false +\end_header + +\begin_body + +\begin_layout Title +Lie Groups for Beginners +\end_layout + +\begin_layout Author +Frank Dellaert +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\AAdd}[1]{\mathbf{\mathop{Ad}}{}_{#1}} +{\mathbf{\mathop{Ad}}{}_{#1}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2), 1 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}} +{\mathfrak{\mathbb{R}^{2}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2), 3 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3), 3 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathfrak{\mathbb{R}^{3}}} +{\mathfrak{\mathbb{R}^{3}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3),6 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathfrak{\mathbb{R}^{6}}} +{\mathfrak{\mathbb{R}^{6}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Aff(2),6 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Afftwo}{Aff(2)} +{Aff(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\afftwo}{\mathfrak{aff(2)}} +{\mathfrak{aff(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\aa}{a} +{a} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\ahat}{\hat{a}} +{\hat{a}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status collapsed + +\begin_layout Plain Layout +SL(3),8 +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SLthree}{SL(3)} +{SL(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\slthree}{\mathfrak{sl(3)}} +{\mathfrak{sl(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\hh}{h} +{h} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\hhat}{\hat{h}} +{\hat{h}} +\end_inset + + +\end_layout + +\begin_layout Section +Motivation: Rigid Motions in the Plane +\end_layout + +\begin_layout Standard +We will start with a small example of a robot moving in a plane, parameterized + by a +\emph on +2D pose +\emph default + +\begin_inset Formula $(x,\, y,\,\theta)$ +\end_inset + +. + When we give it a small forward velocity +\begin_inset Formula $v_{x}$ +\end_inset + +, we know that the location changes as +\begin_inset Formula +\[ +\dot{x}=v_{x} +\] + +\end_inset + +The solution to this trivial differential equation is, with +\begin_inset Formula $x_{0}$ +\end_inset + + the initial +\begin_inset Formula $x$ +\end_inset + +-position of the robot, +\begin_inset Formula +\[ +x_{t}=x_{0}+v_{x}t +\] + +\end_inset + +A similar story holds for translation in the +\begin_inset Formula $y$ +\end_inset + + direction, and in fact for translations in general: +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0}+v_{x}t,\, y_{0}+v_{y}t,\,\theta_{0}) +\] + +\end_inset + +Similarly for rotation we have +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0},\, y_{0},\,\theta_{0}+\omega t) +\] + +\end_inset + +where +\begin_inset Formula $\omega$ +\end_inset + + is angular velocity, measured in +\begin_inset Formula $rad/s$ +\end_inset + + in counterclockwise direction. + +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/circular.pdf + +\end_inset + + +\begin_inset Caption + +\begin_layout Plain Layout +Robot moving along a circular trajectory. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +However, if we combine translation and rotation, the story breaks down! + We cannot write +\begin_inset Formula +\[ +(x_{t},\, y_{t},\,\theta_{t})=(x_{0}+v_{x}t,\, y_{0}+v_{y}t,\,\theta_{0}+\omega t) +\] + +\end_inset + +The reason is that, if we move the robot a tiny bit according to the velocity + vector +\begin_inset Formula $(v_{x},\, v_{y},\,\omega)$ +\end_inset + +, we have (to first order) +\begin_inset Formula +\[ +(x_{\delta},\, y_{\delta},\,\theta_{\delta})=(x_{0}+v_{x}\delta,\, y_{0}+v_{y}\delta,\,\theta_{0}+\omega\delta) +\] + +\end_inset + +but now the robot has rotated, and for the next incremental change, the + velocity vector would have to be rotated before it can be applied. + In fact, the robot will move on a +\emph on +circular +\emph default + trajectory. + +\end_layout + +\begin_layout Standard +The reason is that +\emph on +translation and rotation do not commute +\emph default +: if we rotate and then move we will end up in a different place than if + we moved first, then rotated. + In fact, someone once said (I forget who, kudos for who can track down + the exact quote): +\end_layout + +\begin_layout Quote +If rotation and translation commuted, we could do all rotations before leaving + home. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/n-steps.pdf + +\end_inset + + +\begin_inset Caption + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:n-step-program" + +\end_inset + +Approximating a circular trajectory with +\begin_inset Formula $n$ +\end_inset + + steps. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + +To make progress, we have to be more precise about how the robot behaves. + Specifically, let us define composition of two poses +\begin_inset Formula $T_{1}$ +\end_inset + + and +\begin_inset Formula $T_{2}$ +\end_inset + + as +\begin_inset Formula +\[ +T_{1}T_{2}=(x_{1},\, y_{1},\,\theta_{1})(x_{2},\, y_{2},\,\theta_{2})=(x_{1}+\cos\theta_{1}x_{2}-\sin\theta y_{2},\, y_{1}+\sin\theta_{1}x_{2}+\cos\theta_{1}y_{2},\,\theta_{1}+\theta_{2}) +\] + +\end_inset + +This is a bit clumsy, so we resort to a trick: embed the 2D poses in the + space of +\begin_inset Formula $3\times3$ +\end_inset + + matrices, so we can define composition as matrix multiplication: +\begin_inset Formula +\[ +T_{1}T_{2}=\left[\begin{array}{cc} +R_{1} & t_{1}\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R_{2} & t_{2}\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +R_{1}R_{2} & R_{1}t_{2}+t_{1}\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where the matrices +\begin_inset Formula $R$ +\end_inset + + are 2D rotation matrices defined as +\begin_inset Formula +\[ +R=\left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right] +\] + +\end_inset + +Now a +\begin_inset Quotes eld +\end_inset + +tiny +\begin_inset Quotes erd +\end_inset + + motion of the robot can be written as +\begin_inset Formula +\[ +T(\delta)=\left[\begin{array}{ccc} +\cos\omega\delta & -\sin\omega\delta & v_{x}\delta\\ +\sin\omega\delta & \cos\omega\delta & v_{y}\delta\\ +0 & 0 & 1 +\end{array}\right]\approx\left[\begin{array}{ccc} +1 & -\omega\delta & v_{x}\delta\\ +\omega\delta & 1 & v_{y}\delta\\ +0 & 0 & 1 +\end{array}\right]=I+\delta\left[\begin{array}{ccc} +0 & -\omega & v_{x}\\ +\omega & 0 & v_{y}\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +Let us define the +\emph on +2D twist +\emph default + vector +\begin_inset Formula $\xi=(v,\omega)$ +\end_inset + +, and the matrix above as +\begin_inset Formula +\[ +\xihat\define\left[\begin{array}{ccc} +0 & -\omega & v_{x}\\ +\omega & 0 & v_{y}\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +If we wanted +\begin_inset Formula $t$ +\end_inset + + to be large, we could split up +\begin_inset Formula $t$ +\end_inset + + into smaller timesteps, say +\begin_inset Formula $n$ +\end_inset + + of them, and compose them as follows: +\begin_inset Formula +\[ +T(t)\approx\left(I+\frac{t}{n}\xihat\right)\ldots\mbox{n times}\ldots\left(I+\frac{t}{n}\xihat\right)=\left(I+\frac{t}{n}\xihat\right)^{n} +\] + +\end_inset + +The result is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:n-step-program" + +\end_inset + +. +\end_layout + +\begin_layout Standard +Of course, the perfect solution would be obtained if we take +\begin_inset Formula $n$ +\end_inset + + to infinity: +\begin_inset Formula +\[ +T(t)=\lim_{n\rightarrow\infty}\left(I+\frac{t}{n}\xihat\right)^{n} +\] + +\end_inset + +For real numbers, this series is familiar and is actually a way to compute + the exponential function: +\begin_inset Formula +\[ +e^{x}=\lim_{n\rightarrow\infty}\left(1+\frac{x}{n}\right)^{n}=\sum_{k=0}^{\infty}\frac{x^{k}}{k!} +\] + +\end_inset + +The series can be similarly defined for square matrices, and the final result + is that we can write the motion of a robot along a circular trajectory, + resulting from the 2D twist +\begin_inset Formula $\xi=(v,\omega)$ +\end_inset + + +\begin_inset Formula $ $ +\end_inset + + as the +\emph on +matrix exponential +\emph default + of +\begin_inset Formula $\xihat$ +\end_inset + +: +\begin_inset Formula +\[ +T(t)=e^{t\xihat}\define\lim_{n\rightarrow\infty}\left(I+\frac{t}{n}\xihat\right)^{n}=\sum_{k=0}^{\infty}\frac{t^{k}}{k!}\xihat^{k} +\] + +\end_inset + +We call this mapping from 2D twists matrices +\begin_inset Formula $\xihat$ +\end_inset + + to 2D rigid transformations the +\emph on +exponential map. +\end_layout + +\begin_layout Standard +The above has all elements of Lie group theory. + We call the space of 2D rigid transformations, along with the composition + operation, the +\emph on +special Euclidean group +\emph default + +\begin_inset Formula $\SEtwo$ +\end_inset + +. + It is called a Lie group because it is simultaneously a topological group + and a manifold, which implies that the multiplication and the inversion + operations are smooth. + The space of 2D twists, together with a special binary operation to be + defined below, is called the Lie algebra +\begin_inset Formula $\setwo$ +\end_inset + + associated with +\begin_inset Formula $\SEtwo$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Basic Lie Group Concepts +\end_layout + +\begin_layout Standard +We now define the concepts illustrated above, introduce some notation, and + see what we can say in general. + After this we then introduce the most commonly used Lie groups and their + Lie algebras. +\end_layout + +\begin_layout Subsection +A Manifold and a Group +\end_layout + +\begin_layout Standard +A +\series bold +Lie group +\series default + +\begin_inset Formula $G$ +\end_inset + + is both a group +\emph on +and +\emph default + a manifold that possesses a smooth group operation. + Associated with it is a +\series bold +Lie Algebra +\series default + +\begin_inset Formula $\gg$ +\end_inset + + which, loosely speaking, can be identified with the tangent space at the + identity and completely defines how the groups behaves around the identity. + There is a mapping from +\begin_inset Formula $\gg$ +\end_inset + + back to +\begin_inset Formula $G$ +\end_inset + +, called the +\series bold +exponential map +\series default + +\begin_inset Formula +\[ +\exp:\gg\rightarrow G +\] + +\end_inset + +which is typically a many-to-one mapping. + The corresponding inverse can be define locally around the origin and hence + is a +\begin_inset Quotes eld +\end_inset + +logarithm +\begin_inset Quotes erd +\end_inset + + +\begin_inset Formula +\[ +\log:G\rightarrow\gg +\] + +\end_inset + +that maps elements in a neighborhood of +\begin_inset Formula $id$ +\end_inset + + in G to an element in +\begin_inset Formula $\gg$ +\end_inset + +. +\end_layout + +\begin_layout Standard +An important family of Lie groups are the matrix Lie groups, whose elements + are +\begin_inset Formula $n\times n$ +\end_inset + + invertible matrices. + The set of all such matrices, together with the matrix multiplication, + is called the general linear group +\begin_inset Formula $GL(n)$ +\end_inset + + of dimension +\begin_inset Formula $n$ +\end_inset + +, and any closed subgroup of it is a +\series bold + matrix Lie group +\series default +. + Most if not all Lie groups we are interested in will be matrix Lie groups. +\end_layout + +\begin_layout Subsection +Lie Algebra +\end_layout + +\begin_layout Standard +The Lie Algebra +\begin_inset Formula $\gg$ +\end_inset + + is called an algebra because it is endowed with a binary operation, the + +\series bold +Lie bracket +\series default + +\begin_inset Formula $[X,Y]$ +\end_inset + +, the properties of which are closely related to the group operation of + +\begin_inset Formula $G$ +\end_inset + +. + For example, for algebras associated with matrix Lie groups, the Lie bracket + is given by +\begin_inset Formula $[A,B]\define AB-BA$ +\end_inset + +. +\end_layout + +\begin_layout Standard +The relationship of the Lie bracket to the group operation is as follows: + for commutative Lie groups vector addition +\begin_inset Formula $X+Y$ +\end_inset + + in +\begin_inset Formula $\gg$ +\end_inset + + mimicks the group operation. + For example, if we have +\begin_inset Formula $Z=X+Y$ +\end_inset + + in +\begin_inset Formula $\gg$ +\end_inset + +, when mapped backed to +\begin_inset Formula $G$ +\end_inset + + via the exponential map we obtain +\begin_inset Formula +\[ +e^{Z}=e^{X+Y}=e^{X}e^{Y} +\] + +\end_inset + +However, this does +\emph on +not +\emph default + hold for non-commutative Lie groups: +\begin_inset Formula +\[ +Z=\log(e^{X}e^{Y})\neq X+Y +\] + +\end_inset + +Instead, +\begin_inset Formula $Z$ +\end_inset + + can be calculated using the Baker-Campbell-Hausdorff (BCH) formula +\begin_inset CommandInset citation +LatexCommand cite +key "Hall00book" + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Baker–Campbell–Hausdorff_formula +\end_layout + +\end_inset + +: +\begin_inset Formula +\[ +Z=X+Y+[X,Y]/2+[X-Y,[X,Y]]/12-[Y,[X,[X,Y]]]/24+\ldots +\] + +\end_inset + +For commutative groups the bracket is zero and we recover +\begin_inset Formula $Z=X+Y$ +\end_inset + +. + For non-commutative groups we can use the BCH formula to approximate it. +\end_layout + +\begin_layout Subsection +Exponential Coordinates +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix Lie groups, as a vector space the Lie algebra +\begin_inset Formula $\gg$ +\end_inset + + is isomorphic to +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, and we can define the hat operator +\begin_inset CommandInset citation +LatexCommand cite +after "page 41" +key "Murray94book" + +\end_inset + +, +\begin_inset Formula +\[ +\hat{}:x\in\mathbb{R}^{n}\rightarrow\xhat\in\gg +\] + +\end_inset + +which maps +\begin_inset Formula $n$ +\end_inset + +-vectors +\begin_inset Formula $x\in\mathbb{R}^{n}$ +\end_inset + + to elements of +\begin_inset Formula $\gg$ +\end_inset + +. + In the case of matrix Lie groups, the elements +\begin_inset Formula $\xhat$ +\end_inset + + of +\begin_inset Formula $\gg$ +\end_inset + + are also +\begin_inset Formula $n\times n$ +\end_inset + + matrices, and the map is given by +\begin_inset Formula +\begin{equation} +\xhat=\sum_{i=1}^{n}x_{i}G^{i}\label{eq:generators} +\end{equation} + +\end_inset + +where the +\begin_inset Formula $G^{i}$ +\end_inset + + are +\begin_inset Formula $n\times n$ +\end_inset + + matrices known as Lie group generators. + The meaning of the map +\begin_inset Formula $x\rightarrow\xhat$ +\end_inset + + will depend on the group +\begin_inset Formula $G$ +\end_inset + + and will generally have an intuitive interpretation. +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +An important concept is that of a group element acting on an element of + a manifold +\begin_inset Formula $M$ +\end_inset + +. + For example, 2D rotations act on 2D points, 3D rotations act on 3D points, + etc. + In particular, a +\series bold +left action +\series default + of +\begin_inset Formula $G$ +\end_inset + + on +\begin_inset Formula $M$ +\end_inset + + is defined as a smooth map +\begin_inset Formula $\Phi:G\times M\rightarrow M$ +\end_inset + + such that +\begin_inset CommandInset citation +LatexCommand cite +after "Appendix A" +key "Murray94book" + +\end_inset + +: +\end_layout + +\begin_layout Enumerate +The identity element +\begin_inset Formula $e$ +\end_inset + + has no effect, i.e., +\begin_inset Formula $\Phi(e,p)=p$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +Composing two actions can be combined into one action: +\begin_inset Formula $\Phi(g,\Phi(h,p))=\Phi(gh,p)$ +\end_inset + + +\end_layout + +\begin_layout Standard +The (usual) action of an +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix group +\begin_inset Formula $G$ +\end_inset + + is matrix-vector multiplication on +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, +\begin_inset Formula +\[ +q=Ap +\] + +\end_inset + +with +\begin_inset Formula $p,q\in\mathbb{R}^{n}$ +\end_inset + + and +\begin_inset Formula $A\in G\subseteq GL(n)$ +\end_inset + +. + +\end_layout + +\begin_layout Subsection +The Adjoint Map and Adjoint Representation +\end_layout + +\begin_layout Standard +Suppose a point +\begin_inset Formula $p$ +\end_inset + + is specified as +\begin_inset Formula $p'$ +\end_inset + + in the frame +\begin_inset Formula $T$ +\end_inset + +, i.e., +\begin_inset Formula $p'=Tp$ +\end_inset + +, where +\begin_inset Formula $T$ +\end_inset + + transforms from the global coordinates +\begin_inset Formula $p$ +\end_inset + + to the local frame +\begin_inset Formula $p'$ +\end_inset + +. + To apply an action +\begin_inset Formula $A$ +\end_inset + + we first need to undo +\begin_inset Formula $T$ +\end_inset + +, then apply +\begin_inset Formula $A$ +\end_inset + +, and then transform the result back to +\begin_inset Formula $T$ +\end_inset + +: +\begin_inset Formula +\[ +q'=TAT^{-1}p' +\] + +\end_inset + +The matrix +\begin_inset Formula $TAT^{-1}$ +\end_inset + + is said to be conjugate to +\begin_inset Formula $A$ +\end_inset + +, and this is a central element of group theory. +\end_layout + +\begin_layout Standard +In general, the +\series bold +adjoint map +\series default + +\begin_inset Formula $\AAdd g$ +\end_inset + + maps a group element +\begin_inset Formula $a\in G$ +\end_inset + + to its +\series bold +conjugate +\series default + +\begin_inset Formula $gag^{-1}$ +\end_inset + + by +\begin_inset Formula $g$ +\end_inset + +. + This map captures conjugacy in the group +\begin_inset Formula $G$ +\end_inset + +, but there is an equivalent notion in the Lie algebra +\begin_inset Formula $\mathfrak{\gg}$ +\end_inset + +, +\begin_inset Note Note +status open + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Exponential_map +\end_layout + +\end_inset + + +\begin_inset Formula +\[ +\AAdd ge^{\xhat}=g\exp\left(\xhat\right)g^{-1}=\exp(\Ad g{\xhat}) +\] + +\end_inset + +where +\begin_inset Formula $\Ad g:\gg\rightarrow\mathfrak{\gg}$ +\end_inset + + is a map parameterized by a group element +\begin_inset Formula $g$ +\end_inset + +, and is called the +\emph on +adjoint representation +\emph default +. + The intuitive explanation is that a change +\begin_inset Formula $\exp\left(\xhat\right)$ +\end_inset + + defined around the origin, but applied at the group element +\begin_inset Formula $g$ +\end_inset + +, can be written in one step by taking the adjoint +\begin_inset Formula $\Ad g{\xhat}$ +\end_inset + + of +\begin_inset Formula $\xhat$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +In the special case of matrix Lie groups the adjoint can be written as +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +http://en.wikipedia.org/wiki/Adjoint_representation_of_a_Lie_group +\end_layout + +\end_inset + + +\begin_inset Formula +\[ +\Ad T{\xhat}\define T\xhat T^{-1} +\] + +\end_inset + +and hence we have +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +Te^{\xhat}T^{-1}=e^{T\xhat T^{-1}}\label{eq:matrixAdjoint} +\end{equation} + +\end_inset + +where both +\begin_inset Formula $T\in G$ +\end_inset + + and +\begin_inset Formula $\xhat\in\gg$ +\end_inset + + are +\begin_inset Formula $n\times n$ +\end_inset + + matrices for an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rotations +\end_layout + +\begin_layout Standard +We first look at a very simple group, the 2D rotations. +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SOtwo$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(2)$ +\end_inset + + of +\begin_inset Formula $2\times2$ +\end_inset + + invertible matrices. + Its Lie algebra +\begin_inset Formula $\sotwo$ +\end_inset + + is the vector space of +\begin_inset Formula $2\times2$ +\end_inset + + skew-symmetric matrices. + Since +\begin_inset Formula $\SOtwo$ +\end_inset + + is a one-dimensional manifold, +\begin_inset Formula $\sotwo$ +\end_inset + + is isomorphic to +\begin_inset Formula $\mathbb{R}$ +\end_inset + + and we define +\begin_inset Formula +\[ +\hat{}:\mathbb{R}\rightarrow\sotwo +\] + +\end_inset + + +\begin_inset Formula +\[ +\hat{}:\omega\rightarrow\what=\skew{\omega} +\] + +\end_inset + +which maps the angle +\begin_inset Formula $\omega$ +\end_inset + + to the +\begin_inset Formula $2\times2$ +\end_inset + + skew-symmetric matrix +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\skew{\omega}$ +\end_inset + +: +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + +\begin_inset Formula +\[ +\skew{\omega}=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right] +\] + +\end_inset + +The exponential map can be computed in closed form as +\begin_inset Formula +\[ +e^{\skew{\omega}}=\left[\begin{array}{cc} +\cos\omega & -\sin\omega\\ +\sin\omega & \cos\omega +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:Diagonalized2D" + +\end_inset + +Diagonalized Form +\end_layout + +\begin_layout Standard +The matrix +\begin_inset Formula $\skew 1$ +\end_inset + + can be diagonalized (see +\begin_inset CommandInset citation +LatexCommand cite +key "Hall00book" + +\end_inset + +) with eigenvalues +\begin_inset Formula $-i$ +\end_inset + + and +\begin_inset Formula $i$ +\end_inset + + , and eigenvectors +\begin_inset Formula $\left[\begin{array}{c} +1\\ +i +\end{array}\right]$ +\end_inset + + and +\begin_inset Formula $\left[\begin{array}{c} +i\\ +1 +\end{array}\right]$ +\end_inset + + . + Readers familiar with projective geometry will recognize these as the circular + points when promoted to homogeneous coordinates. + In particular: +\begin_inset Formula +\[ +\skew{\omega}=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]=\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]\left[\begin{array}{cc} +-i\omega & 0\\ +0 & i\omega +\end{array}\right]\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]^{-1} +\] + +\end_inset + +and hence +\begin_inset Formula +\[ +e^{\skew{\omega}}=\frac{1}{2}\left[\begin{array}{cc} +1 & i\\ +i & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{-i\omega} & 0\\ +0 & e^{i\omega} +\end{array}\right]\left[\begin{array}{cc} +1 & -i\\ +-i & 1 +\end{array}\right]=\left[\begin{array}{cc} +\cos\omega & -\sin\omega\\ +\sin\omega & \cos\omega +\end{array}\right] +\] + +\end_inset + +where the latter can be shown using +\begin_inset Formula $e^{i\omega}=\cos\omega+i\sin\omega$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Adjoint +\end_layout + +\begin_layout Standard +The adjoint for +\begin_inset Formula $\sotwo$ +\end_inset + + is trivially equal to the identity, as is the case for +\emph on +all +\emph default + commutative groups: +\begin_inset Formula +\begin{eqnarray*} +\Ad R\what & = & \left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right]\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]\left[\begin{array}{cc} +\cos\theta & -\sin\theta\\ +\sin\theta & \cos\theta +\end{array}\right]^{T}\\ + & = & \omega\left[\begin{array}{cc} +-\sin\theta & -\cos\theta\\ +\cos\theta & -\sin\theta +\end{array}\right]\left[\begin{array}{cc} +\cos\theta & \sin\theta\\ +-\sin\theta & \cos\theta +\end{array}\right]=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +i.e., +\begin_inset Formula +\[ +\Ad R\what=\what +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + + the vector space is +\begin_inset Formula $\Rtwo$ +\end_inset + +, and the group action corresponds to rotating a point +\begin_inset Formula +\[ +q=Rp +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\omega$ +\end_inset + + would do: +\begin_inset Formula +\[ +q(\text{\omega})=Re^{\skew{\omega}}p +\] + +\end_inset + +For small angles +\begin_inset Formula $\omega$ +\end_inset + + we have +\begin_inset Formula +\[ +e^{\skew{\omega}}\approx\skew{\omega}=\omega\skew 1 +\] + +\end_inset + +where +\begin_inset Formula $\skew 1$ +\end_inset + + acts like a restricted +\begin_inset Quotes eld +\end_inset + +cross product +\begin_inset Quotes erd +\end_inset + + in the plane on points: +\begin_inset Formula +\begin{equation} +\skew 1\left[\begin{array}{c} +x\\ +y +\end{array}\right]=R_{\pi/2}\left[\begin{array}{c} +x\\ +y +\end{array}\right]=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]\label{eq:RestrictedCross} +\end{equation} + +\end_inset + +Hence the derivative of the action is given as +\begin_inset Formula +\[ +\deriv{q(\omega)}{\omega}=R\deriv{}{\omega}\left(e^{\skew{\omega}}p\right)=R\deriv{}{\omega}\left(\omega\skew 1p\right)=RH_{p} +\] + +\end_inset + +where +\begin_inset Formula $H_{p}$ +\end_inset + + is a +\begin_inset Formula $2\times1$ +\end_inset + + matrix that depends on +\begin_inset Formula $p$ +\end_inset + +: +\begin_inset Formula +\[ +H_{p}\define\skew 1p=\left[\begin{array}{c} +-p_{y}\\ +p_{x} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rigid Transformations +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SEtwo$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices of the form +\begin_inset Formula +\[ +T\define\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $R\in\SOtwo$ +\end_inset + + is a rotation matrix and +\begin_inset Formula $t\in\Rtwo$ +\end_inset + + is a translation vector. + +\begin_inset Formula $\SEtwo$ +\end_inset + + is the +\emph on +semi-direct product +\emph default + of +\begin_inset Formula $\Rtwo$ +\end_inset + + by +\begin_inset Formula $SO(2)$ +\end_inset + +, written as +\begin_inset Formula $\SEtwo=\Rtwo\rtimes\SOtwo$ +\end_inset + +. + In particular, any element +\begin_inset Formula $T$ +\end_inset + + of +\begin_inset Formula $\SEtwo$ +\end_inset + + can be written as +\begin_inset Formula +\[ +T=\left[\begin{array}{cc} +0 & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R & 0\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +and they compose as +\begin_inset Formula +\[ +T_{1}T_{2}=\left[\begin{array}{cc} +R_{1} & t_{1}\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +R_{2} & t_{2}\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +R_{1}R_{2} & R_{1}t_{2}+t_{1}\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +Hence, an alternative way of writing down elements of +\begin_inset Formula $\SEtwo$ +\end_inset + + is as the ordered pair +\begin_inset Formula $(R,\, t)$ +\end_inset + +, with composition defined a +\begin_inset Formula +\[ +(R_{1},\, t_{1})(R_{2},\, t_{2})=(R_{1}R_{2},\, R{}_{1}t_{2}+t_{1}) +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +The corresponding Lie algebra +\begin_inset Formula $\setwo$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + twists +\begin_inset Formula $\xihat$ +\end_inset + + parameterized by the +\emph on +twist coordinates +\emph default + +\begin_inset Formula $\xi\in\Rthree$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +\xi\define\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]\rightarrow\xihat\define\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + +Note we think of robots as having a pose +\begin_inset Formula $(x,y,\theta)$ +\end_inset + + and hence I reserved the first two components for translation and the last + for rotation. + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +The corresponding Lie group generators are +\begin_inset Formula +\[ +G^{x}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{y}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{\theta}=\left[\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Applying the exponential map to a twist +\begin_inset Formula $\xi$ +\end_inset + + yields a screw motion yielding an element in +\begin_inset Formula $\SEtwo$ +\end_inset + +: +\begin_inset Formula +\[ +T=e^{\xihat}=\left(e^{\skew{\omega}},(I-e^{\skew{\omega}})\frac{v^{\perp}}{\omega}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +The adjoint is +\begin_inset Formula +\begin{eqnarray} +\Ad T{\xihat} & = & T\xihat T^{-1}\nonumber \\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{cc} +\skew{\omega} & -\skew{\omega}t+Rv\\ +0 & 0 +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{cc} +\skew{\omega} & Rv-\omega R_{\pi/2}t\\ +0 & 0 +\end{array}\right]\label{eq:adjointSE2} +\end{eqnarray} + +\end_inset + +From this we can express the Adjoint map in terms of plane twist coordinates: +\begin_inset Formula +\[ +\left[\begin{array}{c} +v'\\ +\omega' +\end{array}\right]=\left[\begin{array}{cc} +R & -R_{\pi/2}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEtwo$ +\end_inset + + on 2D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{3}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +Analoguous to +\begin_inset Formula $\SEthree$ +\end_inset + +, we can compute a velocity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + in the local +\begin_inset Formula $T$ +\end_inset + + frame: +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\skew{\omega}p+v\\ +0 +\end{array}\right] +\] + +\end_inset + +By only taking the top two rows, we can write this as a velocity in +\begin_inset Formula $\Rtwo$ +\end_inset + +, as the product of a +\begin_inset Formula $2\times3$ +\end_inset + + matrix +\begin_inset Formula $H_{p}$ +\end_inset + + that acts upon the exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + directly: +\begin_inset Formula +\[ +\skew{\omega}p+v=v+R_{\pi/2}p\omega=\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]=H_{p}\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rotations +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SOthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices. + Its Lie algebra +\begin_inset Formula $\sothree$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + skew-symmetric matrices +\begin_inset Formula $\what$ +\end_inset + +. + Since +\begin_inset Formula $\SOthree$ +\end_inset + + is a three-dimensional manifold, +\begin_inset Formula $\sothree$ +\end_inset + + is isomorphic to +\begin_inset Formula $\Rthree$ +\end_inset + + and we define the map +\begin_inset Formula +\[ +\hat{}:\Rthree\rightarrow\sothree +\] + +\end_inset + + +\begin_inset Formula +\[ +\hat{}:\omega\rightarrow\what=\Skew{\omega} +\] + +\end_inset + +which maps 3-vectors +\begin_inset Formula $\omega$ +\end_inset + + to skew-symmetric matrices +\begin_inset Formula $\Skew{\omega}$ +\end_inset + + : +\begin_inset Formula +\[ +\Skew{\omega}=\left[\begin{array}{ccc} +0 & -\omega_{z} & \omega_{y}\\ +\omega_{z} & 0 & -\omega_{x}\\ +-\omega_{y} & \omega_{x} & 0 +\end{array}\right]=\omega_{x}G^{x}+\omega_{y}G^{y}+\omega_{z}G^{z} +\] + +\end_inset + +Here the matrices +\begin_inset Formula $G^{i}$ +\end_inset + + are the generators for +\begin_inset Formula $\SOthree$ +\end_inset + +, +\begin_inset Formula +\[ +G^{x}=\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & -1\\ +0 & 1 & 0 +\end{array}\right)\mbox{}G^{y}=\left(\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +-1 & 0 & 0 +\end{array}\right)\mbox{ }G^{z}=\left(\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + +corresponding to a rotation around +\begin_inset Formula $X$ +\end_inset + +, +\begin_inset Formula $Y$ +\end_inset + +, and +\begin_inset Formula $Z$ +\end_inset + +, respectively. + The Lie bracket +\begin_inset Formula $[x,y]$ +\end_inset + + in +\begin_inset Formula $\sothree$ +\end_inset + + corresponds to the cross product +\begin_inset Formula $x\times y$ +\end_inset + + in +\begin_inset Formula $\Rthree$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Hence, for every +\begin_inset Formula $3$ +\end_inset + +-vector +\begin_inset Formula $\omega$ +\end_inset + + there is a corresponding rotation matrix +\begin_inset Formula +\[ +R=e^{\Skew{\omega}} +\] + +\end_inset + +which defines a canonical parameterization of +\begin_inset Formula $\SOthree$ +\end_inset + +, with +\begin_inset Formula $\omega$ +\end_inset + + known as the canonical or exponential coordinates. + It is equivalent to the axis-angle representation for rotations, where + the unit vector +\begin_inset Formula $\omega/\theta$ +\end_inset + + defines the rotation axis, and its magnitude the amount of rotation +\begin_inset Formula $\theta$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +The exponential map can be computed in closed form using +\series bold +Rodrigues' formula +\series default + +\begin_inset CommandInset citation +LatexCommand cite +after "page 28" +key "Murray94book" + +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +e^{\what}=I+\frac{\sin\theta}{\theta}\what+\frac{1\text{−}\cos\theta}{\theta^{2}}\what^{2}\label{eq:Rodrigues} +\end{equation} + +\end_inset + +where +\begin_inset Formula $\what^{2}=\omega\omega^{T}-I$ +\end_inset + +, with +\begin_inset Formula $\omega\omega^{T}$ +\end_inset + + the outer product of +\begin_inset Formula $\omega$ +\end_inset + +. + Hence, a slightly more efficient variant is +\begin_inset Formula +\begin{equation} +e^{\what}=\left(\cos\theta\right)I+\frac{\sin\theta}{\theta}\what+\frac{1\text{−}cos\theta}{\theta^{2}}\omega\omega^{T}\label{eq:Rodrigues2} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Diagonalized Form +\end_layout + +\begin_layout Standard +Because a 3D rotation +\begin_inset Formula $R$ +\end_inset + + leaves the axis +\begin_inset Formula $\omega$ +\end_inset + + unchanged, +\begin_inset Formula $R$ +\end_inset + + can be diagonalized as +\begin_inset Formula +\[ +R=C\left(\begin{array}{ccc} +e^{-i\theta} & 0 & 0\\ +0 & e^{i\theta} & 0\\ +0 & 0 & 1 +\end{array}\right)C^{-1} +\] + +\end_inset + +with +\begin_inset Formula $C=\left(\begin{array}{ccc} +c_{1} & c_{2} & \omega/\theta\end{array}\right)$ +\end_inset + +, where +\begin_inset Formula $c_{1}$ +\end_inset + + and +\begin_inset Formula $c_{2}$ +\end_inset + + are the complex eigenvectors corresponding to the 2D rotation around +\begin_inset Formula $\omega$ +\end_inset + +. + This also means that, by +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:matrixAdjoint" + +\end_inset + +, +\begin_inset Formula +\[ +\hat{\omega}=C\left(\begin{array}{ccc} +-i\theta & 0 & 0\\ +0 & i\theta & 0\\ +0 & 0 & 0 +\end{array}\right)C^{-1} +\] + +\end_inset + +In this case, +\begin_inset Formula $C$ +\end_inset + + has complex columns, but we also have +\begin_inset Formula +\begin{equation} +\hat{\omega}=B\left(\begin{array}{ccc} +0 & -\theta & 0\\ +\theta & 0 & 0\\ +0 & 0 & 0 +\end{array}\right)B^{T}\label{eq:OmegaDecomposed} +\end{equation} + +\end_inset + +with +\begin_inset Formula $B=\left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)$ +\end_inset + +, where +\begin_inset Formula $b_{1}$ +\end_inset + + and +\begin_inset Formula $b_{2}$ +\end_inset + + form a basis for the 2D plane through the origin and perpendicular to +\begin_inset Formula $\omega$ +\end_inset + +. + Clearly, from Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Diagonalized2D" + +\end_inset + +, we have +\begin_inset Formula +\[ +c_{1}=B\left(\begin{array}{c} +1\\ +i\\ +0 +\end{array}\right)\mbox{\,\,\,\ and\,\,\,\,\,}c_{2}=B\left(\begin{array}{c} +i\\ +1\\ +0 +\end{array}\right) +\] + +\end_inset + +and when we exponentiate +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:OmegaDecomposed" + +\end_inset + + we expose the 2D rotation around the axis +\begin_inset Formula $\omega/\theta$ +\end_inset + + with magnitude +\begin_inset Formula $\theta$ +\end_inset + +: +\begin_inset Formula +\[ +R=B\left(\begin{array}{ccc} +\cos\theta & -\sin\theta & 0\\ +\sin\theta & \cos\theta & 0\\ +0 & 0 & 1 +\end{array}\right)B^{T} +\] + +\end_inset + +The latter form for +\begin_inset Formula $R$ +\end_inset + + can be used to prove Rodrigues' formula. + Expanding the above, we get +\begin_inset Formula +\[ +R=\left(\cos\theta\right)\left(b_{1}b_{1}^{T}+b_{2}b_{2}^{T}\right)+\left(\sin\theta\right)\left(b_{2}b_{1}^{T}-b_{1}b_{2}^{T}\right)+\omega\omega^{T}/\theta^{2} +\] + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +\begin_inset Formula +\begin{eqnarray*} +R & = & \left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)\left(\begin{array}{ccc} +\cos\theta & -\sin\theta & 0\\ +\sin\theta & \cos\theta & 0\\ +0 & 0 & 1 +\end{array}\right)\left(\begin{array}{c} +b_{1}^{T}\\ +b_{2}^{T}\\ +\omega^{T}/\theta +\end{array}\right)\\ + & = & \left(\begin{array}{ccc} +b_{1} & b_{2} & \omega/\theta\end{array}\right)\left(\begin{array}{c} +b_{1}^{T}\cos\theta-b_{2}^{T}\sin\theta\\ +b_{1}^{T}\sin\theta+b_{2}^{T}\cos\theta\\ +\omega^{T}/\theta +\end{array}\right)\\ + & = & b_{1}b_{1}^{T}\cos\theta-b_{1}b_{2}^{T}\sin\theta+b_{2}b_{1}^{T}\sin\theta+b_{2}b_{2}^{T}\cos\theta+\omega\omega^{T}/\theta^{2} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\end_inset + +Because +\begin_inset Formula $B$ +\end_inset + + is a rotation matrix, we have +\begin_inset Formula $BB^{T}=b_{1}b_{1}^{T}+b_{2}b_{2}^{T}+\omega\omega^{T}/\theta^{2}=I$ +\end_inset + +, and using +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:OmegaDecomposed" + +\end_inset + + it is easy to show that +\begin_inset Formula $b_{2}b_{1}^{T}-b_{1}b_{2}^{T}=\hat{\omega}/\theta$ +\end_inset + +, hence +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit + +\begin_inset Formula +\[ +R=\left(\cos\theta\right)(I-\omega\omega^{T}/\theta^{2})+\left(\sin\theta\right)\left(\hat{\omega}/\theta\right)+\omega\omega^{T}/\theta^{2} +\] + +\end_inset + +which is equivalent to +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Rodrigues2" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +For rotation matrices +\begin_inset Formula $R$ +\end_inset + + we can prove the following identity (see +\begin_inset CommandInset ref +LatexCommand vref +reference "proof1" + +\end_inset + +): +\begin_inset Formula +\begin{equation} +R\Skew{\omega}R^{T}=\Skew{R\omega}\label{eq:property1} +\end{equation} + +\end_inset + +Hence, given property +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:property1" + +\end_inset + +, the adjoint map for +\begin_inset Formula $\sothree$ +\end_inset + + simplifies to +\begin_inset Formula +\[ +\Ad R{\Skew{\omega}}=R\Skew{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +and this can be expressed in exponential coordinates simply by rotating + the axis +\begin_inset Formula $\omega$ +\end_inset + + to +\begin_inset Formula $R\omega$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +As an example, to apply an axis-angle rotation +\begin_inset Formula $\omega$ +\end_inset + + to a point +\begin_inset Formula $p$ +\end_inset + + in the frame +\begin_inset Formula $R$ +\end_inset + +, we could: +\end_layout + +\begin_layout Enumerate +First transform +\begin_inset Formula $p$ +\end_inset + + back to the world frame, apply +\begin_inset Formula $\omega$ +\end_inset + +, and then rotate back: +\begin_inset Formula +\[ +q=Re^{\Skew{\omega}}R^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Enumerate +Immediately apply the transformed axis-angle transformation +\begin_inset Formula $\Ad R{\Skew{\omega}}=\Skew{R\omega}$ +\end_inset + +: +\begin_inset Formula +\[ +q=e^{\Skew{R\omega}}p +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOthree$ +\end_inset + + the vector space is +\begin_inset Formula $\Rthree$ +\end_inset + +, and the group action corresponds to rotating a point +\begin_inset Formula +\[ +q=Rp +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\omega$ +\end_inset + + would do: +\begin_inset Formula +\[ +q(\omega)=Re^{\Skew{\omega}}p +\] + +\end_inset + +hence the derivative is: +\begin_inset Formula +\[ +\deriv{q(\omega)}{\omega}=R\deriv{}{\omega}\left(e^{\Skew{\omega}}p\right)=R\deriv{}{\omega}\left(\Skew{\omega}p\right)=R\Skew{-p} +\] + +\end_inset + +To show the last equality note that +\begin_inset Formula +\[ +\Skew{\omega}p=\omega\times p=-p\times\omega=\Skew{-p}\omega +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rigid Transformations +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SEthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(4)$ +\end_inset + + of +\begin_inset Formula $4\times4$ +\end_inset + + invertible matrices of the form +\begin_inset Formula +\[ +T\define\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $R\in\SOthree$ +\end_inset + + is a rotation matrix and +\begin_inset Formula $t\in\Rthree$ +\end_inset + + is a translation vector. + An alternative way of writing down elements of +\begin_inset Formula $\SEthree$ +\end_inset + + is as the ordered pair +\begin_inset Formula $(R,\, t)$ +\end_inset + +, with composition defined as +\begin_inset Formula +\[ +(R_{1},\, t_{1})(R_{2},\, t_{2})=(R_{1}R_{2},\, R{}_{1}t_{2}+t_{1}) +\] + +\end_inset + + Its Lie algebra +\begin_inset Formula $\sethree$ +\end_inset + + is the vector space of +\begin_inset Formula $4\times4$ +\end_inset + + twists +\begin_inset Formula $\xihat$ +\end_inset + + parameterized by the +\emph on +twist coordinates +\emph default + +\begin_inset Formula $\xi\in\Rsix$ +\end_inset + +, with the mapping +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + + +\begin_inset Formula +\[ +\xi\define\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\rightarrow\xihat\define\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + +Note we follow Frank Park's convention and reserve the first three components + for rotation, and the last three for translation. + Hence, with this parameterization, the generators for +\begin_inset Formula $\SEthree$ +\end_inset + + are +\begin_inset Formula +\[ +G^{1}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & -1 & 0\\ +0 & 1 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{}G^{2}=\left(\begin{array}{cccc} +0 & 0 & 1 & 0\\ +0 & 0 & 0 & 0\\ +-1 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{ }G^{3}=\left(\begin{array}{cccc} +0 & -1 & 0 & 0\\ +1 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{4}=\left(\begin{array}{cccc} +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{}G^{5}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 +\end{array}\right)\mbox{ }G^{6}=\left(\begin{array}{cccc} +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0\\ +0 & 0 & 0 & 1\\ +0 & 0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + +Applying the exponential map to a twist +\begin_inset Formula $\xi$ +\end_inset + + yields a screw motion yielding an element in +\begin_inset Formula $\SEthree$ +\end_inset + +: +\begin_inset Formula +\[ +T=\exp\xihat +\] + +\end_inset + +A closed form solution for the exponential map is given in +\begin_inset CommandInset citation +LatexCommand cite +after "page 42" +key "Murray94book" + +\end_inset + +. +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +\begin_inset Formula +\[ +\exp\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]t\right)=\left[\begin{array}{cc} +e^{\Skew{\omega}t} & (I-e^{\Skew{\omega}t})\left(\omega\times v\right)+\omega\omega^{T}vt\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Standard +The adjoint is +\begin_inset Formula +\begin{eqnarray*} +\Ad T{\xihat} & = & T\xihat T^{-1}\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +\Skew{R\omega} & -\Skew{R\omega}t+Rv\\ +0 & 0 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +\Skew{R\omega} & t\times R\omega+Rv\\ +0 & 0 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +From this we can express the Adjoint map in terms of twist coordinates (see + also +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + + and FP): +\begin_inset Formula +\[ +\left[\begin{array}{c} +\omega'\\ +v' +\end{array}\right]=\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEthree$ +\end_inset + + on 3D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{c} +Rp+t\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +We would now like to know what an incremental rotation parameterized by + +\begin_inset Formula $\xi$ +\end_inset + + would do: +\begin_inset Formula +\[ +\hat{q}(\xi)=Te^{\xihat}\hat{p} +\] + +\end_inset + +hence the derivative is +\begin_inset Formula +\[ +\deriv{\hat{q}(\xi)}{\xi}=T\deriv{}{\xi}\left(\xihat\hat{p}\right) +\] + +\end_inset + +where +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + corresponds to a velocity in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + (in the local +\begin_inset Formula $T$ +\end_inset + + frame): +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\omega\times p+v\\ +0 +\end{array}\right] +\] + +\end_inset + +Notice how velocities are analogous to points at infinity in projective + geometry: they correspond to free vectors indicating a direction and magnitude + of change. +\end_layout + +\begin_layout Standard +By only taking the top three rows, we can write this as a velocity in +\begin_inset Formula $\Rthree$ +\end_inset + +, as the product of a +\begin_inset Formula $3\times6$ +\end_inset + + matrix +\begin_inset Formula $H_{p}$ +\end_inset + + that acts upon the exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + directly: +\begin_inset Formula +\[ +\omega\times p+v=-p\times\omega+v=\left[\begin{array}{cc} +-\Skew p & I_{3}\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + +The inverse action +\begin_inset Formula $T^{-1}p$ +\end_inset + + is +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{c} +R^{T}(p-t)\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T^{-1}\hat{p} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Affine Transformations +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $Aff(2)$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices that maps the line infinity to itself, and hence preserves + paralellism. + The affine transformation matrices +\begin_inset Formula $A$ +\end_inset + + can be written as +\begin_inset CommandInset citation +LatexCommand cite +key "Mei08tro" + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +\left[\begin{array}{ccc} +m_{11} & m_{12} & t_{1}\\ +m_{21} & m_{22} & t_{2}\\ +0 & 0 & k +\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $M\in GL(2)$ +\end_inset + +, +\begin_inset Formula $t\in\Rtwo$ +\end_inset + +, and +\begin_inset Formula $k$ +\end_inset + + a scalar chosen such that +\begin_inset Formula $det(A)=1$ +\end_inset + +. + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Note that just as +\begin_inset Formula $\SEtwo$ +\end_inset + + is a semi-direct product, so too is +\begin_inset Formula $Aff(2)=\Rtwo\rtimes GL(2)$ +\end_inset + +. + In particular, any affine transformation +\begin_inset Formula $A$ +\end_inset + + can be written as +\begin_inset Formula +\[ +A=\left[\begin{array}{cc} +0 & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +M & 0\\ +0 & k +\end{array}\right] +\] + +\end_inset + +and they compose as +\begin_inset Formula +\[ +A_{1}A_{2}=\left[\begin{array}{cc} +M_{1} & t_{1}\\ +0 & k_{1} +\end{array}\right]\left[\begin{array}{cc} +M_{2} & t_{2}\\ +0 & k_{2} +\end{array}\right]=\left[\begin{array}{cc} +M_{1}M_{2} & M_{2}t_{2}+k_{2}t_{1}\\ +0 & k_{1}k_{2} +\end{array}\right] +\] + +\end_inset + +From this it can be gleaned that the groups +\begin_inset Formula $\SOtwo$ +\end_inset + + and +\begin_inset Formula $\SEtwo$ +\end_inset + + are both subgroups, with +\begin_inset Formula $\SOtwo\subset\SEtwo\subset\Afftwo$ +\end_inset + +. + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +By choosing the generators carefully we maintain this hierarchy among the + associated Lie algebras. + In particular, +\begin_inset Formula $\setwo$ +\end_inset + + +\begin_inset Formula +\[ +G^{1}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{2}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{3}=\left[\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + +can be extended to the +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Lie algebra +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\afftwo$ +\end_inset + + using the three additional generators +\begin_inset Formula +\[ +G^{4}=\left[\begin{array}{ccc} +0 & 1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Hence, the Lie algebra +\begin_inset Formula $\afftwo$ +\end_inset + + is the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + incremental affine transformations +\begin_inset Formula $\ahat$ +\end_inset + + parameterized by 6 parameters +\begin_inset Formula $\aa\in\mathbb{R}^{6}$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +\aa\rightarrow\ahat\define\left[\begin{array}{ccc} +a_{5} & a_{4}-a_{3} & a_{1}\\ +a_{4}+a_{3} & -a_{5}-a_{6} & a_{2}\\ +0 & 0 & a_{6} +\end{array}\right] +\] + +\end_inset + +Note that +\begin_inset Formula $G_{5}$ +\end_inset + + and +\begin_inset Formula $G_{6}$ +\end_inset + + change the relative scale of +\begin_inset Formula $x$ +\end_inset + + and +\begin_inset Formula $y$ +\end_inset + + but without changing the determinant: +\begin_inset Formula +\[ +e^{xG_{5}}=\exp\left[\begin{array}{ccc} +x & 0 & 0\\ +0 & -x & 0\\ +0 & 0 & 0 +\end{array}\right]=\left[\begin{array}{ccc} +e^{x} & 0 & 0\\ +0 & 1/e^{x} & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +e^{xG_{6}}=\exp\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -x & 0\\ +0 & 0 & x +\end{array}\right]=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & 1/e^{x} & 0\\ +0 & 0 & e^{x} +\end{array}\right] +\] + +\end_inset + +It might be nicer to have the correspondence with scaling +\begin_inset Formula $x$ +\end_inset + + and +\begin_inset Formula $y$ +\end_inset + + more direct, by choosing +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & 0 & 0\\ +0 & 0 & -1 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 1 & 0\\ +0 & 0 & -1 +\end{array}\right] +\] + +\end_inset + +and hence +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + +\begin_inset Formula +\[ +e^{xG_{5}}=\exp\left[\begin{array}{ccc} +x & 0 & 0\\ +0 & 0 & 0\\ +0 & 0 & -x +\end{array}\right]=\left[\begin{array}{ccc} +e^{x} & 0 & 0\\ +0 & 1 & 0\\ +0 & 0 & 1/e^{x} +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +e^{xG_{6}}=\exp\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & x & 0\\ +0 & 0 & -x +\end{array}\right]=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & e^{x} & 0\\ +0 & 0 & 1/e^{x} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Section +2D Homographies +\end_layout + +\begin_layout Standard +When viewed as operations on images, represented by 2D projective space + +\begin_inset Formula $\mathcal{P}^{3}$ +\end_inset + +, 3D rotations are a special case of 2D homographies. + These are now treated, loosely based on the exposition in +\begin_inset CommandInset citation +LatexCommand cite +key "Mei06iros,Mei08tro" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +The Lie group +\begin_inset Formula $\SLthree$ +\end_inset + + is a subgroup of the general linear group +\begin_inset Formula $GL(3)$ +\end_inset + + of +\begin_inset Formula $3\times3$ +\end_inset + + invertible matrices with determinant +\begin_inset Formula $1$ +\end_inset + +. + The homographies generalize transformations of the 2D projective space, + and +\begin_inset Formula $\Afftwo\subset\SLthree$ +\end_inset + +. + +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +We can extend +\begin_inset Formula $\afftwo$ +\end_inset + + to the Lie algebra +\begin_inset Formula $\slthree$ +\end_inset + + by adding two generators +\begin_inset Formula +\[ +G^{7}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right]\mbox{ }G^{8}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +0 & 1 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +obtaining the vector space of +\begin_inset Formula $3\times3$ +\end_inset + + incremental homographies +\begin_inset Formula $\hhat$ +\end_inset + + parameterized by 8 parameters +\begin_inset Formula $\hh\in\mathbb{R}^{8}$ +\end_inset + +, with the mapping +\begin_inset Formula +\[ +h\rightarrow\hhat\define\left[\begin{array}{ccc} +h_{5} & h_{4}-h_{3} & h_{1}\\ +h_{4}+h_{3} & -h_{5}-h_{6} & h_{2}\\ +h_{7} & h_{8} & h_{6} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Tensor Notation +\end_layout + +\begin_layout Itemize +A homography between 2D projective spaces +\begin_inset Formula $A$ +\end_inset + + and +\begin_inset Formula $B$ +\end_inset + + can be written in tensor notation +\begin_inset Formula $H_{A}^{B}$ +\end_inset + + +\end_layout + +\begin_layout Itemize +Applying a homography is then a tensor contraction +\begin_inset Formula $x^{B}=H_{A}^{B}x^{A}$ +\end_inset + +, mapping points in +\begin_inset Formula $A$ +\end_inset + + to points in +\begin_inset Formula $B$ +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +The inverse of a homography can be found by contracting with two permutation + tensors: +\begin_inset Formula +\[ +H_{B}^{A}=H_{A_{1}}^{B_{1}}H_{A_{2}}^{B_{2}}\epsilon_{B_{1}B_{2}B}\epsilon^{A_{1}A_{2}A} +\] + +\end_inset + + +\end_layout + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Subsection +The Adjoint Map +\end_layout + +\begin_layout Plain Layout +The adjoint can be done using tensor notation. + Denoting an incremental homography in space +\begin_inset Formula $A$ +\end_inset + + as +\begin_inset Formula $\hhat_{A_{1}}^{A_{2}}$ +\end_inset + +, we have, for example for +\begin_inset Formula $G_{1}$ +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\hhat_{B_{1}}^{B_{2}}=\Ad{H_{A}^{B}}{\hhat_{A_{1}}^{A_{2}}} & = & H_{A_{2}}^{B_{2}}\hhat_{A_{1}}^{A_{2}}H_{B_{1}}^{A_{1}}\\ + & = & H_{A_{2}}^{B_{2}}\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]H_{A_{2}}^{B_{2}}H_{A_{3}}^{B_{3}}\epsilon_{B_{1}B_{2}B_{3}}\epsilon^{A_{1}A_{2}A_{3}}\\ + & = & H_{1}^{B_{2}}H_{A_{2}}^{B_{2}}H_{A_{3}}^{B_{3}}\epsilon_{B_{1}B_{2}B_{3}}\epsilon^{3A_{2}A_{3}} +\end{eqnarray*} + +\end_inset + +This does not seem to help. +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix: Proof of Property +\begin_inset CommandInset ref +LatexCommand ref +reference "proof1" + +\end_inset + + +\end_layout + +\begin_layout Standard +We can prove the following identity for rotation matrices +\begin_inset Formula $R$ +\end_inset + +, +\begin_inset Formula +\begin{eqnarray} +R\Skew{\omega}R^{T} & = & R\Skew{\omega}\left[\begin{array}{ccc} +a_{1} & a_{2} & a_{3}\end{array}\right]\nonumber \\ + & = & R\left[\begin{array}{ccc} +\omega\times a_{1} & \omega\times a_{2} & \omega\times a_{3}\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +a_{1}(\omega\times a_{1}) & a_{1}(\omega\times a_{2}) & a_{1}(\omega\times a_{3})\\ +a_{2}(\omega\times a_{1}) & a_{2}(\omega\times a_{2}) & a_{2}(\omega\times a_{3})\\ +a_{3}(\omega\times a_{1}) & a_{3}(\omega\times a_{2}) & a_{3}(\omega\times a_{3}) +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +\omega(a_{1}\times a_{1}) & \omega(a_{2}\times a_{1}) & \omega(a_{3}\times a_{1})\\ +\omega(a_{1}\times a_{2}) & \omega(a_{2}\times a_{2}) & \omega(a_{3}\times a_{2})\\ +\omega(a_{1}\times a_{3}) & \omega(a_{2}\times a_{3}) & \omega(a_{3}\times a_{3}) +\end{array}\right]\nonumber \\ + & = & \left[\begin{array}{ccc} +0 & -\omega a_{3} & \omega a_{2}\\ +\omega a_{3} & 0 & -\omega a_{1}\\ +-\omega a_{2} & \omega a_{1} & 0 +\end{array}\right]\nonumber \\ + & = & \Skew{R\omega}\label{proof1} +\end{eqnarray} + +\end_inset + +where +\begin_inset Formula $a_{1}$ +\end_inset + +, +\begin_inset Formula $a_{2}$ +\end_inset + +, and +\begin_inset Formula $a_{3}$ +\end_inset + + are the +\emph on +rows +\emph default + of +\begin_inset Formula $R$ +\end_inset + +. + Above we made use of the orthogonality of rotation matrices and the triple + product rule: +\begin_inset Formula +\[ +a(b\times c)=b(c\times a)=c(a\times b) +\] + +\end_inset + +Similarly, without proof +\begin_inset CommandInset citation +LatexCommand cite +after "Lemma 2.3" +key "Murray94book" + +\end_inset + +: +\begin_inset Formula +\[ +R(a\times b)=Ra\times Rb +\] + +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix: Alternative Generators for +\begin_inset Formula $\slthree$ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset CommandInset citation +LatexCommand cite +key "Mei06iros" + +\end_inset + + uses the following generators for +\begin_inset Formula $\slthree$ +\end_inset + +: +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula +\[ +G^{1}=\left[\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{2}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{3}=\left[\begin{array}{ccc} +0 & 1 & 0\\ +0 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{4}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{5}=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 0 +\end{array}\right]\mbox{ }G^{6}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & -1 & 0\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +G^{7}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right]\mbox{ }G^{8}=\left[\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 0\\ +0 & 1 & 0 +\end{array}\right] +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +We choose to use a different linear combination as the basis. +\end_layout + +\begin_layout Standard +\begin_inset CommandInset bibtex +LatexCommand bibtex +bibfiles "../../../papers/refs" +options "plain" + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/LieGroups.pdf b/doc/LieGroups.pdf new file mode 100644 index 0000000000000000000000000000000000000000..f271f35c0ebd6e0ff3c3a1e9f6d207ba15dcb5ef GIT binary patch literal 319029 zcmb5U1yo$kvNjyt0tB}ZEP>!Y1cJK+cMmZ5;I2V~yEC}E4DN1$!EFcI9nHC^4+-PN{x*YoUprz9@P%+A7z{;q%f*Y?li^PI{4L3A!kHcC5VD|CK- zO4d)Nw&uhs)HJbJ`rl z>D<($97ig1H~MULDyxp=z>D3MQT9PO30s?jGMsTrE>0&NGJjipOU1kWGmEYpE+pJX zE3|*?;{0dU@lNqW$b+iE`tL?U51!D6n(;4VZnq0fEhXO?2{6A{XG^Fj%x==U%0`Y%3<6o;D&?uE9$HjL`NS7N(w z7C&6IJt#IgTU5%H>hy#xnNMx>HBRVKomCG%V7k4ThUpsm{&I7d|!p{lFv1_(^5VP_xsW#{{T{{)6qq#O#-n# z)YK#pzifK6L`eIwPxLt9zI5o;HFO;>_%O6%~`I@DPL6B4ui2O#3)>RS&RPo zfb)%DmMbc*+~W#gbXwo;JJ?`lodCAFb3+1epTZ&`* zvEjiVsrYl|uIBbSy!{qPG!GdeVcjidC1AKw4f2Qd2DnPYo8$zA1a2*Atwwu0P>bl zdg81S{O%aZ_-s7>{%fmv;!7g0(jsr=S0#%BO9UOfPgF`WhrlrG^2Vq)n9eUXr0{i` zP@THp%!NU|+7bum1)0~@)uOYPSveNALgM;9S%uy<37)>b{!WChINzwKR5`alxD8(% zco_|qJ_}<0?Hl-6*zDBEN9#o47+j(C#WQWs$B9cr94>4_;Tr`IW#1*%Z%0^8h{2zq zTId~R*H;Z5)9=IdzqOT-rej7F0f>+7z9PQk{dLB5-z~;fnR*1g(BI<~1~KUaOx5YT zX>eOc?k1JjsOtR*t7W6-D(I!E!{#R?1N5dEOeO5g5cQ<5>}Fozjzer^0xn-DlXf+X znIY9|K-RAGOM~o-tueE_)>N3N7bKo|b?qi5=yHf_DMDM1bmTiMcJ{58d_Su}va-i# zRmb%oSb93}^YEEPbK@SDf0GDsWco;zpycq7;|`S^7Pm`P8qP~I2Y>Xbx=lRhx}&@s zf#WUXf}?-g|E2zg<1)WZV}6_IYelc@HlgFDYb@V@@?kWdkWGzzIsRM)9aq&Wd=TA5 z4}fF*SAs|U-g>AQw=M*rHIRN%UHMh?-z>SBnOisG8_O=_^4JDKidEpLJFlj{<9i_Bh{-c~?lAnIbHz7c+?#-r&y z?8#N1$5bRH6*}n6*B7V0f}2r0h=dy$c3@t{876Y^ppayoTK=RX9Ot7B=oSO$%~|Z| zFFP4DNqes)%DLxIFKO^w;Lm%q$i%sMLLFJKZha2@w3bUrk)m;GOxdH^PC!iwg{$q%{vCWK9B@a zg>cE6q&Ef=TR&&aHJs7f*2OYDD=c2`h8Vo+v7OCTjxfmaB~3O4FzKj$yts>)Wu@}7 zXuEN~Ab^nF5tX7uGe;fS>Im$wVB>%Pk>o zeftq9AJ2A-$gU!u%|Dk{Pl&U8`y<&adF5Im2CwWXCSyjuR?>Dk>tg|GSWR>D8wG7; zJo8=w)rsXVaT}cyk19}?6PJ{Lw=#>XQ{3+ovx z00xZj8%f=HpJzZ9QS}w;$ND&p*v+8@Om0t5;q>zG6oT|}s*#X6o0`mE%DvQMi#H^jK%OY3)~>*09KlW=>D#MH+MFn!h`YM*sE{04e+gGf@#OV~@(lyC7JLpD>~ob>Pto zOqJE=)QGCXMv%v8@wj>Y_aZ}S2%=KCSf@Ai!Nm@lwos!9+7E~fPrS^(BF|uQchpbQfv;0Im zpoh@KXGtbTt%W^X+~4cotMxBwA!$1|Kga zN6-vUqWJ95cb>w7VwRwwL?SLCBpP}~tLAa{E(0fvtwbN;d;XGlTp?A23vhW@Nw#yN z$e3SkkH=ScDt8FEV|tBMm8G$djxp24ES0CAGZhQV6Y=^^f&ACJVZhq*#e?-$Rj9rL zR9J6kXF2G~3CjE{ngdYqN>RC2yAd0W~roVfr1T*nRWzE{-{g z2Es@7#m@yVMOX9-ko6K`<39?BOf{r#X;)r_cnOg9kr@<;FFTo~*pq4bVxi-;K@pOWyR5v3 zbsvmz0%ZHffJ=8IGaNV zhs4r7HSMLlP4KTTAlkkZs*a&4rJeiU7~sRMJ!0d}QH0l)K9u#+Z;!e0r|5xI+>(~a zU|y7f8ax|0*Y~mJ!*9~r$Uew5SLuX#iOIP~_@NB$+TZIs-RlNezqCxw{IUJ1!{Ccg z3H4Ea$yR7K%E4shgctz>AD1j1oggFASwy_pl40(5uB2t&vxqUdSgvjqy7=o_hNMO( znQyp4*wa*Jr4{6l99Gmr%){nKc6+~bqjhF%93h26MX$(ctVHPG>jdgaA6FP&vp1Ki z(X$z-WNO#Dq3N>d&SDt5OT3E?Q{pjv1V`I<3guMRKd+1oGzdqX7F zAi2<&J2{(OnGM@Q(h{GJTy{B*&AJ}NddIFXsdgA$!3%x7Q1%p%og$XFTaBw1=dy)ScJ>q&?iusdv+~v{n+Ccrzg37agNh5O zPFzF9p}IequR9A)HZgu7(i63m4nqq%ILj09W2eBjA+v`#+#n8#H` zU#`hE2Mgy`AaKIxSW6=j$H8cJq3>iqHt2pj+B$F~j#aR}x0*aVy9sPdq^bBQG2$8{@3{jQoEt8-n6e7$-Q$xDI>ls0PBChs$f^Lm zXEjN#(%Nr?vvG$jz#*H;%d{gVr5oJy9gHQ#UT(PQKt|jMi&TJ1>uv7E_Vw$jyP_=Y zb3O{P877@}Tu=~ZZV=dWB77eeMu%0VJhe&IDriAS=`e`~p`^JC^z*K8!s1IPJ97^% zTfP~M!kE@nqom^)p@PZm;UwJ_6D9Vj_D^j|NOi@dhG8I$3c=+WqVDT*A644TT@)}c zys`7v#y}R5>CVhF2-lus98qVUZpG;VBEyXrPZ@!!6?BOjyhcD3pse9kJjBdPEk_4q63TuClf zSd|{Wp%xk*73K;XQe0zw6zp6+kyoUxQ-Us@4ev#=`Ncl56afiMjb}q8o|q zW5K6WA^vxo1n8!=z`ybLv-AhH|H0~iQchlOo|7j8Or0nJ|0oc%vvq#fJ5m0j1fKD~yeZJqNYu`qQkU(y0Km>c$-~Q` zkN!*n{B7q?yFd2+PzOqmb|$K(&Xl^(qPQd_tD331Go}7BdGOpR<(~>_oGfgVy#MG~ zjpJGV@VCtMEVKWy@N7~Iz`~Bs{`UaY*q=2#e=E5E)MEcDBPjTXhWL97?EhSVf8j6K z|DMqQPGF2yEjN;^{-oF9VRoMUies0jMhT{7j?H@?d+|cQUq6!0#4Fy3e>|f$v)!z1 z!o+#ygiazZ{=Kp*q=qSC>&xR4*)H7`=6x8NO$(0vXgy>(y~hz z2!%5Pouc54Z=nZobXPD|*?Nu*Atzdo3+Lr-3p3>Rdg)*1HWb}e;1$;l4D@W*FE_WN z{parpN9ceIq)%$KwejHPktbzb=w6?U|0cxO>;;8wFpuw$BoU_q!El>&=QB3ZO zR6YIjIO<=RJaGAeQ?~Ad9hr5?Zt;6p9F9a#4dW8VEf}z0Woc;9^G@4<9~L=_fC5lg z6p>69d2oUv$PEsVK%%yg6;cU)V-1i6@z{g|HK~Y|7ttpI+A&YlPnR9pEe?6U1N#;# zBvVf{IIk}#Z6N6rWQa;|CJMT$xt-;mEXN(HzDS$%jm%xFZQ7r14Cv z)*LFbsbd!VP6^sCf%B0+HzhQ*5g~uNP^p<5kRQxHEso5p>ebh_y|JbX9xkc2AH> zrsSZQ6SoEDsO~3@c~DxFp{x(HEd7dzIn_{V0C{;6O%z8BbG2P@9W%<9imm7B&1=&w z{uff}DWU~dXO*ZbYdQSI4&UwHEpTT^f|<4n4VIA8p3$itpg zCmiF1F@O0Nsi7H4>wXKe;P&Io2IHQk*cgWu#3g}UZ6TAiIwa9{t&eT5&FjTQ%`)aC zJL^;?^2m~YmZeo;`8J}ga8;}<{-Dn~FPxPt`i!cZ$L`P zJWqHDNuHALn+MNNVU>Dy2BtvrQmpF5NfV!bc+YCb>Zscl2el%wG_|#JRXYGxeK-X^ zTC-}ia!ZG|;%EvftV#O)oC{THbf#efzG)x(`BCNRfrZa9*&$-)i~^T0ER-pZeu7N= zx_TmXXAeFn4L57@1zNR1M(M}(r^}nu<1_kwgJDAQAi6bC)J)=QDpIbLaznH7rAx!* zdxx3tm);Lk4S7nM^Tk6%boeJvuhw)OvPY|X<<>HD4DfOG?@8QcJAFL8KHSZttYZ6M z@s}D4Ni+?=CV%pR^EetzePlxaU`@8fKuIDSTjIrs zn~H3jVvyg1!h@jV^3=|Lf(>)HnYMIF`Rfq#Ir17jq^t% zQ4)3Q1ecqfA0#Oheku67)JLPK&>6Fa_=NceHO{WPntRRXe_Owz`8m3WLbFLe!t8eS zX?wgz1Ko@M$))|P6hQ(m{LB8Yck#HJa&PB` zF)){Uk*ss65p|9C8UqSS@;yfc&inO7cuGOr0?GwlBkq9<^@2|9I@!!0r?fGC&S9`nF2DA0x{raW++cz znOBG{p&wMGfJgHO53LI3&2?Gi&eK>si!v%=ZCf_e5Qn)3F)W2JaBqYO>I{#NYA8rX z_+Qdes$8<{JHlPla1iz*%Ow@}zmkNtd=-;&7}jyMqY_B5_~%mpT&U$kxGf;^X|hk zK;}dT&|0W%Tr``$ny2$U04g10Fs8=j91jJBkRXw9P}bw7-T)8n<0QH6#T#`ohIvn+|9+T=Vo+?QJsbTZ71P;&>q&5+;0+d5Yo=mjomw_Uy#Cd9>D`t& zxMYKZ<>$`GROV?^@W;=0Q!3>o zSO^z7_@lO{O;oa$lg4zKGWcX9@0SP^>^@@yS0G?Rk2_+SX<_{|m_l4^KMUY3z0%@~ zJ9u6iKkWDncz2Q7_!rKtc*AJ)hFmk4jv2-%!~xFyyl{gItt09xOyOAmsW~_*8AD$O z68zO0IS($vZy$0SJ+x@_^wyegNU=zhn2(M;I` z1Y2mT3hCqJQ=5l?X?4X%S6wmY;7=yUNq&q+u(2qdyxtl^8R0b>PJJjg|M)BOwg7!O z8UEL0C)vi`-ggnKz0%uE^x(qY0$YC$k$f>lAVOOvu>*?n#-=jiM?}~+KUOD^B7`$_ zkpn7;bo9?uGGPU-4ZOU>+*}(tgKfZ9qQM&puXdc$3l7DJB`{HlX3Pxu{M^utH|~%I zo0*o4#*%d=U3zTz?GuZt*>@QmCb(@axsp}hcKKGNS7Q)MC0KvBZ(fy~%{)<41uf_N zjwZ{jyX`r+hLmGfxC;3<>|8bHqr0tZSC&!e#C6y@88XPlns<;2>kEwi z@qR?*ydAM(>rA(?DEwC9gv*|k^^tc|c<1ON<26rs%|q{ARE!sVn%j!TCU`Mi`iobQ zE9dpw+LJO=nI9I4(1k#(7Yhxb4RU2JuC<~dp%ofBHhbd>*IcJ?<;!WT2E6osx42u?RG)So{sMt zB&W2{`}irpnY^KiYvnT-M8wQ5-_v*kl8egJGtI_L&Uxtk*@W8^E3gE72cXAwWWgxO zDUalYezj)Y9yM)t?G4VVj)A9dX@A?Snu;qPMe{D&Si0IC*tUu5G_a~d9siA8o$WEP z|GI2X>eUnbzOcO1!;NJ`Q^>Vj5@$qBfNzje4Y%b>yL~$8;a}XxcY{4Ye-!;@{6R#Z z-+U8wogPDkkY^JRu zK%)>u`|V64YQK508vkZ*6|fRzwFdmHg}gJyyuM`y7Qys}ap;zMDX@8e+9;WTKXF$)YrD$wrYVr@NK*olh zlKmg_z<{Ka$pvlmuX7h~tYO8%N7C99?-@Hw!7lYQ^CJS=W@bXGAtke#Edy^)D2CCA^ifvBaklai^Un4OKio$VjOg#CYyg*fbh#=MnD zUfkt{?ODKAj?Y&T?U9p(g$R@(kvF1zC#LX2$wYiaI~;g|oAFXXcpWWa3;&6nQ1yp= zkn~pE!dw`U2u|4BB6niYzO1mZMBaM>?05zpd5iX@j^4|xv@dNfZ9Z)tK_q1y%SW5A zy6bau!{c>je0D@De=entJRJ!fSdbTiI3P~GnGjX8Zja}W5SlK5A&!xefV9WUy)(9i z3k$;Fy3AX;Hn8GtlBEXQhaLB-A8l|)fOPUFFqtuTg@u3-44H2*huf2tz@MpLSi&=^@I-o80FLwT(RCw z3bhu%d<(X~!!pp*XC+OhGBY@JfYr2#EgptAfOg(V7XWdvHpJVHiwe73PL2XCFD;0B z0!@qsnoMcPny$Fx-oR3|CTw8CgOxt=1ycX-O{{Cq?kd7$zRw$I1VWdEaRhjf2bymT+6y;PB_5Fdj7m?>HtNrZ8+xMjc)l_afA z35nyFp-%Gz5l*cyGtNB zlEK6Q>pGNrP}jfrW8DBgP9BI?h15I8gsIukXm;|Q&T8n5VPj>{BItMp6ivwiMAlIX zghUXoFzd8AZ_|Pb7}1zFS-67x?}#rfjs2}dS1LtDMrR#55Vmj6!$G~Kum54>Gt{EH zRln8h`M78bmw+}Rw8N<(VZQlR{(C&@cTo(ZPGgD_waVtxMZ>guvHvlOyMGSn|1RX2 zO~L<9zjf`;L|L-R`P0vHZB7w=-jE<`e|zo--~U~Z`)eovI>!IilKuM_pBFJ=feC_k zjT;JjKKRV9s?6H#)!W>m&ly&KF1{Ce}hyUX^`m^EK=L-_GZ}3 z1KEUB9AJ{HE$G|Sj;UI!8D*m|kfu=%wKh&3 z6~CWP9AMlQ^r{U*B&;NG5gmqJR{}uhkDF#!nPeY<6=_K7yOQHJgWw1sk)_d zsyxOa2t5K)p+gC&wNfbWr6w!isb^sNPniaWBbA_zU(=Jrl0##xF6i_rF#42Gr0|VQ zA{udk!B~a53^3mmz#2?V#%eZS_7*b50ZtK(iz4E*R>y@|q(S9!hX*6l8W?06WNSrP zFCwmFk3DzK61BU#naHeZxs-a-vEa}-*hc03puCJpDv$H89`kAoB9T}_g=aZ!nBgd_McCS%u9SsF5WPUd)eh<5*>O44zGB*4*Chg!2$ zys%b*9^>%8(gEv&=C%(aL0gCQ;#I?DXyv1Gr6W6Dy!-4a;YhxRrmL6Z?-cKi-$o38 zR0(f#Q<{Hf4$asd)SrfO zU!5swT_`!j>rMQJ2cyaLrNcmaT6583ndI!s;eU)_MOw)KfhHrdSp5Z9K*=~)rW#eE z1l3E9+MusUDwiB|Wd^j#lQqI+%Cv-MCjOb(R>sVv&+Ew*xl<|)+#H!Cohu+UHO3Ko zE_+ziE>3>lVJqKn;sD>n3RO8^z6rOGDK(jp>wM`u$W*OP*BHeej>dQ?0euR~RumqB zH~=tqH~%%(KXTaYbNpv&YVc>Jm-t~IWLh*@>VGWHKNQoSxx&IPm|wvzm~qEFfOuFD zowRZCYt-u*Qh@cEJ!{Mg@`lQ3|mN&3Ss*K74WT7l>J3j`uM zlfn=Y^NVGHGn~@G#c}e&Y@TKRs`!>xJK_b^z1&Z$t^EyugtVVU0)A3tWwy{hFPn&r zY7v2tfAv52@LzWA9!#~^MEo0eF-!|Nv+}oR#JhnuL!9~PiHN2zFzC=uo?SIjE0_%7bk>-d&(Fs4r*MK zQk5#Z8%g4$O9?r%ak#ysCiBp}9Vda^G&Xzt#6`7NdhbSpymj?DJBKA#H9DOn0iDb& zhHD3~_ISIWOOBF&bzEHmu)Vx>h4!<{Ao@?2;WdmHJelS^M&N$zPUa zwy?t|#3C2PeC4y_`i7{n^>&tyV6cke*UQB%(U;EZ#6jP(daxryVW|FS@~>!Cw1pq? zH{;|j&oV!b{*+a4!N}5W(Ras`?Ng<AV+WqUBG9sq9nrLRqn@34fbTJ#15^wkS8d1xT3q>@wH#-b2V1$t0jVJChYsYBK%N z7FHryYoe1Rq?OW3aci1fk8rAh57QnwZ5qcWPs4w~!3Mbu9Yl9 z>#jIkr;*is>r^faXAKy^ITQ*hkO%J~L#TNeFCpZGe#xrVQ9Ba6aoxr>^3e`vWgHD9 zfR%ez=qEK%53Md;uis)b=V##Ncwd`B>+eq+q9@QH8}Vs ztFjG49G#i=AbcE@!!@Ne=^HTIgRoY(Rl3q#t2D5QN(zu%l`uRQPqjcrdnezVK@EQP z4l#ntwJ-inIQ2a@X>N3?)IJ4icnWDJf48MJIR()=3x&Mpm?<%Yi+e5WL2Rn{6d&Y6l$7jJCKEPZCx z{H#2@Wqf?kOLPu#&sEo=BmpG6HCCE;g2INh`JD`92e(*Q(e%H=Ld0|i1{M90N+`!I z@gclQ$L#kKMb-*nbJY(G^q(Z>Ie|+=51QjNV3~-*giXAe%qHIYY-4{ESQU?3$H_T`H_hkq9oee(l zfcEjBP4>&b^GE=1yjJ&T$24KyFaVQ9h>Bl;;{C_aFa3n4w&bVak5%7hRQH9Ap~i;+ zpyT5=`H#g+HHcuZs>zkdqeL@y8xg?u^}^JXDxp?@d`q9lZ<*zT4AJM1<)Y=%mfvq} zVL^jM%U@ZZMx=l$4H1e3oy@0d8K~9g+1}}QRo?oS%4-Jz(9<2pNz%P-g|^Qs^js~m z$u7L>Y2ItwtnrurQk#dL{5P`Og|%dq2d<|hUB4?Dz3jeoMfz%!d**eNv+6~7wbw^1 zjYbLHWV@3It_FVc$&OL+s(N0?qeY=!0HazD7OO7$Dq8in8}Wnh@HPP5wWR8DK_QTi zVSv@59)TBx#l&NN9uHiU4giZ~l*q5!Mgo#XxhhGGg~y#bI$IbZA4pOmOqsIv$r?5@ ze%)q1PDpDhjT(Kt=y?XDNj#YgCLP$A3U%@wYF*Q^B}5(Nx&S4T8hQ~pu#cXP!r~e> z_@K5Ji|j}IfP#$&0GeQNx~#g-bQ(t|Z_bmu6-=uvbYz?L0}-$tkB4I;r{G(!rOiAW z(l{q{onn7MuO z&o4mH0yB!~J(G&umb9|;h!EN}dlA7JbVdZD^|9H{YS=5MfRy+?eQ_P%o z!xHt;-f>1c7VS13F1o?_efp|PQ%l?UR0f4Tn!2%makKgNVnX)7i0}mUrKJu9ub>|q z$#=xPy08R)`k%h-r9ob5mZX`G&nLlL$T2rNTwOVhJztf zYCmp(=i9|-Wyu@a#5>HwyLF4-9PT)bu+fVe5wqG}A5{AnPb9F0bsfwb;$1EVO(fg| z@-XaNjqKE6Pv4clVc;{cGROuA-Z7XeE*q3ps((L9fDWw{g{Z0bV2qz6Kv4{5B0TOq z%-7R@jhKP)Po2$QLI_Vs%)Y4O_ey;pd zfmEUgU~C}<->m3b>Ux^zJ8mkr66~f;eFPsY*p1I*Xy|Td%j@}kgTEN3?fj%q2px7q zU*Wgz+kuCx6fBIYSCXt>2gF4}7ym1X@n_xC$M+(mj!iJ_ zwhl@h)j{x{ugX-IhZVzhZq4xM5L6ZdaL6Qz8rJ%Y^R{8q+guZBb(W7@SuL~YNx}kv z%D?JpXd2Ze#DB;t)maO=P`hYu94%HtA_x^VP@exPzZ^~oE2faT$HCj(7f=7BvQkWN zN;Zhmt|=oq6#Gjl<{OtU0z&l0(r|uyk6Ob^vSwCt*q8yrF^r3w%a`+EAXHm|l}*fq zmnUjMS2+EQRBw4qt>_V6GOYS6}D9p1rh$}{(<=VThDJ$_j)f*MT(bPCg*f`{K! z#(+EzXQ;L&@g1zca?kRE93-szIKxb=IH9uWYG+bHvLamQqtUEM#2skkpw9YXVP$3@ ztIo(O=)4a{pq$C+u2s`!>7$#+(lt23TUx%SI|33`J|Uyx%rR%X(QUWkvoC|d`i=G} zeD*E)@3Qd974-2>ItR4^VgM_Iaj%%xuS#8=2d+;1@k1?P?HW(!kO9nYHxis4p!%JNGkx2%K9?dR%b5g1Jo42yS_1k8qQP)S1D)5Gi=Wr^ za)v{t2sG3QE=ww#6(bPFi37G_{R9f#px#B5QNzeIi`ttP544dX$nf48EH3~~2;XQXuwe~Y5s6r`LS)wjq-KjR19bg11 zz5RUdhwPo)K%E3FNmdLMAx3lDMSk5-=Hhg}$7h)97*U6#Z4oI?tZOB>$W|`>I{=M< zWJ-DYJ($wB>2y`O9L2csOHvqCcxwc)X#$R0lC0dS^zKDc++7*!0f{MIzsXbzl$NaH z6>f~?u$KDjT|GMz@|p9iO%~$}sDE?0x`yL3=cb0LYsETH#!M_HFfVY-GccG>N~13E zho<`>C<5f{-4T|=MV@LCi7X8Dl5;!^%e@kZ%BJtlz%Mo`Kf0vDc1X>0264BLfOy(? z+2N>{&GrDiE5j$5k`Jq>tlFV^zJ%nk$Xe~E?M$N8;-~NsiykCLAg84eoxw01bhk!TNnbMV5B6R5#xWUTxV z(IDDIriXfYAZJgJ)|DlA*eo0hiE)zzsDd~+k`A83;c|>7x6 zIw{Oxd3y_rgO)@A7eDB)iv#jOz`Ocwz*_1=+bU0iCh$L}hs&8^i{ggG@{ zCvo#>X4>p070J{YICI%&VkN#}lAij%~GtZ^2J~n-TIS@fH^bhoL$pw~4Z7alpD+ zySi*TvJo;&26G5#8pt>A6)%zP{Bvgi(({#wRItkkMDWWjm6qW%{ z*|^|1l8lf5(Y<(t*{#EdKKTC(i%}YiK(N01=9}r@SNb^Bp0&lORtjh~7f) zH-msOus*;KxT^sY`x3~n&(C(E)Hb&`m2WGGcnk0AO&dQxlSnKd zSMej34LQweRs=`Nm-E+#>u>}_-oxHJg5shwj*_)}((AO(-1C3%$W_>n!G`tSezlZ% zYs_T)a`LBkYAFOvM~|AF@6u?HNM4^*V>&Iypd~|NuD`^{3QEB5PjhRz{(ZP{gB}($*?mjwY^Dh#X8GO=5QXDUx`EfcNvE&M|Os~bu zYxadEvzH!s<3??y%p)R6lxSSWr$%C97kw-Ee;SJjTXOZ{3zvEYmww3 zrmJA>b>9o)Z-8=qsW=^OJr-+a1|X#^3_D>RRCj)glXqaQ1V`<{LY-|oIaCY@2!c7l z9rdz9`C)yTv)ak2p%U=s%V)j@L52+c;IG#x~=X1jHwkjutH!6F^3j#eke<&Li$F0Lb;i zo0E6ysl$Zs*;lrrE*LTgpkGmX4Q{MkzvQ>kGoXnFgwwMy{P^?gsNh}GKHW9x&fXDt z5-qPzHA0#uA}2^Mt@`}93*13#fMh2!Sk5e z*r&%C50(t*OudVEsY=4;A(6P6>#J+FP)mva7U5B1m5>RJmgp`8QwRaJY6~C8Kz{oo zS+ZlUfRpGw7B=o3Ip{))9B@!ah{l~%r?ic$^`k?9KI%;J7-QxNRspl~JssG2%lU)f zOie1=mPBUlyNevJK)ynuThPxN`QP`}^6e@Q>2&{2uUoDH?)@I5y`zpkBxp!#R z@X^zk^UD`zx#DB}QH5(7vP;HwuC^iXPuze5F`y#Qvh2sgO1uvlukEog$)=f$9OqG$>9@I9T^KrO z9-?|fS5&RnaArSxR8f#;bbVQ2T;l5h0Tj_eI+A^Tk=@y~e?Heq3a1 z9!xFSt6XUHQGBn_S$hBNL5YRn(tb;=9bHz!9 zvYf1Hsp6uB9dRAZHlcgizJLhHn_jM@NwJJ~cTtNhDzzq?-X^pBHXmfdK<4p}f-Y@i z7iVqzTeoU_*#jC_VqGM<>s%lXhV!pUaXX9V=T-%@`xXqDGavG)zz*XR}ewc8{+NEBo&f6!o_K>4c z`hxzDoH}<&F<`yG(=a=f*C3@dB>P4j5dRg|%-YAOb;XSvbgT#AEfg)(lT=CRZG(Ja z>^yEuqaD}zo@oP6bcws~{Q=itCaXO9^K}L<*|cTFoebxXP+0f4zu*&0Fsh6Zq}6K@ zRpjKK=ZWB}QQyU^F2v%eP&eXo#6BviS>xNnU0eD_=p$$lW}z6od&lL2XPu&l2UhJ( zPkXn3GR@U|JeayB4u~?vkN&hfDN$RjwIbNETI}A9P>N*_??VAo+flmXG7r?XDt_D2 zX;o{P%;kOoc#f%1F$I_hvP#`z%f#F2PVjMq!pUo<-T>+`G@y0AWsV|VC)|8@W|H80 zYJA^#%Hc0CmRvq*9H_iRJI|s;Z~Qx9iHMhW3LY#F%vv$Cp;QYal=$i358v8)GH8_@ z5d+#`;!5y+i;_`JUe-dAQ4i~Od-lUf@WKY5<`=Tv zi(C1rC2QVz`Kk1t(mB_4kP5eTn4?&A65WTLy4Wu+D_N=JGtfhfw-Tb-8I65WvRn$! zE_4Bscf71QITW>n@FfQ~*zheg;CA5@zIP|Or{twW04IQXsLDF|UY<*5*Uk5HAe3M% zJ)zz>q0nn-k*n*gxsc%jAU`gj(WoF}FRkVOqv@-oqWZqKRZ76Yk2DOSAe|DI1_ebx z29)k*2!{^Ip#&8{q+>|wW*E8=qz4cLX6PKcyI;P)wcbC^xqF{`?!I@Od-mSXv(KRw z-l=oV=iTCkPa=IJc>tvvDBt#^D;1Y61z^fnV; zL@Eo>S?+tIT3n5Shc{47tBGMG()n|H{vRmb&5^vGDvQv|)+};+!#;};^fP6%UxZWl zdD~?BsS`4+#b@sco5kupQOSsojH$;@USJFnoHvT+G8?j767N=j%0w+4$w7=Cp(tUg z3Hp&O8pW2nrWbzg1%~6vx*2cr08yFGe=pvzB?yG187RJki(8^{W9T1M+R-p5r9@V= z6FT~^3*P74^a&msGMDI6_yJQ&*IMqg?Tw;F=*GNRt~4eCpDh0S?2MXjcNnhPS#V~M zjLv39h(+dZR~BA36uvz8s&Z%k?Zbb;|2e0CrW0^6JNwkH65?Ei^^($iP7IuEO8#_( zr9?jR2do?EKkWR_!bb3>KPIloQiXI8j{h=R> zdydfw3+sbrv5A%CM~d`bp4s$QsH38u)_={a#>n25%tgl5~h+e;ZXW12QrxG)tUF*9SpMt)LibfMtOD5NRt0uJ=qcBI202!m-*bAO7IO2#28DYm1 z)XU{eZ5+RT1iXLpZ?GS~nw6KaJOr)#Ps1%ryd`jHUV5I%`rwo2(kHTG0gbn?1F(O* z1`LttT-g&gj}D^jP5{8P!AGF|uE-}szsfZ>6xo8b5U@6d`46HZtE4&HkMH`q!+AOgLVKJQA{OhEQDlNp)lx^@W)_WbXJa0a&V zk{PMw>pyw;4tOyYoDnzIg0+aJd$B&sfUIv80d`5Y{t4|N4hVo$h{2j1S?TRdPFtZT z^I2w+(bCCrYI&2YRjXo|V+r%*`J8?JnQyfyBQpbzHxoM>-r|+~Ub9_P4fbrOtM6Ez zo@Ai6VsMz9^+H>Pjxc0p%71cG-Sx4v~CbG{;fTonv% z4U#=w#8A?4shP6HfkalK=vl#pTu*^a95=>~v<5{zA8Jeo*;7_~1dF%qQk+|=BUxJW*#exLkE~dn}zRSn5HO`sgWG3^sqPRBUGH#(z)PHl_XGFdVrc zy#C)cA&%p&w_2S?t*(HFS!=0Wv%`Cmv`b|*inaAV@cJzyuYw0DcVho`WsrohyX94V zdklo03DGp$@V+Kd7cjLi5Yxs#8Qjz1z;9{l(49jD5oO1PfLrg2_BpUwhc;E7>nJoA zvedCCbK>R=n}aI39u^f)6sSEb6{;r%eDiLDxbRKID9<6>`K7|Gf3M1@Z6PZnwLkkM z!By-T3Wrj7XQUFrvV8HQGw7B;qZ!tETd5o4%gz&|2XLCXK$>T5HvyU*q%*pestdtLLM|e=iVyEL!T>b>WMA><^efTfI%QvXrGgaLV*dj|$m{ZPvD@>vEIzih7iPW=! zjaS%MB0x3uR(NrOfkS%&xINA4)tP2bJ{8z$oQS0vp&# zVYi)lla~nnd^l*9YvR!bn>J4snovw!VkbpI)Lc^=bl7O2$&+73sV(qJ|2Ke0%p}@H zZ{WVHiPfgyf-SUK3oMkUV0-d&LX3Te_^(dvN||-FswTWE3L9B(rUNTMdO-$XP4{0X)jfCpzkjaNmT^oc&hVScBZ$8p>YMWc2(iD;oU-TRYt?Y-*v@EcKEb-KX;|q@HHKa0h_F*M)?FZ0ixBGx; zi$biR${V%*a{nLtcI>ke=ojY{NWWM|YJ+7iy`527@OZupP*DgpF_#XDpkzTNtUi1t z138FX`EUFze5ZD690Z5pmPLGk&`@_w^BD=~HY<$=Q&H|vyM%FRKB3PUcsqQ~o8YPk z?Eo_L-*#f}6|=s0uZ?wTfX$~7eJk(`$<6QH$DQ$x7>nJ}SJ5`m_g1mj#8+dj-w6yj zQR}v3lduIU^Nu!YUs^sYgX1s!E}P*prJsjDnPAls{_;H(87*6J) zus#NCShqAM+Hq0{mkEHfY_#Lrval=9UmBQ*9Wi}FG7gZ+f^Ptg1y&@&cFj;*Wc958Az98 z(LGLQZ#1l|%wqW%Un{?*rHn5Nv8fse3)D)IQ3!nEWom{0Lp2x#1b>@M-{7%+uZ7fT zTml(R?%gn!T-YAj(trH=1iaJs3qiSA7hstPLdbS((TxLU+Fm@+KHies)lm3{ElqD) zwO^2M8r@pR8deNMCN|*_q2sd zClf`EFHgYZ^}*t@5_bJ)rAyWAq#|qGf$O69x%=Sp=A|CDp}Ex7vtiwy*2{a(PscF@{2ljJ4(d4{BVV&@0G zqO%tWKA$Oc5$2)wvLE4#n99?Z1qvWQN34d~zG8kjyUx4=19)|n!2CO_5Mfq$`~&bF zqRQdFG|OL_1-zp$94N<#8$9c{HnXSO0_kWgB6$G*MCUd4r!vb{E~yrnC=Gt)tFOFk zwBjBNal-d0WJxHp0{T9F;@=~5Ul7(=oADtW)`+!@Ukt?%l1r5krW@!vT^^RHafV|B zI!1M%wO@3w(o5mN4oQvCV{DF)-#A?tT9Wn z(lTBD$RlpNyHvGg=!u;9sDF(VD4g_n*|%(T))H$m3^S49y)>@@gJsVV{xYRZ)U&1? zAnVQ14Aa9Q+z^{_$Wf701vz;zh%KKFlZA@oygwLxn%4%b&d13?a?viA`9 z>1ka`3n#G4#>TW52d?p`(n@nv7Xt48b`nn!8z+&rzk3A#b$!Ol-h|1^KU3_9Q<$SZh~ZbGPG*2Ir!k<<;sms zIo?2Kv2XvI`0cFs)9MxdgftjRs%~n2bXX<}Ek4Z0pT5DnUVa;C-l#5JIPmgAPNG>N zC65!^@kbN@dceC4SJ=Az>c^RB8=>L-(sn*i+1@-T zM1#{I1A+_%%uK^3u<^m%!6odllpXgroJ&P`P{Y1!@NBu9N&@W1aDmhvJ1M~b%B2nW zFpd6@=8Q_(Hd?u&gRtz%v2GLfioZapVqM_VK7$}D!jL_*vQ_p*&jv3{35XM2DiROe zOv0xCY(Fw7dECp8U~&q_`!ggtP;vjm7cp%j$ficwV;HKP-z?*&)IZ;M6c%}{#NfUA zOp@u&ft$>L`H42mtzXz$P6C=YLNzB-zN5P=r@l2c2G!R*C{%66Cw&uro(_c%{{_q~1 zhv)TO_=@IQLgf$6rH2sg&JW967o?hLn`5!;e=j`(VuvM>=(&6WT{?DrzhNLqs%VCq z{W}F);Uz^gnZEcSen0_>5`*PGza`kD#mLxaLz5~BFWHTbbf4Y+N7ZEW7+>3E?;A`| zj=Z41{RRG=+KVqvfVzzKd&bzdM=lrP??QK`c=c>zpWukDKKVSh%QY4q{EB&*7X$jD zS}Z>(m+^Im+j%v_6b3ANHn55Yq5X=t#rEvEAHX{bw-$a9S%q-)5WcL!yPz|&TN5i$ z=d_g?Tff`ysv5>_HqRL00c*_Cdu3mlnK==k95kh8VitEfnf_hgw*bWP%}HpKk%5VO zF?yvqs+#-!zvKLAZ(o>e77s&FHaG3;BZ6s7g(kdY6fdA&sa&mV_8^ll;(wh6Lm;)@ z7dASW%=TjE{zpx%U58g3Vt;}vD6L|DKS?LUK83W=V^u&wI zUh~@hMP=4c8#$|xQ%8*!f&Z|9-!{wy9Yx`z4Mt{KbNTT{d^5|$a>bbER`X(l1`Ah@ zRx@DSx@|%EW{v70ItGsjVJUQN{ff`l(rS+NHQM}N_Nl!CydT&!Q>Q*bKxW**M1=kZ z9eLJUybhip=P%Vh`Tg!17fA|;02y~V-M!plbHhgxdT)e9UMOB<`_Sq>6D-uOog&lU-#t3puaai-${rZVs0H2Mz3RkfW95}BD zS%w7v3$X^Sjg34)CD|TbR6%jmt}A%cEd|_|*x+)vr@t&h0>fZ|?>39yRFThLjRIf` zZObWG`l0I{5#Q;UB+-v|K-2@kDQPGb4~%CSo=G1eR##MSEu_qPPTZoVNzmh55TgR9 zXTxYU=iJujv^TW55&o0VSo>nU;uH$JcHR^h34u+Mi0!-D9=W=RWES8l(N|>eNgq~( zN7f;`hLrvcgb}f1#BdROGb;D%5X;o3azcc21E*_Zr3=Jv&cGJ|+v>D?MCreGHHxVS z{@~hlt|K6W2HqFSqq)_HNHBEhzh@S1-B-|Ckg*In)!yI{6pp(68pvPjc=Fk4?mv7h zx4^T;5hs({gSIM=#i`d{^O|30R5$zNyq6$g&_d7*4}i!%%Y63*Qr^L>{boWQ5T7-> zCA8kGFo!WkNA6yxCt%G;`3PBo{N-AFcRLT1<>SPsvj46iy@b>SLB{734+XI@sUJlrn0XgFUH@ATLR}} zb3#BQqv4Dp1@T*qe%9R6`vV~`C6~Ie0#|*XGitKvq44W4WBU?fog3P72po-Z{x0Nk z7Wm>{$z60sKq5ci_pY#rd?3wphSnSgQ!CBnp|9xmi#zKH!P@qc_(JTAumnsa)L;Xv z4EY2ZEBzN>T8Wj8rj=E%S+%DJWARC@R`5nZ!v3!yInggeV{UZ_!2$5E@tr zCn3+*5R`G=qn!U-v)IXhRM007X5VJT{$73X(~tBoI02s{{Wl#-!v6#`>5_uRo2083 z4DfDee%(>W-8QD9_N>oWv$aSgHDJ=ZdL>hY#&eNqgtdZY;NcdgM8!q@;8lJvA5*#us{oL zgaRtN@2y}0krm$Uvn{U6udpOKrlKEVXDfyuIQ#^0CB^}?9DHH3-nKMCKbi;%X~MvqWX zJbj92B$Bp}$r+N}KBX+Krm9$~p?ieM+2ed0-mpjZZPEO#j2CJ&2tus_aN*V#JH96F zF}Iq$Zzk-^p1b-;GG;(J(>`ugLXG&OCvXHwh4?z}e#HX|7|W~Eba=Q~I*02~lKH?d#h=i8;}&?t(joUB=jG;7lra!e zJXk?|;db8&)jc@{Gh1pUcK8ykN1OR{-uI89JVC;boT;dqeq3*5@C9r*#_2tR3>^Go zvF$^x>*6uX$xi2-`OH7`dEY^0rBs>HVqQ%((r!Q5xBwH!_#dwc$_SM3)w7 zc-CJQ_oMnW$FH(*VC+V`NyZ`ay zH?Q_`LTKPJ+a#=z2cldhS_zSXDs1dRx-{FbsjHv+1Ai3iH?}H*b~Cg!%|+iB)Z1-h zwzG_Zn&X-_LJk;2-1sl<^=^+|pnJ8>Wz~)-cWH;0A|5bCrk{xR(jMW`lFYYLEQUez zvNjs*Q4&D}=WDglyObtazm^2gUk%T)AIU4svoR(XjnCDAWM`_`zCk~FkaWPde5Dt4&${K50^&Kfn0p$~};wgN(q2(N9y%jBd^r*iJ- zT1}6%KyaW8ZL+t;{=hXQ8QmQ{@v3kj=vfRv)}V1~Jbm+g3|tl6Z2< zJq)b?06%26R_)Q-R`rnbk>8_(I~YCt`5amVTyqYdQu2ZA?`P2OZ!qqUpBycfL^=-{hW^7zU>t z|MvzStgS(0eCxM8MMmh@OR$z&Sf~-OZRg*g*j(_THoC6TyQJk|0lSr}Ku}SyP>(}w zJwx^^C`v&yVj3IvEXZm%Pu;9~bT=!MERh;wmxg_w(+>A5Gw zPgz;|7mr#E80<27uxa??Kk7`f4#CB-$l<^$suenRj@z5v9Ghq zY*Ja~9$^_;(+f_Hiod;XRHnXW=kV0Vvtx(3>!#)ZFZ+P3DH(Ngk9+|o&;+U|uR2~6 z{K`RGFF)1(MnzQ(KDAXhx)!OGiB^Owypu`FJ=}nq)FY;P(fHo44z(ex;- zue1jINMgoFoj+Ws7h1`Y)FR)d0T~x77@T6L`6U4s(s?U)bJUAo?s~dSD*JGx>z_A=4Id(X{#bye)7Rx%RXMw-ghKl8$Sn+0)_E9r9u6|t7h+Oo*# zI~9x1KU|rodUGc^(j4~LzmFFOn>DfdOpHkNjUU^O$~ksCR(l|q6)Z0H;UIC;==wl7 zOF|jaK#bs^bW;UZJpU~FR2Du-mu^h)!o#=9*&a}fqC;$i5-W;g16(T()!eOTQ~nB3duyN4o5)Y(Hc^owrGqC@f8z~@ zusLI3@nT)c!G3J&GqB{`Ry4z|;$kGGqLA1f>-*o0&PvwtB@6Q?(bBrsuQ3r{II9eX z?ARvpOmGs`Wd5lq2=t=>qtd0K_057od!Rfc4NY+Ly;h}9UBfW+Y~lMWRl0pB?<=PB7TD0+N$z>vZ~Gj<`7}SbKxFJi>hCebz6s3T-Su$2e(W=0QRDqsYv7;@a+}8 z#zk-x8VMzDDcjrojxrQ6jlrA+r+x<*PLOGjy_RZ~`Tm1!ZL+}wuB)U?VoGvX@#*D* zTu@hs+RPn1;h>WVY3`Gi>;xjF)E0?)n(L=@=ht zBMMF`Pm>KRA#}S^dsF2G^*j*NpJoDUj0xAf77O+I)7y5}asgZ4N46U7*j!aqj|}Fh zrnhwUtqv;oWvD`Q!9FJBb9k%D47U~!z29ZQS}ROh0Ne%WIb5;yS*QZ z$Z5Y&ivplD9JXM+{XFSDnmoPEo1jsOv}-sN#Oz)6iEY(tV*DKafLC44!w*C`Zmpg@N!XdJe#yo6bK>Z^-547O}YLO(j6p5^68~HmEh!!S! zz=_Ft0o3dyYf^5p=~-Gj%-f4iJpga@@ux+K_9S2gOwc zAHKw(_fwb+KYTZcW?}7|Tp4r}?)z5|(;W!fv^2kZ+bVGfaU0JqPBP{$2LbpkYR*^~ z4E?^b=MkoY?EZCF8((lg)be9(QGXa+9hl9x>q2jB_$QiBs;)ncRAkDovMaXNrjM|U z*2*meHs7Ww{sF9!V|5pTVVwgZ64NBL)XvVjvCE&4%G!NVIOAuC-tv+Nz@5K64%GCD za+-}*e0KgbT3+uNxaN&T*1GYN3lp?&#Ztf@%#{V+9gDHd0WzeDwVH@P>-Kbwz^p^z zhgRXQ^h`1!itnG=xLt{=P4YHB^A3d_m3{>nNG~*mgN0B$sglgC)-cYlBqDo$d5vKB zW+N3QW;Fidmv51Cmv04cRu2wAsWO>T`ksJqpmMU3%WxyPkcG3f+_*PPM&Mp+?So3b znIvP=3>;J{^46d>5bH-7;1|RvP3lGU0^f7gtYscXCW+|KA-v{6We1glqJIqk8r~h< z(3NP{?wD)!M#6XV6pGJeHg**0o0a$^SZG zd|MX)%k{(FL)L5QZKyFTc;;`-l`_F;j%Er zc}ZI8+Y9Zc>Mm-Cch@Q{Wj1 z{>sN_Iek|TSUNi*J3~q2I}=Kv0Q$Gyf@yWwvkPnpX7TU%dH49dV==DW$1*V5X0mAo&%v$)9Ruq%7w;7W94JkRV{ z0>p~dzc&KvUTvL?#`Vl{3Ko?s2fuAa3aO)x#uBo6mBcpw$uP=E!ME)_HTLRX%9_+R zQ%b=KWI`ollvYcA+Th96Z*V%d>OTgD@*zHPvyY}*GEn@|h*Ft-dLhDHzMt)0LN4|59IdrLjTpD4-o!6q_D1W8pve5vg1B4sRB^ zEBD%{Z|8T#ycm(qq&;fA=I>52YMks}Ra@6g*RQ)#5K6W!+DMlg>+EKMc{NtELmvEP zHa%LWR0mR9luP~-!Ts(o`3xM)@FgO$W4kK;*p7Pdhx-$6$rwS3?HF{?c=}EaL3rxm z%l|kK_D4^t`zocZ8v_CIEMy!7bc%K+I(O}@3XRP@Aor=|APnVa!Wy8Y^p)c%+ z%U?I%ff2`~9R!0~rK5ICSlUxNvQ`!y+e$2D_eS%EUmx`FLZ1pO3eTI6L_utC&=($+^Ah@>3XO(%1+?uC`HbM8>}82H^Ev+ zXVbx8Gjv!5C1MTD$(~pi+YU{4$72&#L(x$@NKXx#6YSMePv{MoU{tYioC6LqCl1uC}@t8tuO{VOR= z@Ev|0|5ezk!xuX$5c7Gy=AN1kFIo6Ui)=ZWwARl@S7E5$-usxg+{7n?HZ78c3_KQ= zZu(*skxXFOz18KooVsT}7jCO6sKz@94R(0fkPEC&&CX9#L1${|2BUvj!4?Ho=+dGf z?l#2^%2QP`PS0Pkl2wz8dyl zt+`coyWa}tK=VO&!OQ~H6;f>Uv>k^}ukduM{3c^PjoZJzB!?Q|ihq?F_|WRGNfs#C z$H9yov6L7#t}l1p8N_j&XxW;D?p4RWN_+ypGl)Ll6RmP`>vGh8|B6<`*udk}S-Kf` z2xfw=Z^ zus_EYe^XXY9!6wrRG6z{gO$1nXF_G1eZRr_l>gRw=W4z-WgE57v@mPttHkE-*+jzn z&>VK8C&DM#rVX2)vbV2(YJLYT1k-|FSLPPaeZlc*TpOzCZCYHw?4Ok4F#=-)Pq6ck zGOnk?{}i@#?-LrBk@qP_e|zYnUo$yku8C&g0rcf3HpB`sB9+J!TwXIh8vFjo^GnW9 zyb%gHH_3&Yn=3`_bvU9z;S)LhbsA`B@lxAhPV6W3v8VK^J*Ms|m?-J( z7l;QdHFh3@x)!}EBz*SMj()r&ED7+ayh8M9xmZ*$$}4&sQ0lHpk3D_P|BJGb9-yA$ z75Yhr=$lXh@;AR*-_=d4rq1ukOBu_)4V+sR6Avhplq5~@-a|0zj^1UkJ)Tle@{(tD z;A$v87X=x1(8vZsP_NVJF^=dTL;-nLOIqp|cR>-BiB8cSisXjD*O@R4NzOtobdn ztqT>PynXh+Xk^)(bv6fW3pkpwIH>nmS0L-CSVT-ZaIcbNBbqMpYtvrL??t^^>fp%f zQ8MQ%2?f>6SQm61|ML1-f-Cc5e%pad`uQ7Iu3r)w`DdkO_yhztuYBr?XWF*%_tRd` zgc{kCEf+E-hbu8&z`aW5M=b$~HIR>3j&+3$Z5#O&)aruvc*o ze>2rY!Oo5hzOc~h3h&CX`6m+eFr{N9v}ljjlDVUYH=ZdA6%bt2s^lVzjPpFh_w;<(&gZl|EgYHN|wfV zQe$0VL=x#%N8b9sInb-6p*4{X?5^2EQN{tqL6uEgqeWPOE2)UE}sd=Bzpx zip^r5bm$Dyv?dRYpcmi|jk*sXY=ha1N%f^Pp-Xq|w;9kw^WG;ZR?p$Q4UNe_LO(B@ z%0K1HO$cYo-*YJa+8z3@Hau*!M~$*yJRtD?(Z1}LaV+53(x(~V?UBI!`(Mva8XD}u zCd2C#XL_+??z7mcK5DjP?wvi*)p67*2ac5GW8G-U)06i$-!gy5JOB5S`m6f$YLlJa z|01L>bUzA8*U>BLN9~KNXE*do1>CdWLJqiu`acSiUA3EpP0uxdH~}MIughnwbwgXd z4a(463UmDMRPSjgKUH<<3rPA8F%QW<=aJ;ccQ+d4HdH=d6D!R7z1ZC*8X8HdnO1P7 zH|uo-9>Y!O997E1jE^ZZ-u09OMMizpI{v*cD5GyC2id6HvN~{yEULU~@Au}((PT2- zyE~Dj>~D)J#YV;R$BpGC*kQGh6^>^n3G;Su>+55o-r0v`R}$;m4Nc#Q$Qv>w#(1!p zSLIDwTz_OslO-FbQ4cdBGptRxLo53JsWKXS)-9lVm8_q9$q0v!PU}xKX!T`nmD$e7 zqPs;(-&<+!Mr0U~h25NFd0^|dL^q1xMnn9Yjl{u;x_SJF3!h$NdzzNHGkujDQTF7J zDQ-<+t^x~QIN?xNcZk_mK9g32kFIss#8eGDI5WKFkWLo7l5g(uC^laucdv|~aizmV zTmRHqMF=NMbf==maRy2g(~b?{lc7W4DVp#id{q7=b+t#+gK4c>R^f+Ue_=+(amH=- zFd>aCvD+c^trjIrV}8E+v1;S|W!0UuXx@sjC@|lDiT_}w^^wcdgleuo1Vdf@lm;$M zg_xYHu|jNU<-TyJjuqZD><3)4Wqo|i5w-@$le56F7987QhM0bWT6Kq~UsM#^ufeWV zv#74aj_;N_m2*o6SJ*#h{L?;M+J(moltiW?HfC+-Z}A^>iwx+_*GX7QfRVnp>$PZX_tt=Lu72*ok}i zBlteH4W#~BbSA&KYg)41G$ZU%Jv?hmhVtFIl`gH*iC=#h8ZQw21e>Gj(UPQ+s&d!^ zRROt7mWoflDq%n{SK#?02b4@{}$_j$Qp1UhdIJKY;)^iw;vlWy!X4S;9M&RV_Be&zFK`HIkbHG{(BO)rif z`<}`A+^Gk~VEluHv=7xQ+lqS-NL&^v_UX=)cSEUUcwSXn;kk*JxlOil@GCIlN5Qj8 zu662PYtB2kak?Gx#(rCofaApqKVn1NVX8>2@KBoDdy1twekUE~Jzak#RmYr6imU76 z4ZYK$BB44*U~k~kew$dA?8FZLisL_k&yt6U8?}Gj#8;z`j@JCczA)tSpL4e18%-ss z?lD*y84T-#{rIeWZt}F>Cr%o%x%#Q;BnFLsQ@MXqaSvmVg1+@OHl~^9J*%z;C%v6; z(N0NIkAf>uiF*F~PFnpFI(ntC&uDXKZVS^e$IEApKP6x|UX4^24| zm$(#(H)i<2W9>P!BxldO@?srKEDWu%R>XFqj2U5*U%K*gGmf&j!5O0>c0hO3y|;{& zl;de!mm3C*Hv2D!obsst8!Bl@=@rwKKu2d0>$9a8zf3;MDm3F!UsgJ9L^<)z^ zMr#rr341nn5+k=z!umg9WwU(-V`{RkFrfzqPB>8-2SaqCP|vd^v6j{2^ln5%;PrFA z-=|ucKh0SuLx4I4+;@XRM53F=f>&(r-rK6(zdT#M+)w|ov&!%pXIxl!w7i!d>RK-s zA?4#<5-Vd;py2)-J&tLjFa4$ZvQ@$?@(|W{x#vdCm)Bq6a$GQKD_nx4E6q|lyHA$B z(25Tp5_5XV_270@e)YwV`T=0%8u_Z#`|~Y1>`INmBt!%MW{6-nB-0d7ABGbHhLScM zQ|qtgGdr&|i7WmI=DInNl;Uscsb|UGt3bK|WN~T%! zC)th$HIW~>hYaQaZtb1-SASCVY>B>kMS1p9R=ZKT_t?&@4h+i7d?L4|R>{S;6hLB} zYLe(7bsH!H#)+Zs;OcJ17gT1tQWRI}Su!VfsUUMXCNVpr+YrZR?Om7rB26bt$2n=d z?7x>H@)4@Rk)36MZ>p0xi2n$O$71!_H$s?DyL_}b8FA*TVWtR!qs9o zHZs&dD9bzaMFhxC#%w3F`JF1kbIkLm4=W`QjQmuz36@ffNa)hRuV+za0Htq6vhBiu z53Xs{!2oj{+r1^c|LF7j^h(8R^-Yf^uCiLIla&NgRRRN;nwDzey4~&{I)=^*%Mep3 zEW6dt3vej&~&iL624^;HwY5Ja)p3 zPxuOX(n&<@Hoa2PQ*R#Sa(QRW`I7bE$RPWtPqehT+UhZvj zWg*OWU>4w9;v>mT$($A@PqVOW1d6TTI(n-t-_Ms1oy4iI{oMS5c5zb`kE=J-dbdRq zNVOL6&78s+@lxqslwE?9Faadyy5i2YzjmS%l^G14+!&|~l8rz<+v@E$j*j+pdD{)g z!0g~WV}|GO@|SjFVd$?iOz!}(t@VaT)P%<;&ZxDKUQ4*Ewx7Glw1}%>z68;T)q$5t zKaLt>G_xr1SUSi6Y$Nw-*bYT==VEKRUK@X8wRcZJ4LFa|J9VD4t)NGDh%->FU+BbA ztLaCP`Dh9xzmVu7lYU7P&Q>fQ!avqL0?lQ2a3*bkrD()s>LIgG{we5=8Z3)?vRXs6 z8H(Pg(3|s{NSUe<^q|+c?(*gs>F8wu!@u0aNH30h)M?9(KS1@2?w-jBETJMeyz(F@I{sncjR-MfA=X*OeVuv>Wbo8?Y6<_F3tB6~ZM9QcwI9Rw38Hu_dHI8=Cgo zE?yQQKm9r(qLlP$hv8MJ>4!i>Hfd-wPt~+?5jHSEe5Z~~78|Fz+Kmij?8_ z^`qP3=AfdgV)egXZYswA!iMtAH^c8@^A8QE&@wB3`|PisQy?C~HBh{F_hj7-baPnW zi+u6y#u0DM=3!nu3O@TpONdQE$;;$_6bKLD16zh%X1xow16C+g zW;Q#ENgJVAn}#~3|MKiW`bfoSUAG$9-vAWbodEe+)nh(u5 zVk3XHa3wG}vai|^HRKv$Q_%k2@yAnU=hNkL^F<&}M@NE44Ed{^@`6HHhs$m4LPF1m z0jHh5SuD~Aj;;8!s&m9%;MdFVFya*BR7L<}Vsv}8Z?ZF2;W_Wsf!TTkOPE@Hy^?pu zeolWW^bmH+V3b!EEXOioQ_p*|zbOW@G!yWt``D{bKYI!W`+Kd!se`ve&5|^edWD1^;zJp6;}|g<)!YJZbo;1l9RMG# zI7eqH=+(VL&^wXM9bt{yU;8YVU0h(V+~=SBzDhh9aa7>Qg`A<`rVc||a5oUe{qa^v zc-7CfAt${%>vNJR0K{|v+ke2+l>HYj1vc}GrXab9(f2luFGwpS$S_vlW)!*JA@&f< z4F=H4so^#p;rKne4`m9?fi}P$Mq%|jjIVJIKfVi_D*HJ)<4ZW25IZb1veNwkb|8z; ztPXa@4l83RV6r#Pn$*^?^i1`TFFXFz20YTJpggMln>ANGcL5NeTs!-DP6wf6ov)Yd z*ki;*0V1kx@(w95b5S!f<92Ja1Upz>ve)UoBE(3y(|p53a!&a0FN)daYwOQNNfw%@ z%|?vJa1d#*SMGY=kGo#*!%{Z$!|w1u*`BCG!9ko?wfYn+Q#j<5JuP=mkQHV(Rn$L( zpJ%dJ#Wtmajc9w~XGc|@Yj0wlD{)SFY9~eHfs{={Vn5|D)A;e1YFJG>#h4mtCu7hY zwC+M*>x)^8;o;c20;D;fzbC~!8V}v8@irS)xm;|}Okqz1esIRQkoFjoXm&X5h%w*) z1F{wFBQ&wlgpAgW)af72uTlr?9)pB`KW<9CDxa46I?2Ys5QXfGiSm)*p9{nVFmjGO zS;sm_@`r>o6iKx(milExASIrg9<#?2sN!eZY)ZzmdeA`eJ}ohdsw!{MA{>Oy(pfD- zWe}H7+i|Z;3)*oH{9B1Fs^}P<4y=Uh-u6@9qeEK6&^;qXwb$|z{-<~a&BzHs*lwNh zO|`g`omRqrm?$DXp>!C`@kV_C7pAzOwWocrKI4PmRVUnWGL2bxX}?ZI3}khST@1#d zZyL-;O{GP+(xcKpA4kf`1|+~*cnn}<=Bgus-;>Z@U!;yB%Kk&?V&q|849!$W?q>p3%ZFk$>PHfR(5&3ZScrq+xR|RVMCpR1JSb26fb0G1JPppk8|rqCyH{W#;AIGi*5xikl<(vZI|(FE(6hyd;o!al z(>yq~qzj0o>6>J{2{B(ncI6wSJC_{Y?$p@)bV#53Znwzs^&X5;gkIkhn+L9eJ61;@6Ac!M1f=VDBmaC{2-v%c*kd5xcRE<<3{c5fs<8e@>+>&rd@Zhe%RL^jqdyWuEuu zmu~4?;i~lE>i4ELBO&Xex>HedSI?jMYu=)2f(&aMnc=~gznwnZvDzlY~0fvtA0(*EDkG?N-MBQw4%N`s`2@Cp`2Q7 zUDP5^{~!X6PflB})X64vTi=y`56V93D>mM3wNAsd3Mj_kig;HeiYxQmmkYH%vBld} zru;gHHC2gXs+&01jA>aW6Z&r5-~%q4S{^c`y6xbkOLxA;&K+%PG(1q+-zejRpV8DB zP3H-~oE?K8z-S&j9en>%LA>#U{m4seq9;>|Z#|F3x&w5iuZk@X76NA9)xl}UZ+vLS zegt*vw(KY`F(}b z8tDc>ny>HP_xn8m!1LR6?94Sg#~kPEUf21lXHcE>D<-SN!or{6g)eQ2Msvp7skeLQ z5}P>g!heHdfSCD{_n5pf(tn0I_SIgS_sD_CsoDvJZDn(A4;F5@|0r6gueFF8UJbi9 z9!r-Dj`;ugd`VkYK1=agq+`#uO?8H5asJZkc)<$&FS}R2c3b6Lxa$d|Uc79%nRCy+ zdHRecw8-g`4M62fK0jlYQ+-JfIW|*LCQ53WAiaJCbE(1)aa3R(Akh7%;~68d5OQVh z_5d(f!MhmFMtoI5j06@aJD7{SyfbdnN#Ga*%|_eAq4fG!>CrmW%rn^jfT_E!e53fC zp%BZ=E5x2bhQ_e*pX3IWZ9jcCop(@26X0{WVjH_KPI{AuFl|iYsdDL<{C|Ri$yOZM zR#VAB<&;gH3y68ILsx~qkgAZZ?)y|a(SF%AsT1N1;=Mo?39<2Llt4FFQFRfvd!POF@c-ks~Uo(x1FL#pgXvVLyeG>OyQUdGMyD-daQl@IgX z6{}1l@)}Q!uB2jr_utvK0mgspaS->7nYe!+CGM7V`{CD09uwwWyveMHzMw>-B=vdX z?;i}g3hvw_G~1b=J5wdC^zOeIULe!bvPO5DSsSdn8teWTgwPa7Q{O_>$^4dFQC08t zd94)p`XHtH@)mdoaK@(=6Zhi{-=tkTDmcVuD=wFuR4yF(*o^%Q!kFg$g+o97@3PNJ-`}W#?`=&wE*6x-+HnLJ z+6%h)t#}z+d)e^VvDteCiS-F%5@ zZtFJ5pxTdbCiHg6xQ3|CCPQBItdTKn($4%I6rk_NPqI?&UcbNp+YP@}Jn5vGx7Ue+ zsKil|^l!Bvkj^Q22os>E@8@4squ1$cVOV?$7}UOSCUMrYan8~THx7&Z&ajE_hIGCA zJL3Mdgz8DZT0s9+f%lvizSf^_m%sV83Ssg>iv3%$BR!Y~y}c(ncyetiAahUg;{1sj z?ub{lr%c12oUVd-jFG;|>n)+nKa-`K=Nn=t(}QCg+xFK3D6&@j)u6K4w{m321{-38 z4TrI(sVH>zwDW35>dHd%ATYRY#!d8q=g(J|s32VpgVVDsqJE5s{ejB?x1bf-fR2!7A;{&Wt3Sj-#OElKE3H|=} zqi)+kxeG~fh;ckCf-AO==adFbw#82~4A;CSw5hgvDrQ#QJP_2ZRu63dkq{rYeeG$)hizLt71isZ)Dnv+lKo1`yEU`AApKLM&y;WrY6!S zTvLm(=>-j_`j25S&KE>Bh!A_UNJKGqA>a6(ee|y|a%$3-r*mL3m&oEH!>ib4<`fK7} zxV!A_J^CgI>P#dx2h1*a-Q4aISS2AW!a&|EMa7e+$@#S1r|i(xDVvi$vD-##2H+r1 z)nGN)6kq{43=?^)@XrPdLfT_dTUgn)xiqUEwE<9C)u9brOZ=fV)#b49f$?xTI>kzJ z=@(J-2#ZWeJ1Vaof98$!a_HRY|4dZ1c0ic-`y332ZWdhjbZI2*lc=ep1Q zZkqB|v|x|Ej3~CRMeK(a#X~yyCBDBx;CDio1OH2Lq^M!>X9``xBD?bH{0or{31%8k z+JrXa>Up%KuJU^SMTA38IYd#_Aq`mZG8ryvL^(3;Gi)l@SD7$TM{~~B|C(2>ONiLz z+KQ507ytpN0U!d_W%rBf7FcOk+Av-(xs4gLVoo7@G=7Hy^}uX3Tncdl8DR5oD0q^3 z*bgwqRb_VGW)w!ckdq5QgM%*!fX&O0E8V)M>4!X3KKcC0+JBo@v=yhas>MDQM9Fbg z4qS;PtUVWR<3uka1@RX;(TiO#!m6{;&GG>;IF$ov&zJ8)Fbj{de9(%cJ8<4S-y%lXxk9aRlDwc?0?Ch`NMQVLp?Tk;5v1w8;ve%GQ7r=D6* zU zPTelLM%AR+@whqz5dmYNh@4X2k1e}}<25WV_QH3EX;!4wQz z8c0?iQ_as1i*$egJ=448c))}#pnU{ezwPt~V`Xt@JcKD?PcoC_?gpaj7t8eC2M8=3 z$6$`;8AB>L#BHEUWben)m2YTDKJ{fFA9nJHvOz-I0m3x7WI530NG z^;)9*%UR{~lGzsEM5c*q@MD0@Uy;R98${DZGz%V}nwWDT&9PVjaDef}8~^X`qYh}a ziM)AbM{GXjx4Qz(_kTbAwX5O53+zIz`eVHGcY20CH&=XYdx0_d(iQ3t59aeK8e{oS zU#M9h`RBAzs#-}IhNY;wnp%aeJ`^s4zB-&bVeI(V%6f;^x%vXO%VCG9cJ?neUIxgKWx9&h*xmA(Rl)1a6Qx~nbOQGR7zlpMp@6XH?EuT zDE<-7Hs_+?7mzL3#|qbAHOA}0gcT)=3*@iJY#^C$AoFdVSRgVT*7CZNDhKoZ49?z6 z_=Hao0oTnKMsONk zyaC$q7jz9rD^Jrj%tDvY5j^<$rQ*nI;IOLUH;CFA$@PAQa1MsmqKQaX;2549h`Nk> zhQKVLV#Q2ZpjUC&=sVx8LTqnK8#GzbiuZT9AP5#0Q^+Nk^($Q9!EY{8gIG1Ivu#J< zfyslawM(LBh=iY$7|CA`A;SI$$j$k@BXi%o<$dNm8GZdKc*9<`7myNbj`GXo*_Ymjy8V8i1tsMeihayHgRFPc8IWlAyJU?`D#aO1qU%d{);)_>TCP; zvx>yezJ|=hj0>o9M(In~L6IQM&_fqyU{G#Z|)Q8A?Uk0}IM z)pYS)$f5pt(0RGb80R70p7Zb4bgr`WI!#V8be^MIMmec`V3?qj6Zye>(g*{=VDGvl z?_uhWr)ha#*2{^g@1F+Y+e36q(q$+ex4O-GiS_yFzJeRU-5Wt8)44C%j4uNdA3lf5 z^UfABxUkd7{T&#izVRqgtYX2xjv&s%$9`NT4+%~Yw+5G-o|SxeJ&y~i^|jpZNv zE20p{t}XTOfJLAi7ff9W_A5{RAX;qJ@Tu9^pf9V6nR9b7R|tOqALHy)p%1)TJZ;u6 zu6a-BmeLca?L*$`mzB4?QVaZZp4p5ap1PS>y#bfD_c_#9>0+X7~I}| zf175^HDzSY0!}u#GEPQ(mJlha#KgAw_JFQj+9*f1-#X3Z=RN2hE~jexD$e1|(tI?^ zAtEGiI=i$hHvx8>&l~GW=|QFdBtZ0@j%TtMjpSlX8vi$S@&9#@T9xK&`F-@h#xt$I zH#$c7w&B}SEB-Lgc#_pE&va9u4vLJ{Aq*4cRgtc2h1 zb>nT?e3ptX%U>8>acH%zt;f);lNGUMJ2Q$p#)1}EvqlhC#msvJRnD=7bmjQTn@1rk?zP<% z2g?|npk?C9gMG1|HW>ZOvdCNQI1{QuSS3hR@2#~^o?$xg9IJGy^CLOBQnq4MtR>W% za?eP{cZfQ0%H;FNX#tM!r8+~{gZ`dswCB7ZYi~qxE#r=Kj>{b$ZN(Z}1;*{IO6_ONGoS2zj8;*>LA-X$9b?0u2B*wJpTqS( z=i+7S4n>HNj|7D6h{b4c#O9$z6yP7T;4y+q&D++uweT|+U(MJ|wNewcWAByD9px*h zwmxSFxLlJ?HknhpQgaw{vl2xoII1 zXggdw*M1B|efWtQ|6Lbt4SJs&pCbmfzGfi<4B}ux^Z2z4N>L-2xS*+i1quazga~w! zlf$gKrFhG3ywH(zjO5yt0__g62Rs{MV`oUf0R~_istUrs?*=VTZm@L;oG(@G>+bgU}|EyWq(#=dv!OcwW1)}M5iHmJk ze$(dyot)0C>BW63uw6KF4_~xiA_RXJpM*yk`63CFJ(@~yZEza@Lof*vHY?I9BnUl) z(w{K>{PJ67zw0~W)bE!&bJ_g`;zF^NiDa0l&DuZM3`La#Z_C6qD)-Kso9t7InuyJEkyx+vsfk3)Oqe~&KP@!{4* zR$c12d?G$h4-=~eTpro7>ZML+37mAAcqgdP%WQtmHZUND4hUN>3O%(0MOA3|wCB=N^2wvG0!36+JSsMF971%Y^N?O#;p!ZF+uL<7E4i~U z2bErY{3KbaMvKav*vGwc0Ja|e@l?^L@_Tn$=hT}NJ-mY{7j-4;faz$60^Obr5QGO_ zJsRC@2rdm*PUZtsZ>rE#-ima$!nNcuo9bn=Z@hPk{rC)SP38tWe-^?ZGvakm1Wuwb z2^TQzAu%%!gmuD+pq-Og(Ko&VVra>SQMfh6=~a;V9kv?PbN}b_M~(fW){AkP)U!FI zLWqU%8u8Bx*4xhQIQZo+t7tS26)IL0FmaEN?gg3YhNbM~##AAMv7CifXp8 zwiqlbgx?-4NP1ZbBfWd3Pt6(s9nFDPTa$zqVZ{Y%#G z%+^X6|s&f|MuMuT9{ogk2+2-|-U^GNcLgwMU(K##NON@cT7+ z-m0VnE*#=leX98*3@!Od@`?dXAK66a*7jM-_BpG-D}^)WKOf|`vCcxNwjQF{Tb9p}Dc}Qfo`^)k9(?{CfAc~~M-cmE>Nl!!)uUC6^A8QM{7nB1 z7@q?s<5msi9amOzMed{n9B_biQ22Q2b)JAvs{EZk^|xNJPrtYpgh>Cxk< zEzeM{GP>`Dc-}1yszjfhgkG7-ui=zV`(r)okm9lD+j04}!Y1H>dv-=1NN6mq_nKa8 zM9x-BoOX!l!nB7vQ_yJnP0h;hhiYcC^g%5Jjt>lCyYY{23Snggh^#{MYb=!21C-Tw zNYP89-Zz?z@dM4>+u+0b`ct#sf~JRTzC`L?9X0lGwvM;bn2t0D;@kK_R((I*y8kha z2J$Ln(XVL^hnZZY_K3@S6!mEOham~SKT0WhI%3srWqvys zyyCOR9!x0*#&|DtPqKO|Uef?#?eHFI+pEneHq&?P#Oa@%mV&#C0Yl^Ix(iZAmW#MK z-{#XC7R&WlbYT)+-QkrDv?OmsRQF_u5nS#Yvvb3SjO*CJrv&42hA4f<)@-o2>>kA7~x z0~$PJbzmI+a6p!_EUp%OmVT!?_6Di6qa{OXZ{w9ZBKp@Z%O#&y49gb(C|}TWQElqk zccjE{?~HUA+;*+n3Wb$TJ5aFgf_q8CI9*#n^9k^SL>j0d^UxHEiUqByKqI_FMX`U0_Of9t0Ftki;X!tpFcWUD6b=Rd` zmc-yV*?kF$%pf9~K`#srsE}&@H(LkA4_j8EMv4z85PEH$rq4r`FvKfi-ZXuF8>^@80ZmaqcFR&%}dlaGr?(OIJX6lS< zmaA@%#SUT?*b=Po=>6N*d8Vq>68BeZ9y_T?dNy(5_+7(tJiu&a+L-}v<)-^ zrZ%yU`T~$3rt;I!Z?#q6n1`|i9^dfnkN6bqmFo zrFLz0lQ(N+A=7=qQMCxW8A0PFv`0y5NBH5g3~(?zGF*_z_c_+64}Z{1tLAmV;q6Ph zP33Y=KK0uxGfOFgM@8nLMySKyG>H9;7j8+Drj9ToH`S?m_frAph-0|1hdmTuPi`-{ zo_t|V+R>44FSctieCf#-^?7WRzf0k4!SlI}@a*v~=AqP{Q*1w+AMd=NQNQ)v_LS3} z-|YK!VI`JB8lPD%6O?_(c24MhZq;Ra1fdll-je8r=E>+zP(k&uD5H5^ zxmzXj;*m;QXlxHF*yZPsScOvAHYI>3Qk**+^-$`ZI=DOwV|KzQkyDYG(>X z0{#ADKpK+2&=HgtlP`S()t(vb9LCp152S*G1@ZuQ%?>n6`aS92AAb!86VYE^X-MmK z^iC2Kr5m-wE6v?(LE*=MR{?lH%vF%((z8MgH5Hc1U0Cy67lBqWs8qd{R%qJo3@@;L zb&mWpYmD4&`e`!cVYctPdKW$zTL;Z4CjkT7^sxeLb3Nw?A0xKD(LDTsfat#S18D7L z*IyHtnEwb%*O~Bztq>VmeH6N(nh;p7l!nD@+<0>Egdbrj`D0dRxc90Kh*LI)erI=Q zAzz~VhfhLcq(zpx7_>Zjxo&F|Uf2MvGa{AOnoR3V2;EsMVTCr_YREVDHomrVh6(!0(yF*+=6=4Km%^Iy(*B*{)4Q znoD%>wYFgCY512xWv_+j=gaA4a_lC(Nox6k1mXdzQZa*x5pm2d z%7pq60Sn$#C#&iR|Gn26&iZ1cVEeG??6K^P^=Ydq@}igyHGVnIg193JIy&W!e5EtG417u_)511zcopf2SHAdHKmNQ2qW)34(SS$euWxJAhT;G5b@==c&7eXBLx*>zV-%XY$2^9o zioOLi2dO$@J?mnZ=~#5lCjwe0JVN#YqGh(-$7`ODoX7zE4sf}o@xwk)>?7;~9)^C3 z81qjzPl9N^fPBh|XUjJ=!UJlc-PzM>A0IE}P30~f2=w4RYLH2Dj4ZWDY|Tk00DcDu zY5k37K3-ULnfC041_qm}Tg+%OAFd zm}`wrcNp&E92u**T8A7?Z+MM$^$(?jf6P-f=#n>~5JVv}^zJC*K?p52Vv%K%`|rri z=%;b~q}DU$sw~+z@c#srOs_?%^fAbf57VTsI{vKzqn$}Ij6W_&AW z`lVGs4A&`D{9+cZi=E+A|HS!ehy0_4x5b6Tjuwfz?Q94teh)g-o6_fv-_FLqY*73B zq~DrSCd@z!JodOMvvE^IeA+`sev~2j+ew4?QRyhdT(Wc$1$)?II8?dQmJ8~TdBJht zVV2LR_S$vh5a_5fxRcts0I>;uR~U}Gro9oNx12?FX*iMBRLhSx*8A|aYt8&upE(ka zoDc)aq?eU}%c7tGd_Ugr*?8i;7+{h0#4Qd)in;Hkp@U^5(&&I}{aytGnsxQOG+G$Y!!KUmGz<~zF0wvRH3JE{l3jX7USAF@06R7c>kO;Mn zT5%-t4xy4c5D$)G?bwp?7PtG7`2Mjx1e$7HJuU2*aA;Y0kt;~h^f2~j<4A}QiuB2GaOWR8g5Y!1OO>z$rOBG2r2eD-Bi z6Tf7g8a41 z2$OAMP#Uv$s2P1F3YtBPABWI;k76u!YD|U=!K3Vz_aM#}ngCcZQ+IRJl>9pz0{LIT zSm|Su%fW1oX>5RUe|V=E+8SF^u(0ZiJsM)311iu2Dx>3n^Z7KjpFULibZxefwvAKt z$*I?@ON5j`OV!!ZNlT}n4WHennll(ybd)oJu1le?eI{W2^0}$sIU{b~Yd|E+rx_cD zAr^s=0a$2ITgP26{A54~$mwEGY1=t}#4>@tz@c9JjkUw@{@8(E=HEw8$MR}(OOB+u z;w(Dg+yXCb+DZXH!A>iS#KBeSS|f28;F^L@ED`JC0~Vs55suaS`QKxMqaJH+iA5m; zsSJu?v#zc2uaHWza3nT^8(mdU+lVrVd_3IuRPxagQa;iR%iPFD?o)Ow125>3q42~C zS1c6|;T{mwpNZ$XhLzCcuo?ocBF`0q#0Xf9T$-43lVcfRfY!SSr$NxwnGY0u5&N*xq!=%dTsq(*8hGrPN%}k0v~3fy>YS zn2_&urz#PFqXBpUx=&=zCU1oaZLUZ5$BlFkN%5hoVOfgk3N7FpWO0HD?36!fVWGe& z{h+|;?&D4rY~oyk$=sIwJgYT1YS4#28YF@a>W;k{QlNHbRY<3X}}pLRY1iLWS9 zd|Vpom8^K8$=lumembGV_vs*E(#L9Y#|QVQujl_*(0M=I2l&+OB0Fz;{rFIo)~Z`^ zZD3zt$I=TC4P-LNq~~5P6bL`3o|_^iM|2KMPOnf5rbToV@Ih6-v1tH?cb3y0y{y@2kr^6CyN%&tA7PJ|%v#zm=rnN2*faO5!T68>l( zAL4;!eqz3-)~O+ZY`D^{L%fHvdD4O2h+mdM^dcH4HzcPLP9t(yR_O8TwoHxI;pAKI z?`Q!>_bX9!sqMSbaHb*}%fzb)(@f@i-hF|UM5muzXjWTS7Az&N`hv*;&07}wB$~zuhfiU`4WP19ipM8rkC>xJaCG2r zr{hMJaCfHsOEL!n9|3sWlK%n0f36vV*odrgX_8LXzIzX~g>psR<;RzO0AxL8?BTBs{sybHWaR!l zOu;bRb7rhwF07UHhvsX9gVDaEcJYUFqz~7okq#m zM_WAIlE9rFYdTww9dEaBNeRQ_b6)KX&A9a7=ybn-!~64)1t5Met#yu}<$wkwU7*BC zq+CmRSZ=NP7;gA?Z%4R#x2ST`&0(bYvzgn%_j_x(e(NY_o`6nIH(pR$l*{3Fa2m{- zZ(KI^55%Lni7}6~s*!E=^ax;JnrXpZ&|@ z*d)w5So_jMiZIC?^Lrujvy1_H$UIigI?f;wzaub~(^TT*4p^*D4;OH!_Y&AD)6%+y zyiZ+vQC+p)M=@W%bl!9-d*=B=?bb}A;|=9o#Dl-)yy$a#v2zAZsL7G_ZA}`CA+V>n zB&#tG_eOu{$m2JJ!$?zycL8GeE@*NE0<0`-G`j-#J*KW@D$|7-^S4HQMM0Z;uF%m6 z>!w})R+OE#yO#!(e=ZN;ENj4Hm`{U9r8KHb~+pbS$Y^nT3|JxV@(rdHF{xeY7A=22GrXKx%d zWZO6_t0V9&gbQxozM6^2ED?pCb>Wq5M!xA81I5aS56CsXpjdW`lzQQmk&#Tjl4oO@ z31p|uM&W8wLWnyzjZ=j1HcpqW@fOFMZ;Y{e2Gw?)$8Cb^tZGD;E~zn3C}0!($8_m2 zD8_aN>L8_GBj!MTN}oD+$2cfk{q5?-8l%|ga+G3WEMIi6cR|0A z2>}VFRt+N4n>k^=B0zb`>OA_J$nsmRYt@6LRgL#qhQQG%9wE&{t=y2`14j(G#pVO# zM->{1P4Z%1$H_i{0PYr?;s<4e{F+)j-I|R@F(?k5D!iAYK}~rHu;zU6~=#O6KtHBk{&+qFO+!xDQC7LGXZZ%?S;MxFb*!itxAy ze`3uI_?SHq-*`$gkQ+6b25Y^^F62kg`N%w~NQ=pdRgE15h5mFn^Dwg?E9<)cX6fr; zb5`-##d5X7uK5!*aUg}dn|Y_~Y>*Ix-sA+}Dk($mzRj2 zxz~mR<|;v^ciMI@G=DxC9i&5jbJB5$;B(SWYWl?yj&+E#y_7nBc#R5AAotKhSH^vk z%f{?oXClSdroKWFIy+l7lia`YQUgdg?!t!V1$t(F{vJc*ga{Pc*8e33P8uC2{bvhP8lSqffuN~(FG~c2%W^kK zg-8jx5}NRVmz-^e$&4Tu%jaG;j>NNOydT=kd$Ej0)>Ez|hr}@1rsCo7$Iy25XEd^L z3Y01HiTz_?>!Wzg_EtN?aO1@}tF9KaO3p;XpV?dPDG=rq-qxyfPjFg^)D3%RPq~iI zi7t|Bgq+U8xcm0vS$-y84L9_czxmwPTK%r~hH|!y3G-BZ-qKG1?xFWK8axPDN@w`g zU&(_-r{q5{sE2%5o5_q%R~I8mHF_pWGOWUxd!xQihPI#=@hrM$hfl6}^WWJi8E_c? z?j0#?LS*~DgRzm|{1r$dEY9d4)TPNYbl+<64FvM^kDx3I&h-&h=E&2}_fH$Bn#_^A z3B_$my7t}!TC_M+rBPv8 z^z)q|0H!tYecr!ZFfMucnHdE}g}=m2DVfRMG>IO8lL7i&86mGd+>3|%^Bodp25g_JqKGd^FdFweU)Y=3Q%$#ck`q+|Bw3X}|uik)8|U_W!IM z6IGHv{KO<*F#d7T^c^Ce(%7{4QPNl)5Dd8!MI?izm)lxLuekRgqu<7qGCACZUwmXx z*8vVMh`l|2&wY8BnLe~HjJ#Fy@$nL6+-K#1sP#A}}0iK9@-o%2<@ zWhIUFm!n|mrxXgIOa8$v@nq@G!(L)maE3p!fX97tzr}_pOXP=}Uv2U3{cs0PKe(pR z!3}=ZFv!Es{^0PS<41UF{f2ZsVhC9^g3+F(-1kO0hRzQcaQG{?33-kW_m;0IBdZPv zzb}kfFN_TLE_t3s$=5V2>3tLS9iK4h9PTa2Ou%*I&Tu^Ti{<%kInuf-Piw^F*3_^X zVID+PzZn=pJoqm@iZOcRsKeeaC?b80`-N&V*^huMI8!~JMoZ4%B59IFivLLxJv)$A zZ)4d+JS|`Jf^P;3`J!r|SqhV z|FFk66#9S1@__RH9ro-a(nf6eq_`~?ryG#l0`>np4-XJ$s7ylVO6@cEs>K?-QM-gUvw$uEQxDhi@+`3-JSM@*ReHll$mr4RL3!;V8lk zAKrP`@#OZW7`ot*8nKuVGOSf(L0smEJI(h(<4Rk^B>uxtu@B*OrK=s7{zToAl;&2S z6HpSd6#`qk{wo*=U(R?e(i3|5m*VB-e%4pE5V$#pINDx7c=wnt1MOe)_{zKUPE#9Z z770dGhqdSP%EpNz8kSIxxnvWc20SKI9QlA3*xzSi+l1DCHvIZtBp&~?K7^H%Z_ca@ zF8FO^g2J3+uP`L<%Vhi48eXU}wVS#c;)184PgxU7J zMm4iURBY-a;nMy;PPz%i;Q(uXPGUvc^rxE3cWtbd#y=*kuz6&&yqyl^Ecafl@<5)u zobHNk#|J{9#>dOh!|P6BiU|8rVr7e$P*R$y1DdQj#K@Nx1qzxv&%|**OpE@EPG)R+ z_xA$?mQXkpq(1w#5F;!E1Hk^2Io8dS@ol!hb zov4{);h6F~Cw(Bmi+WIp!^j6UEMq5BCgw)G!K?Se)wHH74Db50 zuDR-BMtCLbwrDOq&t6-LE{x8}TrBFQp-`nE5KizVD$;I6KBqgdsP4SBck4%fa&(Mi zecy0zZmaa`fuAJcffweT2*A>t>|U`4QH?4A2f*Rh?M+^_^DD?3l=7j^{1kZLyqk_b z4;_!+!$*@bUbQk)_*yoFFyOVa4&t^R+x_$y6TtkL7xe5q*s-;5t#blQs?=hNWOV&B zowM%4I*#b}#`Y!0gs%nP$AgZhzvyZJ%!Y~M3enBhkHzgv5%tBR>#)R&lK)PqR*C-4 zAy&QD2n_OVSJ>1R=v*M}p_TXGLb_~U&ST|qX?})<@TFa2@4*FS1#WORfyBqv?MBr! zh`-3*x_^M%J6Ktl8j09R^wZI1RsZ)%$@RRstF7z^X2!=(#=HApynheqmv$!ySgvmT z`XopyFSNq)B+@^s{GpAh`r_^=sR0Tf{Qy|oI_)iBU@65zc)VsoGm&PeIc2Xan|uuWP^1c8Glt z7OE~TX()^Pur*IWkj~n@63ohaVkt%rCJ)Xfh)!P4j`uPC%73`(AaIdrRP+#C^CXSJ zOtVzLwHosb_7$3^x-B*4t6%(O7VVEKM}%JtTnravj>M50*&(^pzg0)Ju7hp!Jl6c{@+}tY~$yHu2x#%$C3sI%RI)WL89kGbF1T0}bhi zq4&M`sSuR7Vk2-`{+%k=;+Cs?|FD8>uCIz|{#cIOkp5d}K*d$9Is(w)tvGP=06jP9 zqPJsB*(xH2rL}c-b&(tU@gq3l=4UzITFyq7+$nm4$byuuKAd;TH`?=F`*zsamT;HG zphnO3P&GeipH}5sQ&FZR9>y5@Q<|wJe;?6dd)XyaZKq@Mt9e4Fxpa=FRAZCBn<4Er z#$CdDs&p_%&egdkT5G%e`1f?m*U5%z3pZV+GK6!)NSJ9J3U-lTX)~5t-dW4j-Kfx8 zSGCRGYUZ{>$sd^PGtVoGP`J;l$gJqe#d?E8nlGTv3SBHi(&a468E~XiKLiP8BsS%m z{doo@R%s3Rn=1ywg#B-U@d zPE|xHrOq76FM^yz7HdwzkBmCSc?wvD;&}ht=UoPL(XihAi|~a%KW=UqR;D% zEV5tDF7H6jv$1jk0D`km z1PPWwm5amC2e)iUnk3h1k6)6X-fZQf@|Ka3l0<+qBLh=Pxme|#r#933)5Bi2pLtBv zxXEju8!Yu$lJ5OtcA@W86K~e+fBdzJgdN}+5GYQCl?wlOIWvK~+%{wOJJ@N+kx;a` zsY>uG$uSn-n3;5-?E*>}YG!?NgW)*er_Iisp3}A{8#6vM>!K=1S<)6p5SrYm^I-xH zsh~v(rN*JnEiK3LUYZCwig;wu*Py?@2Q*E6-2l$Y;%?r|mh98_k)t}j zdd@RKJHtOU zo>D@5rT*^LmP-UpyiV53i^xbCLFwzh7-^*tw-pgu8(c~&CprvszYigZ?p}6aw!i(s z4X%c?VRUSi%niK?05iExjZG-A<6(*T-tE-t^j2YFsT{HL%MLeN(WRT3vf8Cm?n5^A zHP>nl<+q#(orb7>aj!|ZLFJr-ZjT_^tiG$fUu9SI*OA(%GqZ7#VQ-04LntQpt3hoj zqTZ-n)|4uN!rb!ME1s{W-;*T(ik69n(hfP%R;b|urWdwiRmLW~HO0zvxjQ=C(D&wv zEvLGM_wI(h(*MDiJx-OH67lVy${e%Vz{Ihe2ZSz$H26&7qTwLZ(Z9ElQb za|-!dlVt6$T3g!;V!DzoL$zI#pbvt2#zPFBg{|t*i@$v)p=hu6{p!X zDz%t~oqvz7QUUB&u#u;=-+=vEWP@Fa7C-Q6x-w#RNbb&PPs5(!Mr4=s(_5K!V)uSM ze1zU#OH*HBmbV+~Uf(U6Lul>&SR8EBC;+@m3pZ2Y@K5~7h?83W!HJE%VYZLA4<)ns zTe52hF^DI2O5yygsE2d(hNDjbQKe$tcXYDgI&5hnxMl9A_0>^rKTO%=u(WDvT$D^{ z+?KvQypHQvo&HMXBQ>T%v&64cuKiDV(O=Hg3n-IIetUl@Fe2AwbU{#dp2w^Dql-Jl32 z4a8n*!`DM@)pn7ZcDkXS;Q9H@Du`2 zA{Tb#TfRfpvo`YpP&rq>Sg&B(nGP{`X6#-hkyI9c3k2OGPm0AVufq&B^eS@lu!1PLJtyx?j0Pmr>|2TUT*=?!ZIV~rjoL0}ke*dgex1k(= zBG4YSMNzy@!#F+eG%V!3SkQ$5dMa>QuC9_QUJ|<**Rdc5O&G0M#x9_G^5kI|R+huh zA`fPKDR1rlJRt}aE~T0Avkz(tCT$`$@3&Fjw1fOGs}d&0^_16Ug1CRly7&wfd`@y# z?Bc75Ge%kxmR;Hj0}9K+CMpkD^%X+qar3KB_4mloWHq0Y{-=FUUCQ-4r7ccT{EYpL z-YF^pcC+{vQYf%NPV72fIN<5_H3nVz{&+-)%OdTT2w|39vuCwjKv8AyuikHCDJ%BX!M7LZ{2T&XHdTiyctjSuLAcnnW!X`jYx-;lerA zhk9_zXffpF_KXophXNVVkXRy(`k>Ug`ZN{-wS9r_XwG5#$RM4T`J&aBH!A*Q`UV$f zF;1w|xk7kqldC${sSsUeUoN+wRxy0RSD2wf%sa-@0oPbA(1BCp88sE`HL&w1UdY2g zbv@HBdl+Y%Do@w3MFL+gWx2Cp<>KBD5X2Q~mXbgrrN3i41 zK$M=}D8Tf| zY92agW~S`e?AiqIPoz~!|Dr^9n_-neYQXGSm1^}kN#qOG*UE?or@q~1(VvbdH98xu zk1z+X~zMYjwW$5@X|hs^&< z5jYt?r{TN!|LPBa1)`>r3Idh5%|`imXq7(xS>}BrmTp;)L56&$toj%!7hF7eWPl8q z5H5251a5X!Eu5R_8JABD>y}kP1bsk78w6CXCN$o2L!2Y~6C{NNvg+FumI>0*O+$m? z5tTo>h0(@dX8bvY6T^{5PJJrZdi?rW9p%EGAiK1I5ng2F8?>i?R0h9QQt9h-o#O6R zBzX2H=ECWgz8`UC>}%q|Kq3A@Z86?gM6mOa)gpY0DS@@O8QB|J`Cy{1g~0&AV{zbj@1{JAMU`c+a3UEWgkCQn`GLW`t%Xy8s8b|6xRygH$A7JIY^5~bq5#Zv zDR7-L!$~OXI3Pv0>e#fOo;v{Zd5A#kXkq|xq75p1SU;5Sp<(p2aGly`m(5@L@!&|s zv^`|~D){w{-vJVQlN(t6x7Kj^h!P-%jEBq#DDS;y!KA&nM-^rPgfe4ofC~<`mqf?{ zkIdmVr)&_H^yXhxc8a4;`X*z5JZ1wRLrU!!A*dhmXj~uL&@voW!C%#7o1NcN;G^^Z zxfBIn6!&)(qlg-uIu7Wn(Ey&Gd(M-OZ7v!m6GI#^B*mA9sRDsN9!mO{ybC5$M6!-d zd%BWQ8vheERTH92vw zA@);*q-ik#XNiBeDqj7LK~!k_{kPlk+{&w;*a$b-j&Ykh$ONm5(nldj;0WL4#UUh@!!!T7Mm&Pn5r60})Qz}@HaC}gUV&;;&0hbw{eH)^Lei$oq*C@A&0_~_pntRiy zhX;k)*hUb5byH?YjPNzn#kBLxqg4{;^%zoob z$pDXD>^usYeR)Y?Dwd^WrSl2cW5Kk-nRk#i6s|^U`;)zSG^)k?4s75()T0v}bwZv4S{0`WzNCI;B!3N!b zH>P6TNoww!I?Hw=|EGH}z?t;YDmVv*<@Kxw<#Zp^kQT{et>vb~nl~kdZp(??C3LIB z%q3w8q3i|`k{4;63t5|HU@>6AjPWpq9qaP=>AjZG6oc33-#L@GgP=^0(uIe*yDqXZ z3d-_6%_G?pXNP3{8F)qiaID2bC)a-P#!H3(l3WYGc!Pl!b|l9-RtQkCL&anjhQF=G zX_HWGoXc-xpksP``{DixNTEqo)uukVp}^30^)On>`*ze#rt-9ur{U5V6ut$3^+r5X z8)<2!fLipT(#@T;|Nh}js2eYJ(an;M=;r|na))rOXmws!)8%Cs8cvBL&uIMB&HK_4 z-KO^&1ID}W#lM+nAI2G=i1iYWh!~C$;FRrZ? zF4D|SvX7DyknBkew3sb&85%T*B<#Ngkmm>N0TV5v`2`TAw~J@Ntjjr8@xq<5#6iZ8 zEHwZ?Ka^=gsZrqZGWOn?J3rT08xNu*Y&p`6n3O4%z12s-G=U8~d@Ix6)w%T8rSPmr z^CkpsGXqZ6IveZ8373b2+oF$0Bhr!ij8cLM%wWNkvX4N*$?I<^)?qA0{JKjp7h`F3 z2V@dgC#Az_Z31iWy&c8UNOmK-H^P}AaYVg2q(N|rUF?JR&>%jf`g3A<#&@z8;?jRDXRX^z7q z`Oca7SPgn0CIBCx%tA`nLh}uB_WS%Oh^r|w{Y!AK9Rio*$4!tXze{(fMl=3OG!^am2Mv@*Z8TUn$rcO2 zYTx3)9&@eFR@d>sJW4S0Uj06KjnXof@alki>UK&7E+kZ=qvlVQ9QDK4dzOh0ei`;CV zG}Tjy;55N{fVPQ}+u!67XlN%3DB((pLBm5Enub0;K;H@<)|gwHzVvuJ%X!Ucgr=ib zEcR;aFPCM5b0Q0%6bXT+50syD2k_*t>L!TVa+ z#dLKLJRRmukFv(E_0gHdP+40cpW{YG&c)^cuoYc@NjLhl2SP-#{fw?I>d32J883(N zdNImFd3U-_5CqUsIMeMvhFjOnayT~dZ4@?C5Hf-LN#nZ;uw~O--Ps2`kwddxbKo6Dq==hynDTcYBlAAC?<;6!2z+Zp;Bai;nT<3-^M>?ZWlAIZf#^IFa5G z&7I0M&7K*~WI$}$M29h(WWuuTG}n(_p}nd1*syDoR9te*mOoVEk-K2`%!wmhpz3-y zpZl6%!KdcHR8D@U*vU!h;@|%n0jep>4-yV%Ui)4~J%eK_Hn2}|wYsfGW#Lb-G3SaoYdHn6 zcl$ikS6oI>)s@Q)lY%vqvuR-Oj&^9+Ja4s_D#*oY<8}?_gPghCgS1W(p%x9>u z7&4~7ejDcnmpt&*t_(JSIz~!&UUAnd!<)U$SAbFZm_XSliu&g>ia5P3LV@3F>IPyu z+IVSbb!E5oGv;v!2WlSb<2#TH#*rDy<5{Q@wpT_T?6*30tSh@CZd5gxt>;WEcLR|b zYje9)G^fb1`tGRNGy|U|60os!r~!XWFKxe5A-;U%zI>n~<)(oR3GOrq{lz3TmHp~Q zL4v5>@jpDFNJ^(2v^0MLcSI`RH(^}ciXRjiJ}Un3ZLBR0`TiJ;_D3{vFn zq(}{*#X`%7Tj&7*(+H=FVHd!pq>eK)b$5<)MZgN>B5PEuc%a%MkWVtC*U^sW%}`G> zxth1`8?i2)3D+?STawU9^9D-b`UIRMuzQ6APv-Wil(Dx;)ZTAHFtEm@5U+6~)Vw=y z`}vzmt}o+)0{^n7ouvY!_6seD(CGrZk8kvd&Y%Qn z+TtLp@ATLE9ScthBwI}e1Jzd!Hr5e-mDPnFr7X~n^pv^89P_}DWPpO3txX>mzyR&? zi7M6nDvS8?!_$0OGF%W)3@!w`1u}jDjuET0W9_KFu)2PB;{hhT!E-d}>rjT`g9jz9 zYRMN5gropGrxY)?ptGyUDp;@^*dCPi$(%&L_;)9tLH83)?Ufj)Mbc$^4#~Fe*glII zkvy(7u-IKnuHQ;+aHH3FG|u=8_&9+2cs-cKfz>%vSNEO+b0$DCJGqzoPA#jr+u)on~2id^-f z1a{2y(E}hD?FHJ?81F4B$*eoaluvMFFQUVDSFXgc0FS{fjKfX4Za-bbKZ7=o*!POo zJOwBai)pEqw|r7e7Jq2J#3>c5?<1;)yaB~kkT{hrF%yssemjrAwB%LW4^gzk)X0l! z$CAM4z>51O6L&yc5b1nW+EZ2&bw}SE!$o!E)mnWYsrhv4Q+v*%TSivXZ*CeM<3ee6 zrho4?23VLn#PNr!`-xzfO?o8oVo^cn``wXD7wKRz!$#yQ@xvSayuhVPQ z+WanWq~}FDT6dnc?Atw&nW1JunQ`M^mTVtNjG*0U01>S(Nq!Zr(KA8AdGfG{j=mzk zWgAfOaKwe&9M$<()<0^_w7)Wwr?G&*^^J_Zr)Zoa_dQ$D@N&x-?HfXe&o#_`j7;t<1eo+x71F{RPvC4-XYqu04TZ9|; z#mya+29g*4SO48lI%RWCTs?yC&O*EXDkv0Wn;U|iHbDiXCNz%<} z%<5}IB!qgh!%xzyERRMbuHkD8w+>=oKSRek{~%qA>5ruJ6%>tnr_89R(xMMJfns%w zYdlzir=s6_w0fO2SlPe3!DN*CcXLvG;2;z6bY<~Tl~qan%BUxDvcr&dV>?t5WR&E8 zR-9$k*g^-XDx!aDHNKmY1or3J7)Zw5&-{almKA%l(mbKaS3D^lJlV&C-zFprgY%ch zpOtw2!kQCT{953zSs%Ivq=C@wCxpA~2^7${X$gXTUdjtmsuYMX<2dx-|Ihk_WTHW*Z8Gja;vw}cMPx+TRu zyW0L%t?;g}bL;>9tG!8>A_|QRc+C~_B&l+3So1G|Ef!DQ@{a0lan~3IKg@)20ZwE1 zms-bztZH^OMhjz(=P|(5=fB$fmN|dW^{$jY{{mJ2_&?WEY8Irgkp1SaDNLy)x9DG}maYQmY&dbiNvc%|Q|_#l-%#Yuv)V$$=sQkGnO zJ4&`!FGwXfa6+?7-JFWz1?`~17WR3&;KVY$dBf7j;)(BAU!ZWx-JPg47jIze*??(f z?MT9Zcpm=1Yjrw(@?W4odULkTlG?D=E6P}{c%^`}Z(~ko8G;t>C6qCNLX3c4d-n!v zEi$wAB}$*!Mx(30tGuT^g?pN}M9(yrZ#Am#4I3dc%O<5A&13mksfMt=wj&)t4frg#{ctMo4&oGR@p0xGu*#W`KOqe^ zh>pW3>V^wS0TX|B4A09fa+GrR9DIf^)$)E_xSEI8X~mb?|yII|EptYfj_bc>`41Hxm@>4O+6GZT32 zDf*ml2jq4PjJ6IQbYgaJnQ|H=30A5Eg`F4fIE;;FzAa$Rf^FJOn**PZq_`L_U?V(5 zdjp%Tm|saz(%J8XgP)c>9P{tU%8t_8Naj|L*P(?}J_>7zLf?sxnY&B`z zsES}T>f-O{+5y(VN9SyjG*RQ6u4s@XJmCQqCuXR-*b&~p<1qTUiSm(zPC!8BP8N_F zM`rMdgay^{SD-;E2pUZwOZX|3wJ0MY!UAUx*-~I~=-!_l%oKSm2TPElo117ENk|n{ z$NaupmjvzBAYpiunrzdCy!MXw*&CUAzyEqdReeAku*T^crG@0PYxEV(faU4E;leBN zQLsu`2Pizd7%ySGIg z;j*B#eiT>R0Pi@SDql7!m*3(UIHFQJhs?YC6oE1ES3GY;Xx;Ghw(0^&9>e8%Ft!;Z z`RkdI7>y{#`!yVRFZJ3?n(q4zmviaA=JlgPYRyxRDjEtx*IF1~{<3D_8A(qu{25?` zMV-4#EYH)#H=3&@h}=FZ2p*j_RRsLbDJJ@WGrnN18U*a(7X&S<e)oO-5xnm=qwS2kCNO>^;i$}9EEtKLwFT*= z%Z{dn&I3)rVr6r!@6E<6aRw9CdZw#6k2CHc8;wSs%qjT9>aB>SThj;0svP`kN`6e* z*+ZjYYAs{_HL%Te)NFbuYVWWRbQ4kVF}agyvUngjtEJ10J6u=GhNTYAbyv*`Fc`jF#;VREK>&SQaamwhQ&Jt{Qn%Hq934WkWH_)V+X1zt z=>dfW=etjJAbk&+D*ud9Mt7j1=o`XMj2&e~6T(%XP|)^30(~8Jb%0JEkw#x+1dz8GrM%J*xAenZO6wqVTlPE>xaR&@@YOTWS=X2s|BzkBD!Q zyPICAq9c__2#mnykAVw zIx_$YTvt`9ZZ{3Zb67b6`wn4U6aU>Pxl@=ow3J2k+Qi~4YMplE!mD+-8K6yS<-Nl zeEgddoXyWsCy-@_3w-&j+W0hq@s+9dg7@>YR$W|ADDZPk zK?-q4U}kR&XAFV$Oy&if88vtKu5ro!FtzaX;lDhmFqb=TOzA6ItnuCj7)(wFm0g7x3n<&T z$11yJws&&nzNC7T{qOiLI0f&V_xdeUN-Fn0h&7q54>tEjaq?T-|&x6i5NhG!IB z50F9~2*GY-fzV~mbkYKz?ye-T^?fx)wT*AsSeL&?mb1@)5f(Ll%uBU1(?kI;jC)H^ zUq%xIl+7JZw<<2o&+krK4&Ifp5`)ChS9NuIHMqms)xjE@+m-~*@MKgn@zJ_Tn6 zUz1)++!$C`BWE@aDXPzpX}us=t>w_9Lkyy3-(DSmVD`>bFpVTBE@E*`@Cj9wW zss(y%Q4i4|Uibj7+C1>?eeYIye~RrJLk!pi21mGAkMxSCrx?VJebMq?@Hrbwakeg= zfm}i zbj1B(_hxczajy)k^}pz{SZ|HKK-dv z{u7x%K1p0^n1G=^b|Iy=FpOskAgT}pbyPHLG^zM=mwdSXI$0T9>vk1 zZd`HiP_uo-68WPrO-N7355mTf4~ys8rfGqkfrmR-{0#aEeWT{Q6-X3-lb$m9Yi8Ky zd2x3%aLbgVYEdVEBYK|FKE#GCU}3SJ*9Lquz@D-6)ioP0_k22V zc#fHqd@i6-QNU(woG+wxaExN(OcOZ829$9em#DBaxm@ynkx+XQIVW(=pyZgJx+ZM< z6Q%5VBl#9WPTY~|3!)`qsxCqIE`PSeo3cUuY5Y5a8Z#aM0O25IyDADbZh;zu z;Lf-oyaiN!wxm8(awv7L%6l|y_r?~aD*uyzBhe6A6?j-oDj(ED#RDEMc+?J%Y& zU6JEb*;Y%Bx@IR`K%YZ~W!jMKq6TMEv9f{ViIe@ivVL!cv$RIig zG_gxQ7Pj!(nkXPbh5}fxw4optaRla%Q=GL6OT(_&zBupo{)Jg8yd|q`8QjJ+={7}M z^(6KR_y8dWgPn7N)0*XwGx_p9$OB_ zD6`4?w}bx=VR>(@jnbRP0@?|YIF&*OVTPnrx2qLJP!p(F_CWNty))HAHIwEzw`SOf zLAFwmjnXk_+au%sH`8oCG#K6IaOCtj@#`Xi7%F>at1htUCxm?4ggvbV#G{D^D0GtV ziGG{hn*31`_D5$K#~GUP3Eb)(mS_`cCuaweDWjlHdO=u0s0xV!h15?xPx+{xVO`!L zWCH7Wn_Y6$Vmp()b4DM>MoJ41hqpO`h`$-EM{Locd6~&v2L)8`N)hY zReAynK!F`T%^FFs*wb|}tFmFo-pwen?G5}kbn9RAfei+V!aFmmxA+m7P%m?xhMk^{i8_h-k z=OrgV^zKW~2S60MkjQk{@XDC{x{@!~Y$q%ro1INCo{|ZM^S$8SHCUyYV%KeM9KzcU zdEi{2OG`n`M>fYN`bmXOvJiQvN*{o^&bXF(L_H3%9G7rwe$E{hMIZ;=ffG(-dt{T+ zGgR%A?EE`qa$1KYpl|6#RsZxGu1^gV$5s0EF+_QXiPwA>1@xp@_$2^qBz^dp_hHym0^nw3DkGhv6Sf(!{D#C$zVsSOoLGEc=o%^F`Yl zC>t{RrMeGPDEq%N_E3JH0@$FND)_8e&zNoQ(52uN(-<*pSGXk&%k&62WahFUI}u|7 zA_L}XTYg;Yc+-*h)tgYUOu5>9yWAZ&jxhJ@QKR_mykfx$vG1U3iWpf=smt#7PCbj7 z!NV6WIT0dg8KD!;c4r69bY*V?dDSBhK#RX~g8V@4xU;a60^GubNmt+=O08B;s|$6B zdhOdBQju2L8;N4ZL|tZgS@Hf_6=Bv1gm{FNn*Q@mGPJ5C8m9CEBOqQ%255m-NMyB~ zRE&K$44Yre$oUUbuSR+@VL84al3eRY5{XKs4ctsWDe00n$T=zNSGxr*WArTd=SLsl zV#E-WehPL1Z>ZU;`KF^QyKD*I)1-=Z^dgJ+k8Vj>+*TRFXMvN3bG{)qYecMe*Py*~ zCi-4^0?OI<1Ow^jEhN+-Av;VNQOZoP-uCCzeWZL>GG`L!0_S(Y^3e`E5@9twKO(z0 z<+3zSEhT1{>$nfr>2lSMisM?g)<8z5ZN-e3VaRe$zd6b9&nW2&dnZ&1;AUf-^6XMp z;?`=_mT;R|zZp?QAzm2!!M=wmH2Fj$1+lU;s<5X7`m}FSDTCnLv~>Is)mnRmkiC6^ zJYK2n>Bb77Q!W1a!fGBcsPy^Q_&y^%BHg&Y;sIKpb|QX0s>pnXX_h>jdE@F$uR2uvthEBPge4(qT89PQO=+X>gY54LU%H z5Nw~xJKieal`eo*ixo&FXY6C>=|gZP+F`s1Wuzufa1FxTxnRc+EDZ<{s?Dgnh6!l! zY+%kE0VeF>P zsAm^+`B?0p{Z_MdCg3C=te@)i-u0eul{|vl*{@bg9A$3pqlkeqOH0|(an}|l))Uk< zT^qWaiDGoA->Z=oHUrA?6n>9O>)x83&21H8=#ha}LRw3Cn5gy{OfcxzqbGs#-Wtfe z=mQM8c5BYS)}S|wmL$l(nggl3xs~nf;~aqy=c^m3D$$sSq61xb=0L*Pr5&SreEO6> zGc|TM!bw5xCO@wy_9m^;$)AKJ>JXIDGNRD)Ar;wI?!Q^-+yPj?J;w)3!{|qoIA3qY-qx|bG>78RdSsIn)czcdaCN}SV0ASgE+$^mnWPAFCwkB z!!)#0PQY&86aC~%+t#1&@wtBrh@5sRr>worwgj%!a@raqc6)ZWBuDVF{-`Z`G;G{p z8qxV^6j)=#M1GobAzlPO>88rYi?k>9TtO-!VS68kR^fkYtK%SUdF|O)-rchBm8SD_ z3HT5r_27no=g$5{>5WSkzECEKnKnf)prMuzG$fa~XVoTZDq8$b7T)cJWwJd#kZ12y zk)^+WRgS)F+5=6#Ho~X@;N_4mxSH3HRZ=7K?{@$iV0_%BFPl!~1BZK@BsZyNhEiA* z6h$<8A4xBj;9ypDOyG-0y+sBPq^*PUeZ@CH%Q&YI-sg@l!9Q|)`N?5vgESNSpEc4rk>$3CI?Oz6JLU(^LbDFKG;EY7MT?q`Od~o#Hqchx2ui) zgGHjfXinbIKXrFbh!u!5+=A7V;?B3dvyhTJ*a=wR=A9d?(I$051di8{E_KjJzD^>- zjmYi4ev9z85zK&ui#UKK!apS3`DExPQ8s{LWCRnH8o{|fC+XcUAC=E}uiO+j5yOME z*p3AKUQp1EL;G~ISd$#7LMxrWBH+gFF9@l>6v_KMU!1BNputrq@t60pBfiQRitS^z z%XViQJ!Wb{7(XiTfn>^U=!z?~r?t`$q+rL-d;=aV_2?n;yZF?ZOxb$SQDlwp zb_bt$@?euf*x6U3PBs3^ru3i)JK1Ja9lMN#njEhMx?%CetKF~UZVVc!}u-D0GK9I>w%cu)W7Xya;zr*x;lgSET#TeYaBUys2ufA^~gZ` zNlrM+k?ljREjV7r4MZ1f*_|$cB81N#eJO z%Q}t0Lqxf})?^ZSGD5*iOpD6?U`aMM?A+clR>$^r5iih^!6 zANRrRg1@G|8oA)g2S$lpDqh*5A~u*WTcZ5T~l@9oui;c-=t zM?22HzSD<(YvNP-8A!sLlB?2Cx+X9dg{t9^@ScA>;yIFshz#JDFJ9f3XUwH^K8`_# zn3+r1mEVqumjUVOqJFkqj1!Yk3j7+O@!|pvR9KfJ6j&$g@8lT(*Ry%I7ayg0hdRvu z*kgzD3r4y@kw5tH&G&2#AgXetG2<`!Y5y(G`F_Q#=<&L@Pv(Ff=*)zr3b+a#&%6GR z!E-`U%9RPbtPo;(`1pC?VcG4K>S9CT-cBd+Qs><%1!^~!8ixe1 z=%wfz$N{Y+HdERFMs#PBO78GmL|28d0O-l5g;7DJr+H&8rhU)td9q@v&0*8r^ljhV zeGolm*rJBwmt36yRvY#YAmk_JR3y+$jQgUpmByN9XV15Q1Tm`9EHk+DXfM|{g#1!D zh{db%V(Uby#@|RYDs?a@5FB2kQL$?y1=+Nlr5ZJH{-Ong^FFawaSF9?mMk4bEgz!m zcUSKy@(b=4(Rp{=|255M2xR7H%>b?hAu&PTvnDRL+`1vskxLIT;B5KBKKJ&M)iA6L zc5_2hLtq6e;Kr0q<#ftPy3G~afKV+4Rc8>UB!8X@jY=*Ys}`imwi6Y%{eHusLS^({ z9~9r+05m<74oc=_j6ha6CGUia*&ex;rp z$cn4r2Al`P6sBHCTQ9fNgGKU~#TP?wSwrFAhNsY6I@|E8TwYydb;8{TNiA&dDkZ_Q3E4dlA!@!7sSMUs;xV1 zixdM9L(c*^MGBy@_*uV(Z8N_V-xu%WRcaO^jJ%CH-)_%kC%K&ib9$VN>P;e_t?JBK z1nJ3L(swpFt~JMp3#!SU{fri~B5y;?_Zuz>Sp2s?$mYZ?wQ))_NgIz=PX$Q<2mP~c zSo6ceYWO1JZts~7)Y=Ned()e>sH#+Y^n5#u8T*J9d$=r95%FBRWmk7>c_M(g?=^8C2=#H48PktkjcTAokjc>xuZ{EuMu4L13Bn8|D_SHR}OAW zH9uWVxfm#k&m#VCI!2J--|q-nOSCc^@*m*axpeh&St~rPs?mS_-qK3`bX{dr?Lv;2MtZi^^2$VmI*>5EQ%^TPKP zJuu}rKVN&cZn!cseix<}_vH^}r?f|J0J5d4;syYgwcRJ^Uzd4|5K!+Sp#xh&TyPgm zCXY<#zG6anYUjRV|L7ypf5SX7?L;Y^nyx_r98U3}0rvcDfm;fH?e`j@(mWxEJya4} zCxC1@`t{r?+zo(Urri8si~KW3&y4k`S86+B6gi3By}}TA|6qQ=rOj10o0#MFKSsp zJ;t+)&~lV<-Z6U7=PzABksdKON42w{RLet%aKEgpD?9Gb=_3m1seJGkyszhd+wdb} zGJn_bEuV|~d~gpMJtd^Cr{Izgj%vRjv=-IFS^Xh#wzfN14iw1~5#VLmrmf>d}WdtnyxC zl)@>q6J3ww3c2;ItSsx? z{;a6%rDx}}Fo zFFCeW@!W0SNzfF1X8)UZ716hf`vSL9coY&6jaQG^BW>fg)Oqkv_1kTNCGf(k{x*^; zUh(ODu(CJ_8XV@&v3*4tlq%7LQRuMruZL?1L7iJHbjTFvTp4k|5&g0DIM83SO;Mle z?9zMoz6djWRt>l?jiCdT{`bwvQ^KOOi|sk;_5t-s#L)QhR@>?D?xRap*1qYB4^*0a z4OG>NSk|<;t;w{0G@4sI`!XK;tm+>otUX&MbgQ;%^ECJKdpW=74L_f}QB*$OQu0U8 zUF3PR^pKe}5w8p%bU}9aQUWr|Pu$wVf!Q^o@_{tM$$%};?CY$`SE0JVTr$t0#lP57 zZtt^ZE1sT8H#*@K5mG+}sZXTp)7ApN)%~>D>P|Y40CXtKR~Zv9Urvu%rV2swwJ7jT z_Gj!bm+mbQBhR8}Ca_%4l4mSPw>BRyc25E_9v-x=41DT1UM~u4^0d%oS(>iyC?B_2 zZ6q7=0gBgUKlubB#`fVk3q#6~@BSGxcpPli8C(1N@nPOFDkR@bPg^*A(@GuaElIt&@?+|7&h)k8Oho*d{^oh9 zQG9_WI|Drtp|@<23L7)ed@~niqXE#Zkw~IrnflO=vT4H)*=`tQ^q5k_D4<%JulTA$ z=~$6fh4nhD-|y%+IU{YV7E?V!kvBOOf)w8v;Fz8t{9uY)2B8>mdwyHCJDwiHV^YVN zJX+wZ(z8TUXU2z**d13mW-?Q}1kHiIse+g;io=&wNi_{L$Mv0nwJoI;tJTSorK90o zbiaWJD3CDw`)2(ZtGY35mg3vei!u5hVUu43g`}ENYEfR)q3wPm@1BKiNWx>POpgWbR>+whcg~K%}0JYU;I_pW(EM! zNQLn@ABJg|t}$S`7ZVlD#MjJQ{(g*DL(6%KV^argy=?N zBQOmieuG*-r6fLbthi@ATGT&oVI~79>!8B$)Sb)qOWaQZbm;buo3cM*dplNT(=gKo zy_?B{UTAeM)qt%^+R!d&7|@>4@AFJq@bpJyY8OoS$Rl&Vb48iYEgf>0bS~fFe!C>h zGvi&KZbeZ7K6J9$vi7mmb(psy7IYggTb1fr!_#PBCSLY&;{td1VP9|ll2C4g7P%(lW4|?{c!tlN0nuN#WnQCs-lxh|A(mf3 z(q4-Sv|K#isyR@OiE55WstBMi-x^uaP6~sF@4@yWrdRO$yM1BpwT&9hYjnc2MGN`9 zws+VVToLFXI_`pe@bJNL;67hr{!BhdrYL_qBizYePa9I2uLa58+8Kmbqd|z)=jlcTIwZLTpX2y`25tr`Kq*M?F*`xmk=VRjQij~Dqxz)4@*RL zA0*APev$HzIR$jf$xl}GIJe7ka?J0$N9(@4Oq9@9h{}sIni8it^Y0FJyz2UaKM^=7 z8Si?;@s>rXAOsOG(4J9=0|Cp711R*=UA*nI>MJL4Q+d~xX4$cfV{DJ)TH_RG_42ptwS?Z*r$4;O@?Uxa^b$LolYfB{np)D|+k7kZ zJx_V5iv?9LrEh?&5Po|A0xTj7j(Yrsh!W7!8DWFK{Z)jFV$N4KJ*yW3)_iYG276cG zMy@2IbJnvUHvNEOJ816crl*9vM*-SnbG5_LPrk9d6s)o7m(AW9$6x;}d=jy2PcJ>ZAtCP%v^+_UAK0; zo38fm*=jtxaZ38<{7LFIe}>YHmPN;=jh3b2=QNAA8R$V}Va)MSC1=J1Sow{r>mQ%< z6%F8Tr=@mE?9_LF8SofJnWjkeST&cvvg2^?*~XcoqwVHFT(;SBzx>>;X1D`lylnL` zHp;{Ww&hzKHsKb++l^Nah@63$4ZQ);v%RL(9V3eG{5^A{8h55u>W9RqrpLrt^h?J_ zkHXBZ+*_phfNOFNIX56Yv6h@W?<3e(Su&W~%WY5j^`8%YbCF!(-cFSqkxw$Om+a6D z_QA`!Se*~WuiIYzkBVMIp>zF@M^|5ZStH|)-RGVOq_0d~-=F+V+x~DCQc_VOfP2ON zU+?ov^4A@@R~Z`F4{Qq0^trj_eJFTkkJ#T|xBiUMll7E85OiL>9)7rm@9MlR{33X@ zSUK^#68-RVs<~gEE){0g$LMPKa-F8J7tXlFaQojMuh-utA+HCo|7u+!!WFFQA!x8e)} z4FB5@5fgqZ@c&x{MgOl=N{WGB)6vt}--SU?4AG{~z^~2lmVsX$WwWv!!L#;bxjmB1uR=#LiS42=#+A%7!p;zk(d=6Ra!zl8jchkF^bAsjtC$*@zlNGe(|_#(~6Ol*f6GXFtaCDY;PV*#o9Ib$)Dx&=rO5tK$O7ob1LR^z&O7+M z(Xv<=L<|@_$TXkP^rI5Fbm?)VD%Zk$1BQpeus2rER$x6m3B|5PaCenK6w}9eLVjjI( znz-O}#}kTvp@_NQe1e8d=z!&hCLKc-Eq~2|Mq-DJjrP`7q%28SyOvRycpb|!4iG0l zM7c|=GL-d}+9_V#KGKwBY;du4#T45(nRcY0Rr?$R7zeg5NrEczmZL8uPcZSZuo35y z;3glANbLFSh1k*i#61)!G1aAOs^YWA>c8R4Z_hAPSl4o6>c|XL8?M9_%x{$M{C||a z1yoy6(=J@JIK_*#6e#WzoZ{Nx?h-sei+iEPwYUUnahKpuacQ79!QG*_LvQ-ZcmIFA z-?f#slD+rL-ZNWr@|>BI8JgCwUxvUg49#EL68+NrLjAHtr2<&r(iN~;v2M|ku)a+i zPGw0Irgt~kZ<(?zQH(_H3tyMPEd0PMl%%1=UJ&Dw%p;Yaq>}`Q_lS@Es*+;DX#8f0 z$=~EI`vMVDncSaTK3$ExbkJG+Q?xxQuNvpUIuQzkPewe71Equvs-6 z$E-#iO(IG%hgC*WO02?!!}Oksg>{|@owbl9h3S<>TmFqqL^-H@v!YjDoK1v(+poMye;)Z%gGs)rP(dSXi8Ou3G1Ecd|1YS12e8;UW zV4l92!I!qko6PUd3lyl}Znu-;u}mvSI|8&?$7U>~Gp6gNo7PLPAF|(&wzB)MN2J82 zNR3d8AhDK`OtLJL{;(f3fC>K+UTNvOyQS(8s&Q@jxtDPs;UrJ?%VE#cF$w(Oc;+|{ zeyZbd+?vyYFK4of%-S4hG*`Hq{;W+KfHc}Hvx``@qIpmr3LlEki_AqGQ69-t<4~_t zdkEohX}x?CP1r9hpPLu9K{1dR`#bY6izh2q_;C%qmAURWcst~mc-wYce;#IhVLZn% z&GDs@Z`Nzpzw(Qdj}y3&qA~0k{n+SQ_71gjZ*-Ow4@rbu1U^X+S*_ zJ>4dkn~4+YwJJJMS|z$;xePgLSr3^Z`99fc`SysbNRFsiMuIkLr6IZ&e3m!d6*Zf4 z#d9rl5wgos4V)AawNb3m2c}@CSKqp_GG8i2N~QrzXHxrxo+!7t@RQoZa}Tc8P_dfm zdhjgtV=SZ1^BwZptkxKjVb`_f(^rg5^hs|;72OmUGXyg>Q?#=A`mZ;2&rIp>-~I*$ zBob!2&}`Mx82n0NNv6p0kt(KtPvB9wmtUc9K%yUxCHrMhWp80}pbu%i1&7}9qntw_ z)`RQsQ6AVGg9Fn7e=E!V(OL1VwJM~wX(QaC)=OtyWLAiw0SfK?9k5B$HMPwm1;(U z)jzy@mYr*yZ&$9snXQNvo~p8oxg&iS>u2luZ!;4{R^WcRr%O9POo)%tk@7W|!I9MI zcxAm|%PieO-wA#)gJuY69B&|T^sV>byHegdAHF{Rx*T6`SxsA=>t3`r3KMy!#h`tq z?XAUsG%;WQaTc<)xHNm+^xJN+ti93e_r3pve`BeC8N?ylVfZ@n%I5bcElTZ$ORg{sBLp2POJ2 zmZ_9vvxu?#x2#_5@HX2p%*!5G+7ON5d9ocf`8usNL$bbSiS3|_nzpUFt{IWl9{iL| zjbh{!G8X=r{;_#0@-cbasr7iHbMDclZJ?v*wzOw@#vyig-e>1JyW`m7@esF)lFSL} zWU`07e{d9c*vbDwfXge&_h88J#}Sz)^!NK^W8XNhs@;z6$Ft`K`1S$(_w{za0#2sB z&Z=GaoP>FX2_f<}jNBacDEy#<%WuWGzn*M?V=GAa+{FET@Ox3OtUI4G;J9H-LAg%5T7ZxNZ9s>3eaj2T;XWP1G=R& z*rWUj$^-$L-ra*AZZh$I`?ldYQ}r}stM5SDk!eDwbGMDMQ?JSHzo2&DV_UqoT}h?6 ziU^(~S+{z4uY=lq!Vn((na0neP^y@fe31P@l)>L-M}z7!DS;eK(k1pL!C#Y=LLrGOCcs?j%eay4 zkE2P^Px>cd@?VfQYYoAR?+3$q^SddlFjm6k-zr;JyUZbrE@Opv%ygq5zkgo)L+>Ru zHacH)1l;`C^u!1;|92Nv>E&DkyY78$T53v3h*7FE)@&6a92mA}w8`5wpN=r+byIO&0{sHwhXpH~O#LM-c(4Uw4 zpV0sR1n;v9hhh)7AkKK;7?n3+r0?dtO(pj(zOBqJa<#?E**s7W=q_*@YH*rPW z51)HiBX;Uz1qs z(?PbkzO|5Z8jF_BwkX`J1b57(AHJRbI5^>apL$T@YZjL~sL%5BnQ`d!qH*Jt&u{69|Cm7S1^(aN&P{6GW7bZTaOoPBJ~*i z(UIiUClMo0!N#?Hzr{;34SH@5F*!JadpiH^q39ctA>)DwIjgoHUA7TO!J|27x6RqJ zRRuzxbv*G~q(XaavN@!$ul&74pi&d{&RLv6dXl~|>}Hw+wDrylrMb<+_fy@~s%#te z)xa9gmW+zQk1waDeOe~SNK+N96L|T8E;Cn$+1X)BcycsYOt&~>vEUw7jNl=LF_6{u z%ge@ybW3(9MX~izOefQs{*l|e0`)rxv$IYMN!z?6)-Cq z>UJU5t=*4HQ}`+TD>jXedQXZ=x+Dh0M|J;$U5 zar(Kx&m_#2|MAYhA||rew{{0+YU-8lIIWs9J=dE)j6qJreEU8y!Br#uCy1GRoq)Z~ z1}#?ehe=}Q(cCo#kX7(ES>VwJn(w3wgPyBFBYtI{Ka*WOZ^ZDX8+GXaLuqL=^nR*7 z5n@h7rJwwVTh3(jB*iL3wVb+!&Dp*I&JopV%OhjyiPeL8hU6cK%9Z^_OU&iL;ZdL{ zd4^h2>xG%vIbD~=I;}{){TJTv+o;6HIY|@vfo&os@u?!rXqjW8CBg870ZM|5t<16N z;xPrxG!2Dp93!-byieVkn9Bzd#8D)dppL>Q>oep`5L!^q+>RBp6K*Y{Yz-XtQ|X!L9t zO%pkP{6;F36by6)u_rDK%$?1K7Y$SBVEGxGO^^T5(OwD%_upWstMk&KjE54UP8;$X zq9~x*4JN$ISx5(*p^4;8HQNp<>T(HL+XNt4+Q{kB^&l~D-jNhIC;6_-r;C5YNhFb{ zXS0bvnHimNE0Bpl&8V{Vv9NKUNkXJo|9O~~K%1yVv?Zz;b7M5>pTIDJwPi#SOlLuT z)8u`LHeDiO>Zz6^xxQ=z-qB61@=iN`Osp6JJHCZtdT`zXalf+IE8$`V9ikJM8En7Z zd*>djq)+GaXA(|~cEL!ffkdQ6ljv);&@zO-)Tm-QB!p4hn55Nf*T$LL_{MF&VO;y_A|eY zS<1}qx>y~BCgy5Nj*25fb%HCeb;)qsTW98kq_+MIx(I;!;j!t`f``Rb!VRxj&O#mO z8ROfomsT@hP0napr%K6XH=>^%px%F99KawiL!z-)z_VuZ)~VE2Cj{{p`%{)S$Y2(; zIrIL}ONw_ws%AfTIp+VKo%-`tglQqF+gmfvL3=qPU)?0h@8N#PL#9j>*Ye~_eOO55 zoMk@ib=V%ETBV49Jv^MUr_JT}Tyz<!M zX_?gbq}y#BDZ>=M@HJi3u|B32ULz1qb!)rb*|(Po(2+qUUbisPLB7CccoMO5CmA`pjw2_&k@( z+lchYWgwzqZofqpF!@*bBt?U_`{S)tq`C}Ng}&<*6anRO_(ZqMc}dyZQe zI$AAs$7a!YN(@5NAV7k!%6NIfymze|LzSp@z8WYTbR~tDWw8Cy+2!n!W$2AEYe|!h zG|1(D{#|!Usk&tD-a$GjqgoDEl%T~KRv@Z&L)d}=TA;7Mye;N^Ug*FgpCjsEdyR#Q zyde0>mDq+$@^uJ?lB0!0Xv@tzd+Ek!Ew@-=S~jb{D{$l8W+hx%9i_#U7FN?^?ix$w zjGt4-SEAPYKWqb>LIDl*;E3{8s;o)98>YiwlB8F1HcJEQVLy6C|T z_X4~?Pch@U2!}gt)F$2b4u|jCKitP zY=PuyY5EOEEcev2^L&EUv?O7hDmrYB#;9!rdaQ$^PN5PV`O@p#xr}Ix(ew@MIIrVw zy0xV5NT|1bddIIomh>He<{qtC>3w$K{f^}ypSI>L(B)azv7;AN9vf=Ex8^e^a+KK$ zka3*OJ3ps9JU!L3nm`Vp@F*E^C>s%?<#&JS|C;LdXlg<4kTfnDPfqdUF#Q&r+8b6l zexPHE|tokKQc-Ig@7rl(>o7gd<- zQgcjNG%Sqb3pI?W6~(!Netb>M*p+^=*t;TLmH2~e7WZB z2@33|@foc3HW?|NH?On62{UY2CTc*K&4mg?B6{_rusNYzP=sZwT<*BWmxe309igyNAXeTJcdP3U--=Ag#GEHF97R%(<`J+V<1G>gOLc4@vMyt|}$??)jKxE0CdMw>}R=;Z$Ra)p^ zgRK7mt+X^|3o*y+pUE`XKdTLUOX!tE$5vr0{6R$^3lp7xPWM`AZ#B||EyI2>qp5N% zby&PhDME$a*mJF*uRC6}ZU5r|BtZ@BYj6inDvT<)#|IQa3M8ltWv>xxl+LG*;R3q) zcb-mZ>9y^D3HffSgn>7P$PD6*E;Q3!gL$Q165rHZ2F;3LEZGq%zN5jC^V*B`_Azt}x%aE=>T zjV$8$#)etSkfh<`Ca<0N+N1@G-$3p=IPguEIB}uME?!)i-%1~K3yU6#sMM?azkxCWHt)}BP#GCCN=*|9Jm;y67t_$tq?x ztB@|CKk`_5MeW5)(`8r~T6FzqoKmChj|;_aWwG6737Wfo&gpGI5e}}6?LB<_2muLN z4|Ihw$=4fx;KnD34V^-ZBF`8(BYDfI@Vy!db|y2r;p$~%yYZJwqqqbUXZ{$y5mSrC z{ULh$WG}fV2DV9Ue$P{0j0dJSH^gubYF?0N`@C~O#CJHy3bj+Q^qWOuzvosQ8*oxa zc@duKal75Jbop9j(k>U@ge&t+fj-GEq0WJk7k2{VFp|g$s>qD+ZZt-mK+9_Z68VvA zS|2a3Bkg%+Sv7WcE2&6=U)2_N6E)`;ugX|)|ukym!&^XqQyn7 zeT}f}@RvS_L9S^0R}wJCXH(Y%4?|O5;ce)gE*F~eJxcg!*Gl9ZEl9^1cD-K1J`p#X z^zuDwYzmAkBy(&Zpmydxour&=_~tz$KkcxpCT8M?<7msBhx(@pwelBvOS8RHfRmWa zgg1x%}AWhmyn;tv*ilbVWc|~iWdR=Sk z@g8a(W|Mb5D)rlOB~_GEzOS1fwwn-n2*bfPk?*OOvJ|j2b5BaS#nU-99-gSl%;?`1 zZAHJ@;JQ~%nOYld2LZp=cKQW+8c`LMc?(g5IR!0*FJzCQm>K?|@3pyY=zQKZ@HR#Y^G3ANf*4)V(7z8U+ljbak}6NqzN8j#`r*&>SH*`xzZ^=l zm3#<{PbL``;f71EJ3ci+m?X3F>VvwIT|b^finN69em_0;c$U)tpN4>c+`9iY1n>$8 zaR2)rpXc9BzrXH1E$j63uVLlt?CxS|p%k1X_XY%%z;Yunhk;0JwQ*1cZ2u|N8v?mXAsDCW&zenNJbhmK(N6SBEOv9;b z2SWH&d3l5YG@J@nb~d(d2qpQsu{foj!Okw4AIvSSXn6nHY!LI2vU77)vvQGkcKqP% z^mmUCPT2pGIp(k(7Dum`GPffH-?c@q7@esg+oh(A2oozsqi%S<@bY!w^DNXy%)`DX zq)A^56slNRC*=3kq?)V1V1>>2+35%}NrDLaLa&$LJtYYX*<2)?e)2h>G7I6F*mAx5T9Cmu7NB8JlK~+1`rQyBE`_H-4*y- z2+xqkmch94WueX{nS3C-`KjyNW}?<%ekqsE9c%)Zr}C6T$ECk+QDz29*^XNIa< zZ1A6})HDc0-dcKyVP}4uQ>n29<=Jw5IV=S~nW^crm0BZd1MDX(orthy01Pv(h5+bC z2UDWG_?U>x#grKE;{2?P56IF&tkH^&vhj*P{uMk;Z_E)s*k9of%$NUv@8VE>dRHEy zxG-a)^942!X`^_ggM3hz{h#Zz2373&JNX6UHneVj2@nz73)&^3dg)cdaH*kOE;E2E zk|k9WO@@6jw`sx>ldPam1C8gIq)qn$la8+~vQ9sW>-!vsVt(_F2R?ftr{yI=_>L@V z)GBpR|oP{s=XCu>QTkXg~1E zw4tJK4t%@>j-}xNp&O`ufku%ou^Y6yZ83oJSuxo+IQT+(?_OTmSp+$RFI7kmjZA%P zN7=ePj|6vHQTDaa?pIioxqq`jNEIh=4r%pk0BryBL-c*Pp6mHR?7K zg@X)6U;j&syML?me_zP89!LJ)z1H;2$g-8x^Cl2;ZAz6wY)G&}&Fhqqjh|g%6!=!ewzyGa-BL?}P z!gFqJsU>8s_HdbqESc;yD{{mc9+@*PoEfzKskEo}x$!2eF=IwYy``zUwT~Y|8>ywq zVsD*72Cbj%1w2~c`u1kf+8f=HLIz-&qAwoM*oLM4g#a-IT_`4vFckAycQ{r&EZiJ9 zTm|LVn^Kwv2@qX_GDb~25QDf^SO#Fx8vLRaTQZ{f%P-{km|tv?GI9V(vllD`a10os z3Wh|Jlui0fi@;utf6%O%P#z^uarI6 z%w{t@3fzg?yNK-TVI|sj2%jkSAs8zPT5doCt+7`r>!zhF+pc3_`~OwyS&lS<+s`I` z4ayDtuY)!r z+%_Gi{C%)LD!raXv0kZ0it{4sO6k~V=QK&btBZ}&fq_r0I|C01i-&6j7zh($P1bmv zdGVNAlOK(yk^Y{0j23YrBjs+@Du|CsN+%s6hO=3Clqk_rGV`)0Fhliw4>b@m669DS>LZ$Tf`2i7FL`JUQzkTo#*0dZV{dvdE3=i|b6ejub_qW4L}FVQf_ z1zQC15zFSjLP4Awltf!OP{vk&)KPz;MPveE7vH*i!ycA>9826I)W5MKSQ^;uOjSUZ zD}@d8a{pNw9qkxo8vol-In<4Y!JURTvd%JSus@dCSRn#zq&FS=GmDyAJ@T(Gyl8tx z5Xf@qD_(Ct9!M_UgRNSVEK&24rzSWQP2-Y>vDAbiiVOho^KK^eYfv=8_>y2oOA9em!y%3UqcdPK(Ef9I{z;fH zU?&{)1`**!buh#OS7_HVL$g7pcORae9`CMhVbl zqk`ZLAC-14gBW7|VqZ|*DB!55c|}T~NnQnsqIjSLmk+`;_df~4=`};XFvH8e^qQJK z$VX^<+2oKXRZezW{qxeX=$K|n2VW7X{RlK$OH2YGZZuEvtHPs960rb1s&uCQ@DFL zxEDdV!hz5IsksZ0kOg3qo8->(g6PKg-9ZuH?k)N;>j!b^rV7JGYs97ZVH4iu{m#89 zkg_(zFpw$yCRu7ZZF&(|0E?EE63tS7P>C3%7ShID){GYZ8Kd;8fc2#V z;uKZ2YuiVGwaT{yoIxA2%PjS>0G63Ehye7|!8v)JmXgHb7Dfrbsc%$rjE{+|w^+7C zazdiOB`8M&&1J&Au>R0^!OGAhXT;Or(jXBBbR(EW*Zs-~a@BDT*W{8j)At46TodG7 zqe?0cGGM@R2@x94O2on9-cQc1?fWWbj5}H0_CWBL2E7`h(QF$Hjs;qs@>gmF70VBS zWnZp#D*e~*1)(KuD*sWDzNdf1X@%6H)mO8ukJ$TK1_L%}P;J_t4Qnje8d#?nI%v&3 z8K-09@5>7%=O4GgjE7kirdFmY?L?FN8`3~e9Y5aQ(NcOF-j0&PZyK8X{NrQVD*Se$ z!G4BD9UX&m%Q_vda)1tY4%3x=cw2(=!MuwcV2#jF4Dtc!P_B=F3{wAw3{>!!kYDM6 zgZ=4tF=#nRkmr_ks4S~Eb6+J8oHOLr-dq5wZ^)yFpcX0ox~x#{#_z0{@iD9;86z>^ zpN_jqQlO1t=(fvPAn>v{tC<@)@hf^^T&S=!-!Q7qCjAs6Nq;5F8P43M6powr%i!Vc zANbMXaEu^K;0wAXeTj#>jd-BlX_m;yfs%?lcD7-&u@|mVk0!Id7UDXNd9CqZKbzyu ze}6x#%dMRmOH~;sW^#z1dM4sw!c{y$D{Uq=$}$FFzXfP3%9`qgZN+Doz7FCCJct%o^tnh{MDrmN=bd0mty&nHTU~gHiwH!T$CbcZYDW8~aX&5olw%zlC20 z(30Y6$^rf8Y`H{1OKCjP%t;21o)Zkr*@;1*1p@5eT}

f*C8G6g5H+K3;8hTCEtd>_(y)QP$?qf%xj#KsJfrVTK_;;KVPgr zVG|qMpT=81->$E%?2LaZtN(n%{_M)Y_9p@Q^ELb0`d5VY`YwKL`#V_qPY6p$MqE-@ zlUm8yz}DEn(OBt&jWmstwSld(9s@w>`zLw!C+!E#!1_Bk_J@l4pGW$miB8zU)YQb$ z#Ma2fiBJomXHH1xY;NLgKuBk2190Rbq%$_Lb~b>fdv5`-*?RppaCEjXur>z#)lWI` zzd3CIP|ojY;@>)L0c?qWhjGwage;5zU3Gw^Ix`1ApB%udvM_V}T>l%O`?FW%31)TL`<+V^HH+wF@P@;#@y41sH2V$Xi&pXwuC$@ha8*RAw03NhU^|$?S{hmtvPPD)^KmQQ`Lz9cJnH~C~QJtDBkdPD! zpJ@dpj@=F(3n75?fY;O$&~zRFXOOg(6Y-1}r?h3Y+%RbsQK!yfG0$;oh__OK?>R6Z z?hPaem_YIx5Bzg9zuv#so65-gm%;oii1>4iymGOB4yWIS*KZX)|7{%pgwo7^7lQ{p zN*X3c7C?m$2VenEg#V`+Jb)wqomK|a8~qJSb1?l?4gL>S8PMl$K*Hf~Y%-vj z=r3$C>u;RzUlH`Lpy&01{}@{TEbL+X4SE0G0l5 z*&iu#6gyCG`%g#P54CD%GW6V*AH~m4+E>j^-A->lj7o0h9c3uPo*C;6BuM9!>MM_P z`l8^Gt_x7DP!i8!^XD4ixD&K~`htQMSG)^U?V5ibUH!wLN~CzII@f2>mbZ6y$F}_J9%B#0Uj_V>8-Y1Iw{| z>1$nphY68|!9#t$is)i}LCc`nLxlZfdi&8qc?O0VmzNG9DjjBDL89Yz{8wX-%9P3j-TAc8?x?Ai%HPIfg$6*f|6k z=bJAb*cucwG*X1GQ;$9>l|gNUJhtD~OD%|rFZ5kc50M}yt&t)=E5h#o zGCDU>f{;TS^y#@52wDJQ>1$GC6F`SA=r9l{AxJ)K3vdg{Faac61d?FIKH#<4{%0br zgm*o?0F5b2^W5syN^CzxWd=aH$(miqDqGziXJJw z&bt7Iu&z%A$lW7Bu+)77Fk}gziBf@aRl3b{*WIfQ=$os|Z{hrTpZT_yg}-=;8QL}g z?<<3Vo(cC5NBAkEW|^Cw^TBnkcXp-3*c)@lUs*md1II{$lgzDqo>>yuqk;~h;~Ua{ zr32zGjvH`pGWA84WCZi1vV5vqh` zne*@pNzRPYDn2Ppsk0Fp8BLS%vzuCP)DYp~`3Jp0HcLvG4E_%oP9`JG865W=tM1Oh z!DI_A2P(<_xi{0(85_%y2g(gMS+NX^26qgPHAAQ;6ia~z%6?>-X*3=s(5AavW22tB zs!g-=4lj*KB1sJr3i(S@I*u&{TuobY{Q+BH2OpXeQjT#E@8YH@tyJa&G;XHE)k9jn z_Oug@*Ltw~5~6zvoAriFC|T)9{8b#zju#Rq+yg$_k3xGzQe#DXx_%SexTJB61%rIZ zj5iI{X)&zHxS8j544NDRm%AB>Hz^~&E>v2%eIfp20=jciPQrAAv}sKO7jK9wLsNOt zVQkMaNmb38tlpoCMYQYUvC*W6nd5OaNbjG#8Q)^hfnC^IGHY6k@m1A{Hv>Bzd(MeA zFV59I`SW%x5CKYeLsIL0NK;b}I=)pOY<2ZCLwi4(6@-P{xLc%Y!e9sU%Fe|AhK1Nl zZ0RSbh*KT9m5~Ec2AJdy^?Po~y2R36tCY62NEuMTQk9EnDEcFuI(T3H#R4K}k$ zHraBl80y;(xxtAOy68HvdtN0KUFlykC;g+~*V8;!o~TJIc(i!bfXa#|!=;|yLe{yV zi)wu3YN;(}MwM`iF2t5>^tx)IcUEX5KaFY5YIgkLDQtjcrwUz~w;5|vi>gX{!YKtO zj4e1esnTiI=@6O|b5t03DV*60|LqMqdB*C;^+E=>VyDe7_hG&^>DcF*F8MU`bB1CH z>RHXDVg8@2wm)n=Z?^Fw+@oBQ(NdC09+$q2$JLB{$s$$%W$ruga5pNh2|3 zWPuNt;_aMga&#j2YooR3$*f+>tI~;ed}CPeIdfif)6t!;a+q(_i)V5`5bJ_m?w50c z?7@LiT!OVbyFv>B%k}oDqJRGke{+$%^tDoW4s_V_!;keqFXT{60%K}9LV})xJ56$j zJjNMfodAY|WL|^CAX<`n_qqU%t4>Lu?8D7cBTsT$&y}VlbN}>N_qt{m@em!h04jE- z`=SNuxITpV#(<;n>isuHo{HJ`K4?vJ}kX;kwr^n-?3N?KO7 zmtZZiLU(1q6mNaIRKu~$tqAuHLmh~V3Ge8iXM%yD^`-9^&Ncn z!JE?4V01ypQedb>ZA!$c*J-9!&b=^G=?BUb&OEKdb~m%FqA?|zaK*-WNnD7vf~xmb zVMJUdd3feg{9KK3UvZ4*ss2K2f+CbseDkJo%hG#;Y923b@FjmcA=y zwL^2JBS`J|J|liOKU-JAODPwj8~c7INMt@-sGN)SVg_g zK_<#W8cO6kl`x;?AqK?Ir~Akd+JSpcmg~1I7c=`^B(jgxqiP_FjbVBo*4htTFSq@h zJ1(vsF|h=hx73f8u9qvGYkj@B#mfd}S?Ii0P%V8^r}x_R7iIy>(k-qo*uoHY^{O7+=96KZCSSgfbE$qi zE_vbo#F3}nM{iXR^05sbvlbJVq3nA$FGU5vSnkIe@->10!`b$ z(8wh1sVgbA&YMjZ$*U^E0voH%*JyDylK}fJ%Xo{8G#OSP*NdtaZovOkvSOL~Vv%>* z^I76aIytWmC>R2{jmjL|ZllH+gT$$aT285sPsoEZTkxQ_QFB;$Fa6lgiA}c}Gc|qf zV_Je@4?(Do2v1f?g#G(n2lCHrMO(m2kCw6%2HKy7oF+^7GveMm=yh<1zL8F{F5^xjoBAQpfiZ`6S!2E3oZ<+6>FP2x zsvXXAvjH3CA{a2O&D0)X67@rttYKA#>U|;^%VEA>W!%+swo%HhV1I8;btA=!F3J0K zDi|{!gwK%R;5ky;X&Cs!JY0qh?`7xo#=l0NT0>RNIPqZhDcTWTEQofXjR!hosLJ| z)(_cN!UKkq-hR>Ja6;5vf!{6(b7L_vDp&K5D~%sEc+@?J=}5V`G;Kkeq267mS;;|$ zttT8|rx_c^cQlu6%ck4?*r8p>K_cB6sV6PDJw|k3-|Fi|@)$AZg}Ld#l$o5H@QpzC ze?&<+TEAUxTCRcyOQz!yyo9<>{jS!L7lFBl1wOo;z-=HGTGX8wMlnP=r{3F6VC5}r z`PgRnTONR(+$tu3+2ez_@igW%>Fqle5w zOkh)+mZFkYGwLi?34^m^|Mqxr;*lzbDM8I(>9E7jcF0ah>$(M%1yhuU?SieQSh$mk z@+($*89UdOQN~WEjP@q2!D2_M=&_3%)7uJ#YW&^(qC13eKNb%3+$RD)?5hrI*`p|> zi-e)%bGIgb1eJ10@=rI<^=BO_qQRu|1|Kw^ub`^h)jy}&r4A|Y^hVsczSD6uaHS>&9n*ik}QU}9jVP}TG9$^Wq zq6ix|Gc%oh^p|s$34e2GC`nKVrD?v{IZ&F=Ek!`#W)~L~#%pXCBIRk0n%X};b&;8G z0nYsm-91^|54kvc{Mb`3wiPSAXCdT2_?}m%KS@T zhzLyUtt1IPx#xKiM0XvL{Bz6bl^TW+op?5tOZSrrSFoLl0$bV=wuU0UT?oc>;|gOI zJdgXbF8uu9D#`%LTmt+u5afeo1>~I*>WTIfHeQvGnPci2K0`Ww!m{1s)G}kur(McJ zdzH_Q_wqKWBJr1VK|^<-k_44I-}5V&dD&%0%7&V_T3l~4)?fstt;%{vvZ(U4rp>N`Qa7VmWoK%t#`y8N<48 z7;HV5)nR>cNm1e{o*xgxFIH5rY|AC{ygnSMh6P5C8atLK#$sLKvf$Se#M!+k$-?g0 z57R)-L3N=n-jkb8VI^LZmsy=?wR#dZpPPa6g+7GnyE z36~ucCjmvUHJ{qbLj3OYM%7yhZ*n{aX0-9lIg?`5Nh%~L%35P}r7~ADWM!ldirqwk zW7;vPy=e33vHHT*@w7SIZFu{GV2~@9b55o@GEh__AT%aR#}lBjj}uRJ&+rv&o4nT? zQ2pV?>ChB|1|9?_?gzzleleeWskO@NiOBN^n9s*dNws*+w>b`%%G26<{H4qcw5NbS ze>3#MG+JNj0FVc}gc0F*l!9K1(m`?*%T8 z)sk`v$vTQ7D9<|Np!?9pFnVOSL*pe|-@K*S>F?8t$3?@FDB^1k*zAKv$OQLp7R1)Ew%b z5>aZ}`~5?qS-XeQo@r?}c_cGIJPyxWK%r~;AJA1F4Kg>H3;RUD5DN&rRmo zfPq#PdJRGG_EJHxZA%=rD=UZ7_veq9*r1KdWx7`zA=XY*wm=;A4J8^)&$>RfT5h3i z$;|ou<5^5qFwenKu!oF)RAR@zq!HwYKul`pVZH9Dp41Z(fXldNu-F839{R-7-rdKOSAp?7H6ALqQ=U1MPnUNj(_p(%m*UH{s6e2U*A5#QhN$@|X2r@DO zdi`0K%JwgHsXtqOUHC615wN$v=i=G^S(nQ8&$`r~<-Ll4V_Ez+H%Y)uMxR#N6lH5I z>INGeG*$H%X(S77=u5*E_iZDz}|LlSA*Z)4=rA5|0Xzh&Y!-`s4S32TrUnPj3*1_~?YYJ`ITBa+hAiZntTs8L zu!bnvC{g$wS6N@V$}mIZm$1oi!(IE8c48NDtX(r(N)vN419x^byf#>mEEnHg80i}w zz}SJ8c|#k3gb2Ilmc~a1yPhU*3K_T{FMPh(yD~R2JXOBg1A^yQ0);f9&d%K|OqE;o zDZSA9@T~F_eFS%ORJQao-tZ)Lz-L77<_M;lO5ep;>v_-Ycz!zA#BW(>l zEd7#$!?pMXIR?IWCg)f5JPLbdh6vHuz^ZxzWRwl{F85>kq**tx@{5O#DbQmh%U$Q^ zuP-!k&vq84FReSz9?{QMCdJQk$uC+DkEaE1Kb4oE!j|ztuIXWd-hyF);&hRZ0&M~L z`1Q@-zZ4ki+t_YDzvNw>P8@Xke2xw&PyEq&k(U9>yQ?$TcZoufg2@YcbIPB_C7IF+ z9EmoP5itxz2BDfIe}>dq>tFiq-P1>!@ zRSJ4JO;S%+EY(5BIq#2`)2JZn1uF{aNb<(grh6Yt>wfmm0qlw*-4s#X3VN@q|k`dGO3~Zirt2a!_T<;k~6N2{c{(Lb`MbO5$iD1 zuv6F84E!9c{i{Wl)YQGFQ1r$I6WmkxFoY$Qo?1P=7%20O!!H)?18i}_*&+G5Mg1EQ zDM-kq9F)Wp8QJoE`p zNNDmpdsp2X{Mvprd>HCG?Wb0%fm6Mo}zsd;iS`&tr{<0UCFs zi)mS$L)4xNtq-2Ok~|mc!eCQrup2mNa4xa&b%;$;&j=(b5-(eOuAirQFC-Miv!w$m zaUh_F=+=cPYO>kP`&bILGcA9Gd)f>R7uCgyoD&hJk~?XC<#iCh4NHtm_P?Gs^Q zZRJCnue>}4Uv=5lLnM3?3GSF;F|=|*Y!%F-1s7b`WFHqudb8}n!R#FEn`3^>P_`(g z7FccH6|@sCiz%WVpFpbqI~pZ?ez z)z8dDVmZ?=M1xlOn962xqLZ50PQ8P%g>Y~0ozUbJVQ!~t5QD?ge#Iv*CaD+?OrJaC6uXX4rPK88-L@ z%B+fTqPN?qEY@MBRfJ3|1mja_`0~CoItFRlrt9>&J?MVJ5hjNzEU--! zN;{^kpBJU{WVB!gC{P#AJ}a{CIJ8c(3&KBcmC2#Od3AYdp!xJbb|4E6?%V?sq~cAv zT`ocFIkcDCPDyG@M38hDzTPtOiuW-b5|p!@VM1JXppnj+R@j%$R__b5F{!2-4N{Qr z1d2nz9VIyV{Ps{+gl08+mOwjVm5=3nRJ7in$xezom+MtSLTY^SWnAo&D!#DvER(%j zE_%ox;O_c8w;!7NGVO2OeoE&g$!6+KY~p%L+H57 zS`~kIXQ)2e1dfimKgC%MzbLTD`js=_yRnC?(a10wi9)qZJT;0E@1x@`Oq&5}H=U>i zG7oYBW<~t+`rG47Vlw`GZM1iQf0QU7a=fKj@FeB5U2)7QE^pG0Kl63_Ll6j@Q>%fd|dd~#ZFq4^N{zM%uyXU)Y4 z&4@RmKCQ7>x7+_=JL8KPU<$P_HYVw~ow%m_u7OZ(*KWqakerM8G~W7)}N8z-F-s8f>bf2N&G%PB{}%`40;98+BZH!W5!w5MrK{F03|&CPC)OJ zw6HTsD8clhX^j++hGWS`OYk&-yGrJ5;yzLU>*e4YP~^2Az*R7>ry({6?jIhn2oP5m zBs=yEbHgHDna`TA*XclbXt7Rm1LgB+;cW`~>ca0uT|V-RX7n{-On}Q1h&hZ)8_qV| zzjTLG**->V{KWF?!o1>6@bj2mHRk)!tTPniP9%ne<;1p&TnYTd9ZjjJQ{($6!^czcrSJ#{xDIL zaaHIt;9cs=pH%@a7RdM`Ayo=9Uc%yBkXQ44cT%nZP&B%QPfhbJer*YEU>y_lvcM_% zgJ9O!55tnriqu1Up|iHrbT6TXQ2x-Ltw)pggG%SNEca>a)bI98qfw8I&bsX$D?JNH zQqZAVF75nT`Ly4-o8giP;M5LIN_qa64V0SpP|o0);bP6sD1u4apznW#1&=rG5&#P* z`*NX9KwWn)5EF+5p`(~m*fld(L&FBOrkZ*_2X=V0cfy23)qJtFU$J}1Ia^y3Li7Jel z7w#(X;Fi1E59O1yxZdxwjr7_u3GMZYSH`Mj^uSB2)2uJ^ygWC%ab^->oysZ%dnGsE zJ8H^w`S?nCO|RCD>!XTH)j-BZzO=Cjp_zBd)-6lh6Ji$$kDK`;>8J0;5%q(U!thi;<6e zRerm@g`SrNqcQy08`3E%FaQL)arY^q?d9goACGU{Yg=uXI2?BnMSF4=%ap7N+vZX1 zWOVX9z-{$-o7vpraW}2SF+q26? zeEDV^w4`j!^-^2jg)ng5lTXle9H}v-85r@T^_Ubaf$Ux1r^p+^g&v?17u@FR+xTNP zR~p?xL|n?1IDGxIr}X|VxuP5VOT*_?zZfs%iWn`Ldn-=(8qlSceYNY;4#5U}aHa6i zip#k5v)bF#X7#LA5Rb4nwc>{tEFP;u?R)!H7|xPd&AanmsR+OBev<65~YyDIi4T+BL^@y&5%gDaK^ zHC%Eom060YQ{lC<#NyvYr>jYBdfXG;^q11GgWE+BN9%uedf#PufavYxKBStZD1lg^ z-&_>pBoM?0Zz()jf4Wvn7!p^Ms6x>o(q$y^Bf0;wQNz(-ACih0hFQ1tas?$+=W?=p zL?$yx9ufieL%kcg>Q`6kRsFLpx5DEeIM7+m2s~K0ghOuAqy4w4gn5ijU7H*Y?O(qU zZm&_0rO3pf`@zAR$B8N%=S6|7MN^rdA*4r0pKq)#iV<1v=s)J+2oK?A7@J-!{21YE zo;StysWJO#u**Op6?=;B4t7hj3B)tg7KMxtRjsYBCMP_|u_o=d4?HYGmQiWDfD^HQ zdjK#gp!mo{ob7+0_9%NyhX9ZPqWT`)nU0cz>5V>6_&r+%6)a$iu0A`5uNPi!vr<}% zB&QlfP&l5i4B&>9$gQ6ScGY>sQ5(UiCJIJ?G971sE2m;BCJ=_t~z6a$-7o(vjqkW4< zxN>9&f1f^)>z>v2f?u1veN`f8fqa?q@;WDCdx^x_fx78@#aNdFZrcCbAfwi%m&GsDL^*JA6;@^Bs_eD;M#LOiST0ddjToP;sQ z;-}mkl0}N==M~wa3U1!AICD1ZJT?qM5!i+JH^97NkA>Okcd|n3dAz`=OdY0d-LYrl z07U|Wf{nq!>JK)4ZrGNhKQwh|<-Q89ku1HLngPtAH)~Q6?#-lgw41&Q$4MBv%_X62 z)vw9cgMVsbr=~*9a>M`T6bNaq*B&B_gP^_f?!-Y)&lgePK)t4vdqg=rZ`OA+`+_1Z)Z#cYnbSQ zm)YtW?Y(X(8>qqdvco@V*>=>`PW>vnBrl^hHf^**@b?<9{O$=${yPWrhgW|5>pDQs0)|J?E zyqR5ajrz#cxm0H39j6f7YQnw)sUP4?`&VQPg&L?1!mf|B7i1P3W_A=atr%!7ypbRI zd{@^Ur)(TZH@p7!)G!ZCn3VuGoB_U%jJBK^3YL{`L?Vc7oC7JGZvp2p8uf9U(7oTseZgtLNaC?F~-?}Loc8SfF8^>OxK$kpM@;m>G zy~{W_|9L4#iNdgc7jpnbsO!eRk*M(5ip*4|;L8K>`sq{wB&PgJIOJjjkB9Ajsz3AU zZpbn%vlfURSBLbs^LI*#85mt3PASAV`<0MYtBV^3Jv+fhx+~P)uzspGPUv#HgFg@& zR7qNc3G8!b=rhvOA4w}H!Im)dNWBRNJ*vZFM$c~-%AAL;1T&H&KcDatD4TQTMhG}z zPo>vJfBzmMlf|g1=61OU_VOf6vZJ?R_`I(5Nk^y}GA3ZP``qNYofN)xx+f-5+!@RNKWT&=9@=ycva;Wp0cq=G+$ z-B}LZZx3mLd)rsdw^DUT#lJ*0;AYo2G~t#wm8LW|&N9E4Xg^T!X)aI&Um7Mg1ktj)^;R zN5xr4bKl@{dYe*~e|(|n91nWj$PZ5m@_s9OPZI^t zpjxtDpWDn`Q4UM9F;8H5N4u*}qa*RY?>-8zz}$S61nHAuUVW-zFX;Wo45*O^z{hkz zsS8+-c+V4}?qt`%-}A`qvv+H5tg7rS)q>VD03CVSxcM+BFC93$L2z4TuLi`GN^h#ad?Q&pI;eB}P;bVD~O(EvBZ11E7U zd1r8qcN;h0LcO3)BS)~sGM1-;HRCCJ>KW4J3w8@O&3!Xgina1@H4mXvFtLZeg3iEw zgbahzVpoZ+Ub@p~p#@hCC-O6KKGwmzGM%BwNYH{2`E+cK32hvsnAf;>U@S}l+vY+W zdmqBVOF#%kyOak`J5^u&pMvWq!={RE?Z1ECK-g`=*9-R1~3Cp}B< z#?L@(xrgax4WMN@@_~zBKR6FeUEPBtHiwjEvs@b9xV%3P(W|C@d-ddLp4!4)19-bR zWBL=fw;YHW^^$D`p)u;MIq#cC#W_ReNe92n5zvyD4~b`qBzvn|PuLjW-ot3FGxdBR zK>sdft(|1U+;`7*#XL@GJmmQ^HbIj6Ag#2778_(UDGOzA`kJSVE+y?U*;#kgU{aXW zJ0;zt<&AV#aKCjmEOaY}!M+HJUGS-|&* zq)?6WjX4lqupGko&6q~hH4h(W6we!*3-Cu4Ck@v25{-Lkl5?yUV_hdd)u`^xB;?#w zu}um}7F^(MLorV`R0_;KLy6{E;1n{sGPHRNuq<*y*rs9q*fvquWt>z^xtu!1z{%9F zfF37RFzf8Sx_dtRrURPeN2p{OgI`|qa8@im*{Bs?L-`TedJz8Xpx`6=8aUi0>I?>I zDDEyA5j9#u!yV#$pr=gap?$%`#VPiT;^S9~w@^a$Q$0s6aK;tvC0aA2D-@zn|BthG z43ezr7PhC2Y1_7K+wN)Gwrv~Jwr$(CZQGpwX711p(#Z(L!||PyBKhRXj;3cMjytPq}u8k#^Fq>t>!N%lv;H7wmxl_W}pP1TV6J(0ja!>m2;0wa( zz;Y^{gB4eOr!Xx=F(JK!0?}=-p1U3fYB4Pdao+D<<(4S(0^^iXWP3XOtoBmVj8W8c zSs~_WD~|3*zoL&bz2Q^&W{h>3Z!xy_Hw(dFb7Q&iovVEmgF@D-`avZ(O7`@AtlDBY z7vs*7WEb{XA_)6r^w}%f^<~;C#_I6rwVSiw+sX5)RYkj$`*8IF90A7px2LwK?mxw~bnk2fk1-)BU*dQWX1OpIyu ze|J}%G{vWoQ63f?&k*6La;H6G(tpyB2#i3cd_mc#ml&!>2cn22m3krDBp(@+OzkwB zFKfc|n5Hn9$TqdB7-NO%7<)Mh2dmzs7P$8>W~dMM$RC={mt~EAZ5@b`jqSpStLvW} zJpIP_vQkaflA%uf;$0tC_WDA^W1W5)k`z&D>vp+^T;*6M!rhu$dZ@SGi!Z z?Ga){j~a{52G{Jh^4b+lK`uwk>Go{xj0g8wwvGt0%huX;nXzu1Z&*9_k^(Ed0itrN z$n)?{Y7LU<#|!<;oFe|&3N%A(XQ@)Dtbx{9lI9cM1n<|$fNfnQ5V)8ycTx(>-~|O_ zv!U4fa#Z!;*f@0~i zkHUsXQd7p`IG3nIERf{Atz{@UrQ0e(*<5lktbRj1;joXlvlrBrZS6zNF{;n22nuok z#BP-M!KXeZ_#1VV6FUpT$DjLBrkIRoQe$pw*Wj8=;km<^24oko$`gU-@~!MkxIddZ z(`bBt2yO!qn8TFOdM_BBIVDp^I`Vd}*^+j6bv1cC>rQJVXSibMxmJrB_FqGJuFkp* zj^o>RghYy$tD1X+QY}PMh|^$;^V$jY6P(X!PGG1G371_r&YT^Ftgw89LVL)5YHN99 z9cT%y{jP&8UDkT?NvfOW=()x;RF8=^1p4Trij)ECL zgJ{Rx>JHtPZ1-eCcz;6$yMP)9O&Gc{;L3z$0Y#_-UpDOM&-|W!s94>1SJX-d0tHox zMg8_!RUl54#M+_gCBmJNUR%7#zNKl$ETwDJHg0rqPBaGnPFYhTw3M%CAVY3{QXM#? zA0N$m&(!843*C=t%t+>?EQkEsvui$EYPd!eNOjqJVlTsDi_#NAO@)2VdTXpIL-YAm zRJ*%LK1v_Da`J5835^dHhrdx}9kG&`|!0pK>c?0Z`HRD2AF7z1lq;Ev{KH|)2H7_SG z5t12SP6Rqe@U7uW}rxKPih3-!8B2DKCJq zpwdp;wnn-}q)P=3(*|~17{Phg0LoB$rm|zZl*tBQMOCx3`v9c`sShx525f~-0kj?Q z(~V!vTg^gVbm)>tB#M~i$o_fVSX2O9joWPmbq*w2qrPA07Ur4&mAZs_}2BU(eV*BioXv@ zH^|vzpkV7;L(<0(Yd9&I#sKDEk~sc6IyeoX0UfZzM^vOg866w?|N4>(z~XJ z>(m-l3utoOKFgG`T@ERIxdkc|j}DYE%tHYNb(I1 zllw|!@z!RQ`+dC3$HC4#9Hp!LY%O|6$`eXqCgG1)Ez(d|^>i2YKqTXM5DxjmJda==x)7(XB zTC4t64L{F6Hx)lfkH^D%xCr_$u->DW94S&Jaq|^PA}b&5VQgPJA6j`rueeo1T{yZ_ zgc!c)?6qZ!e&3ykXh}Sc2F7D6?qOFS01{&cW7j7&z}#d?a8(O zPOiHihe@~Z&V}mBJ-(!fJwxltt9GZ7wk4n6r&d)6M-a5BNbGN0diDMxxu8c?_5%Z= z2=o5<0#=A7xg)mu2$dTEJ^=;!*4unEGa@)r#Nj3v`mO-sDm*lDY7Sr=is+t$IXJvz zQ^?fG!=xX4mqk(cyjdr@y@h{vtw9rFBQaL-Vqh3*bZ2Nz7^6_0Ao<4*%jpdLt3>70 zodj(}g7|JeXhTN(Rm09>w}xo%F%gxPvEU*JUB6}NZNFnvCzspRnMdD4G@M>d?+=q8 zHcBH2Fyqd3Xv*s7@NtNMb;OR<_8NK6lK{C=6Rg-3&0N#59SaCtCHm4sb1^oo>qPBL zz4Go@MVO9J+_g4rj{yaf0Ve?I;ueW;&)>e51B#_rbTSGJz<({Okl*qMrU#M z8GbZL2oQ@)6k4so%- z;z$6J!7-S6$|aL&48eSYi%RH~A294SC3i&K^CA}W$$X>Q8Dz6O>pumnD6G|Db+oHQ zfI`(`Z(i)z(TN@=;yX^|0H-z_geRFZ$8Yp=(1>eDk`&La(Lukn2{LZ#no+x!;HW{* zFnzSJ1x9P!+1k=a9r@G{&bDVKHY;RArjZqVBcB6luM~fm2My zI%#cq`t-m$OdyEqd`h;yD@eT@iRT z2T1ZlgiE^nNPKyRy^^vw(qG}&DY}v64I9GMP?sXOsON%LD1yT-IV6_DHCqc?TjB>u zyS5|EAD|jYYaWblZ#UM%!?tU1>adG$ZEHY-)iKnQ*TG)L3qPlJO!*xnT_K@}&pMBV z2y25E?-m~tXfl`y;ZTD; zzU!Z&(vT!`Asw^Y&MJ2>zVsZMxX$FE!DiSF=$Lm~UN|iD?^ZPKu+Ptg8Cv(P zbC98S(h&ilr@|=V9nxid$Wiakm@n#F#82x-^l4U-Jgp?sJCTuGcc3=C<#auf7YQpX zTr?SkJ>#Oy)WKp=eW-(qwN6lb z`9pJ?2T$rhII2ENupShgb?5-lAN(0z#sY#pMo+Dl-ZNWOS1HZ#tAqyRYAdQGtQr)q zRHTC~{i1I%zix+u-Mp2j&K5#yDb=U^-1N+q0brz0n$q>n8E-h%ADtF0 zo;VQeoVl9`kyK}^Suc9AsA(HQq%ZIU(+bZM)v?P{R=#)SX9xwfW4UtUC>f*^ud2kM zFtla>=)1da(}>um61&geyms#6{@PMxM?;!cqr}lp;AB7n1x&*WqZp~Pz`1s6ZUKOY zL$CI0O{{>nmBe)G+Jv;4q+QZNLs|fStl;{dJ9bOzqTY^dgPhNvqtV@qoPv}xgK6(n ztrwot3~~M9g9y{w;*LG=vtnE^#L23p1Kx?CudszV3ZOjuzCdfbcYQ9KzS|TST?=9! zk4_7ZFV*K@FbI#yWGhaN@5qyos6Hrwf2jevlkmD2hn_BV;KBHnKhb6cr-6#&;fj3< zZ^Ujc;VN_v(M0-@a3!meUT*T!63WVYm&d8mPY$~GWf5Di_?Z}8bKc+aLrRdxcxdP} z7B>oir5pX~Og-eJ!@L>kNiL~k8%*>eliiy>K&Eh8@$6huT`PIxuuQ4qs{G;ucsZpi zMFhCjy@WN~sxr;$;Ar%P>)wqXN9+g&-vQfYf|ZAcgT+RGg4G?H4FLR$gFy*w2{1Nl2nA6UQ01djRp>OeSAW*SEk|arAUN-$gwI2hS`qtALHXM`bGDvD;LfT zK!>#v^hcs*ei=*1JENHkGQMWoe*bDRlwO)Q<>pK9Rl@Ncc_XQm3BTLI2f|W>3-ws< zp(wE>EV^E;uwqhO^5OtaYC5`EeVgPnXZ{V@9#Q_PT*cNygP9m`4q z^=)>9mU^06zv7!Xql&L!1jf!4J3<%JX%;L^<;XO+A}8Hne2(kPKN5ogkIrX6S^VY- zIxRz$svdSPoBX?e0-!A{BB$z|fQySe)CBdK1CN@L}2>hC(`$gooprlp#^r z?&(iKJJShNUv+%p#wmVbIdw(O08M$OVRvQtxlr?;8Pz_Tg@I zi$o!BP9%vFZMB|OIn-zRP9uq^QUMDZ5qax+AJT_i;6;}$c0zL2Ne`D}UDvqt1h4OA z#ZRWEU+bhDhS$C>-DGhpKN39Vparg?c(P~;iT7kar}X*Bh+v;MM*YL7ho%bhBIC`N zVpmIvfup4(Ud{gHSys>?^_nrW@@5&Be!pPMdH9e{NX?D@uxgToOZ8J-@!~pb7o@l8 zF`hIzsyJZd!MNa(nTbWjP_3Gy9?MQO!xqmh$2X3ED=Cqdov>7;#m|(B8C#6y*Q%B< zVcDpw^k$hGc1Fif16(s#I0&~N0yg0Yv{Tt22#B2;6I@PzSN2TG1tRy_ z=IX1*``CRIUrBvHtX_Uc^aeVL9KM6}^Z!oj$&?v$2zv3`^0da-YOU<5Fbk$~8S}Kz z5#sZdbR&(r^%L@xyxW^eJO;DaB+IDGFrTgg6CGBx+}(<5wdXBErGkVGBJkvq;UO(a znitcaG+?hO2^L@uCvNb0?u=i5IbCrVKQL0B;C%!|eI(UIEDA_Vh)AD;Ii2OPh$$AD zHRVU;!s3{TW`c!R$rSfngv^^&B=Brrpd3#2%p>CkcIV0j&|$;J+yN8>r_dSKYbtdb zLs>#9eRVm$zB9vsqq05(9v%0D!{^;OmxL|c{wm<=GGC8G)V#XScJOU}9prj54(4k* z8wu^mWd0%{8cInp$JF=c!x1CqybWkj$5RsWi=2cd!fSd`K~?i+IWE|XyStW)A`S)9Hjsp#>ZQ4|ls9v{rD{f_`m+~!Jr9Qb!S%HZtH^;C(a(`auYJn}Gl)8dJw zMJGp-A=|g#1#qwrWwFnXU(b)&c;J;0y%oma;BM+_SoZilU&irwdMVQ5V+keG03^nATF~WfObpjMyUvUk^4VRl81q+mcm{6>Zx8@Z&a{mABh1I!qM> z=>MJ)1gX;{>{IU*_RD^8bl5Uu#+|>G_F3jGXO4uQj^r$#FI{w~MtB%AH=L0&Oyv^#w|N_x`5t^)7)R ztR7B8w!6g+0r<7+52#yQILlqq^vBXJ0tP~uco)0@nKyOY+nPd*2<09TRJGzksk5V$ zTS+@I`XzE0(s>}+qX<)1%woBjWJC5wrhM)L2Hx<;9|RXZ&m9NmRN8*D*;4L4u%6&= zC64tcWjT$DxP~%=c`>>wx$Cqgw?RGzJ&Wo52OnOgiAb^5NR7BALBg`P3;F|>KvTaY zRT-n5#{fmHe(LB>Tl>PJl9Br-napU1wm%cTrTVA`#b zKwX`B+^1JeY>dC)E~fEWLd(_e|J+R-8H!FfW)~7ZM);Y8agW<32zeQ_18{J|x;QR* zMh}+@zUSM~3Kys|EXt5>sD5Ez<2z+-=QGnd@lzBe$&#eg@~WNwoaPN}R#Mt>U8f)p zvYUpiXmN!AdG$tsre@z!$$r94z#{Nq2ysm3RAV|JB?3`p!AZnZ#g^SL!vsq%ViBDz zQW4KUJrmMFDFY9ZoY3@Dkpz@38Y-s0KWxwzcO3MG`;-}OfD8h70H%xqI#&aMR3g>7 zwzG@T&lE&eKCe1S!ROC&PN0XEGSjk%Ye~03U(t6=11|&uQT5dDRhsMt;13p%Z|mWc*^)oGBqr zo$Aly+LMYUN<%6{goGf;e&a1o40zzZGYiUN%&Np8II$s98Qz32KJOZe$LZ{JZ*8FY zN`5xnMs{*4Xk(Z~3K46Nm#hJKlzi>c8tDBtorxb*)BZ)Wq3J}!dvX|M!(do=x zJ(5|~Jdqo%M9uOX<(t3IkO=;gj9*7{~k^bsic~c zQ&wgmPKL}Skw>W=2OL{AXF^B3bDh-L@BB{KHPfG~u2uH?Pb*r}c~b^(AuB9?;)7h< zdjB};|NotawTj6 zF>168JnZynoZ3YKk2=wbmgk?&sr_kEP)-!1QOqwyK4+KsyJ9gXcHj=PjD9 zf{GRwiJk{#!iCf&H){b^O`4dShw^k&lI|zi1VW!b4)253sTlA$-U?A|&lJ8#dMhns zFVo~4B#PrU76(~lvi7MQzQ0;nrcTg3l~5yVXc|BY8nmU_A0T(S61RjR(7@o`Kn&g! zMlKAq0llAZWIf#4mGod1@affU@3%n(kCLiXSM?J9TK2-sJMd?O4<`Z(4ttcAJlHgYtjThyn)vDwE{sb=7f> zG0J!sngqCh9kdHYIm-h z@<+8)a{SUCWSUQv@9R`jZT{_IZfljkfU)z_uRfLoZBWx(`|{km2JK$1)7m6ZHeZ)S z@x%{4 zhmRWFUJ{p07HR06MoO6snVxE;6#cJGkwt zeYpjZ5YH@GBp%Y*MrD@!3g$Fwu_c_*;CZI$CDq(hBExmxQNXo5I$4i!f(B&nEsI_x z$-`g#W@Wo$F5+k~Czm=G#EPs`)asXk+#s$jPJW&KHgQ0SuKWd7D!C0=BFmoZw1;Ia z6}qbW480Uej?iXYpYepZ#{Sh+w#G)Mwp+lFuy=rO%$j#W#=e?Dg{sc+WWZHVjt&ceDrf+h{pBx~R8LU2mZQ>RVib}qI%@&4+WO|WY>nR&3 zJKW9<5Jl8zu@Z|ME|izq15ovdz97}3a8Q@4GPD8?_t1m=mi z{NdYw9o+X9d>z6*`HX%V{`vy^Dx3KdJ<~M=VY0P-`&gLnMR@x9W(xnK{eJ*?|04bV z;D5iRy>$O9Z}J!K_g9#O;a{SEyVvL$8R`D%W&R8O`!o1oP~N{s{yR?j|I!00s3-{v zEB*({t6*f}^gp1y|0O#6zoEQ;fXIKMynjT;|Bdqg2O9bp9{YFf59a%){SVytFG%(` z#`(Xz|7COj)AtX*^FQI%zk%Psq2E6+?;rT|PyEmG&l&y{V)>2s{_bJ>4d4FV^JmmQ zfZso@e?Y)=e__FYX8-f~ADRB0??3R}KRNsb0MpSy{u==NU%CCs@9#YS0LTBip1Y)`u=}Fz`wKom&gBt1T+2@RQ)d_|MjTIjzwDaG#KkYNM+-rFAL^tIhvwKo2=H) zR(`)+tTb_qj=p<&R60#@ynn2ke72h`R+O8gRM8)!v7*;z5M=tsMFGey46VgQhh^P@ z@eNIk^^EfO4oM6JONPq;nC=0;#Mk%6#X+nBJz`HvO}l;R+tjWzz1at-LTvYJi?BynuZQoFahPa1j9$+ zTN}l_BY86osB3CqW%x8bi*?fN4`=)B1PII0FW6Yem`_D8=aQE~-Isc1Yiy!-_Z(CA z=o?+_atJ6lJ(2G)8fU{ALs zM3hgLjOe1b=&u)Nx_1R2%gAnLj8!y_&x8nCs!t!?u7>D0<0Y7HqB-Y3XFzqo0i&g| zuc)83d%gYwtZ!s}S3#43F|+eu(;WeKFK|IxfLGWx{pIK}tw zLmYaSot66rDX={t9EK6XI9(P6hfs~^QOqYD!=eQy>+-z>j=08~c((wP5Zr2Y!e=I7T| zP}Pn;@)4~0vL}0HK8}{KZqlj!a6cp!)ijiSj_v>f{1wT3P|tC2IfQYEEO>7pxvCapeOL| zCY+Y&g6!HB6(2oy6qk_gMr@afL|`O@>rBpc!=m~0Pr2AsMw)%~IY%6U`5bN67B0{2(SXiH4N|2cF$MURKYUMnjX6do@A)JAp~;Ub5z-@ z{Jh%g%m-sQ!(F-0n4&~Vx5aRuJ{+iikZ{{yy=BT}hJ0*jO-t$UR7=EJrhXEAZ*cgC zNi}!=IAjki2s=9rmamPsZ?ApgW{zKwKfi9zCr(f4jys_pZ_U0+ZIeY7&?K>D1@7i2 zP`kr(^=94;S)$|rje7Q_nNpY_(arh8;SkQT89sF6$2yNAbUwfZ&z8#~J)h<_S+Y(V zJs80%4s@g9P*(|c4;VHP6B1EM*cp+5oF{@29$V2u!-`Sd|Ip>2Icr(vkcb%c>9WG= zf&k#;Eb+a3P_rmsH(8eUbpnV|{z?of^IgFG16$?;DSNT5%XS|kI-M~_ zga_{cS<1oNZXo~usAOoe+3PO&SVrw%jpFPvDn&i-Bxe*K940c?C=1%(21|kGS)5&? zitOtkz+n-R<>TXL{v_1?r4Cu58neEHJjn;%uk|YzI+IiWye8zp5|S0>`;TwK5g5hU zYi7;~CfH;CR3;)JCDC5-hcN20_&x8P7esBpaWd+|8i_Tk!qb+|I6U|>V2fEQ(+p#p z!wlpe-8#L2y{8ARX=BJYb-6Q(YRvMQbEqBHU6Lvu4Tm!|d?ynM zENVn2lsT#|&6;nHG&HmV(Ce=2J7!QQV6t7($5XzTQjah29?*tdQkFGjAk#I&)7D6> zKW_qth%ilDc^785htZRM47FnbgOI^lW^(o**9MdSnBst3YO`!xZR~Jfk-DDO=CZ!%N z7~HE&+8Fy!$(ybf)trP(vq<9Nk1} zO^1+KZTHQSo#1QLEhco^CZS0P$?N(#vy#8GdqLu=G8)gQ$FP%%jO|2|q&FF6aQWQ} zH!1%L!>DrFM`XwGFA;Zs`qF%wngPpOn7a;6UHqgxdX_7kDt?kUgw*eVMz3J+d+kkM zt8)@lyG;n|Hj9z1R%GbRM+Tj!(H1DnxP1i!w^y!lRay7JucfiO-%$s==k6xfwIKou zop_k~-qN1(rO05ZU;@O@_^wkgI9yohP?Rv(l7aV)qqEn|36{iGdLIF6k>!L@$s##w zk}#)WES;GM{4E4_>9K9`d+9!KZcCKprGcnL_Gllg>3Gj;QjtR4t~xt&-b<@&^8?l_ zd#uE}>(7i;R*>WptG3+$KLuHpo3Cy)i3BE=jX6`F90{pTw?BqTPPmyPwzycAf%W)X zGTM>sy;~l~9W9s}WSHHx%yLuohTk;mlN@$a#VHHunv%H8POHS5odn!(!@@B*AEI=V zYNoH$3MO6k-an_JE!2!3DQefj=rtdR$mZQ+g5(y-I>}@D2W5*G)pNCK>ATx^iToD< zUCM_zd1pxwF^e@~Q&Y3{Nd^vDUeM`ikwKlip2G`Wr|P;x9s4qHv?pyy5mLIu5BqXg zs?Hp)!YZ3}$Doc`64#&mD+UBbGFi2!wGyfJ<&Jh?2DyZ(rVzSpdI)xUZ>N@^U&(X( z#_yLYTAs0Kd`?4Erdh*gcpYU@qNFv&s--{(^t7ynmy(qlu02q5sm=}4=xM25r%{Uy z($}w@;!m6H8C05WjLy5O;EdLf?J=@d=Ek`dz(p94)F|iUkGnVV_*5|9y=Z@iNnlG7 zCC`uYGl$p>jc@=5vG{(+oWxDNToW}a{0J!7z)(auTrD0l>m`)&+w56oq@v%l@v&(~ z?r(D3nV1whEFy*JSjNY1mKS$$d%P=PRW%C#Wj&T;N#CYJW2#zxl(N&^OrA12PkQ*cZts{B(L_VG{|6yn%~=0uwP` z1FgsRwt}wV9(ekisQ05M=fyy}o}uz*pEK1`vO&qX@(d4#zjO$8T~u87v3i*vV-ekFXkHpmk{I}9-!)F4A{?G;};U%<=5Vf?gNT7A#kT^jLU{!jJ;C?LI|!j!De& z8>e#S>NI=l!OkNWcLcUklR?vA1`5LnIpB5;WU%qra3M`JaCTfVVJ73ydhuWw7{!Lc zbqB*c zbYFlClJS8%vY^N72^qc|s9h3+@U$IlH`W{lv9|LG{k=70fc7o1C^VbpNi%Bhs(#r> zx*x>NIL|mgXZ)Q752?zovOp+Ns#6VSem2l$8d&wf%mZ|T3 zi@NlU!`kENoKIRA}!WSiAw+82l?Dy&Ytd{otPX>|k^W^ugOLdV^K^tUe z+UnWRuLEzdf{o^uzlGlv58q43v%9py{Dz8h74iH|ykf5^3Q1)@2wK5<(*??~ROdM&$ z4iX(_qK!~+&;h)4-`v!$k7B=GezN>}(f|`H?P-v*={xBR@>7y6+i`mrt3trK1*I=m z0thuC*76{UJX2v%wsBpC89H(MTok(hRWH`1YSBg2@GBSid+mqY_Yi;NnO{Res17#k zlq?6s@Ie#V<3bPLQLq$=VOAMqxJ1J1u#m1c{-36xxFRfxj#@R!R z>IbKmLBw*_4;l28Pp74m6cJD*#5K!bzPBU1{*Y*G>4}Wmkbl<*H;0TNr8`#zszuYf zieS!AP5$12TC9xBe@J|fB9psOHRA{^00ERq6= z%(=gU1(2^9!FVb4$~)aSg%^xUM2@0c+M+o+j~sK6nJ-Yd?f}1NQRb&Hs8)}w%pr1Q z+uet%YOU;jjYft5`Q>YPW1ba20G-DwJ^L=rN_~$SO4+vLXci1c zX~ilFqB<*-G@7x0Wdhm&TU4?nc-hsyNpMtZ!D$;Tn(($EsxaohT9z8}!=tUO5G-=v z&(9hq8Jdk29P;44NUSO}zB2Z5VcT5@$X?rD;;c_8xA!Y?)-A<+HP#aQx%ZIVYE41N6+MWSM z5N;;n9^z}dKh}2P7NxbZfxI^wc1q?F!qz10wT?Z5 z2te8odNI_i+VlJ<<oFDaTi{+WRSob$FQ#-slr<0v@WU17b&?oRdO0O$(pXgC(>LmOC zb2IsEFs7VX71s`UKBPCrTjtz4l-XlPn#)M>nx2>%o2vJC+Q`PX=u>hLN@R^t_TvN^sr{ZEBXXlV-Pt~;BY}r8vWCU zN>X9komujb5Zw~SMzB6rCd_ycsrJsh)==ER)0HUD?8KfIO}DM)LPk#0|2h*YYpzFm z`NRg62FNaeEEroa$F57}OSixWw~;fpFVZ8f^#{c-*K#`RXH%;otXQb@;*$-gRQ@1X zT?D>gESVr&`eAS%R8;1xZR&y=6I^7gljYib#xQnk7P0m-4{Oc@Y~OL`ya&P9X`)!hl;#x zBCIenTh*b;^|;9(J)5{<$!lI&#cONe+^e+&eXJK;s`k@3#IzZ&XR(=(Gc|yU$|S3| zHbb8zs7>2PHV)T-(GH^=HRR;^F!3Lu>UvqzutzCyuY1EWA}pihO}Q>q^{-^xNFK*l zm8gqYWM|=B!MRUo@FM|HZ)Apm#_3Quix&9xz#CBWg>;GORHX+y61-v-0g6jA>t`JC zX{^&V#Lq;J_DI9Bljw{T7GNg0(cF*gsyX}Hdmtt_QGB_pjmNkw@?BNHP-xeMOgOy3 zRd_MWBHG?c-JkB4zH&S~3P1Hwf)jSdvA1B~^Xn`x1bf_o(V~QEZmQ~Lskj;EW+%P+{`2? z7kc0s!@)9}s#(c7A9}XxuO{3|=f*aKs^HfiHsDwbYWuY)i6JnM6l2+&+ z?lD~xs7|=f;a*o=u*qX?3_F?4JU{@Y292@h5H%V%7?aC(rPG-^l3dMxy5Mnuf>=2_ zZ=y8Nxtgm2_XJi}!$t2=-J1 zWKl|O%1YDd4<|gcObV@FuUjnK=Iho)XYogfr4)418Olgk01Sge!@t0w>yVJ{uzPzt zM(7!fN{yFv;LK0ZPj}I9U0)eA1`7PXQr1~PHfh|r&7BpF;|4~891MHqNs@!836RA| z-rIbt-qnHF#ApC7^aIH{msm0^LNL4=w*fX0$xi@fiT)bs^@>awU(iG*$;Rol#A-Ug zD&849;|OcY8FPT`xWXPS1g;$PVPw&#R5X^B28$7`0V@<1+A}z8xy1jq5D+}))H#^t zd-I+!at^p`3qV4))D_D&BWOMNj_}qL?u`kdjZLa{=KG zjK{Qtyg%pJ)R&I(AxMq)(YbmO4RnGzWg#*ulFPo2K@$)X&zsEJuJQrG7FRKFF*h-m z-U8aVx`2bp+iOF4!4H`c41R!rGBV8ZZM90lPvcvvvyMu!XMf@o55HCek?VyBLz^v>2$BUu)1(zRCGt*i4Y zd(aU5ZMF2w0e^K{ur-VVu=t}H7`PAXc^kCcup?6pK13jo+}T>^lP9r_;jRwEe}tD5 zv-8y>3qQw}E>FYK;W_WDi<^gJ^S?u!uEN^cgB6 z#&L{)Q3A<9@nM-fqXI5QcS-$dr~te=3)U(I?G0-+L1)3gci@Bn3;LW#%^mFXoDMb> z70dfTo66mn%06dfHmz+nkG=}6fL@|dGqzmL2x4}+Km-^^41C{x!b5hUvRyjlUeW1y zvCN_es@bQdPb!)L`f;>|!WYrrZB8G`z!KPt3dRiltk93Xba0`gRmi!LI8zqNrrBac zt2#xlC&BEJhX*Z&;PZw8o#@X1!ViiDkoR5!?mJ8$(-1Q(fMkN8U$s>4pZ8}8K<%ZI0t1AOs;j@!DRa_~hR^SDX_Ftx# zm#7*owqVn-Fki{=HZ8NXsyPz-!4zRhy>Yc9Pot-)V>U-sxWPa2e)XJZrw+L;v?pT z>(co)^&+wcIQkfpQSvF!y4(6sl)`e@`wE&x>SVt>%q zEcq2gB~-Y$*7{$LLW?|-F`+i!8znO-Fq^Sv?qeN{eRGJ@N$1mD9uh?mHK&IX|@j*ZrC zjv%XjBlF5xqxS6*l_h{HOCv6HXa#bfa{jv3etNA?aBlTVg?VM{Sdrmc(1u!`!FUlf zSDm&dNQgMZQ~YGIP7kW6axid8CG!BevfD&G1;?=im$r$j3^{&X;fZa-mC{L*I9>M8 znAX0T!k3^FSSMuD0tLF3n?0(DA}|LrW%-aNJdiLQq7vQ^0SAmp?h&2JQlo>XF$DSE zy-l7VJwmXKV~F=;NnnmAK-5`p*wd-W%O5V+)&~?yE(-qJf%9@b8vlAIV0pT5V-ecS z1M^PNt6a&m$4yh4>9+*MsC}U~Y_JKTMT=YBB^10S7NBmkGtEk!{+R0IJh~58lJePs z@BUo6zZI}O9L17|lD$_15G2I3DQv@PM6LlLG9Rw#85&$|@gtKrCF!Rbz49N|5Sw+) zB7My}76LDxz$(ge=DPxNyskHVXY`Zw+)qk4MJL>*DX}MXzkX22wdHZAh6q(0?5y6h zUrnS4kOz_c{t1F`=d2;YwXE%%96!q_p&l0=@sZxzA$YMMgtr)CNjAp45V3d zVGF{8^hb01$zER>(8K_O)RT)#H@~8Cwi(>}2{6cg!G|5V<-G*=zW&u&X^bZ+gHIG4 zm~A0;(4NdlR%SAFFL40PAO4CRWigkUg?m-Q&MDG3AJUn$R53f^367kYR+@=n zK;cv*o>~HK!`IxPib#27Iy)YCa2S3DE);E#=>DCg7EJi zON|z^imA>(cx+b{{sRpxIp-^VR?`QkKR5uQID)tKCS;ud$6R>#6um^*>Y&6u4q)-X|?qNe*0sW&O zWCi$q_wKpetGY?sKLGaG6Ne3zVLiKJ_bSXGJI9+*sZ>PF&$m8d4MHL zZ;7^AmU7J89PfLodrPdl4MnpJCT$t1AwLihpmhUmwY0(Nx^yJZS(M3sXXcR@#8p-~ zpI0x(0v25z!HK{;-T&9#d>h#{d5zg)%}y*)ti}zFZO6J2En|_uhLJkth<%OxYvZ zvL&04l}$#r?3wXBFZbPj*X90ve&0WSkH_!#2M>R^Uf26L&ttsL<9MCJ^JF$s1|7x$ zZ?nK_F){xc=jj?Ur$Bk`wP0w=T~`O6!K~3e+rOQpv1WW8d*^WhkvSsgt~_Iksut*7ENTnhuT8 zX1O-Y9Dd#vAmi#gkP)3N@a&7+6EE2G@^&7%Q$%F4JCW0KHYRO7?dakC_Rh%X#3Z5a zCOMBT$_}K`e#^Z7Wt@-iO%Z|79+l=`{kYQV3u`5)_={4?Z*9ZxwCQckq+SUQ9VChK zo3T2tL8;Gn_{DOU38u!6l0Jo&Q>pWl#-tg?dFdE`J;Q)Kx%5TbM^}@r?>S)-_MIIM zmEskRBm5X5Z@dWIkJ&V2ou zg-G|KwVa|DTG)EgwhvB>P5q&Ij*g(vOQPo8mpH)to$qp3-ftRC5FRM`29?&@Evs!T zZ`b1TefE&<@udg6rDmy24*UmSCl3pXsXKN%M3vqr!;@t613Ym^rd>t5`t%W^@2UqA z%JRQ{5E+T)+6tQQxz?Re#5cP<^J2s(OF2~O!nDG}{2kPsy8^-O+50<5Qgk;f1{CH) z0+}a1-V`C=nS1Z$!W7C>ni_(2SuTo5RC<9zi*BABAL8OAoLZ?wpWn`F$9a-c4YJ_CJT5hj5 zjg6<8u700n^WMf*VP`{n^SQ@-vr8~fC|Qz23a)WEbrgw~<~^%?kZZ-=A*e5j7?-9~e9mdT0$^D{u?BbBDky$J=~rD{|r0 zTgHS^(Zm?Nrb|Zz??T3vk~hEcw5BX%PC4eDNqwcf1Hxnb;L@^H9WX_C$s|*C9yHcT zlffp9Z5Wkb<8o(1>uo0oS$Jl^;}wW1!GXtTPn4(ZWFTkD@|M!->_^6s2fhWQ#Xgy zV7lOz%P4=emzmWo$*FgC+4y|wXR`|RZ<5lBr9_IHId8LBcP;U8x^wdY{blfiAy{*uC)}GWBCQ zuzm^#%Q!IL5qM+}ex9twu~I87TP$3TS}JaW($lctK6MPe#HD+- zICrIot)436Y5t1Cg|a!;avCe6z8Nl9o(&0-J7Fuc(S6Rp)fH!wK-qky2ogu9C2*Vj zY(hCD=y1@&O5Vw_rLqLkPk70>a9G5PgG=&lyy4mzUgFpc-!~6dF3&sS+`qs2jDujO zy_r0GOv>%y*%(WOb|)M?$?Z)ieCbRU415P0*_=j!j3 z1vng3=(GDopl+||5TxTrYBmasF3W8@S&wVzXWY2(ez=pZ8=qudBWfy0?1QqAQLDC0 zp=2k=M}7~mQx0W_h-)^Uog1vtYuPuJ_LwLW>pJJ$PG=ZHqt=3OLahU^xe zKVk&QUeq5Hb!F(1$3O5&33vokoD!Q`;`N{wj9%Y)8QpdGL8k6=8}nHNu8P4^ZZBwvU31rAWmBVcV=vhmOuju! zqG$eHJ1a=Yz0`v$T^OyB}WgE*iBomSSIoXF>{fJxHyI&z8HtprCyJeE7 z+8Grbb-6jw@%XZt#m8*&p8AP|qpqfxmia{ri=P%+?C20=jwdKPs1BP4-A;zA(LLH( zf|dD^y{&^6|FjG?#k1REsF+)R7hBRf{8CtmRn}qioxs|y-hAnO6v>aSgyFUE56>@# zl1hKWiSEgCObh$TPir-uTz?(j$nE?PJ338CQ7uQ~qbP3I&~%W@rptF+ZYE=?{!Q$1 z`cb(4_y^uP4R@x;wZvD(`8EWbu!Ex3(8E+Lt-o|BN#^=+VP= zDHtVv$lK{9vbM|xRr1f%Ch=Bty&_8wov$ywJ)0kTq~FomYR`Wowu8OWi`?je%6^lf za4~nly>x;ETD~sCVcJt&n0X!{!ZDJ9EwM2@Qu<6q*I3FNzplI=#H4YE^x$z|G4Wj1 z_cPs3{V0KdE~fLlcTt3Jo_hV}H&H53o^P%1coR+WE4}_6xp#(|fv}B&e(r|Lu0<}N z*w2~`&_2IczlnXJ7oOjJKh3f;Yn)~yK%!IJv}h7bOP4+*JM7@%du>}k*6?kQX{pF2 z%LndT%Y4@luxpB?*2oPHgHyx!IVFqyMBc31T&=p>Q`r@Ck!NbT3BhOE7hwJI;^rY= zvAQFUsvA~c^NfzR=nS`6?>p;pRcdlsiXL&+(4qS2qR-tNg7P{ZrWvoO6+UJA%BR^fPz#8urHnt#D20cJ&JaE2ziDqT^`^%uI*H;#n)5o+| zKDgtpT5#*RN{CFqi=Xx#&l?Wqui0eU`ezJQ1?L$q0(v zaH8viy=frORnFkB%S6O@w zc#IW`*gx$Yv;M0ep73;BrgI-gUpjD-ZyOs68W6UWawx??3r76xSQK5~ez@&tcdZ$? zAp3!DfKBR?lxMz#X+&&cg)G&|8$y!ek!p@RrqWn4wX85%mWC!|W+2{7t?-4TZR?u0 zXCvA7YA9xx?qg-OK zpcrqS7CI2VU^;{_BnDW;_e4H=($Xno$tCo7Fl0*RP!8X$_19i1P_R0S?Pf0+Qv?6_ zu{aVwvZG~3&hbjshTH>7{82(;*PGVGdxiXmG2+Aal(%loiOj9oywj4~xZyBIK+u8-(0OBDU(+Z;#CSBc-qVBs<|8$fe)#V3*vz zzI1<4yZWthRjRD6TNM)rt@5+9cSWyuLivQ3&Rc3kC$MesxISxodLz*X`%H7nSWQVO z$#CD&6DdCDejUQejYkxl*@=DoM{4A3k`8m@-8Z$p^SL;D(oOJPCY-4+muZU=o4!%*GxY@zXz_$FcB&Y8z8D3%7r?bs`qap^r7yH+wkiC*6ZC6jI9tiSqsrtSKw z$p^hcvo{r*F9bFpysY24m^GPinDLcfoK%0(BxQr}&C@t96x6ul-5vhVFRG|m@{PTp zEG-XCiIH&zF(IXHT(Pd-y6yT(IpHOA9V&p*A_oD0Jb{^ClYoo)O5 zW>r{1zrod`XYa1IJ$Uabz&Y^z!gLgk$WX`7y|*;b#cP zuiIDbKs7E86)(MNzi&e;m?F89^teAoO=t6z6uz#=cPBueNITD{kzzxnemhBE(nU+)nxOGEPjaHoI(H*}Nd7i-N4W zowSh4@5KvaQqJ*0ALG`O06N=WCyMOc(_6Z*8sJst+mns+UnXBl|f>BM05@wN6WbYDp-7Rn3>trlz-##4Y@-Pd&CgOlunY!iI2d$c)jUt|Uhgm@AEeXT zLg}#6@so)kVP}nOKOls>|IzDYc~GtUJTN>6Sx+JhDwqDs;Thz9_56jQ7;P3DOSjHx zhxSDtBEivH$%Y?NIwYHm12>NXiRx1ZP3&S~e0<%Cx)7hzw-K2y-Y8QMReD!xTc~Qp zJ$H#ND@cd5^gJpdk{i`vqPfJ;S1U(aHZ*Pu>3*_N6&O|g;O9Asp5j12dN?uq*;1%9OT*anqE~BozztdBTs_GwHGV5 zCd4Tlsgkh!jjX>dC!f8gca6gPE&p$Me57?XY%Kdp zu3h0#txLKzIqCG8I=;m$K-7HpT5R2HXTYST!!9xr2UY$osD_wi_>gb7+E!)DH1_+7 zK$ep+pCFxQ17i-pi*Vj{nQb?B-dFN_Bh}VyF0{m@r5#z`uEM$-5$ZFmwp3vogz>>-bld6yxXXCtA`Lgu& z3;CF2lTO*k9_2+{&Xs#53u8%Pri60R$k^cCykfy;^~I(3M5U}G>9VEgMdTX2TyGwM zTo!lJ46AQ{(+-9B&eTWT3G`%@G4<~Pf6tG$H5N3XtoFLFFFQ;k$Vz&KjZ`B4$83c4 zyfd-I#6SD`{5IDcfn$aI@YW@D2PT6_s5 z;%2_XXZ?v|jJ*8e8P_9Hd&b97luhJ3nIjaEUQ2h+&2MP8|7?y> zNTZJrFkK&sznOd{+0=sX&Q4mT2oy0AGC}7W33Y&XWYOxAg5>8z;nCw;zPSs{*|jr8 zvsavykyo)Nz_!m5dWd$v|9eC zhL~4xo^W@Ry<;S%F5~C<9;wA8XF2r-QA?-tCYW#2L)Z?52y{P3(M^zi*T@2{r3{-< zt~GmAy=?P>@2;L|W|A=PvcF1ipS9VM?0MqpOupO@yQ6WTc^*Eqt&cn}Nm4*eo)uh_ zT@qK{(ialGHfwj^im7#?jjr0_LtU(EWdRv$oMpQM#;4I3o!;}uc?-kV7zml~x@V`Y z&z|(;=oytq{27T)ABD1YN3@azoj%S)4Juh1!y^r;M-b zDBayKuVJ-zO2uV>IbKIT+oA|5fwKM)IUEn_L9c|Z<<$#WS=*Wnf!cL-u1LBap4)Vj zsgl(>^J35Oy=WIbxv#>f+hwu(>(oWV(imY>t)GQ6c?TW29xVk(cKYOASXWqAj)NYa z39XnFeD$tb_D3e8z8PzpT6>H{3xV_t%95mRf+4l-l1WjCIZ;Iqdu*07Z}*4W#=>BN ze6I?cWpy+QCPD_8s!ZkZ*}ZL@QNCx@yqS0&-}#!!|1hUHOgk(}3z7pLzd+s^PO<=< z-Wq;T_lE&v0jEP{4ib zRe6Q(aeE?x462UnuB3XjrmzsW=w@tVm{#hR53{$JILiz|eP~YV9;{UryT&jJWW};A zcX8Id-FL0V{195<;ri{m#PyGi?HqP-U&iFjDp@u+KW?Wja}EwO^5XPTPeGD1X&_nG zT+S(i>E_bzS$Y*Y$Kl(u9Qk zJy(a@GA%r%I`InUGV9_6pz}|QTf|x1^-16P%4(0tuyp6_@40ow&VMoCZ05SUE1A)=-`r)DuTu@m7iSZA0w+ zA7V;ApMDVUazb9GSDF=FRNG?0LXIl|PgJS)7n;^lz6fHaHxD6pBGSR!hHE&o@aL7pys6$&~x=STQBL z9O$!-`jece?7sO_+;6u*t@@IM&~@5N%Azg{d(V9qwCGCs(qd#A9s_8pdR8J_DmiVM ze#g2J5;fgI)}Wh?@=G~uE+WBswM8OkGPR5RZ$7__iAhcyOiA&8sLtB$fVDD(YGQzA zS<^1yjk!^UnfZQoq{BNo1G~o>x-2AXlqsZWHU}Zy;OWI$sV;oV-DJ0{9*iq^4?aUsg zB6#U;E~I%wd#zk!+bUIyow|vP*~#d6rIO?LXD(`p&c%l6&=Q+XXVxeVK=bWt*m z$TL-?q~F`&spptWr`xcoLfsr(ZDVlt#5{b7BMhH~CReh4e%|s`HGrsdUn6N{z3`jy zf_Duz<%;IZ!kK7lX#e+;m^zx7wvc4Dp)sGeO%P&-u3hpxaj>rlkA|W~pHv%I zpC#K5^BCY91F}(ggQY7_F>v5p3IPtTq{$meOKjG~X$b*r+j}Ov6gxsKj{4W^_2~w# zTpe*-ey#!`l}YGxz3*ZaK{@v2vUh4OX(6$=4INR5b|Ce^qTt0Ph`_}alSgH5Zqay2s65S)nS^R*8H~?E zX?$)U%*e8Hn~6hNI+~@S4#kB7f4U`#e>OO951u($&-|%G(E_&=*2h=LViZv+j?e;}~dFJw%6rJXH6;`>9x~;YJP;O<4Iep>G_iGN94)s5mXO~A9ByYZM zyZzm5Jc^J_#APc*ca|X7nl6Tmj=#U){rmB6TMMcYNMY3;3op=>*hh^|>9v05JzS;} zS@}w-Q18oIJLSwgCG`!)SkXPx{^{@=Co4OBgy`GESbnOD7WuCO(`~BE6IC{-<5pOV4^57@0lp=0JWPT*_1$1L?d{NB9otsJ zqLp&L%plIk-gvDHUxf#X5UyWt(Rmuanj{vaX`4tOjujB-$7Z(eW8Q)A=tJyIelEuL-qD}-2KjeW54YWn*YCB4NrwH%G?*Q%dM0+S zln{|dd-bY!kq#q@BgDHhJb1m*TF>MV7Ad_u&qNHvp-y3Of~Z8qb{MAGX>(tD$rXiD z@k2R1#@~0k={z%*~;_% zlZ{?so&o-y3*8&jm*<6E&m=ev;|E3EI&eroWcesS7$B|t%Cn85r`9&f$S~#7J({25 z*C+SdI$e^M52)jWgV}vI2pI|~f6OmNe*5%Qbpn;mX0#HBNE*faKucO{^LeQ(W|yt0 z(@J5vGdpffc;QWm34VO)pm>1(d3un4x0`3l+Iv6qyKQSL{kWF5Hijf{$L<+4dE4zj z-5yX(E0B3_u2^6pezM%c5*#j6OR3DKuDp?pLEh>dY z+0QrOVf#e4d*SUR?G?M9xfay)n%f<$qkMz#x&a%*=i7|ejB!V>#SVI)Luq%{sD5zq zxEkgb^ltjm4C7k_D!nAI`F!@pvf~23pQ+NrDs~b2htV^}ThM!ICG?zDsz+1Ns}={B zOMhHSNK|)t@Ia^{cT^;)dXs4*8H-t}-r`PEIg}c|#){-d8d2rO8xc2ms>+a^Ppq^W zd~>z+4(3c;28<0^38p4TEW#?jR%eSJ9#PQ37T*yI=Uu#$uIzSc7kRm9mn~&C!|^A{ zS2iMc&A^wBFR7wzwkq^CUg-IS^7HfOP@cQg$!P8AbY(Nku4bdc-0eI)<+aS&$kzMk zb|WKXk}WMc6&)Zu9x`#XFy`)czeeY{J|VqVfr;*fbG&NZsl)8pbct{r*a3%k@2wynW6U z{;N%-uL@ce%ol)ahilo>89)E&P!O#s79t# zNvh7CfEJmj_m}H0R%pN8dL2WuAofo3wWIikeVsE|L;214;y8-fDFRw#;!j1*O_AxK zq0rF<(D@`2ia0AuFVwY3BSYyg7VhD^ThSKx_Lu^ciVcqLv{W(QB5gP9LuBLK@~Xn` zZQpN~pl&ZQtCFB`)4J2C!yoCueT+pRGFq%oi}zo16z~6hKSf=+UoqEOA61vbUo0J8?-VOSXVY9Q5Ny;~ zOGV71s=gQoj;a(|d@jG);6Bu|!BkL9&^i$4rg?KXLbr+3)@_8yI;pWESel^g2alVE zX}Qi~Dr_d0AVs0pAY(a==hgvxNaHVFw>`c{u-}3$gu9g6uS}z|(&qlA2#`Bx8 z6ti4D+mBt^lNBU_Z^bNPdz4L7)0Xm>yWbrUNo;o|TSvu4;CP95AH4Q=&9C&>T|XO| z+{~!!W4Ahz?4rVe)oiTv9dR@b^7N5HnVM`Yc>UBrGRn~oZ%`mxTJG1Lpe+eraQAeg z3yss;^*ylDie@{Uu~j}tiHrXuq&NR(?&f3Flpwv%MO?nnToMebmaMISC1ZiYwaJswcw~oT>k!M#dhZ7sG5$dPdhneGi@7= zQ6p6SmgGDoX|sNF?_4Zf%35_K5Rcpj+GOLZUbPn2j^-I)i+mfPOVIg|;I?f(&(9QY z{BXfV-p0lb>6)*sy!bUPu|v~Gop^d>IQ@VjS7G+k3mpX6OPVlV+ZoS@>eW{cV=~%4 zu#my*7XHbD0T&z9_UnX_KO6EFD($E{vTe!=+;2J*+3Z}F=9Ko@$*E|%ZxXw_9ccS7 z)^{dH-rAtT&aJo1&-x0CdO=12>8x7q>g7FJAO>Fl^r}@{y{dB@o}iKU)qUVC%X;KN znlw#?vx~n%^NnTe5u9$6pm(s_M5=apFBX3;7SFd&H!eh6Q#phGR*#gZ8I|!wjOC+& zLQsC`nc?7}AO8VkIwq!|F)Cmr;x`!6F*oH{MnFO6V#j|U!&ClJ5pdMMG8&4ka0?a2fdk04mQ$73R;D7i{=#sziP4sXC>`(a4 zaba}h(N&N&vNmxv1)wr$7S-_#Aa*5win00n9f32ogTg^q3LE^71a8L#N9bQLp03GV8x-80B5UG1 z&!_9#9B!al+d!dLHxO>hXFHlYsSGcVVmAzU>?K#S0mD_0KGU@Q^xYE|-dm-hiBeOW z#pk!$Z1*aNRH%w6t8Im(zu;xpj7Q{nfLD7t@$wU2jT()m9lXe>u4|;dWS=BkC>UvJ zTOw`{M%c!#+->SqZuW5MQ2jjUjzqpiQD%3MR@>1{TrM3?<@~D-)=Jw7!7s62ujFM? z>bvE(BW+4;ul!fC{X%p>0KC&bNrfKEUmd9IW@`j=myNaKf76Tpw;Va97Xb(&bZKE> z8&`t+To3@o#0CBT9A3nGoDILji_priHvf|}e6kc=+FFJ)6ox+Pw;YFwL zqEmR$DZJ6kc=+FFJ)6ox+Pw;YFwLqEmR$DZJci;p+EeCA3{PP zf8vLZH;k_SpH=;DdJbkKkBK=@VEez2IrR6r0CW)-3=W}(K#_2I6da;Oz$4|TXK7|2 zWNl(;1hj%j$ict}=nNDD_#3?+^am~&`jd#Bt)!8eiK!z!uuUaLBddG#FhExOTjYX5 z;1D>$@i&sk-^l5?9yg610z&|S=xP8c8zTU0gT_ZGqFG75FhR%4uZI3Y=Ai!OK>dr% z`5Wc*mw-m*{7qu|OF$!Y{(|uUu&4hWnX{y5p+;sx@tzS+uksy%IWCQYCbqvJ9*NW? zndju0x2F=>b0Jc!&AJer@UsxccY#6l8lnnM#W?7jSn`91$t%8jT?VnMDfa|PDhT-p zDYOLK(cN^LKV0cJ95k8v37z3vc4_}vHPf$V=XZ@Cmy&o|H+>k(@vQm-9g-p9WSl!8 z^z{u57alX9eBWjYMk3FVoRz?#Cp#lVA!!1RBER~P_(kwTdf}E@<_FK;G2u+; zUORU-_u{3uxo5szdZ2j`=d~iG#16^LhmTVXwFH>4d_e-(t@sl8Ay+8mz6DBhp0}(_ z-!uN)QGvzJLQ1c2Bz*4dCkSPzKW+#)$=S1bIz%hFmwXjX-Hoc!NpPaV`>@3}9xHP` zZI!fpz;*p4!E;4iN)86e31NaZI;Pzk=J2C)8S=pnX^XW_A9UqVc~W;->_ED_;Z2X#+v!-`2$gq(T9r@-xfvR->i+sDnWIU z9pddva!V4u#m2khS@A{Y`wiP`;@`<)#mjaWC>WDxK<^&yM*Q3c9rp1h5%n!{OKos} ziJ%^o(+f6-?#t^`c(lVxCqI%)b+*C5&Y?F%BwCdnOtvVuIGjRTO0HVD%8_!IYzyz96cOiJM`6g_n4y<8IB)79!7&>6F->M#oKs_|pJz!@p;#*w>R zm!$RnbJDq2;rC7C7Rm~1YeW!~FCC4jc=S?QEPd4RV#Dahxwp9Zo^a)vky~fov1K;@ z&>e1LRgQ-*y6j@Vd}X%9cfaFX0U_=DsA)-c1fL0!*7j6n+?k(y#$Feq_q^AA9U2p1 z?Ju+)udjYx-EEMIvydUyYSN18ykp93k}}QRZM8YLYX5L6V^@~HlyUJott{n$`FhNm z&&BRu$rBs+%nV=Znv6GH8>d4wKQCy{jv6^fe&V`Rtgs#w&c)dO#;35)=FaLwNqoSF ze*Dmj2P(sSs$@eV)0CFcchjCpdm=xKsZHe_uBuMs!pE(odA6wvD+GMrimdnvZ{Ibn zjeilOJW1+|%Z@R?THE8X{qL_zYQ<@NG= zymO|e1V1kxaC8bT!d<y8Gc` zigQFSuaXE+OwZG}4^QW}9EX&TUMB6Y+6~bb6o*wBx44sVB@x7DbQ`H}TxSUlBgky>Ab@*~YBS{49EwFb9JtaXPJAxCawwY#O4Om5vX}_hxpWRV; zX*+lmwh?`Jo2hDJ)|#ceCur+mh~H<7c2&PNC~dEz)y6aGpBfbFWxA^qgL%WK?$=nU#4q)wFB6 zmAAL?uSd&I@&D|y-t2jo|3Yv~HVos?c`CW z@3r%*9OGNeqH=Lfi^hq2s{h>U!wlpM*}4ktn>b`KRUe(p?g!RR1}TlK<-pLX2brzBjNkhUX@d0 zKmHPhxuDVXVNX=e1ajQK5AOg<_Z{lCcZ3yAbP&4p@zqBX?#5)2D*rXUi5^L=|G*R; zy9%_`fPf%~e+>xQTA)>41o&U^ms148K=6OnUwFUYJSF14F^B(~rxcQxyrUuWKYPk! zUf^$@@?Q)1uc`bG2&R*zqnUxFjf0W>u~pLoT-NV6Of)m`{~CvhMDqUONB=5}VbdU> zzqy5fc`m@`{f{_IuuUyJiNA|?{j+A0hfqghNtH}V+CgQfpE#gv6p9yTpPoPZiS4A6 zQA=2{E#P{sdV|Mng=&XS461u>#*amFLi(IuUGw>`@ip$@+e+P^-;qt?(iXE!4xhgw zBz^9qAVI$2;I|da$-u_UktW7nP|f%P1ZJeBR5tmP!B1EEp_uA>kKQ@C4!nxDX`>Wl zGfT?p)pav3Nu-m69R(w03rm=-o;yZ8mtu&h(7s%&d!)_>D!b+OBjO!XUAV=rPFmt- zaHzB~3y0MptwyKD$Mc@=IO>(@EY}HrY;9#vX4+pJbDU`q*uUBH>#XMA@kATr|F-m) zIf4nn{Qrxi2M#3+NB@^{B2|u0lzx#^!SoQ&UuOdUKrkVoKRiDai1-KJdg|y;9sQ}J zKXvq{j{elqpE~+eNB_%GK|p9%aqP2xbM${%3$*&1qyNiZpvB)E{a+pft^VfdA)sI8 zpIz3>NW$L6$=2cezq|Z(4!{mv>7|!fqF18_gSe605c<1LdiIX)^a`TlB7m(ka&`Qz z&@b!9E^e=9Z9y+;WNE2qWdBkYmBj z##$7B<^u))W}M5}82%~97`eIF*c&5nxi7zRbZ<^cUeZ~d1B0{RSzp#cqqqHh!Y83zIZ*XJ=bpuaK70^0*4 zG0H-aU=X?)zi$r$ha=JE_74q$KtO8FS!Z-vI7U0rahT%^ z%yx*AWf5QqMmx}P|4|l+zGm`!+rTj3u)@eIpe*V{+kiOCJ^;!hFzXBj@xl<8?S&zE z;TU5Ml;s8PXkpX^$qPLZheRPT>j#HIf!kOZWr5=eqwm3RCI{qq1hWr-TdOe4eg@*uXXhAYfr%1BLjtc{!K^a^0S0E_Kg$Af!2Lr^4TafP5MJO| zz^n@}UjQRm_C)xq@3h>&PKidHm zJ&~upASC)SA^PXn90v3h0=+I`Xvh=&f&vEaWLeaSV-*DkG6rLNC@=(b4g+qSA~EMl z;Qb>o%(VxI113t$?IC$Fj|Jdr4-7N!f!sZrrzoHUG1?21h4NzL0ieM#*CPlF%!_sl zzxNejOpusu1Ii+y7}0381t9`oD8tUVeS{`XpDRT%0i$R$2p)OFy{zB zL!Qt8dw`j1fTx0D&bz?+1_EAK^k*Lc8s@xF7xw1zpBfQE!%*7-j?5<2cgAAn&f z%y}FFtkanD3tBt540!KOEI55ld!qH~|f8+-6o+dcPu@CqS z-V=2Ov=jLU_!7+Z9PL$3)CB?sj1I8=x4y^V6J5lIFP%TeT4)jPt0}z8s^#!r1MFC z0B9%Liv&)=FmniSS10n17lp(;e*^pm^2FQ;XeZ`Qz?VQUa~Jg=b2bVD*nW)h0OI~b z15DwcaeyyA5r@_={U6#tV~!hI!}LvnhQQ1NKm%L|#(n{th}ky4I|7M%G7i)GpySZ5 z&HFw701cR&PH0ffyhq2K=mRjA7jt}p^LP+uZlE;6Xv)9asN>l2r*Homejcw?GTs;0;6nGyZKX57rM;gOWz)x+}BXB|M_}U6kTQ~wqz``OXFHZ1(0H-uK2mk;8 literal 0 HcmV?d00001 diff --git a/doc/cholesky.lyx b/doc/cholesky.lyx new file mode 100644 index 000000000..99157fadc --- /dev/null +++ b/doc/cholesky.lyx @@ -0,0 +1,170 @@ +#LyX 1.6.7 created this file. For more info see http://www.lyx.org/ +\lyxformat 345 +\begin_document +\begin_header +\textclass article +\use_default_options true +\language english +\inputencoding auto +\font_roman default +\font_sans default +\font_typewriter default +\font_default_family default +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\paperfontsize default +\use_hyperref false +\papersize default +\use_geometry false +\use_amsmath 1 +\use_esint 1 +\cite_engine basic +\use_bibtopic false +\paperorientation portrait +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\defskip medskip +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\author "" +\author "" +\end_header + +\begin_body + +\begin_layout Section +Basic solving with Cholesky +\end_layout + +\begin_layout Standard +Solving a linear least-squares system: +\begin_inset Formula \[ +\arg\min_{x}\left\Vert Ax-b\right\Vert ^{2}\] + +\end_inset + +Set derivative equal to zero: +\begin_inset Formula \begin{align*} +0 & =2A^{T}\left(Ax-b\right)\\ +0 & =A^{T}Ax-A^{T}b\end{align*} + +\end_inset + +For comparison, with QR we do +\begin_inset Formula \begin{align*} +0 & =R^{T}Q^{T}QRx-R^{T}Qb\\ + & =R^{T}Rx-R^{T}Qb\\ +Rx & =Qb\\ +x & =R^{-1}Qb\end{align*} + +\end_inset + +But with Cholesky we do +\begin_inset Formula \begin{align*} +0 & =R^{T}RR^{T}Rx-R^{T}Rb\\ + & =R^{T}Rx-b\\ + & =Rx-R^{-T}b\\ +x & =R^{-1}R^{-T}b\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Section +Frontal (rank-deficient) solving with Cholesky +\end_layout + +\begin_layout Standard +To do multi-frontal elimination, we decompose into rank-deficient conditionals. + +\begin_inset Formula \[ +\left[\begin{array}{cccccc} +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\\ +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\\ +\cdot & \cdot & \cdot & \cdot & \cdot & \cdot\end{array}\right]\to\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \[ +\left[\begin{array}{cc} +R^{T} & 0\\ +S^{T} & C^{T}\end{array}\right]\left[\begin{array}{cc} +R & S\\ +0 & C\end{array}\right]=\left[\begin{array}{cc} +F^{T}F & F^{T}G\\ +G^{T}F & G^{T}G\end{array}\right]\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \[ +R^{T}R=F^{T}F\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \begin{align*} +R^{T}S & =F^{T}G\\ +S & =R^{-T}F^{T}G\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula \begin{align*} +S^{T}S+C^{T}C & =G^{T}G\\ +G^{T}FR^{-1}R^{-T}F^{T}G+C^{T}C & =G^{T}G\\ +G^{T}QRR^{-1}R^{-T}R^{T}Q^{T}G+C^{T}C & =G^{T}G\\ +\textbf{if }R\textbf{ is invertible, }G^{T}G+C^{T}C & =G^{T}G\\ +C^{T}C & =0\end{align*} + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/images/circular.pdf b/doc/images/circular.pdf new file mode 100644 index 0000000000000000000000000000000000000000..b0f43f64978d3bfd4ded1bb64c6ee9a64ea98ae8 GIT binary patch literal 62900 zcmb4q1z1!;_qVj9BF%~-C`k7uL>d%u>F(Gimk=`I23 z2EX-Z>pe~pcX6^=+gIYR4po|g{M6PZwP;&<&4=fI? zyIRk+c<;!#D$C*t$TA0i)e3eF7SCdQedj6G1Kg3`dZNpW`Vb=S3#pd@cVMI>79!u)RhtV zCqdT9(G64Y%J_Fa7~#QCh^@JdlLwTSG>|b;HE9<{?t>)rnsR?ysG{j6$PJxj}(E&3}nSZ6S|4J1ZF*4|>TG&A?-5CE` zNYR0hQTQJ-l#uvqjDIoyOZqqCe;HBaAFX))sltD=;L&_%;r0)u{$n^s9$i}q#^3_{ zq5vb$YpAWYjTdAiJfSz5)<4xY_DB=cUdR`*4~7RDWbnE6}caz$^+p^tzqoc z!$TR{G))6>^^y_0++*#RrKcFKQ4%au&orl~OTrXqCQWpLkkjxV z^f%0KXLb4ip`Rs$V#nXf&lvx}YZsD&P@p{!tuIthJPKJ(G?Yu^y0KrR%Tz?t5Fevf zP1vInUh6X=V)@6IQa-?_N0w$eCT=A3KkS7NX8FW|@7!0=@_6w;k|uo+8oJd*J$&=X z3StTSV2#ZLvd$Bt{vnWfAFmGK&j9ck7rq~H(c~zNft4gzuy&HcE2nRF^=;}kU%(Q_ z{-oJQ!`gE}XgOfXfYAu){x5qhnPA6)Ar#;7+9xbarnXgtO*#D>BlD-*DhLU>DC}ys8NirCNe6$a67K-rwzh{*HVab2E@qeYV|CAA< z#E2Z`(Z%U*-rC(lH0hLmAI^v1$HUa6fX!WWTJSLF9RXryIx~}Sb%1%$$fG@Z5 zD}cMyp5+CCuQIcLG&V~4S88uGY+z>t;Rab5ZLmTx|8KhpaXeCf&uKQ5>Yn?KvZC6@qBln^CyGP zRIeO2y7GvM7AC2oR){|N00A z<25+(HVTl`wXTTWu6T>^IE)paxq2e6=RY_Uz6(>&;=(kk;j}eXfmkl&)jU=B&%)qf zbI@i7EXH$c zC2_AtQQ*h{z`*5X$mf8_9xJmrGbSdunHmXY7!03iK8IsF`3`_%YXg^fA|i zK~D$;Swu5SEO>!wDeV=oRK98d;D1+fXnM@N?8!_0I%wo6`)I8cWUThJ$cErU?XN5^ zG4p>JgzH9+#>LIaSAvWQyq3z31xxXMDEgl(`cf)-y^w|{TPYP4f3SD)wle78x2il` zHu^_JLy=MS(%5nL|IZx$OV%F2Pf)eAf6&K0EQkZU0A~)0b7URDO`I){6BZC*MR5-D z;zPb&qLpZ!a6Y(rzB|9pNh+1 zDS3dH&gAQ~0EBsD`yC_<*1q<1$m&``wyxB$)(W%qUaz9-JSE@NCBDr;t4MQd_kb!> z4gH^oo+rr6Cr`{`3llLhf$%K#dz2_4YQaDFitF)01Me1n7PdOE$9Pd$leS$1Osix~ z*a@;SHP2ox53o-j!i5nB_D%`YOdu-z3nU1AUR|r?5E~Ui#bwBe!Ty>m6HF*`x^u1u`XXH6&xYCL}EO(J#A7CV& zl8QmbycwHX+V)aR9dWe0=z!mw>+z_G#Ivb2*b{Da{I*ajqFAy6E)F`~`0lfOC4wmA zRQZpB?A6mpJW#9#t)CV1`WV|+vKVm6LMoHDtU01#R^TeVkRB_(u^1gAA1?s}ozRE{ zVJy-jFX?--(nchmk0B%Cz~Sx1B@@Wg@M4e-eO^=N?GqdIqttsN66S4a)ZE;oFt5|> zssJ=|ahon|qkqIX{hD@B0G1vYzJxo2?Mw7AkU{3(kl`Vk7CxNf-_w<18-gfWxMe3}mGbvFkzJ*h6nl-bZg54EogfbTvi2vk!&2acwjkL00Cw8ieG4hD29WZp2$B%Q<=` zka2%K4-GmJCE}mC5rshu+Yc{LpxHQBvHmsGI**cc~}OKIZkE zf>~tcsX)UhzLsyL#!2qD2?spuu}Tu++B?q_X&oj?jksf6Ft4}!0}tDxa`_B@cb&8} zmYEUY5gM2L#YEG_V#wO=kE#HH0@?x>n@w0|z!hdt_>WWx{1kCV5qDUBb9~Bq`y6GAZ-0RbP|1}39i+M;x z@ZI#p5pQjbWJhA7vauMbV_*;Ir_|gamNrtKelmkTbqP^2plRuc%@2CIvfq-*zxw~_ z0!3XvCNp%C_?l#1*`(hdSe8^Uo~2@^rqg1B7~v^4J*@T}kyp}Ks9rwe%!i`R9gA#z z#Ux|b4CrYt$l>_yubWMt87f5JY=8vN{14Ztg4 z9JHlGh^p=JUCHO!tH7-_MXK4}C`<}KrfIHq2btlD5xMb&WDjDI%$7$!6$AX;(mAuC zZ{|W7lEPtoMAwC%WZ%~I@LL4yy)3M6 zGpOm|X}nQn7plzgMbx)6WNk|*OvW;PBo0~D`^AnXQ^CjZ&bsX@ldYw5t^?z%qV1gK zY9DOi$6)sg-^stqcz`!Wg9iqf#!s3Cl5$Hv5r6sk`HN7$PU?L}hJE;p?|oyMTT&KC zi=9B&-rl2}n|#i4T)5Zw;kldLFIIdG(!kl-)X1$SwO$~&zQgm6;_P;sj3#GW-fUt0 zpQn!Kk6n4QA>6mUuOJ%L5vt#sx%Rcv?v@>8dZ%7~_clIJU)Tm^XH02nSLlod-z z!VF9U?NCNkUI=bW&&f#&cwQ<1mrW}GFF8g63H^el^cGTsu1(GL>QKbT!reZ@tjjo(c8Vl}Y86_ zJf``T#sm)RlcoQIHJzi?N78rrvzk9}3=BNcac)9POovf{L^e|bvC z7CxnCICv#29+_<&Q1yOqTaY;y;+Ewz`UY#+Uz6VIJeDjct#k2CM{`~c!9o5c!b&xL z{5_eBkN&zF-kwaWMNi&2`Jes!ExLO87W;|>e9=rbRj8G^KdAW3pS@B;OeeMmk3}W? z3F&5VH!H*91JpabEOAI~iD*Q9fCF>*8anNJ1S!IEyO`g9V#v8-W8AR6*3FfpXooR8 z@~s)xHj?O*8?#&NAs55^v7V~@Eeeu3D;}|P*c=Ue$)??Hd?>wLdXRrlSYS>UG8ViP z1FmQapVOT>7qEVWei(oF(^i1}=jtf-BQzv7Y8v`#0s&tgj4u$@ zV|yYtzTdaL(xb3ewBNgKZEtl%Kvg{5`zsc?_3LSM&hZ0{<}*{a6Wz52^m(PG@z`f1 zTPelvqqJtd$^|{d&jmKUB(iOB(j0uxDh!(9HN0?yvEgVG8tL$-H;3LMVy7GBfSY!G z8qr!jha9ct6BZ>dXVR{7No`c3`rcmho8KeKtHI4^e7Ic}kUtd96V|dlX-aW|`ZyGS z9wf}Ze%iZUd2jTx_z}C9iJeI%OyZIqsyb^@RH{9*8;|T>$or(F-9|k4J03}3Iu_x1 z>1n-`df00Pr`&h5CP7f|_geXBQ?|c)0Zph*{avbU%l%Q^Gn@6IWI2t%IWNUo^l!-OVcr2%LE(w^kE+lvNXRjrbhO> zCz=zt?^wsiDwW8Ms!~&^Sg3BxArw?Q@C22+KggQ$IT&__a3!bd@L`RJWXdjM`6uFK!9$)Ky6W* zt2OTg`?@u%viyT`dDuOfUg@*myvs>#BcG7&yoXNVkv&`PTlEF6aI|2{5UIh<$f!L_ zQm57J0vBx<_J{jL8eBc9;RY906s$NJQ-S0l`Mm0d&it=y=+|q4Lt2%#H-Z`U<3|Zn zFM-m3w9(NuuZ)iq$tW~f_;{>!TvyYduZBkzDr2HP83LXSr$*;Lesx7ov9TqW`bJ|e zpK2e}Mf^ioQK9?up;}Czpf3(i^zw91PHLN0H3_JWhXFlcg0qJf6cY3mxc(WcFVDj( zYbh!mHDoB2dcY#_jm6So3N|fPg=&Q`hKLdm*OO3>8N!xzzdhaAjt3We!98DtWe$jY zmgB+wPUou2#{NDtV69pDN1i%OTqE;u;mBuuB;stT{MrLfaZSke2bpww#Bk+nPnjiE z0kF}I@&)plue{R9$wEX$*jX;CcnB+3*ZKp3G=2Ix5(#wGl(75{o;kcHB1gS>FI72~ zeQdF!9LFtS%d&RH_X8`}P@RvtC>J;7E+AucPW#PnB=OYywprXDZ@2-8CiUz52VD6T z^{u~@Y|==y5^1mAbU%35`F`E@;7PSUF;CC>gW9jwo>c;zJuG`9Rnm8(X&|m)h9lV6 zE9%4uj5ysDvib3)d8g~c@(Ly4k}u51Eh8>r%iERq*Hd$2 zKQk)L?LHoLkiRVEbiHiQb(ntf-gEj49^w5O+}0X_2rC{^)NtdUa9nP6TK3se#Np{< zxeXtG3jY@^ymXFe@QuNC#Y?lSe{zRwl^loguxadO#`R9)!c85vdl85TekTeze9hQW}CcirOTClrMbfzdYu<~ z&n=REnggT`eH%={4SLU!HUgAAlXhck95ohH<={S$$BDx~?PH;0tETA+cQG+|c!Dxp zGRo=+eMP0CO?6UGTBjO;Ge{e_hVGUXrb}s?-P`i=U;CeC&XSB-QA{xQgm95Bq3Qq zP4^$f==SJo&tF#Y;o%>+-CyChNJ9qH6>ICbU}A1scMa`$eim`jD!-h3xhMRyD~Fz0 zTmEmDZc#!SBGA4rrSJfMq)|FDH`GhnWhX5AR1T?>x;ci8s!_jrmx^Aex6bN%u!;wv z(5J`@zk5>W3{ae!-YOP|%-`kF4>j_oW_@%+9v&*~4Z%*F{4 zBtNX&%!_Or`3&9}Q$W_A3%sTow4x+o84!06(4SOT4nDJuXED0;F@7IE%@zClrH)wj z=||RVZ}Cn3k?E_jDrj6mw_QGZb?T8exfa!pg4q}L?HVz?b%8-VmL1HZQ(su;YdWxdj&uf#?POyEygvNozMAW$KO>lcbds|+_H4c zUR4e9OB3$f!3=Mf7u$%KPmYF(abB|iBXcPtw&A+aw+pH9d4PUn=+=9M8;cZ#KhqUS zLavLD;%k7L`EJ~GF5U3&!BpG~f=!AH_Dsxwj(GwsID^Xa4wvY^Tt95!8`^Q~!%ZwV zRJM%pBesrwHFv^(UXIIo?t_Gae>6Y7Z1kL?Hd-uzz}JK?Lkl-P^UVI;Y-3n4w$p_z#Z`)}ypmRt3~AO7cW=ud1LmFEBwQ z?icfv5woTO*35Gfy~VRR3q6(OFQuQOAKk!WqtbR0^?Xt*^$$F97KN2doCnZ7#_td7 z3%qs4(hgk%m|W{~fzjxGtD_BO9Xf@x-({q(s2IXTWX$P|*yrTlO8sT7`;e^tQS$Lj z?0RfC-lI*%Th1r?6bS>?PvAuGNWB6zu$+gFLDA%$_*r(J)ZQeQ6E|`4CKod0Tr%jH zTygo96gXoQBl42pQ@(is+8(E<&24b z_YK~D^^)*e_iC-*KTv>jFZ#5G!SZ}^3ENaWIqZCn{XtwXF*AV1uaoo&900oKd2tZWB)2C8O~R|@3^ZC%-4Bz(b+ zPho;99vxGtB5+h#;1#B_zr+!?bh69)>P+{nL=}LzMEd@`*?cNQf1)fzz{;)H;~juF zn|k#7nRapywMXWuqs%*E#ckMOlu`A2p4CI}8c`bZ%Qp4sIGQr}$D1tv06h;?;OGEgc&@Y!yFk zOf~Gy&6p>58gi`aom` z?Kn}PY2upz&2zGQ4=x#C$FCTG?MiAwp@d4cwFi2OO)6|r2MT+{W2fj6w3F}t&-JGQ zi{e&VuQDC!6c=XRDT}_$QOSM(@z*){&y_txz(jBQE8w1X?jwo9Phx%SzQbETE8R@m zqWUaDESI0&tecno2=dsLS`Y2{?S|@s<-)%Cezub`hn-9JMetula`FqCwDrd}~6OJXp#%}L7LclhDcxQcU>(e9h%HkoM>h_Sq;$_iK zucDe8r|f2SZmNHxe@xg-d1vpV2gpP|S(vwo5&%3KJXF%rV+!}t(H}VXrt?#~-~Jfk zn@wAL9O1=K(Zo*$|Lt`^oT1_O&OTbW@}&;Ma!@S^IXjl_#o=pd$ul#nz(82#x_-Rs zh5Vks?a=jQW(@soSZ_qf8#2Zpa=bKqQ{Ayn!OjH}T!H@1_xWQn&O1gJ=#*Q%AnWl) zqI^*Vv+jS4)oSw}vx;Z!ofY(wbABPl3zSI`lzqQSG5~n)VCi<1akFKW0d4@tfnA7Hfh5szfjYg^rHM*362(+jR;O^Zv-yd%hAA zNk3+%W;^MpWIB75J2m_g=*v@nR9<}1c1X?;(5g=zdXF@Ji-u`+!4pSNOXCzas**bO z+6(p+XstxAV#)b8-{N!U+LiBw2MtqAD_(LC}svY!;vC@u8*929Mc*cYAx%FVVjgcsvzu zv>iLwQ68^US0;sL9P^uZMmQ!Vo1B4fPWOV34hX~yV0)M#eSA%2^V3~{iIrWw0BX2b zTRfiS&&vavJ>i@=jRlpjM5sdwjZWF zv1#vWUF-ZnMbnvwig0i)$hj9Buz<4G{FUn^^^UkG$xC{?ze+ihL}ch)#s zYHvjNaWwBWrmzee%%nR2s_$a2+842^t(4UJe?3eS1&!L4Tq+7IhN4>s10-(I5>Z7Q zFuiums65wzuOD!Hb*fspv?aOyRVsVm?eg_2=$8A|3sn?8l6(Q{LffbYZ(IucP}nCK zQNT6ZQ&XNz5sV7f?R6zD$N^DM%IG&6!}1mRdUF!>^Z6dFIE7@+*glWZTI*_;g4RKX zcKJ{1o9!xW69qkv0nC{S4Jcq8#PjOno?@J%;gFaRES#Zy4Uuq*=TqLKn)Ibd+S?m&H;Oujf8& z(e(pu9AAJ(rtL-Jz$2+`g%j>eFbyI5Fc;af1Xhvt%Fll9<}#8Q#*jP2PvvFw(`q`R zlmt~U5c(UQcbt+n1M+SYH3`2E-1I3Ia51%y-M${(RzUJLPypcS{%)Um1r{{ec<*Z# zgrpisjjytZ&-I!{3ATh-OPX#2Ik7n$=HJpbQ|gZ(IA_i^AAc7wy%)Tvi*y*;5o5kA z(?035!nNcP+f9EVUcDqdvy&$>zoX0*gSVqNMQ=UzNf1$p%y!!!(_(AnJ-W5hgiH-r zR5*WZ%l~PGb9*eK_lAjIswMk@onfCv5b}wl*;o7-EY4Pme(Js0ke1=a;41J zsJMFElqH5B-bJGXHnSni6_IXL#z)lRQLKcxkqV-gnxxS=LNU+MHub`9JV3rU60XKO z96(Ig)AnVoT0DPnx`BeSuZU%3ZX7)c!j|UY>(r?7HhjkqEWB9He|-oX8ZsB{lZ}SG z&d^%zv+0eYhU>=3uOf`eK&Q*&ADt^_+Z=|g_LiIY~l#D;|F74*1h*jYQLwXC4VnXw6W;gKlM+hQ(EvjuUbl_AC6EFNqLsP{LVl6XIZU+`Y%DuPu=Gnc$&44?g>{j=VqFw^<{dVLRpTFj~S+D}MD z-p0ft38}?WYQn0CEhZ?;D~W*2u`rf`r%R6Og!l}w6AJ3pvPZ3~U!(oh$j1l!ajTg* z8Onl?y5kzIF(S?WD~sZbkD!O|-B;d|o$zS9f*pc<5;S1&BxgiV$RaX;vO5s~(FPuq z9&|;K^M5VV*j9KJpaqAu$}Xx432qSUP^bksl7&3kEtFacMe;Rq0v<;c3>$>E*!S+v zdIdscc_NW38H+CXO?YICS&u7{TsE&r1KsbR;?Kdhr5;zj_VSrNQU>^D0yDoXG@~sN z==iqA9#+&h2?D=~cEnt^2Ka3u~_kxFDiM{Z>lzgvnCQ3 zALKvp^T~RpMH!Xlck(N#v*8s^N&BYF@|!^SHoE$b)!FHX^pMBSC5o>PJp0%iI$E9} z0_vIfOg8a$1N$cQp{|#7&>>Ra&Xbl`4rI>P5AIb3f?5J3&X!S>bZjc7&%TffuEo$Z zgYelHfvk0Qls9orCG}#kF&%hcQH2DSVA-Xxuu?~~+_JCn^hbO)O@Rqtl*UDp&ac3- zH)FdK8Ekd5izly(%`9EH?+DnWwjCaYS1bu^-M_(KXT?yfRXJ4Z3OF8X zt(0kYcuo^{DQ(0sw_pKsuNXLG-x0GX_3t7ALvQ33dbxexS*B1?&0uXF>iwYO)BSdZ}DfA{r>?V;#~-FYj8r zc5^gz&5Yi8%^?RESb^B&7$04XH`>%`0>GCmF!D`W-{?}2~tzX3#8q#U2+gv&cmO2 z7(mb~es}1cOogG$&6x*o7z;kZp>bVKf?9fJOokT69Dkbo5G80Wv*zZbdWz29YKk`> zr}Yk^i2s$dP2i%?|K{oIE96HK^|$~Pt*1kZMph}LUM8Py`)b9O${%?M(l3US&a+LC zTt3t0s6yfki-_)}Y6zKYYLgx{T4-|Qf2Y*u`KsRzz>~5Fej~TnKWz%vrmhECXtfkr zD9*t4Wfu4u`V4WUPi;#d>uOa^d6pM8GT+YnBS`fE3_?u~Dm1Q(3oHxA4&21h7TY6- zMt5{mW}WOR=_4EQRaL>$cb&Sn@rw-A>eFuR={mK|b3Cn0g#CC1*{H5$*ppoHBA?R~ z5)WVYoCK^Lgv>QBF_T*2s0Jn!9MfyO$kaK2m3(PCv}$t20!*7_<9U_jRr9Am>1gQ!02dXbmtKkdIL>E1)4j@ziRVVsRF*Bc< zHrlBHwwO*3R^T3#o8Nt~e$F{+EWBrmKw4X=LE>)+uP0g}@C=?;ZrPAc!kkh&gzq(iMB*LS&ND(SPzwu%kaunU99V%%R^ytge7CO2}=m}uWyrVhQw*CSR zGpRTO4$wzfi6Z-za*8q#(a=MEGv?$7t(d_uyR@jBN>LcJd|S8-4H9t)?34C$nSMA{ zI^t|OnV)|9fQo!4-Ixh<>rN@*LAig|a zIxy@{+IA%pXkJ%@@t%-{yC#Y$0qzX}Mby{Qxvjr+)_*5IGbC5|ge(;r?D}SE9Zrkc zMV;YKle7NzX7oIZ9=aM)^&62i$uf%OwPXtF*~L_*ZI zANl&~&2DlLRCnN}C}9B$G}*M$<2tl3KUW04`20M{hN__9<5EXNN`TRHQQK}d4zOcD z0CdCu_=*rI*RFTM%vOa503Y3}I7fly@565hvi*)IG%q+SjQ zuAr$5?RS43IO#F7VUCxu_quIo-l2hSbrsK|G9*ZV**5_jv=6UxxSwwMRkMI|47N`C z&4?W|@3=X)uiFgnXe}bb2EC{ASon#^wvkM(1*S>^rM>hOe;cj21%jP$KNK=07D0eM z`}f@Y_-;!AI-7GJ@P{?xZ4#D)QTPvDl;CF==s8^-eOGxNj^^nY)3K`kq=Ob;2@fng zZnqk1JRr3D%`UL=S(I)QQiSZZe&&}^c)?)epN3>U2aClUGo`#@3#ig&urEPY|=Q~Tz~c_bs(0w1INus?|Qv-3cG4-OpkM5 zn~W(%n47-EW52(bbOzr(jk0O);T`Y#h?ckwk&$_#(35v_2^v^s)k`N{bSh0K0|zU= z+mhI=M`W3`qYSA!hCOtdRy&~DRo9&hmfYvu8q!|2dn%>T!snpiCkRD?(;2dyK2bk# z6=ysv?j)Wcku~%&xF7fI@zC%Eis(8Q^27C2OZIwTSioJ0{eU}dA1j9NTS(g`I`o5kAKs=Sosx6H{L*6})xSaqg| zV-L-j?8c<)aL^}w&GthJ;H^Z+9vc!^6^}fwVL_;lI;E_ zGQ00Yb9Dy4+%B3JkrZit*7az^Y-M}Yw}U{!20S#2YJLQ&;qvOIAM^s;L;a$s79I<) z@mOk7_y0l2cKgkvAn|Qy7Z-0Rn!2&!Rvh{rBtoDz4llASQx0ALRfa{$hq%+v({&rZZA>~aW4Q+KdzOK~Tt#ujBKvuC=zkI@Ow%V*} zc|Sf4iju0Enj0CC#YBq>``|<0;8`!TTVdX)Dqc7srT#6+ED3yb9l`|^Hj}4ngPVqJ zKc1i#p&#@9m^jNz=MTx3rh`vD-#MLz8qx<9JWj`)^wbXPa=?St7`IL2;*M?N+p^t7 zWfd4#bJ4VW92MDpo8HK1nkUFt=usF>F9;Q|kS$J?gKf(t7FxxVp;w&-L5Z^}FfxM>OYD;x@60?$ZH`4?PEO>%W(Gp^%yWe)n@wR z9db{LuFuUyR!h{52{fQh`Q_&1U<28@gtYsa*H$V6v#FlsyDy>#d)`y@Dury(2b*cH zUsrExba*@YG5VM!kTh^I%epk3lq@&@BX37*(>;v%o5|YhYREhsj|hQlnj2B2pX+aX z@Ih|eu&ga!s=3w$Cd+;`@ljG1STd2`+fSrdjvW!V5Al-Ao2<;n&p;5IPu}khWJ*Jx0m6{!Fw~Dde-se>jc;DKisp;H5M8SMM>qwk$!qpEHfyX89K-Ayb)vy z16JJ|n1uq6-o?AZ`*!Tuz8!@-OP>iKL99LaQdKyYbVjzD!X>KDZC*@lVesx7!}woK zb4ED8=40{w@1c($KZn0}&=jAGTmJq0(fAdX1t5ZJPDG6v( z51+Ya@vv2;^=%u=C~x|YLK99h3O*~3G`5yaJ5rNRA|piW~tam}S2Y{pl=q5EbCjn}k)^^xjRQ3gD*t(&OR$l>5QHxL27k3mNsbcfTy-G1>(<-K=% z*Q8*wUnHqQR(uKW5Kxdb{Na}lU|HgM>?$!{4HI35HAZj6oI1&ci+ zxva8UpLJQonQbm$N5u!0xiWsW2=Whs`78e_malrScs&MyEVM0WU>Qd)`vhEP6Ji9> z%0LV@;FLU+h6BQ}49}vE6s{|(hw>{jUl2B{XyWxa7sM$6syQ%P%>~!Z1?_EZcDT>9 zRlHp>PH`#)P8(K*}KY`0S*tO-SWB`$Qvp@LIU*+boN3l`AuQC$R zX2e|h%s~EXEv}pGyGqM@NsJQX*Wg}!>H-3T=Jn_+Qfr*I@@=<^0Y_#jq^Hx=L2Mwm zcxw1{OlN~OEF+dQ06sCbL!8Y^Y9@hOL2zy=AqVE0R2H!WE+!WEfhY#UIYSD<| zF(u&6J@~deUk{)QSOq{t8-e};eglb^Pw_}6{hS3gU+axns^A|Pfolf}VMyDWl+w3G6OYWs z?lnJCE2`I5BU_hMq=HkFw^=?CAsP&E_|wWyiT!uct{A{Kun-)6kChcDrm2tHSw1z9FgNLfgmQ*w_9ujaE4No~n~yo(RDYp*yjp!qF0- zIwh4%mgmqfq|J;8e%V>b_2?<1KX@%{N%C~&vG!1bnz~}cA`i2!bphJxh-Ijz^^_Bt zKR4Fckpve<<$-iATM+E-3obtoe#BB2pGCYMVf2Xk(LipZ- z)?A?meXK@|)IPI6U5sfKFSov>I|}gn(wG0sxCQ;^fp3Vv1v^}}GNB(Zx& zSzJw3zEVR+g8H`q{8f0vK3UkZ`Ky;6m16;5Y9)YeeRH`ZG->~Fi-}qjeqYYQwLQ^< z0r6bhq)`bq{JkE}F*ptE<@`Go2k?7c9}bI&e=K>JyzYd|Gn)5+SWY>WRNBJ6d3?0@ z1csC1Idy&<9sMd@SnqlLQl0w+cVg46tN$@mhvfa|SHD(bjDeuy!E(Y&S1d?n_w)?R zY^8%EA;OW1InlNy{16v(&Ss@~?+&@CexjJeO~ z-VOIh4ZGBa3=P+{nTOJmJ_AX(-d~$ejMe(G`E-yQ?$s}5cZrN1szoJ?nv}me)?4Fv zaB-VjPBjJPq{?du6;}rCF~d-Y2NR)mDW+OMeY~o>u5QWe&-1qBcSG-WJ2`iqKL90Y zUK`@Wc8%YSUd^s}S|`r+e%5Yc*p+J(ujtPkT}bTO_M!hlmmX|*-v9keboJRcZ$#n1 z#H~n`YDo9BZZ2a6*%&7H0UgVr&>zuF2M5axtb1rnWM_Xjo|{oWL8Lyzd@*3oE83ZR z{z;DF9Ef-Uf|NI=+-DOFdPC(FbA_#guG)|b>e`YkxB_eU-@7L-z5gwU#`one5i=ND zh^<5`G0I=*84JHI&8{4E^-~|T9PIp67>m2*eeMn;qcoVC)>I%ik- zr>~|MgPWr}PBn+4OzOlz*QrjvZ)OOO=#m*TNTKCDf$wtoXYlCnF|&;wo(k$KF?Id5 zs3Y_-=-15f?(ek18cKJe$61jafJ7cHuz@XI5%73H(WY87i^!c_@@{ZB0C-n)YtN=UE~uxsnnpVU;KUK?A7@GNP*TfhQw;Rz_}y&-L6A6J{WmKE-2@p}cFP z@Jag4HNGi<5WP4ic%dyL+IBmcFyfKZs2sZhk%Ze^DWN}yv1~ni`HRXj_Za=KC8OZ< zxHwF%QIYzFh1Fdf$Cd@=rkkGsclV*9rew^?EsD8LQwctNb!K_h=htQV*Z$MdEr&A8CU(L`;F%)_vGhFL4duW6?PyRqk+| zUMmD^aX6;=87Lx|LyM)Zf^#;hdA(&*^nz-uNbJ<}auahcYGE7JLQrifnGzp|)Q&Bm zjlW8A@Z5Lx+}IF4trd$xw-Tp4>YwBD++~8F=8Ao|wi1L&WbasH_MHhQ z3>W*NS@D<+ckA9UgPGX|Y;~fMo28}iwS3h32i7rBL8XJIFGdm!htS_9KqAGuVuStY zv?n03g`L=kzZI6FQ00Y$ZfLLjw>oRtCs$05#|T!ow7yOVdigTHM3J3XC!O<7!+w~* z?+GA{EwTVoL77j$EuyaYfI#lK`#}f`a zAAt;yvfS-St5)p6b!JjLryM~~5S})|?#{5`%kP{tGqyJ;$X|{L@zz41$kP>{? zYZdt_S1b2JUj5leAdLxudY5AUULSg!?piirCt`G`0dt$Hii*TwfogU~S08eOF#Ob~ z|A{mpuIBVhK{&O7=Wc}}$4kmbc*Wt7KJ=CKOTMyMfhQI9Ab|)w?@9uvgF-C|fYNZ- zg89$KX}7VI*)7gQjnWF+h9h3o{#BpwPOT=&`!W!XO8x5oz5Z%2Wt7koC;rYu0`yJ5 zNd=#c&y?2HUSYaGkVKR*$1@P1YR|%9)u3LvOq5$%QBnPDbY#vSDL{n%9F@rj)a<2b zQtmv{v$S+rv=g4e2JQ55r$-6(B%*jF@lDM;Nap+N&05e^4tBp#txk^WpW=`QsgDiS zBMf4hm^-J}1|0?Z#tY)Q{YigWnqR+a5yc#Fo6IdvHfAp)1#p{HoY62CQmwIv1XWIk zbraIc71(cOX>cyCnO34j%-@fgL~t8#q!v8m zDk(GViIf&3Xs#wi@X!1*HP6J^Nygk7Rfl4OXg&so@k>$o(Z0OvgSKdzhfqpD+w@7U zd69p^N&pG5Lw|;L(HjQht$J;9&Hiu*pUan{A^LJl!H-spp#TACtgrONf%ibce>I@w ztIm;srE_ z*_%C(V~#C$I@PD$RMi!+FC`uzUp^Ao$2@}8zdX0wuM6>fTe|TL+va%XyyczV8rJ1I zYiwohxIa{l{T}jp`JDXYpYr=FWgjqg0pqJ+^~dj0+k5jsQ0V9JdoOsZlEH6=$x5Bw zy)3%im|VP_;=tmLaR0BcKC&zLqkLL!A^ELxcvbmkL9yhl%`&orcSEjjb<(~F_`m2& zbwyc?`tiBbf%<}b|20DRw=O`>uE}~1*{-Fw?M&H#Gs9I=AC#sXiP!bnf6JRa2V>Kyh-3&~6lRyjt=8h-GGWN<+LW-5z(XF&?)+YQ%Rv8)dHbOMcm&w|_H z@sICsgQj;vGZ{%gOBG zVj`DAA2?D5RuW>8cxT6w)os{*dD;iwiiR*1WV|SNI zOxo`pOO62nPkvnPD?)RMV`7R_5_~do8|TEKbs$hF$D2Ie!+V3?6ay30LZHc%({%O< ztk{LbgN=G2&_ETWBD+2yq?H!9A2&Doi$ZJ)F>EiqnsBkMai!Sb*{QX##WQAyoT$Dw zQQ?HNCq<$-XnCc9MdkDvNn?HU2{AD;>Xv=5iJ?@T?b=Wzamqw(D4^NHCrJ?`{CGDA zQIrR{=K?CFYqOw;3r@pd84q_DB!*NtEvK0F*I=Cwno$300K^kIQHQBPeii`Q18LV(n;AX0E{Ex^I)Ag<;VGbP zSS0&d!x#Hqo${GDh_M_rrfs_->DZBOFV^d! zzr>Fh)Z0H$h2t4JRm9)Y2jm`bLYt_ zTN~$ZJIM9S#~nw3tSm4uV_KlEF{m!s$owzl#SMMXn>IG!Vc0ZQ2ec<_;PMzHu>Og%r)6trDL%z3s)@#f@{5~%&Xa}@A-S_pca%#>q_5sY|P&I6(ZD~n(& zM6Dnv74VYv1SJq|DW(nZNFAgZbB*QIotp}91NWNJLR+8b!=u-=KWe4?oTxMU05es5 zuKL#Iu)EVQ*t(7^Qz(i9dim$ZKQ#K7qK$Y!w*>9Tf~7xoq-=hs?|{J4bZsg@S*l=4`<4JnDMBF!xgcyLMV%c5zYmRsG|`S-0;!wJgB3)_8#N=ufm`ddYf( z9@0_p=qOFrj0dRs>E{Gn0fT)Tll|afg&iqdM9$xdW$<=Hh8GdLum+NWnlK|hZ0(@wd`@I4~WB%$I#h&*|{%IXMR#^xR zpa5xSdPS&83%Lg8>D6d)Npj%O^Q14rHf@1ewBV1=^Hl^I`h1k%oUQ)KO8;*Dd~_9w z?CH6KX~|7_IAGr-QNYA&W$kGQE{|aW%IvK!|IDd*8ozK`QBFJFPGYpfw+3Hedtz~Z znhrSA$S^_=vjMI0D^MkcVLUC0Z8WE9lw3Z4AjPjhFcd@=t(DJR>|;|{(J^b4UxOcy zP>AV_Hj1qrjyV))B{9mT<{Jo&9CLt1WFRTZ2|G2RejZ`7;Z&S8y=;v=w)kQQ^r}*-hs9Z=T@V z;v72Yhr3tlp=36P4KkqOeH_HZ6-$F*=Z?ZRXOjPHN6AzzbgjDfBJL6gov9o0Kh!OI zWLt)OFj}|*W(ST}W*cM@L0O4AQ{(=HjT;VG>BNTGcPL)%)HBo@n~0G)jaY>@5r)D2 zKZSel0mq+>$@UW#M&ukSfkt4DY`p6DhopL+=lhEkrvF~%UT(1-@4^DOFg4G za6H|ykJPFYrsnDs=`W=yb#FF0>^uf}EqYZz@-*I&al9?^7swlN1?|!Gu&P{?SM)cc zF<6rtd-7c14^2HIh;E8cD4r79JMk8jxB1;x;SEP6U0xe3ZS3!D=-e_`>|?2f1Vx(v z9+cStjjv#PKcSoCdz9UVtD^Z_7-rn|SSCyz`8wp$*xyI1VJM=Bu6T8{T@p@ZRnI@-%z%} zk0*eJ#;8k6BUFm2)`Aw<*M;(t{sH?@@3QUB+8e{R1zjzkxoGxPmcwgkpNW{Y;a>fc ziEg;OTmAdx{9c^uQX6MZx3VRFaRi`h#x}q6_>W(FF|IU-RjCd4EB+s@%&<5jremdQ z=mY??L_GOGWZtqe?7J5>p+Wg@%Y%}|kdTj4c-i+*sGr|!&w@lKzCQBKuAPoxj$lT{-HP{MEO`5CE9JXWa;YdPh|d# zS$jO-h+FjG*9ll(RzJsWP&Wz9^!s;@3^trCt&33BFdh3tJ)_cEjmo)DcjG=NEgW7u zO}D6Rmv~)g)fSX%^s({5+len~21{U2%9Ol06TewiDB&1Lt_m(xq1LNSSRgMXdJRiP5lrR;jrP-f`1oC^h0 zqP<8|r;A_St6EJ-na6>X@75JYB;cMkkDC9R1Ea=oln&fQb@InaYSL0txkuv>-_O;i zuDr!U_0Zr`7_((a!y}MDz+vqED0UhtYR|uHg;nF1E~<~KOsb$XD@c}@J!Fm2;?Il! z$Q-g1v|ccrH*;0?x^+OpaH5sN(}lzvpFge_b#0Tth?&o>m8(1hHh^4a)oIK(dp*Oh zkgxfA%(f)1I?oRjXWS0%x&g!hn-)t!{(lEJRMQ7H4O;D-?zyb@>g}Lo2cn>hHU%z+ zR`*ZP)0)|1*SI~AIh!`7B8$X_ZTbU`n^OlzPzxbsCS8Yw+dy_x3PVX9yCwX&Ql{OZ zWzWMjo97{Xb@i#B|^MiqkWmEaV*HE zsaNNtzjrdvztQfU-zcCryELEMPxFf%%YemZO|-?5rT^dl&bFg=SzwF|KiftV?7h6d z<(4HG-~6zz=BwKCO0%8a2hma&2F@>}Y8Vv_>?3-ydxu(w3VdCa3@{Eg5&#wy2a z-~!mc#jY07h!`53-}z_nXZ?KlkH zn*)!SLInPNzXvA!IE$Hpnp389xakA+M)`B9`Z6=@kVg0l=To!fc}Jz%+C)45zlWt) z;_G^K4POf%)n$s0@nSKr${KXJJ7h{yCF-V;WSKFUwq`sL<-Mb7%%(my3&SE|C%~8=c+gOcTn;o0DvBY|WPFMv+p2dT^tO7%;^ECIGz% z=rMJA+%$J)_%=tBBQ<=AM@N`D--<7UWU#X<++r(_MK?OYz_xQ@sw(7D*0-ud1{vT= zo~8Hw#Jsn;d!@wnD{W?ahNtdtg>b^8_%0fpXMo>ey~J>SX$B~fq8T4F;O*$I&ejA* zAiZtVYRIAAFvP_4r)i55MCjcX_;wI=t4jlUH$PuVrB*+GS%Hrhg{=sSg68`!?-H&w z-}iWuT*=)*JlNSsW8~3LfXTTUE5Jq|_Jt$#ZHTTRu^~E5>*HgtkhKsZSt}e{{;?xw zkR=|_Y%nzavb@M?4RWQHO?w@AjNj_so?E+ofQ+)SC?lc5)dYfjU%k8efM1XysggMxxAA@5EOEV)79FqGow0oZJ9n#)&h z5_VymyPNVL27AxA)syfEneA7GA6dvm)WF=&^ks_4^#Ry;M&=t(I>=HEQ-`LAn_n-RqQAgBOxLc_SrmVc(M_)BpO z+)V=G-BRJAb3E3>ECDi0j9kj!|GEb~NFK>WE+F;b;w7Dh<=hi(V%@qS3MD)`MzfA*OPh^nyrW?G_RAWsA(f@!|f6ivj4eS={8l>uJSwq(mNke*eI9hIy~DBlj!O1?@Pp*iUz`Edb5eqBD7oozoJn=9!U~n%}awq-j*wZ4Bt$PJ;R( zQADArhu9n)@1|dG)88I;+r0&NOqPgEzA9#dvXseS zy#D(t;LY+CiS248wb`2<93xhX#rE8-8^UB7`;4L&*(1}8BMc=kjRE`Oml8kJ+f1J; zgbk6Wh=u253#Whr^WC_Rzs1-3wXb#NT|BuwkN6V5u84;aB?{kXhvG3+6gEUio$Wov zlANHEHp}kLVF|S{H?yM3+9YHD3_Fns{Ue}1=+bGM+<@}L@$MDp0}#J8FAEQH|G0s_ zN+AQK)4{PY=<&e)ukjllWjljopbGpGq!$wVS>@d9NngNEDd^^^Z^OwC6zUCP|D>D% zW0Z!v^*1$rJkNJlSqc25G~uC__FFS9M1fY+XY@NoWxO5w>fJuG{h_4;%9Xs>qfo3qGaw| zgym))W%B?t(ISqZt~dfEW(3XnZ|=(tBWC-3xj{D=?SsMMrgQ-jWmNZ*UenLTb4<-n z&JhrcOkw9P+LKQdpm4XRw_h&sTdcUcHMsYi*KD!UR_8`2q$RZU#Aa;QZ!C?QCI7^c z#aH57U5y-6771y&SIXi{mJ&1Q$ao4p|Gs@Ac@<#KJmmJI#%k%0ru99l8?K9(I7g$u zOFEun-WBKY_EzDfK0*TuxCPd);VB?8MEp&TMtFppJq_RQHTZyqSBv6G)n^MVlV#(! zU^hH$GgtWDqVVqrJ6mhwHK&Yx&;eqnynX6-%NQHzvuu8D+va-5Hw;Xa64w^kXx~Kv z-DF#IV4TF?#jURaj{&silHq;w=_TJ93n?MNl=`MFt^ZMG|7hu1u*`%>1X3=^?Na=KTIU?|CF?A91j`IHYP?_Z2MF3Yg`axo37tb$$bX{t zajp6kxy#CMaS+u9WpYsz4Zfp4Pbd|5Fe-db0N^&|e-G&yR>fni`BraC8II-5>D^sH zx;&_+9Y8o52&Pk23cr_0-auC+yOMNo?4-nOA%zX&A*HjuMq?T>%@83%BR8DrV;5so zict5{C2-T~aYh$3I`sN^(7#jNtawYd$#75&6YjgwAvDF)d%-U;cTcHecbIo8kmpGU z2b(m%Y37A(Ta%X5VCQ<72n9dS61bE_ftu%Y!Z@aZvE+}MT(h`E%ps)ra?kS-Kdi6Z z<2WDfAY2S*D9L_%c84-!q4_Rw5bP$$O?bO1zxpz^wjVTd4S&__|M~V2SZ$XLRjb87vyd{+C_JNa+&bj^?*E#WN;tnKQH?vNvSVnJC{fermw z-2T;FB3;&Jz|;bQZK%e=mF2IL`+qN9A_5t&KU}QRVfsrUH9lgq(@Re&B@$aNOG8Kf zmOg&6TDXbf0Wx`UgwGWa=tQXTv_HCbPHN7W=+&S+f&#u-g%AAfzt;T&6%i5~zoeNw z^z-z5%YGu^whFM7Bu#z17JP3z0nqU1&?|f}?_YDze6Z%jil4SiGji;EmY+WVmiZhHJ#ieeK=zP|k& zG;5R7J>s*q=l8WB^e*&+)ox-;L~vNPf5gjZK#;V>PDG=s8u4??^9JpeVs(uCRDv0n z223h+=@QhvDBX`Vw79qJAwUqKW75V1aUI*eCAo9|^ZN8k`D@Kh?*{JDYMYalWC}H6 zBZ!8sTEV*GZU+NX`-OG5xg?guX6Gd^6?k`id*}>B54F1&?9zDhGAsn!LfzrXd`bu= z!;|Ab+ymGhtxklj5=K$E;l?Kdg?t#qqjwu#DZkfjM00znnsUjp9UK|`jSonWvXs>d zcs}77q78i2_~`o4A;igTzeln86%Tv1aN9oabz)hMP3`P=L5{;oRY)iFVXC@j`t3`* zeZ<{kky%J0U?AHA6pt8$%c}P4v3EjYoVY2*LFePLc`>&r@i)?8)D;~@OIv01ocT+s4i-GABl#bY8%ejw~ROI{k^Xw*Z zZ`tEFqfj26YGOZYjdfMG?uF8>MSr!Vc8AI-tHwDdO9~UK|F|y4|Jq->F^EbJe45D2gN*b(h-{jKaoBh9mZs4QIJY1%m`>N`)bG$`56C;t@Gj9)S1o6D-GH2 zj%IXgKWSM(p?AnLkHehVaC;rC4vSgT1KO|9S_c=oURm2 zc+I_~7s`CY@YG-#4`GDV??f_4O&1zhhB2doxT0#v!`oY~k?I}k=6B~cC zbsmuHw#D!PVf={J6i+*vn>_bLv3#jayOzjjP@GY?#w!}S+SRY$`p;4P=w!IccKK7a z#Uob1({Ti^)?)o1f7uN(Xq)nt7d2nb0DK{22O87k$L2yaezf~7;P&HI!rEu$?-fvw zNcCFsFOYKCHqI@fck~gzUppqrsLM~kPL3|2c+zHkRbs9k3jIqFk;+>!tx|{$O%~g! zp_IY?)LHF2Q9$Vy|hY|x@V!ATO3k@aVwclM?9K)s(r^MQART2J2FQos7Ur4-`jQ2+pHIYy#r3sKGU!J&iE>DhC8 zwQD|~V@?6U7oH3-tgh;!WcT&`+oHy>!iplzVL#8erlXOAd6t{s@VR+1BU+U7%5bmK zwR@Vnw{Vpmkt%_VmytmZo0dqFPZy4Sa~6hqdH>UyFFgr1{k0mhAfvA?vMzOwuN#&n za6dF8oF8Z%ewnQr;RsrxNt@YhFQTZo%ic8BHy_P2Ed4_h1^LwmK{sYaLTVXAG8rhm zthBo>eAzsz~Df0))s;RHO@VTjI*ae zK;H9pc+dPg>F|muk36`Q6_`#MjWF~|2KA7zEDLa+s`;mrJc0g5DaGdYo?Ew-szW#e zZ%Xr~vl-n2_cJs&uW)Br@MmXjc-ZQb!59EkmJO=l|GnDf)WzSWYDtPkvs^p~s$EK6 zKSmycY-|G7dpaA~ehfjEpQExA-q)x?8Qm!7j<6=JuLG7#FD|fGUh~fbU!|OkxGHew zs-K}k%v}a`Lp%Z0cgCC5zg5Jq4Z6L@uRa&00*IUe#Qp#@HRTk=t-x-1(GVsZjn=ZS ze@Rg;PKmMkI-|&~3f+S)*BRL%riNN@B;y1O+NBDOq4pp=Mq%|jlD~fMZc-;UUFLH_ zX4E$n33fj-J+<&#$2>yrFd9AR)Xxm5)Nv)h4IcJ9 z3S?_FAISs7E4$2`aHzx93I9}+N9id75^JUi^+oD4SrVZGK^`nW2iKnTzWRI@s9Kqf z=VY3)?b3glitf+u0$&XLMBUU`qRpj5xHIB1J|D-(%6v?QH1QfiC@s}SLcjk)`9(<{ zN0&Z8>gTND`CCppmw+RO*Q)lH5wl-j+cnzeamAs<1|b>WVSkl-4HP9^GSl6&=a^E= z0vc0vX5~vi2)L^?<)|?pIb5}Tg6KSy2Q8VVnRu5iBVtyKLIJxxgd4-(7IRzVmXIQ^ z?6iNr1l|TSvf8#d&x4e?UbWjb*BA@7l4M<(tGw_OX^^=KIat}{^|vRYOl;xzy~0Mg ze+os(JXO4qrcbhq2u6m*tS+apwqyqIxXhAxk`sbp!by*DM*eo51Ux;03m@ge0rVdD z3Q?Y0FythZSmC|HT?j5Duz#8t$NuX=UBdiLD$xWukc30!2JXcz%dk5&Hh*2Xk@s_Q ze>ScW5he!>MA#OYI8JzFXZ+_pO*!RV-x(Zt|8E;CYftQY@jK9= zh8yTV6&$A{LdMF$+D6oo+$MX;D`4Wuw225SBO`tpbJT@HWk7cmsbtSr#GusI)g7l& z*5{|;i-Y&l?in`CHA_G5$t&5?zrs}*hG-H@ZN{jtiyBPD$zDBw8mx1RtO_%(a%Bzq zbotK>4eq#{3-+kIuKTUaVlG-Az8KhZ?NoGFI%i{GtlpU%8C|(Z&7m3vF>XTV1k8 zQ^no5TjvzgnQwEqaUTP+b~OreNn0itbK?#_a{b2BsMnwN4E~S}*{{~ip5cqm{K?iO z+drotake^mixMpR*hKrY`R1b8f6dNi;GjZ0LpH!8%N90gKJmRA(HU2j*_4(t|4iv- z(qzN@_Q;g`Zpfhqe^4jVt?AZ7Bj&UN`tkVWwE0Sta>Aflwd{M?-=p3l)7@s<-tj?0R32OSeHT5j>Npbog^jnVS&+InZjnD}2-GzbQJ^*DsP>B(BumrG zt9Lf^MGn`O}!Of+oQ?YCcCuYJ^te6_Jvbh)*+t5+mSzKake`X zd*`e-GkGoQ^i3Kv^*2YjfXl~{$sa>@Tb}{-m(Eyi67%wkASVF~DcTLcmC?!@M-nT9 zUc$$r>L9Qs{k!wQA5^!-*-l8`m1{)L2)c4uaaGll*PD%3;pS1(=(#R=t!%$n-L6bw zFDmHf`HY_Yn@pu=-&{J*?UBEA3UX)WhhTF|HIA}1>rHRmd8{_U(k|)&|x?}9AV zh)?>npg&Zgs1TT{v!#gSm1(_x0@onKVxU_QMq~^;Lr8=V>mHkE7agVu0y&bC$)Bk@{lX)qmuo%Gh6h=+fP;sjJ)tu z*Lm*yZ;#$L?e%;`guxwAnMJsZdNIb!)3`}N#e!LZh7JaWcL?mMDn=|bc)C5)F)PI_ zuAms&?QrLoj*1YpvR(BdveVAFYV2wbXS9<92>kAbeceeitG2OPDUJ4#&Q%Xs2bU+2 z`wk^Wm(y^*y*d2Z!*aV62k=@Ri@W_KaW!MmZFjEXJ#5*=pUe*J`j}{vq%}#A?qSRW zyYiIKX<-Gfp$nUsycU_o5vi$}18Z*VwKi>aRR>04k6|)&mq4utfioX4@OOs%HcFcc z`(Xy4lBY@LUx$u1NY^?x&cE_w%NNR-sGn{;TGxA!%yB*84 zFyJNn;17rI-Yvnc$4`i3tjedow-3O~l~9dH$88f5=kI2ea0bDbn?Ww?YWw*<(B`mhy)gH_eVYlcj<&Ji@&+9ooyGy0Le>9U$`riR+aded3 zxRx!d2^DW)QtasUq&O10#8jzHAfSk^+UJcWj{DS2SlbZA5j?yyt|z;oT53;+Uhfyu z(06MFcjI7w6S^e22R~021#o%lZ-kV(aj~cle1hJ|=OJY8-1>#w^&{~kdJ7_yFVaV@ z_8_|rHi;L~S9^sMIz1REUO8F@?~V2jYOgw-_h240In948sZ>^YfT*>nfZB7J`k0FX z$M^r8tx2C*>1>6BR*iXzZt)%bP#1m4Si$W2?2Nn{Ph!98zQy~}=0T6Hadb@cWd?)D zW&DFPiZCReW6$dC7qnXD2Ga8X4&a$Ma=Zv3vJ%0+qvuUlZ5;WZ-ArQ;!;l{VFSn#z zF^!B@2Y`Ok7xN0Ai|cKJr_YfpA#D<5A+IuA&$j&iLGvRo2o~Qbni|@NryqYZXznR> zrwk1W)zN7_G;w>gzW`MN5CPsq z8T&+w(%`FC|>kPH*4m|Xac!3F(CnLIsb&!-VbJzJ+PP88eUexEz z>8juVf>LT(__`U99}j31lt`C_lKcbChTNpMJgQ&|Vhx`ocyQ+X?-(E-7Rox5v;u4( zdhgx*Yo6cl7#az{WRrhKhSd_p%l&rOB+r&>8RJm9bC#hl>SD>=bki_*UP#WV(43#_ z&J211Gy;i0sj z;tFPoc67$)J>hqlc|r3kL9U^F(F2vA$z|}9w&8y*H0J<%u2p7J2N@Zb4|&vN9hka; z%6;2q@E&~P$$4gz_2QqsUvpw{j4}?0iiB*~%CAb8*jP@CBW*lUi%!h@_fMTIgv$GU zYv*?5h*INwZPI!Zb!KysQmyb>!b&k{aQ(wAgh~olgI8(?O90#gnJrdgw$V>)hY3Ow zLkZIXd>(1>OO{44uhbh-{+>z-j>)lO@@!jhpr?&+S{*t(k!Yu1Oms7HW}RX(X5aIq zZ9r4Hg_!4G2sC&w9GYDm@F|A1I`SBB;s`k^t3prO8LlzAg<$7DX?z6`db5VA&-5g# z4r=8727mKxNVY<<$j1BQTcroj)j~cnDu} zwEW$tmQB$NasSr&sd(-umiePp_43jH>PbuN0AZ_UUKqeS5L5wqhB${y*$LNd_$3U2 zON>q{yb)X3=Ah#=Aa>MXvt0@m=i#KDRX1?Zsd;Q&d6t@EwY>)BwFpmKm-}Q7(kmKv z+dw5a`NH2G-C#G+xR7VPd9Ey%BKJacL}TD#WOU>G9Q;%Bi*16?I%_46u@Q)jCHFn3 z;!5$@Rc=GeGcK6X1#s&-lympld$MmRg#ujy)*H-n#aP}`sQTDdU0%_%ppRA8oxU^F z$J}s#$)^q=ZbYi6wjjQ+S@W$xdYODQ|M8SJL=)_m_jnf^4BEo$;tky#-){v*o4v6t zZ;j2R{&@w{d3XHz*s+3-IHV0TAB5M^U+d_LYAE~EERGlWG7##H3>EOrA7r~R6lyR; z9PHOgBUMz@36wPEf5Go)^+n2I&$iKfEUmXq>{nR*voDYqlE1Bj(CGPHkv3NP8&AUB zC7Y18n`o!Cr070awH@+&T$;RKG+0BoYgp3{< zeBOXZ1UGTv%MmmpHT;#KZyXdY6FjL_A>mok<~TO3=KX#W_wp7D0as__&xG&6uR+Zu zQwGKZ<@>4H7U474uY4rA#bSta&^Ekw5rV;?{`ftEx`nD&V#%rI?C>}_2<9~I85I8s z6$>_J1D?g*!CnQl<=yeKw#PompYuys_y{22VGTRwv6UqP-Cg7{H;UD?Ib3xC-8H)l zUpOUy22Cg$!BhS^$e>O;pg-ABYjW3}IKRVyk?3>T&}Ao$PLMRX;d@{PACB!MBFxb+ z3T4+8m9~PNzN{e_-7H@Rqbu>FLC{E>Low3<1*a?sekw#Da1itff}!?m3sKPgjUzv% z@rZ}bwwFW(eC5pIYdiXZ_3;9}W<#0tJX8*JrD~-LS5egqn7dzU{aAKSa<<&}3IURB zopV0vjJODax*6wqM}%F(D1pdl<6yb3+~aF)cU#`yoT#^ET$QL0d(J1ICf4W5PtOrm zOP@Rko2pr{(WduVutABVvJqY2;S=+PZK#vD1S~u1Yz;g|2%Q|Nc^Z87qviZrSz=Ux z@l#z;eR8Y@mFJ{vI zuHNl+n{6{Cyhps@w%C-$Q<7Gt!~Fo8giL}=z=RvAYWs+6_w^ePv!`;pa;hm0 z+QgO(GE)12W#ns=gh*jI-nK2E1M-1K597kIsNYa})PY^&aYZu0x%)GUbFmobuVFc( zS;cLC64ZBd`D1;ky&ouo5&-X?3}vvHp#I=R8vp0I`2Ril1y2pIP9M0g@Ja3NjE+&g zto=FDMAFYUlw@|i6y^gt#zWqN)Vrv$X6iLBj3+@AXYR?08GKsi|Vk51Hm z;2$BAi;(A5-2Zfjbw~OMhb`g)dT=G+>*u@@ zs?F=NOk&pGf1vt>%5Fv0qO~Y`5@H~kpzs00?@eEjHfXoy{`1^8u%mW71GNh0RFm~L zh|fsnW#3wl+X*?m3zutq_ylNW2m^S`Vx}?9c%!B8Abx8oWD8!9Ya}7pO#U+e3>6bX zEi0PAGm7X4fD^rm?Zgr$3fh)Wn|@XQsYV~%V6)n zT~yES3nskbVqGQqYw4MzH>u;T)!?5`MI`yY-R(K#iKOP{_g)#!>wMf5%%5?$G&Tm} zq@&ETCX?-cMa)pPz)^-*dxL8h#XR%R+Qf4e6`jQ@ab9>C_EbCS9PE*uVbmYuEQ7wU zA`el)5o_QWz2(>(tcarBr_48y*?kGmk}ST zV`+f@R`W&=V=gwn^jH0#$6-CRP#R4?hk&NMC?0`|!7-#tJ)KMEnf?{EtZQ?Z8vrs} zk@jFDyLhf*JLY2UJL5|fE+Su<%wx3^#;{~O&X2WmymqAlsqF_+EDR8j55StYXO8q} zff$b>%+O+0v@OK%$n*%>tNSAp5o{Ev{&A9|l3C?D3U3#L?pA!HC)>e?EL!U1o4r}NYk5+r>dT~@>rvuosFbC@k@ zq1E17j-KWX3-&D}k!&Di2Y7AVlDZ3DEs-Gz(tw2}X;s;t6tY}Dm8h>RV>#*O@?($^ zCccBsF(}rxY3tA0Q~Ihd&(jkPQ0w&bjer{-HV9jLT7VTjEfmC|^-+cH4wzbWwlLrN4~1_ z0`%ra z?RH~d*>ZOprfUnLdqTh6TQ&a%pj)_>aHnkZA2L7eUWao_`OW>)77{z#e492cA^{P9 z*L#V`7w-2R*x&ye&3v)<&&)4DjY)1LD$B@-0@x#LJ1z9YI!&5i4LRJ9(=0gKs`R|) zd1}Jy3wI5n+5L`FYbpBsKVIb1!1>hd6}W^LsU`uPM8e2yCx^==UmJzP2xqlU5|Si& z={l?O>{!}P1<;-MOuOj(&!yL13~s+JQr;79q20AqY=cLm0g8+pa-fgIkhA*(>$Rc9 zk*di8kY5*YERCNM0a&||>P7O(XB^6A?LQqo$E1U2}!vjJ-3k!}I0vc%G zhWbaDSrt6>?wKJScYHdQi@35P2`j=*1gZdk&wRw#(TQ`9hg4}N$fHxSBI{$gxd_0! zuQFZcldk&iS`*-)cG70ZE3DSfZacl#6nhz$B3kmCc)15fiyFg#J&LZ5SZ|NDEX5LU z*mnntuxQjB*Dac-VO&ruzCVG@FP=y^)*%et$i~^s5erI{bl!1K47<8XwCRj{N$N$S zCLpC>P=TX1*cQL=-pCjRF}6^jHq0JFXxZRBs~@FV!(1S;4|d@aYj#eP>eN6Jq#8MJ z)e=Ws(JmuG^^+?5>YC_fu}s@Fk%=pB6}W{=k?F-wskfPS{W*)MAxMr8`&`C4vEeRg z9-h4~wN??@sg%qWS->!#MKt82vwWw2w51>ND`4_=yaGDe{z=`vxnpmc-&%+D-T zL3Vfk#}lI`!02juzn3v9J5t+}?A}9OHlF58T2pV*?_yl%#~IS_s;Xq5z?zYxCKY|i z)HVtHbH#x$u&{_ymKn?Rt^R>$bCk5hbM_aqiib}RJl?Dl9EQ{2?zeOrmoqax{bwvk za9^5rZ{p42?3-*km;i*3UgVql-KfR*3vm_wmv%35cSt;76^++g9z@oO7l4hthxW3<9Ojsba?nMgv?a<{VOIgO2Gjv z#?VK8V%|ZQ@zP}Wb;aD`Jxz;orjLy?IgPwdFmyk(9Ar`a{`RbU5rgSAYam? z^R*63d{0CBD&*c|^}a0`C+fDme8*%n~ zI3=Ww?2ox}VsCq-J6>r7~yDahD#wCaS)h3zD6BA{VE zo6UMjwhCBR)Wb!q^pq?gOcjqRZGtIWRJnp>yzI(r87P&*=5&d^zc70O5mk~Bo}f;5 z6n#^@w}EyY3H}~E7(J2(Xzg6IcC;jr-5rJj;T5n;l}k#<4x(W6P45h(pz(;&FJve! zCJsV&Pu0M>NeSx8DBz+?mh5Cwt#tDA8lbO!r&{Fo6TfPVP(VX-)LAbc95I z=a@{1ox=js21Ag=&;wg_Cpsl(8LiBNr41KXLNJwYnH+L?Ky_tw3qM6YeKT-Q^#wq; z`3Qi+nw@9%haNk&APE-X+u$ym#5c{qi*sCw$0~t!#^EL4zW(RHb@cF$^R`pROo`s1 z2iJv|2S#6`ncqj)fz+sUZpN#CBoVVJbO^B?MKWL9e%d5p1`k}bZKEtY>&Nv|XDJ=j z`LJ=^xgZ|ELPq=rhG;csq|~MK`vhK*I)R0ur4CM+`(OM8w6hR>BJ~H`7OLU?lryhP z=_^ZTzT|2QhrF20#gG|lMZ)_ro?%jJoc=R@p7VxZ#qUT6b|^*%Upq|*j8&Od%)&1a z1z;pF%Z%8{rO;NW{6|Vg#+8+2@U2}L7 z^94i+MdzksmG#u@@Qbo6x@z?GB~rUCe-cqRK_J5pnzK%R^tGbppS`=CrF0imSk)!z zs!ET~IL8C?E0}Qxr#3OXcBKr;x`TOcTI%)z`iz9Co)A=hHcsNeO6F@AX+=Ut zQGy0!fWO%I;t=b_Tjl~OnelT--lO9r{JKsQE)1=5Vq!N-1vG%Z2sj5|GQUzVmlvkU zp3qpkf`8NIp@_4_uIgVl41^&JpQfa$+Xqvo%2`tfQ22#fznV)-E=&0SzTwX1`8Lc? zHfLG^x3b~)7oOc4PMYcdExANie!Jt7$oo87YPqjy1_P|aQj8V}LZzo)ac#*;sd1)7 zkJIe+LP^+YSLpXjsN>j6(|W9T;jh-n?O8d{);OvkmM9PvYtlv1YoS~53buVI$+)6g z>LZ|ad1hfPO?p4yGTa2S-I)q-y6`0`tk=;OhW`2G+OYl^hQHzxY3l6+Bzdo}kzD<7 zYC*=ug={0Xtv7Op{)^V+9ZZmW-Z<>}L~CT$&=<>aIv+I0UpLw{@yA-1KC30-w0DHXjadUkzzL?BCv^r)N}J#y@h{HluOll8Jm z}cS9HwHMcIVYIMgRV_N2MjxT=A4*;Nm&b9tQTcK(m1ua0W#3%V_C#hnx= zP+W@yrxYuNrntKW3sS7OL$TluZd^pB-UWY>vY&9xj5ucz^L}LZC9jYklZNmM`<9TLJc5Gr z>GBrY{sY~^mi_{_HoWQjb%^i0p{# z2~YxtiG+X1Wn_R|aEmY^i=#ood+H>0J(1hTgORM_6Qu`dZP%1?k2Y7GW{A5AI^^{4 zWfs^IULcR*t-XKf%df-^6GZ-FXOZ=IpBHSvTAKD4fKd!ocQJ&4jWl2x4@g6ZRDSs} z@v@Bc^VHl+4He7y<2S|o>+js*v zX>-Hb`^1C0Fo~`9wbF+O{kkI}Xw@kAgMiKRu+lZxbHh)ug@m7Fq)p^6!^t@I?c)DN zEEe!1NfF2@Y~J-3+Y0nSqt^q3F}p;ej0x~` zo{Jemiw0X|ndQEnSeOi-#!lBvRB>}r0+gQjHMZ^_VByDzm{3`q+g@r|G2BU(sdDWy7KA@w zGzLHHDuU>edH~C%4!kWr{PT6P_H=I z+U&#Et-bKCId38oF(V2gky%#-{w@z1!S>_LDZmmNd3*e zz+g}b#%4txgE9P&zL!Tj{|?CKkjcts@S=Gyae`P;1%D8n(xG%BrG~-kAtVAR_+S}e zm_@ihj@os!W&vZr(o}$#L~Q&p&mICVyj5QZPjyox{e#We34xB(AQk|Lep^W7*?#aZ zcdYu~3Y@?O-x-N8yVwmUBJU6i*;BFLSk|6>X>T$6s1!{~MM6NPO`Q*2{ORhhj4jLR z4ZW$qs$_Y7a1ar-kYhUt-tz6@aK^w>Wz&-LKjz@+mjC@xw~zv@(DYy}3uhI`W;R*s z55C~TY9^Cv3nlCzoM%y+EzX`nY&|itoAER3+vy&f-?+#DHsK7hsOT$*FrrXcf3Xnf zg7rz?GKFVxI~*pz3gBuQ|#FP3vu0-9398p+zA?i8@dfmAK94 z)7E{3|0(>zd?o7uy*%7`(7aEWm|pv{ihIGAX+ zptj14^C-m4g%fFAB~S5=C8_)+;%fZ`j3n|^)Lm?=-|Ky1qWYOf91SM+_`z&K$-W2U z>fu1MkC{axp{6|Mf$Pk_Oi2&>Ge6=%CIhen^k`(SXa5M{+CEI2OdIQ+5n}^BN92D% z)oKG%30G$*AiavG9V}$%)nAktJbXOxf=yj2pFOvwzAb9cP8tqjPX-C2g8Jj{$CRjC zSd}vEvUm{e-dDXZAq4ki89uJ9uRdDy#F2KX0R42s2>xb6aMMETNu4nNB9m|aV?lkd z@)+S$w~y)lGw8>Mgxh@HPw0XS4fU*v3u_?KA&jc$_PL&rrcan>RA{y-bM(SA+2lV7 zCm8>e74^@@5|vz_12$)(=DCLU?crNO!rXwjTEU;>ncX8n=uhH+BUWC$aizsAW~vlI z7}m51)lc&oOiL#YqduWfhr|%i7Z#Tm$7;PA5{Q<2ohFzjh|P-*;tl(0CHP8M1L=<7 z{D|I)7?%^IeBYI)(K(*}$2$il;N)>Hf~vMtnT%vCr?yJDk2cF=YUVu=*hq1%;v$_g z@0$u-HwQ8ky}GE7zMB(uU4q)7)zk>V7Awg}34!fuJF0K1N$aAXeL%mj3x z*U4?x=>u(n^r-_y*^o@LUL*;x&?sAkiSQ-L_$*l~_RHvUKRAeM>wfFI6KUW|R9}CU zRZ1t}Yj@+{8T%~DmNX$!-7EoZ`q{`tzN|R%B{Wh8Zr!gvnX|CJPo$sIVc(e8hzn>s%Lj3uB;A?p@N!Rs91hsf*>N0tyH86=7+u`(>f~xAWCzD(`~5e5 zvP`%FOgzr&T%zwdrG6e=AV*Ij-^#%MVWUL}Ho84N6skWehtIk@PE>p|cVEf*Ya>5w z6YIhg(Cg*S3y~4wa@-Ei0@)D#r9r)du3eDlhc#_S@m_{nkT=0{{Q;9$Cq{b071ti! zE^@%<#H)juNPC4Ogof|yD_&IfWV(0QQl7Iz52(U$s_>h6y(H{HnRXm=(qEbx(A% zEs&i;n~$Dnp)}SiTNs~TpW?S)}=KC_rsvGlaeMx zif&zL!hG4vxPtgRyhZZ9)!XEnVIfLVJ~<*$qPA#>#HH8}RRd znOn`L`Lf*QKgL7lL3_t;fXP~$wj=&dq`kmQYxhWFG2KEE-8<^`K`_fZGhtGgjD%;} z#L*wouD;_tXVK&dg@EN9%P?-(-z5kb7%)kdzVFdicok_U%J`@%?mW7l2GFaXS%U1Y zND~cw*{!^pTz@9|9H4)984v-sb^65Rp4TC^HVk`2DH7{FPV>{2v%O7DYo0^om0x@G zz(=1UGwb>KqLvLIi&*QEYXwIQxh@W?`e(tbv>n(L~_+`9H}NP2zzqZxPl2Cp!eyS>~kojGQ{f}*4uMl zbiLhSRm1!3nhB*L1I_SX&}BoB4Bd`YK_7okSOA+dhSa%xrXh0msrTYr45E|k>0iCv zbtQo{OA=cFdDuDkjZ{C7d<*YVZ1)x=C7ubD;T`Qn1TONWh3afqH{)i5TzofG6M4E#~Kxr|B`URUON_J!0y2regHPYpL1JR`-_Q4`VV7Q zN|KFamP!8-yI#hbL!nz2$yNu+0@*xks9~KTUTXWb-CF-6*)b6~Q)K_SSZh6ABT&0y z2$(?)p3pabThF?K5r_#u$1r=2n!z3tbj}r*~lwsV@ zWD&S%Z9k$Eo&We>rH4<&Uiu$K74Gw;?tR^=5Y@#=Nb8Xte-@#b-s!CV%!G%x=7 z;&$(>vugy{QJI8b2@3!DRoKts>#pPTU4qP>bnL~os$Ncx(jilwbseMmoOROLesV;< zI78a~mcGD$Kt?8!dTOKK3E}bu&$a79jM&y(GGS70Z^vGmM=CEB5aG^U*3!Q6iiw{; zA+bORRs$uBe*zOTB`L>ppmKLGEQ>u|ZT>DIEF`hw)K1doOcwu|BdcR`ge%GZ2-mN9 zEAGx5x(Tjj-dmy(M?qK7)pgk5oJrSY2~HhvW%dj~J|FYH^dR-v_~vRjLVhOh7FYD>@rGcfN-&V8)V~1xo*cQ)?qr1XE3&z zb0az<0Lisgj7L%ey49Jf9p-S(6r-wweUA)6 zrVQTBx*IRZ{6}JUw6SB=CO&7n7_JFYI!lxOKX=R}d3+7rfS>*rOUaD}eVRt{b__|& z6nx$?G(he#OjtacZG^Zjz-f z9fUE*4IJ{xSM2?FeMJI1OH@%I2F(Z`{5zeR2rk(mOaUbrpN6@%d4-)=uPP7{zW()A zjs^YUoFZ@H^|!yTTPWHr5JyP_I2g-D!A0JycvWW4_atwSFNC)%fUko6>_e&%` zZ(xjN)XP}f(kDx-6O>8ghvV^lS*~m0PR@cV#!82g1Q_Px@Xuj!wYk# zzNIi>gWN=|8+$P%GQD@X?x?1+)#3Lfq&hr=aC|+muauqfmzMAR&50Hisj;b3oj7jbtCQ4FoUu%hZh^c3^b1#uwI{J;CK zfMWFUtSl%S4;w^x34qHqU~7(_MHY*F z4pT@Eg_y43MH?^@H`j-E8FVpw5Dujao@fw-hLF72M3g4vU3yUGl$pToV6)ix zVWM9mo2oZ^p8FF`G#TxkK9>+F*nS9T>*4loAb35OQg|Tj_br*^-bsEkTL{?VnK;^A ziu*)Kmy7ampuG3)ebUkana4n4>m#~Lc;ymAU@dD%N-nvS*8!BcA11zF1r85c+O?q! zn8)A$6;8yyY7SxL4e2m?5(uIxY+O9yQyY+`tP^rE*tSBYe{XO(P8Puc4Mz zyb72qI*y-sS)cB6G=m(g?B!Q}>B!HND?vy$|0X7lU zp+rXASop5SOF2ZdpM8r}DHPGk7w zo5{HHLmGvHe^ImGS+RDn`>~ei(xR?M@0ZN0lpi%`k&QHdZM0uXf4SbQma%b)!=S1G zhK!WLWi6Lqxy{j?04_+L*UnUoa^UCiydlOE;6-9Kp)>FSjB40%RSCFZl3byG2VM!m zuEbF1q^`il-v5bX52Eo#3LyZ9mPp@|p|yjD&QbIfzu^_zs(Tx0HqCx{!fW6}eT_ZP zm)Iu{826)Xzo?6BVlc8sb_&vZ{5$79saA6elFDZcKQgj~K=x&vd<{(tMjL9=Ra^YK__^nn)a#hysqEdh^$O5$=SP_o=)AD6@|+TQKFmu8 zP8{voy7zZDfsCK2L_d(w4O90ndW`Ejp}JeU*PN1)OLL}!&gUS@Z~G7_kXe!V*P>vA zA+?oNkk!F>sjg>Z9(>>-{3Blc>#b;gnwJpW6>=A?TvUVln}p;X>%P2}nTuMHz0S~z z?zQOVipd>N%3bBZONvdr|MwBA{(IOn@@-$%))nYdD&wjB9rI46=0x6egR;6L*HY-W zee2-q9eFKAa6gVj=;lG|=PW{h;o}|u0CyEoO`jT(=w;mN$@b6wnrZ3HyhWRx>@X$< zN@tU!lPK@)5rgXf^Z={P-Jjuai4_GmSZHGWV}Ib=nyIfIO%fX-u~C@7t^KRPQhJtZ zESTqe78E0KL6&pDjw-reKe5tPeP2;Xsy?~_NxR?+J}$KY0ND=13+8r9D68XrE=u^> zX27W{%K{r6iHr-;2{j z3_nZoHys7;QjE*-Q4KU%Wae7c0&exs&)`IhD$ejNl;lU5K+GYpKzTWkufPMv<|WwfQP`bm01u+U1hpND&eTCyCI8 zoFL<`UDuiTb5G!zs8lhXk7Z^A>Dk8^pFtmizpy zC*uZ!$*#!vlUd1Bq5PPE zG9aM#zEK?p)a9)`b@zmL?a{>@#GA3zMvu$r=pN}Ic25!~&?7Cb3sXC;C)Yg427^d~ zRIR_<^eVPG@ILtV*xFTcS3{AL*T=|)s>RoJMK%=VSt(~wBY$%9&*?c6x@?ktg7x;g zra#+fblaN^j~bxXC%+I)LXjiG1kCbq9-EE zz9T_*NmjN~c|Up^dHP$G2Ak>*_&d$r56Srh(|wkCgDDZ3?TT_8E{)90`O&I`p>vOfzF-x*P@O`9JK85_x>`J z^jBTB{nOnZAVE2(gLBur*-Z4Ujg~iaXGv0SAYI{RR@=ZcBoS(Q@$uB6F;)K8-K}2d z%@XRV_R-N%0DHX$n;ajQ{?SB#Uq$QqU6D=NAV7K)>ojTTSS(=1LY?!PEhK$M)ddPV z*Fg#-+%JU>xOCD~mZq_$@;cYyWmLOxsEP+0<-`#hEaZ&C-l!-@25Zy7ent}Z#A)?Z z`;ao3C<${Zy|c)%O!0ZYn@{r7#Z?8uc|G;l&9yT|^y+|XK}qql-A#x*H%qKB8};Ud zs%=SMqvT2{&CGGkF#zW}94E;t2);TVclw77L7nDS@A*?ITw%Wm`F$NBC4~o6WuRxw z_#p~k^3q|{ygD0XtNPA3kCDFht;I^8CGD>t^a!B&IpuN7q4?H526T#Li1T4CqFSg} za$yEzy=%dIJJ@;530I`Ot?q3y(Zvg(Q(oGsjw?jkNGm_p9fa=kH*0a>>V~#M)r0}x zypN(ZV@*d0hHLt$&i8D1NC7BMsx}F0@94Nt{Hg_$Crd;GB?sMZk7$|sx&t}k75%(< z9R*jKq_h4Q2ZNb9)7qeSpX<<=Y-*?9xSIVZsjgBVeYN+l^y9CL+Ajak;bkN*kvx^4 zL^GTbhL)^}J6}`-14n&!{gPMFTG}_F z1&;AW#NYm_Kjd2}I7V#@plp2}6Z^mq6Q)g_%?`UiM)&z{%`JkX{1sGR0KZ3qWOs7G zVJLl8(!HJ;uS)xw()!Ay#Kv)cSAHMrYni5j9~Si>s*g{+q!pO3ZF_a6m6o9*PT;iX z0$t{L16T;$R#A<+sABZ1!An|@uiD?k#%c|xjn~;`eH9Ty{Z{5-2rBb2#C=1U))s@@ z+L`W|xjzJZi|Su@WODdZ%njKL>3W`HBWG$ER01-Q>NePh5jdSyiXH!%+nnDoOR1J8 zP?hX)w-Z@=Y^Z5mtL8pqW8ZSC*HBgFOzJg44vT%A1slSb9Q6j?qRgB7ehhy)`uy`; zE&SSiT6o-BBGU-)Z2Q%sHWuA%{6o%+B8kkx>f&o6U&F8$O8@{R8wa2rbEd6T!vLDy z*@@PfnDRDMs4f*9>T&}#EmAtJ+RILwAXL?FI_c?N0fABoKI59d@--JEdDCZ6N2(d8 z%k@4RtVVx?-nN+8T<89th!yE_4oPlEvvE4yVvcH7tZd#8sS7!7^yViT^J@3f>OPve zdpXmvng>lUhc2YQmeJVn%8y*05YX(RDDV-sJnb?7A0=ID+ixk$_!?R|G8ZExGo?*4o1u}>>d!Si-?;2_KP?}m;WVzK30y|qnts{|t z2Z)jEWoR1Im$sFH(?IECQ5~MOGB3bOPuA2w8#0ea-n*MNoO7B^e7ET?$KS{1bo>@F zostc+xH@M0Jb$LnE8bR-W#9U-!z|(^C$a7m&|w1&an+a#JZVI<*jH-v1K-WVqZh~I zpNx++9Oxf~k2u4XWp@ZXhV`*w`nOhQz631FyXs$aEZak99sF1vZPmztSiddZ&4ePu z`O{&Sjr^lCyT{{fp?~nD^7%Uo8b_ZIPqd7(<#)08ORtP3Ujs!xR_LkF$w78NYb(JW zOI0@a=Z(W4RnxQTy0vK$l8@7Nueu|fxPCSnY{a}&V=OaINuF~Xrr||JU8|Rpr&n%! zN0l0r>M=MXch|=jM#oH}#g-}B4KZzYE^>EQ`KDLeRs5Hp~Hl@o5z;F_iS z`k)D5zy+>d`mFVX!+;?K^qPJ=nUCyZK#s?fF2TF}@u{0U*Bqm+C|K!izT;%}Iy6#3 znU_6iYJ66#Y|~iikv(hlla?2){f%tc1eD6sHf-R$0SSL1Q=H1MEPNIUE&rGXEnq`@ z$|{+aQuJQ?LIyO$QJV3X*OuA;(U}febK;?hp_M7yUiRjahv!L45mGyAn-V8Ugh?=Byos)h)8G4h&6dFaHiRDk3AdLnhkCE zx3r=qGuxkPZW|WS6?ZJ90HpApJ?XyhSpA~yG7tz~YF=$tGV9GIv~XeQUnP=K6;lQV z{Y6|>h{7Kt40rWw3%{d1ePCOVhMhjw&Pk|eR7g&K%47wkUrB4j;)V&-1Qh+pIq-qq zj>3b}YL@1zegU*yRi|!CK20Og9lK9faYD^7KkYm&=)GFn_YCyZqIcZir`1XlxSKSw zz(!3OtXZb+0Q!og5xLe@@awxaP%#AeUv7C!Pm#>A_QEMP&kQFIZXmh3yCXW+E{61JPChAcl!5b4zp;jN2zEPil0Ye_#VLMrH z*u6B&re(V8G~ta+yqtf;09j7se(c@Ay|OL(yws}{SL5(Q{v@k*{En|I_Y(o{6i*LW zW4%-tOpayTR(jmR&YyCp2oCRKHmJc*u*+1W>)9s)uUE4?S+a6*?+OZCU&(9O87{^T zishv%=9sbi?rg|@=qOH2WXCebqL&0yGSV&An@ zib}sq5rK!4et?RF%ELo?;%xuhGkob-IHvq)XE2$q&&Nuo zs8Svz8#GqWdTt=?O5dHb5Q;H4g3)BJd5;FLR)iMvZjHpBrVA@9erk^ite=!dYzGoT zh=lJ|nY|YfBYFG&%KOJ`JlW1`Hr?=cg8Nu;l|dYk(3 zB90-S7968vwsCx8H;cD$R)k{23r>9w6L`DNa)FnMH-LXZ;s}DN?vq;$>S2`(joG|C*0=m0r%jJtv{kCHiu9sw>r?VreNUc*E;Tl92{k0|5aRZex2yXvg^IjGvYkzs)2ek! zSHZKKj61mRCZely@7fC^fkF_dz-=(Vze%qU`+J`EkxUvsBZCG@q$!CFl=aT*+1Ek? z3=8Ml#zAZCm2;*h+J@f8`?bDPdN%q%h*k+Gn+~fQal>o_J0m591yU>P<>rYKlJtGQ zMm!^b3^N1O?JPu7a);Xe51g8`_LW4HVQPvwClJeo?tWf0#VgFmf3#Y+O7V;p>frF3 z1qq&Q>M4JQxzT;@XEB$^cuZjFZF1TQC<{v3GSlNpa-iVA z#Lawv$9ZQ@2Uz%T*n2_h;*dT#K}q%(uK~pjtk(a$O{0)YEs!$T=fpoP8T}s}GOC{i zex5}yO|5t+^Gkqy+>x({p-TbNJ`8~pW?h$zA`B``j=SJj-Q?C6miRs#`$_p@D5 zE0(9XoI!L4=eK|bDgNX%6&$eKUn+R?aeo>C)0xkP)*)m7;BY-cc(1ZI%Slz|app3$kN;qgQtc>wgrt!uBJ2gvS11N$76FJ9m(Rw-$4yQvIWjB8150PLMq@XUE3qjd-Zy zaEP6Vkk`z5;?MDKl|-oAycQK&H~RT&D7rhXE~M>SWY6Pfjj4uX^}mkg!CAx_#4e8w za8m^Fjver?OHCYHo84H>=Ur$j4Tz$wA-86E@W!-mRNCkAnpL;&L$jQhTx?RG5E*s0{ zX}m=P-jA1Cvt(6T+qqY%jg3LnACR?9>bk(ca1jm9I6{C)Y0~*pBQN>9nb&>BQ zEZ$Ur-G@{rwX055P}s258dJiB`4d6l@+otUT3iNvR`t&i`d*mGO||SII-;@s#nj6V z4MGIM+#-M&sva{zu0!-GN$hi`VX%GekmOtCl=d)OhNrN)Mu6dAvJ&~bEJiY&9 zZwBcJ%MqMX$X=d0_6vV=jQ`9b5IbiAI?z*hmG(!P;iF2WqCzLdn*}BPG}# z7OF=zLgnFhx4J-^q=<&SokNIRji|DDWpq`xw%g)fh?MKE0SB4yM+H1p=eiL8H2|_b z;18V+2owW>YXm15f$%cnK(E6T9g`Tg2c$(2X9lQpXuBbi$Re>wAcl{|ULOX}DaFvILL<|HALYBD6A9Ca zmL*$1APU6%;qg=zAHp#hoyZbI4UkfOm=z=7ly>i?QN4T|l5i#NvPi-c#Xf#y-4FXZ zV>@XU@Vf^|30T?)HfHD=mCP$lm?W|*65&ASI6$;jo;7&E^&I{fN$NIP9= zENe7!d$7XZxT{@1roZ!OC*e6U;Xe#-AzpGQ;TVPU_d>-OVwce9!d6&j!B=*mtW2*$ zcCAtaq81IvNggqR37rS2}QBvR~^J?r+Xy!n#_;^v&Y#= zgTUF-WzVp4f-*E^(uY#BVn+p_+!!S=oJ+R>MnSbob{S%U165w&cuP=V&`ozYLd3k2 zV1`^K9B3Lg#VHW${WWFEzqO4^{kf&ESgihAkiIi)^S?BR1xziQ&f!sB&O`A1vWfC=kYqXFnzBvq!CpYC?M?5d7Wvt zxKc4~anzg5i4P?9#j%sU0|~B2Y%Ial)U_0NIb*+;)kR`%S}*~v4ID#&Q84EeG94m= zpbIBW(y3_f2J17*^FR)vFOYy>J$5D+4%CXyQx&9S{cnM8nwy|126Z3Ee-CyC`*S_ABPugF;0Nskeu!jCJ??{RuG@1Ss^33Td z7Yn;s`^#lgW&7<7py0)`JiXWZ5k~+|)}nfJ0VK&+UEc?YJVpvDoE--YkweDA#{>aC zO@qhOu1deBL&WZphkFyD;U{lkfWtBTf?xub?UVH^YTqD|6q>MdQg^)XFThMsDALvj zQFR=9Yr&&F-lSkNqVg|llh{g23sh6wXlNOD900c5%O6QPzqcXJR%|CBrMZonr3*tv zNM0AF_Xyt2mcwTS&;bok&9F@IVT%@u^kTC)bB(0v+2bPvj$3jMD@rq$!eTWP=k3 z&(h)DgNOk-C1y2`?(F=Em5a2DOMV2LQ90Nnh25f)GJ4nqdi^B$dcj!a zx^FMglx~#l?r!8D1@|L%j5}(3!%I}EM&!z0H!fzw^AxoDDA#`lTg5u-VkZBIOT4 zSPTtEV5gq*jO#t{Kg&X7H^v|Z!)ftNoeXcP%iMuY3wLkFFo+gnsc~3Z{_IpBOWs-*PfxA0(HjT@Qj?XWuGMu_o<~KLp zfyql#TePo^(84qwG16Xj#|=l~;i}OAe(RrGjM6@D-glheRg-d1#e;b_Y586=OO2)d z=Ri&VjNb9zKcY)YdvEWq=_#~DQJ@2`gvFW&|E;xuu)fYyLFX?M^t}=r?x1;A$*1n2 z&fJWV>c$L16q3Oi0Ra5~@L8W7U_?^QmW8f0-L}|sfo7I9xK7;b<1CO*(x=_VlILY_ zTP@W`SM`@-Ej+{agVYw}zTXY2Xn@PZs5f4%3mk+pza9&i+Dk;O+*bs>%ItCot5qL&bPeE=EIvDhsldxGQ|N0$&?y!H&vck?Gqh%fRQf=ZS*=C6%jFofuf~3Y7l56JOHt}h-KE5iy5QD%a?bfGWSX3NX zrP4h+kAu2rTMMW(>*%zuRO}oR2p4QoUt#@8KHq~HuMg^-nI`~$j6!o zWNT!*@uV&^tidMP^bT~A0(YRMPnus-Pd^s$10eAwn}L(6b@r)VJiz_2RY0r@Za138 z97*K*7m`2B_d}L#*wr(r6bX?b}X-#%V!GtB?gtK)kE z7r)Q|8z(v#0Wj=_?9b!aMke1W&6)-k4+-9#h4^nRT!`TU9=zd9eKlJSCwAhAkd=M* z?c6120qW;sT591fpA@t4Z~7nM3fap$&!{1`Tq#vd4E*fI6`tTgaqsj`E@aJ=rZA^pK2Iko1N`xTFF zjx;;-zYiZAf-v}+5&UP<15jG4PN6Y3-X@%&v!oSnD|>Z@=m z5rEz0nMT_AcOlsCGJF|&XWE?%2|yRHO10kLSTomJi`(h;NlBOz$S$FdmnI!r1t*&hhFL@mAkWi8g6h#2Dh{o-s;vp=RIJ9oe}WdY|Lk_^9__=glN%yVXa^@#qy_)%f^(JBJ^HZocm znl(4{M}g-rvi948I~?_2YEVnJG!U`=_&i_LI_Jrff6ua{0pZHD zo>M)iYT~dS!Tz{-+XL)czx3P1-*~syS`5^obikyIVI}`viYgn(R*GPr$yV#j&NtFk zMj2U`lK85%I~L#CT14v7xd0P-K6y=P%Y<*rP2>H(XF=~|N5Ua_e|*0Nwx-uuzA_qc zhzkE>Z*i+!>{@K;&^dbDP$Ntoj7bT+mD#o84$o>_wFbR@7@piGpj=i-kQUdu_KrLNi*EUQM zJzgwjR4PieGC5eL&LwIZIHUJS$$Xl&JCbjvHDNP+G9nv%Hrgm{-u(~V4 zH4Gvv<=`71D0N$bvHHU+not<_;hPLR^?far#!u zgsWpy!Q$fSMgA3v#Nb>#y*O{?^Vb|W`?RI^w?d6+?ShBA;ZfWl2o%lMX7G}oE3odk zTmO4`e`FV-lLzopg+Y_*8uD9X%A!{CGqUc2CJYpz;F<7q5NwbvXzZ9z6Y3?z1i0S5 z)A|UPnY7ARNMsubDIHZZqB}x48^S{-YKzvYRkr(do;}M(q-_kt_*iLs@m!kKe=pia zW?1j|__Y+ul@&}ftToI3U4e%z0qb6kt*~uMd(r_CW!LYI#2q1=V(>4veBGw$!|x9% zytP6ljyid(qGl=~+UZg-+{jm8-uj+|obnp1;r#@k>>1RdYIOU!JMmB;E&M*;To%|?#{~AG1YSues3#A8@@gWWrp&NC(45@Vzq304{}r=Hy7k={xoPG1 zzO$`QHgJnwboLkGiBKZP?j?Q`C4taTJ!VeP{gC-xeBK#%m}gK=Mqtj61K8?Pg^y6? z!bmD-fpL)Fg-mRHIOoXaWLA0L5HaR#cs1uLpTL>={K7gA%S$qjD%K)7;2hr#H8s#f zl^(0Yr8RU54pF(cZlC<&ZhO?P|DkEmQ>`b<+vg6&%P8F(;2d# zCwIGhwGOA50zHZSM%ept&dDb0hO%%!sh)gl@n9K|L;FQ;>6_3f*#WZ)lV~QT9v!m5 zt9~dky|lMf0#mkatLz2xr50GejYFbLazKd(Gg4-PWU(HD*|-j>49lH5|)p|4`F zRFyUt`AS9n149GA%zOWoE$~(F5T`vREQ(OLTM5j9a1`4o{CD8TI5k|vWf-Q0;r)^E zqAEC}ixp9bR#o!XFXN-l>(Q1z@cwZ{{q+*hkEU+!aT?q^6J+AoC-FJLhw^d$Vgh zT>N>;g2wDY{NoCA)8r8?CmCR90I@Cj*s@A;c8ufZLcb(ev8H~-DomjAP!}$H;s%+mSIMdT#)>J|r>9N

rKI~to}n-8d{5q?C-cp#XtK!c9Y`7~CqoY8!|=XbOoCMhNC)caI7xsXG{Eb#l8 zl5s+>HoM)hp%&X9M~7=k5m~V^K9=q-E#Rm7T}NjCuhD9VrB2H*_C^%G(!|+}j>vKS zSB<210|~y`J@1)=@cN0;Yh zA$}E$q(-yBM(I~+!>44 zv{4Ew2HK7>&;;jp(|KjVnlR0X3X3r1=@&3S$69zQR9T-wO}D^daV%YpgfbchY)iAo z$gjCae}g~zrPPbDjZ&F^LLs@;OJ4LPNgPvSVeYVS3B(t&-W|zUfmiCO)T=X?52%lX=6zTHdFmfj_%QWQ-E6^xAj~tRKZlr~@-yINa$sU->%M)m ztLWC6|7b&o;k+IZ8=)OEfTCERd3xT{iVxO2U-qUr1)g1kbghCWcJ|C31+fed`!gQl zUSX}_NVHorGXY|YAT~X>G|=f4y-eyv2z$6ZCS>=V&{Ye_^S2{L$98OM1QQdl#90i$ zsbTU|_vA0VQ+#e`G1bm4s9UiH55z`xztXcx>A1APZ{Prq`{9{>AIDC8gTmxt_%nb_ z9zZV3Y0d%AkT5gRbNN2$6qHgwZk^kun%t-E-$ z8v{Dl0t#G~d{5bqp1p_&|!+|9~pO+kAnE zq1iEHjb173p`4+_W)mrAYzB1P{#&~FJAHJ*<9q)y!G7i~qJP;0qSsIhdJy#VtkqhCh}y#@t#xZx^8lu8j(NY5q#%HF-@Bq-O=~|J zELtk5P1A=Hux224A)q91@VlG|P46h{-kSQ64$<$gN4R=!DFu!kNNF?FT#uE9r7${Q zekod89YS*v-OuV1Y8l@`7V7&u(5DMq`frkfga9uoRj`4U63}%6dKk1-g>*!KPh{D+ zAj-9fpe$-|zh~8aI>*jwgpKRo+r0#0PPWtY0h@SR=({Cla+Q{&XgS4s>=`rB zbQtXnBc7;}=vQ7;H}A)3;EhrHntx}E#Y=5$-L?uFtIq(E?YEmows1a~R!THLi12<}!~ic>cIWcSbQW`4s0(fLULG4+^QnCEutX+31`kB`Pn5@jp=C`b3{n4Y>Uak~v4 zpjk9P|3NLSVg&8Oq7DVAKJDfLHBPn3xa57;a`0lIj&8U`^hThPk+YD=ifb}bcJ@{o zrjDs{ARkRBO0<%!Ceyil&j!yV;O!fa7~_gslW7=73_qutBm7@CTfZ(u_B~Y3v@&vN z!+wc*>!@B#rc}Vo3Krw0ssU~wlKtm~`9C;jGd{!=vZHq1}q_ZuCB z!seRccEJnLj(Fu^24j9l`cCo=w)oNesPONfSw`S=bk92;CTb)|qA3Z0@`|$B!8e{E z_Z=DU6y-_D=Vt`KN`zZyku&_R0lWI>0mr_m8@muT8H`g?9W#T(ffvR)3ULrKhgTf^ z(Y;m%ftu(J&ZXGt67YXf^)sWgSX$xcV>PE9!-~zOi|<&uil@3P=#<^aNQrMhGM__x z0&@JV5T6dT*tP4Tqlb`Vyz2ohnfr)_q9Xbs3#c67@Iy4(aECorTLHxDbe%aQP2uUN&PuA<_|}1^g7!z{w%yM5O8gXe@flrr zpE_pHcxYDZrY_^P6tf!s$ze$0z$Wo-w`xdMdruWOe}?Fe_l;+p=h~}pp8h|Mlyzd= znA~>OF*tzg?>qW++42#H0sC#a;%79l<*5epnj_T7mRo8xq0Lz^(*CXM3kf_=#ExkM zHS2}M3wS>h{fzOsv-X#R)9ky-xM&qUc|&=DO3PhnH=BW>n4_3>dUs>=el*JomyLaB z$X2IrqR;@MD};q9uZV02;=J2ig`MbkSFGPYOGZU&27Tg3FWXM6)?e>WULIJko@cZ( z?zNvtJ08gB_#(_IvzjJf!>SgBffYIwvgdg8mAFkNz(Dn#1}2*`2yqsw8DvbL0iw3s zLG``EH#)~SF8ZN(Tl}S2EFr3!-=URO5TJ2!WEgEn^oh++g%8A8) z6j|RxkIAX8zm-}CdeOxYKhtEDgp+bK=GHq&!$dUc`b~noJV)0FvS@) zMn3%T+m{S7+RObGAgeOPgwrmJyck~$L*Wkp7$q8Q*(+40KBl_|Hqr3Oo88Oo{K;)g z>>#~nx-Snm@*oy4Wk?Qjczjr$C6uVVOxUIzL6G`AqIgb(_3mBZX^+S-e4PkI4^(=qc_( zggt)|XhuzLG*&`{CM&K!ZvgryVx|pjtRy#Zt;qrj_|;^|Mwg{`Y~e}>;!N-qH+YM` zn(2ckhq^%FIhqa-3YqO2IGWKJCWkqg)q0$ChW6HkeZ|fy8rv1QWf|8nC2>~xUAq|( znTP=pQ3v%?hsp4LUcyMR5o5?69sKn#~9Z*f<2G(B=Sl z5a~h{A(H8|d?CO>;oSCa*?di#@#YS-li?T)#RZeB>e>EN*3YH@{>fyRWTzUf%g52Y zTVS?T*^A3BoB44F>F1g-PCh~;z+!?9iXRqhAV{X&0I59JIQ7r^%Rlgv_nMLbwJ8jcDGz}~4)hgF z^Y!S(Tz+P)cJ14wuD~;}CFyMuwc;R)qPKrHeGbG}au2d<8?V=_ljMv7qxkBB7#AXN zmdP1J3Z^k^iRO=jr*CUB#8yLC6>$I=7UFGzToE-9UxZ*cDnGF-Ya^qgYaG18jQvdC znLb}G~Bt<2d_Pdg$bVXmJ znvdBf8-yAR3R+h^r1bK`AqQ?c&2gEAP;kD4vb?ePg8y6w{?e$$obr@e_|}C6 zSx=D)L30TvsGyTB<=LE-$b`9^XDeCY+fIqb(hVp7{syxQNz+k zfj?*k)>?(cuxmtLJ#g-qAF=n)8^POZw{(Lo6HqtvLXm!rgldRXtso%x@R*{D@{=S) ztF3;G*+NLOBD5s1Ot+K)<@Gn167b65IOCayNae=bDM`}6tOgx14t^G{OPkLpDRsp+ zn&gka)%5(C+^I{@dl(>c47NZf1}%RJk(!uE3|pBiT;Z*g>->n9pMm4eu)Sr=UmLNn z5DAYgwerCvAjkS;QYpv+3poV`RJH^RPh_tjBKjci_pO7Ozt+Sg1D*!lLYGIog%#ngGHRSCxp98Utn25#Uh4`$cEN+6((%4UOMRu zP2 z0^W@o7IKyU+N*I%9eddKzM?X|Dyzrj!A^DI$};%~;%Cj=gafF#U-vz{lNS97Q_Oz& z=zy&@HfL7gI9~%$;uV6%D($4VR>bx%Y_FDUKpgtXs-i4Gq4cw+fg8Rf({S*gQCjbN z`L>iWKTe&rgSvnkE1t+2Me_TV-zhtm-ajy5?H*eAi0NT+h}!O|uV$JON3`~8z8e!; zCfpN({33d^>K1-mI#ci59@C#c=g}g+;Mg4sf@Av(U$GTB&9(rPstqBc$pc@!4sJaX zPpoigtv1_*X!_M~ zh{xQKZGsmnLLiKwr#%j*Cu?EfI?o_tV|w7cRI6N;j3c_|6)c6L zl;+}j9rZ|yJ+nL|#<93!fHuvCn5A`FtpXsNyl@O7TMPd5E^-)&pxxxIaY1uDcdI?VUnQ$NZYD{|HkdIn`TAlXQBTh_e4)tEL9CGp< zG)hIzb0ryoW=oh%G~vT`t<@2}Y;Yf%#&L>>!dF6_6GCgJ#j z@$F_2vI*$*LQwKu4op@XQ{qdW1cHys z#O;9c5_U+>yM#@{I({AgEE%zdR(lNX)v2yjutk2N`r>IG>Q9}v+K4kPv|<2G^6P0U z-D1K5GDME820%HCokizy*&?rNXOoHGJm#0CFa|Mk<{PyyuTLZwqUq$(L65d&`tcx$ zvI^43tW&7chvaVy9X2loIr=V6qMQbHeOO+OY!Ei>moOuaQ=C*&jlWNR??&gIUx#d; zE`tslri9~m7;8ktgVFfC*v%grj~uyfDqV*wz%fJgpdyQ1`XV>Nh}?u=j!+%yw%!41 zGp0}4PPn^AQ+6*qVB3L-goY?Y>r3ap2VflsD`W7jei)cPId%7sybTl75c1kbpH7GP z%Bj9FgM`S#0+ep;km8|GC%lgr{aHmM$4n*SEF2HpH>LB83tr!bI}YK^WCUgNt_j+( zi&73FErH$=;tmxkc%(S)$F)9wkvd{KwU$_hn+IK%DFNy=H@7LH^1*VJA`wEqQXEIV z>$&q21feqr!Qm)PfV35$z+5W$#CF&4xzMr})A8d5{gp}JfR6F2&;6YK1f$kHr_3>J zH3gcG_of^)=h59cwrzOM$5D+DBsJR&nYtK|U!@B>tseV!teCH%3=DGt2MXVlNNkC{ z_gCp<2TuHIwfE-TtT9+W%U#c=t?1yhfDZAYiK*t&yXE$+wI&jn-riXL$OUo!${gN3 zU1#lBgLbS;d?3C2sNh?{kh6}1Vfq}>f^U@I!*SQsT;&7c>&PFK`^^A_4_t4$qTeJa z-QpAJxYX?r4-}`J6~*KKiY&XV2_a(edPjCB@8<>{W?G=#<$b}i8O?2?QO6Z#=iSRo z#|sb@+U3DO>lqTen7*sqa3_yh(J>t%Xc*hA`|R0`tY_?1W5Tf+^)ZE>vb!SYjvqYh zaOHCYP696US+os*04x-ITHw5fLgY2V=n)Ul37nU)>Bi7l@$lIFes->CV>zz2P%6Cd zx3Db{{q3(hgTng8i$=4Ix1x!~Wd74KNf%KNaeAwqqfK{G`jd{60x0aaI0p?5enU_c z;=3|R=+~|r@v8@ICXl!p6tzmcTx3987WvFP3fobZc$S9`Ul^*cA0;JVy4ZX&n@rokOWHW$ zo-BM^=)H3RK?undN^QVl{m~%4UbWm>JCzry-kew!{z{U#clwK~l zsyt}{ltg2^$dH_a)PYYr9S`-XVsB-uyvJB5>zZvG;hNH{mP2xmC<=|1>veH`#evTx zfvXr6QYpO>OP6X2W}ilYYLzPHYMj{C=c#K#FQvDGafNS3;S7pVGZw&oU?{*`?Ed^7AFP>m+`OdXzNcJQ1*d7ib~3V_G@UL8)Lm9Gco%WbeR@ z9X&<}=IMktTMMeZoWS?_EdEeqmJG>CZJjt!FHp0F7&51yN2h|&dC8_@7xN6%V1BG0 zKWEim(0MIHm*0D(d}w*JV%iuhD$J_~Aes}YsZR7B?bb8t3FOV<`0BP-4>UJ+J?S8Q z5v@22|0p>=PXlI?FU(9Ug&K$<0jdOUu_WMHV70fC_Di8Q&aB;QU|6A=DrDT-IvI>t zt&K|t(RC*(QF<@ZsyP~iqn(5imi)d6y1b_j>6(4&1fz8t|DLDLM|WI~)%s!xF&>cS zN4Unb)}S@I-dQYeKc6`oWX@xN{#jgkeSW#4)6gQ@nO_rkSFZ*Ce4b z>pE)-r$8|aUda1RrTOAWY?#H;ExFA?t4!PP!LU@9mYb63Q{4J8b_|0YU&x`W&YB#6XTNM(q{mb!H#&u17Ek!wD>bO7e#`%~! zKYx25a;&72cVP=^Omtr3UgeW47Zq{BQRg3RwtwlwzpcZedo=%GRDP=ULB?Axr1A#6 zQN*_0716*-VhI3CT+TGqWoBOb4@VT2nCaG%IGWM)jeRYE+WT^{LWvg}E*$Wwkopl7KYyx9j(NY2gC<`zb#?{kT?lFQD zXc=ZRf7+O5;HYyyGRzVLm}dLTu=v;J@47mRSBc9KEI+mX(#u3onverckD;m5iu`G| zuoKkJX`z1zxVS~$<?n`<3tcT z!GT{>&4}JIB<=s&*FuBd?PJq~bQ4dhTMD6F&yOd}QER=#iTwNfoTbJEeP7|VZnAyh zvesC7@TRx)e(#sYAK1r_ zbNgLuSNi<$_C(9PzKF&4-X>Y25mKTH<0C;z-ZZ_G<%z@aE6gZUp&PlPU}Ew!F8mQ= z>xHEiagEBg+9~0eDeev z;z##MNV6=2`Z&vHM)tL$hT@>Q1*oJtCx5Oe!Y`-ahneCx2o4Iw%b-`K9%NWLpiG-} zk#jsi*~Y7ViJS3SQCKd(p3JM>nNQ|{*OOr;-E!#l^YatE$Wi? zV0xzbsuUn`r|Z6B&7E34Vv_q50-%)zXN@<+cJG{IZ{a8*;FvfELV-(CQhErvaK$g6 zK$MG%KD0kT!js|dmc7eLux*t`YJ457pXXdFD0a-TXF1IumSf+8H$%rV{o!nA&R&{z zBJ20$^*WbCFc;5hn!6$#!EmL{(qfMux)hz;&G`!A;QMZQlq*jdOJ?1eO~lI}I0zAN zEY5^3RT1u@eSUC?ccmiuVZ?`O&tl52^61B9Zrw)!*i-+7ee+n2S0hEb<)`WzYRF`m1Em(6HSDi8ts7d{2_4ppnw&80B2Sa+=B%?`d# ztU*d-eX$;v#lgpD^b@A^>GyG`hP_$x)aVOcsPGc#3XVTLiKXv;CT;-%`%{hjKgRTa z4n69$!)4MVv_MZ4()PC<5~4E@Jj|#?nsuTQAlp0?{lUKIno#F%C6Ht|I}t|6gBm&V zjkULSSL7lj!zX6_Wbp($%9R2YY`!eE7Tn%2Cl-qy$L&x>v%zd=q-}MzOz*?1hb2m=}^tj41HNUTx3vkmt)n- zRvrww_$*c!V^_@jP2;0@F>FR=Li&5l_0ZCIC;v?Ldc&^*_g^e3B#Kneot9M7EIvCO z?P)VSDdkE;id1)hzKZ>!FWylngNerMiwdD&Nl%OJ-QIKC zV$Vn$PlJeNrme>NSb)`(p*d+v05*~4x81?z)4iorG?rT@(R^?FEkNvzJl7Ycqt(L( zYT^0EyLk|HXZdC)>H5SiZuz|IS8$hcE82||6sx^v0Po!gjWsCyL2{!@T)Sf7EGD~` z(qb??;5=emvn4JXz|#bkezZi9WD=nH-N1lTRMvIlixn9!(kETyYGs?@ z(vF)!ybf#x>JAETu_e9OVftEyvDP+^TD!d*|BkK%X2I={v-b@olrMky{ z8->iB{I)t1R9lIeR5ZXH$}&fy;06;8f3*6Vcxp6Ijtm|h0el4Q!AN2y z@a_sH<7U^*uI=iWB2|>FZSixL+pd2;)XQnEL#R$_96x9!V1w$?^mi(-GZyMU%x>dZ zf)dKxT>~fDb&4ALBxGFdQUboMk4cyH2#k&m2+*qM4EFDOe>}CR7G?*{zcWidhv2-e zPQG&3g*Ay0!sH$=+VakB{5vN7n0*{93K;$FMW0U?YL^(gPbPy^{Ii}{?K|%z?D4!N zJMVT+E8FS(LiTJXA8d++w*z*`A_jP@cApz-A0)E^Z4`0Q}EjTAf-LXUVGSH_;f+x z6x;Zoqw{?I7XOWrgwtbjXig{^SK!!A)pId}|EA}LB}F*#xf3(GW3m=f>fro&nwx+acjiS`)&TM=%Xs#VbA%ucN~VVpXXKjImDh)#2zQto^b!z zi@i<}d{AwS8@GR+ddTnBZsYi~_5I1x=uyb1eCB=0s2d8%=!w{$iPI*xt+> zC@PBeuNgfM3qN3LYRnULobJ$3z1kIj7s@$Fq6!RnVe%4q2@IE4L_&FwVWRqqp+F}v zGLJflKvu0UXckMB{FT}p#z?HU#04dc4LbdpVg5$d?;oCZpR0Zw&5bVIWH{dl*smpg zLk@T|Koo((hyc_|WxB=z53oi>6n5{-e;FTs#U=3`$uXEyY3SkCEtcU8GK$f1bx%uY z`ZNDK#R!bcklbSgS+x|)NbZd~K&94OYOWY`D$x1`_ge&2&T!{u(hSY;d8B|H=i0u7 zDKw5{)bMv?L&$_Vh%Nz$oTwkVh~6StuD@vIHn1ER4azWIux9!SE9?rBWUh|+J& z1AEEbZK#USJ-_- zCcw&Ye*EwdDlS>!_;8FkR$APTv9D>&W$DzTf6|CiGkmQZqAMV7iGD$qKa@S>ofx35 zMyLtklitgDkr;uNgST(Wi>D;xJdNZ+pc^=s6E1j&o7;>8~NnIMJDEpFD zO#KB@T7A6c`$Z*d>V^a_x!wXy?zC^>jlj0A!NU+I`j)Tl2|lSlp+1?y@BLWlXbM@( zS$1d$S?Cf+QkYW&XHV-vhRZA+_)l{*5!}p~%!Yg1= zxkJg9iG{_6^^hIF0%dBGYc#yhI6_`%avE`(b7B>!TqbK_Zn0=Nbeh~@x{$t5yra8l zx!AcF+^!mlWm0_|MJP-N!zw2%d#%j)f>Du?nPrg?jirb=nUO-hz2H_d;+xsG?TS7v zX4SZszQR$ePVU>QlkD;gJ=K|Bb9(B17OdsyV3uVmpwd7p0tP_7>%`(qw zlm%O(@PYY~)8AES9+&8TUwrtuSeIJoQ3sl^&T#de1N>h2b@EI2H}!A&-=e>7$arz= zqhCj}k+G58@Np?QkE@RFqM~CfpDT|Ne+5^El{7avwJ`M<)MgQrzLdt0rk!Tg@Q&?> z?UtyG&5JD}IVSo2DA_0?OBvw|^HN#2^^oqk;FRE6YybV-n_ht$=f<&v^vei48R99M z19#g*$fNCr?IPq)Jzvuf?8Cxp28+EfnD?y=w)3)sG?6uhouHlQ-w56eD)LxxUvgfypsz?AIWBKS z7bom7Pr7jgrBrFhX~#CjyBD|@-XK%@W=m$HWjh)PttE9H`$>LB_|E2s%xX&%rZq`+ z<9=qevqt(32Lrd{g$Kze3dWZZy#V$zqiWag4q!geL{)(k!vfVFr<2kYKc3>knURT? zwx0P)EmcX!P)EDj>GsE}g3Ftt3*iFCTOg_N7*uuQ+ytV~D5btL;23jMd18)cuh zO?kn$TopCjuo74+EJAAaOCtwaMBNvbs6!)2tw;Z+f&y;}MskKO^Y_G#D;;4jQNcf| zkLYfkZJ{DHQ4Ns!TE`d$OY}X``OLOxp%Leeq;m>}X4*tLVL2DM<@C4d+sT?)yaPAe z+80K&4|JzWehK&)PQaZypzc&6a}rs$*ZUG$MLf5ngMtd#L&A^YSW>|U$_Gm`gZ+q` ztuJW7j?y+oSdY%96WrtX^fru3d~M7R#}_3#gC7_xUsdi;a7`|xUcQ}YxOqr|$xn>L z2zRu*dPjK_y`*Ba30<*F1u-YAHQd}n>0z2ETnJ6YRo+%Zlw{b;vvHixPQZJKT*wDoTAJ-Albxg5DU`MMg{0IsI4&T}o^ zm>3rl)1=qB*7DTkJN~iQ;5ZLmSzejHX+E`DF7IgaIDPPa^ld8hEr;4f*^JyITw9*{ zYXY>Eev529+zXDkZnnmvhoGb3hLRtBb1$h9D{w8TN3B<@>;2 z%120vC{r6F{KWNV@J~LXj8F_$4BsEKtC`BJk-;zNal0A2=g9@h-E*mPs|0@-1Q#=w zVxA#Smw^dh4CTtDS3`QekUFwONnSxh|$C z8gKACs9grcp5TjD!1L4a>=|;n&A>hNZhv9_rnd!KZLhWi2^cz?x2vC(azp$OjM9mV zZA$rREd_WT5dtIJG=Eh5fYNtHA083}^l@_z6V~6T%`pzo%<0fbJitS%5$hWuUD$YA z93qx>Oo>#(Rqrn^husCf+VC+?g}%nasd?Ea+9H=FZp5jbK^VICIYYKW7MMn`VuBMJ zz_E@<)!rX~YspTg{{<1SE&B?fY+ULf6-sKQtalc7^EwQzzV39n*>ch2=7BPpWS zb?cCjW25m#MJ$+{7@g_E_b+x;mG+I3f8Vvgof9pi4T&zT*!hyqdfiotDGv40GKlqd z!b59D05v}RfFD|BU6f7=+!@u2@);M=h)&bzaqS07n^ZE<&6u1p5f<}8hXb;)E2W~g zd5f3_lN5p?ztAxZ{>j@GJ1lro5_{ymbGT4O;h@5oSN6AX30x=8G$^k*xRIt%!5+Nb^P*lL$RG2F!E z6W5>JxOr}#z3nlB-gVMFVfemK77jb$IKVX?;P{SqkMQK~McF~-mF2pVsfk|yC;nO? zz)fePum7M#^c&v^S_6xHoken~tY#-uVnc!5B9y~$WKW-sJo|#ZbQHQBQPj~K) zhwzLP@2ckaKfU^YIO~7idTs$uzJGi50{?RA^?)355)$uCoXyRE|M2wHfd>EP;rS28 zU(?e8?%%7LSeiQnIh4%JtW4h9djR$R#s(lRZXmw^w*int!rs-+-PUE!ho~>GsO5CO#D-(go%p@#NP7X!v9XH{-0O;dligICSah722cmSPIeGG zH&D&h#L2}As46KfVQ=SR?%~4pzh~k7*DQ>Zg4~>3oSZzIyxj07AEz!SCjneR zIjTA4VnedQD$=>Wg-~XSjc{rI{U~vMu_^>$t z_W?)dvSA0{s^a#LdME*X-ZpKlnJg;mZ3j8W%4- zX8SK1&)ff&$H~dd&-Y(^d~joc@ALn<7CtX0e4GCl4bI2^-!u?6=iC2zEjRc7gU0_q zX*}Hju@)C66Dx?h6V_jQ(6I7?>zNP8p>A&vH=}=A4~Lwcg+1J+{-Jz1Nw`%B3xL5~ z+#oYPJ}y2m2>jN})SR0~fD^>eZ^p+1Hsj+J#rprV0RLf?&Mt5h`o{+c;^yV$#-gK> IQjx~`Uyb_&vH$=8 literal 0 HcmV?d00001 diff --git a/doc/images/circular.png b/doc/images/circular.png new file mode 100644 index 0000000000000000000000000000000000000000..71c346a8ec6458757638e023c5ce29431482a1b2 GIT binary patch literal 1493 zcmV;`1uFW9P)#6s{yOo z!plL9LGiyx<|X`3;S_}YP0Jy8$R9Hd(jzS50X;+EZ&)%P(-RavLg8Zo>JrX@WY$nk z<8Vc^PwG4li*Ju#r5s4+GhSAZ$Kf+pzKS?pI*ki55Ly_H6$bO$V8r}w^wjP)bio-4 z(@nudVTMM`15h_1F(_hjNEB)mW)QUNUXDR`w{=aV5`osAO&=N*S`>OZkOQVD%ur}i z=&qy-svvBfb%jQB_6rwuR?-Pm6dDw|<_kAWP`E&0jzY&Y;DHGWbp-xZ7jhK#E9rw0 zg((VGDD3q~AM91q3pEN?LD(4kjnS=xurYAbK5U*(U6hhA+?H>J;kJ^~Fx<}iA4FhX zNh>3;9$_X1>&|OL1lFB*<$&$EB&i~gW3Z~EVL`|*J{ey2xlqJvuFBR;-iCj)p{(Jp z2-NlKBmxZzHofQqqd(ix{-~ik?cc??>V3gidxT z|2zh1XG-!WU5IoA?_mU9Kc{2js|-6$Fef@UnGfZ+LT z&JdX8;(7nnj^8prR~OGHtp79|R8B~jfO2ps28Y}U)xU=qw@HIRGdRppsNFC@VLzfm zVS+-5LNPexVDoHmo!d}$p&1-zgF}r%H8_+g6oW$!!p2XzfuKQQhQb93Qxqx`N)!qd zG8A$UHkaDEP&Gdq0wZQ9T%b^+P@ynE;S7Z$3afVEV8qrMXb2hDsR49}I*s8zq z!}h_!Q@59r0})p!T%a&Tp+unwz*aNz0Bjze)lWZMp-`hxg=a8JN4Jbj(65&|Dw*&zhp z9lb&j9KHH!`S#jqb6h!`e0!rTRL}}~FxnpPZlj)kvR9R|5}LD7m4R5!uv3d8*7~pa zhF#ntFd}z9o$WVI2@e4HO?koE2jEcwPu)8KT2S6Dp?hCL3!d#3m%xX}P8TsPq1=>% zSx+c=>fT$>fnzF04FZdVbmYyRynJfSag<>|ofHnx>hy|R1Pzo>^$pivV z$MX7mriwvHa)LmmDB0sP2&yp`aVQHo2ZjR8cS-+>><%l^SiC?shsbiO2Vw5nJmdIL zfoxz|Lp?a8OTxbaL;x5VyfsC&0000ybVXQnLvL+uWo~o;AW3auXJsH~Wo~71VRU6= zAYyqSM^H>4M`&+zbaP{JX>fEPC}d@JX=7zQaBgjKVRtDC2Pe+(0000qbVXQnaAamW zNNG}Kb3$)*Ze(e0XF_jy05dT*E;%5@PE;ltao2<4} v0000KbVXQnaAamWR%LQ?X>V=-P((&8F)lL-h`nWL00000NkvXXu0mjfnPGIR literal 0 HcmV?d00001 diff --git a/doc/images/gtsam-structure.graffle b/doc/images/gtsam-structure.graffle new file mode 100644 index 000000000..22eb72dc3 --- /dev/null +++ b/doc/images/gtsam-structure.graffle @@ -0,0 +1,1302 @@ + + + + + ActiveLayerIndex + 0 + ApplicationVersion + + com.omnigroup.OmniGraffle + 138.14.0.129428 + + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {559.29, 782.89}} + Class + SolidGraphic + ID + 2 + Style + + fill + + GradientColor + + w + 0.666667 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + CanvasOrigin + {0, 0} + CanvasSize + {559.29, 782.89} + ColumnAlign + 1 + ColumnSpacing + 36 + CreationDate + 2010-07-13 00:07:47 -0400 + Creator + Frank Dellaert + DisplayScale + 1 0/72 in = 1 0/72 in + FileType + flat + GraphDocumentVersion + 6 + GraphicsList + + + Class + LineGraphic + Head + + ID + 19 + + ID + 35 + Points + + {191.649, 522.933} + {191.649, 558.208} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 34 + + + + Bounds + {{156.649, 558.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 19 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 tests} + + + + Class + Group + Graphics + + + Class + LineGraphic + Head + + ID + 30 + + ID + 22 + Points + + {220.827, 437.595} + {201.125, 473.266} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 25 + + + + Class + LineGraphic + Head + + ID + 28 + + ID + 23 + Points + + {198.977, 245.588} + {219.976, 281.282} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 33 + + + + Class + LineGraphic + Head + + ID + 25 + + ID + 24 + Points + + {234.015, 373.654} + {229.931, 409.211} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 27 + + + + Bounds + {{193.649, 409.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 25 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 nonlinear} + + + + Class + LineGraphic + Head + + ID + 27 + + ID + 26 + Points + + {230.126, 309.655} + {233.82, 345.213} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 28 + + + + Bounds + {{200.649, 345.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 27 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 linear} + + + + Bounds + {{193.649, 281.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 28 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 inference} + + + + Class + LineGraphic + Head + + ID + 30 + + ID + 29 + Points + + {152.743, 373.628} + {188.492, 473.239} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 32 + + + + Bounds + {{158.649, 473.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 30 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 slam} + + + + Class + LineGraphic + Head + + ID + 32 + + ID + 31 + Points + + {185.872, 245.631} + {152.363, 345.234} + + Style + + stroke + + HeadArrow + FilledArrow + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 33 + + + + Bounds + {{112.649, 345.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 32 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 geometry} + + + + Bounds + {{155.649, 217.708}, {70, 27.449}} + Class + ShapedGraphic + ID + 33 + Shape + Rectangle + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\qc\pardirnatural + +\f0\fs24 \cf0 base} + + + + ID + 21 + + + Bounds + {{86.649, 196.433}, {210, 326}} + Class + ShapedGraphic + ID + 34 + Shape + Rectangle + Style + + Text + + Align + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1038\cocoasubrtf320 +{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf0 gtsam} + + TextPlacement + 0 + + + GridInfo + + GuidesLocked + NO + GuidesVisible + YES + HPages + 1 + ImageCounter + 3 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + AutoLayout + 2 + LineLength + 0.4643835723400116 + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2010-07-13 00:17:24 -0400 + Modifier + Frank Dellaert + NotesVisible + NO + Orientation + 2 + OriginVisible + NO + OutlineStyle + Basic + PageBreaks + NO + PrintInfo + + NSBottomMargin + + float + 41 + + NSLeftMargin + + float + 18 + + NSPaperSize + + size + {595.29, 841.89} + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + PrintOnePage + + QuickLookPreview + + JVBERi0xLjMKJcTl8uXrp/Og0MTGCjUgMCBvYmoKPDwgL0xlbmd0aCA2IDAgUiAvRmls + dGVyIC9GbGF0ZURlY29kZSA+PgpzdHJlYW0KeAGlV8tuWzcQ3d+v4NJemCZn+NzWbYF6 + 1dQCuii6cAW5kSHZjeQW6N/3DHl5TclXUoNYSOQwnPeZM8Mv6pP6ogw+3mcVE6ndSv2q + XtTt3d6q5V7Z8tkv1Y3RXhnN2RjrglzXVCR0yhAantTtz6vdcvXX29+PG7VbQy0xFdXs + kopeB5dyVuS8dj6q5Vbd/rS16vvX4kKuV71R1jlczcoTaZusH+pNmrlpbLnJ2ZWbo865 + my6WmxTCJZ2Jyk3n0yWdKR9YP+PnqJPZXNKJ5EjsiHvGz9tfVpvHt/U/q7vXzetuvV29 + 7dZLSXUKkCrJDaYkl6xRTEGK+YQC3is7PNeS3j2Ukhj1cIcK2fKPG/lC7aWSSPakzeag + HbOq2rzO+JFSP6BiwAcJPowCNjpFNteaOOJW5u8Wytbq3uD7xhqDv1xUi+1w+6PVqLha + PKnf1NWf14IyUldv10AavveP7WR7rX5Xi3v1w6LaPsSm9TVtnqOOTF5Foyhqh5zEoeSg + 87APtQmShaBJB4KSvINIh+NITamV9/ZUpKyNNdEph1hVH+tw9UeLbApxvzofox2BafJX + xjgKMrD11TGOfXO6muRPxzjVE5HVwr62X7bTUav17t8+/Jl6SX/Z5HWKRIVFAluncIbi + ewtkMuM/vUlq0+pWUCLkVlBqPekcgHHHGRULaRDhpDkA484FbRJaZoMzZDoGj7MIzHtR + +LmcHkjD9BMU3+PP8zDjr7TSZJId2oHBh51J5qCTwKMzyezQhY6GA5OdtCDSlg/QKN4L + XRDo4hj3U+8PVj33HXqI/6rARb6MDXR6H6fNXI3nidCPOx15DDHHj/hHa2+uh4qJqQEO + evxMQqNjpxgeB8QtCQUowCdpcIF1JuNPAiBFAQgptmhZzqkIo8bRepxlnRNGGqoBKmRC + ERi0kH2gCoAZ6QkAJxM8Cg0uCkvAtvg7mnQBgDTRdiaVC05n5hFzzWQn/TD0ABhrUOon + xBcQBH7SRH8TDICZWRiUtmqlFBwJDc6qOSDDI9onGoEEjzHdRekRGAhTHf1Fc2BYN1p4 + ab88jRNg1VCymwhjurM8T5hkKj+7Rpgfgjo7Gpr4RJsfxPsBMcyMQgIfSXcekqfRxgAG + C3RvPxSRnYg1SSZFPxWvNuuX1ePuWi2e6+w70Rckq4VklxFt8NC0lfVLxxziIMTIwZ/s + C2LpJZCTEKMPkYswpgXYqZBgYicsRZR1soRGAzGSdaLwM8x8lL7YF01oEGpjotibFH+N + 98LFzWQh9xBLDJ3JTnq2L0rxvr0vCoS+qS8Y6/J7X8xjoHSIR4jH68LVy+vLBxyA1mWu + He1uhPlhrOfKj94J3xBjyQqgRc5Zc/RCZ2Mv1wE5jAOygMhFXMS2DhwIuRaFiF9xYm0j + VRwkzEpjy1nysfJjkx466f+BA+BWTDoTBQf5wCT8jTYGDEPhl2oSZ4ap8mMz2UvXAYmN + 9xzdJXB+AEliJfIpyRYBOIPq8S6hiK5xmcckEcaCsdg4vGGN+77cjdo76waPORKClZlB + 2LI44hZ40OaxM2Zkz2ZEaHMySFHeF2gyOasG4ZzVSIVMjNEgRacplpmHvmgGmyw2nAv5 + kC2FyOiEFnRYn30GPnBksO5bizPMo2AMowaiiQxpA5ooI5RSKPVCzNi8I86w0OAxJt5J + thJaWMZqdCC8QhWjNAYr4qjSZxNSvGsmZQgGwwWVzaTDg854EwUizaSsAdZhBvYmVSdd + UyJbVNmh5PGEJxceO8c7VB0Q5f00j6a641UFHsvYuf16bkS01xJeWEIPou5obMryHtF+ + PScM9bnUNudpMu7byf7CKl3cLg+1FAZ5Z2PjQNGrNxj/mB+ahe+OiKIwjuSsynogJ6CB + sD2JsDzbkx+EMcqZLFKyFUBPd4ZNekb6LArqiiLvSvHNh+rbu8ne38lkF8O7yaGTFhR8 + +g8FPYzxCmVuZHN0cmVhbQplbmRvYmoKNiAwIG9iagoxNDU4CmVuZG9iagozIDAgb2Jq + Cjw8IC9UeXBlIC9QYWdlIC9QYXJlbnQgNCAwIFIgL1Jlc291cmNlcyA3IDAgUiAvQ29u + dGVudHMgNSAwIFIgL01lZGlhQm94IFswIDAgNTU5LjI5IDc4Mi44OV0KPj4KZW5kb2Jq + CjcgMCBvYmoKPDwgL1Byb2NTZXQgWyAvUERGIC9UZXh0IC9JbWFnZUIgL0ltYWdlQyAv + SW1hZ2VJIF0gL0NvbG9yU3BhY2UgPDwgL0NzMSA4IDAgUgovQ3MyIDEzIDAgUiA+PiAv + Rm9udCA8PCAvRjEuMCAxNCAwIFIgPj4gL1hPYmplY3QgPDwgL0ltMSA5IDAgUiAvSW0y + IDExIDAgUgo+PiA+PgplbmRvYmoKOSAwIG9iago8PCAvTGVuZ3RoIDEwIDAgUiAvVHlw + ZSAvWE9iamVjdCAvU3VidHlwZSAvSW1hZ2UgL1dpZHRoIDQ2NCAvSGVpZ2h0IDY5NiAv + SW50ZXJwb2xhdGUKdHJ1ZSAvQ29sb3JTcGFjZSAxNSAwIFIgL0ludGVudCAvUGVyY2Vw + dHVhbCAvU01hc2sgMTYgMCBSIC9CaXRzUGVyQ29tcG9uZW50CjggL0ZpbHRlciAvRmxh + dGVEZWNvZGUgPj4Kc3RyZWFtCngB7dCBAAAAAMOg+VNf4QCFUGHAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwY + MGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAED + BgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDA + gAEDBgwYMGDAgAEDBgwYMGDAgAEDBgwYMGDAwDswyVIAAQplbmRzdHJlYW0KZW5kb2Jq + CjEwIDAgb2JqCjQyNDgKZW5kb2JqCjExIDAgb2JqCjw8IC9MZW5ndGggMTIgMCBSIC9U + eXBlIC9YT2JqZWN0IC9TdWJ0eXBlIC9JbWFnZSAvV2lkdGggMTg0IC9IZWlnaHQgMTAw + IC9JbnRlcnBvbGF0ZQp0cnVlIC9Db2xvclNwYWNlIDE1IDAgUiAvSW50ZW50IC9QZXJj + ZXB0dWFsIC9TTWFzayAxOCAwIFIgL0JpdHNQZXJDb21wb25lbnQKOCAvRmlsdGVyIC9G + bGF0ZURlY29kZSA+PgpzdHJlYW0KeAHt0IEAAAAAw6D5Ux/khVBhwIABAwYMGDBgwIAB + AwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBg + wIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYM + GDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIAB + AwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBgwIABAwYMGDBg + wIABAwYMGDBgwIABAwYMGDBgwIABA48DA9egAAEKZW5kc3RyZWFtCmVuZG9iagoxMiAw + IG9iagoyNjMKZW5kb2JqCjE2IDAgb2JqCjw8IC9MZW5ndGggMTcgMCBSIC9UeXBlIC9Y + T2JqZWN0IC9TdWJ0eXBlIC9JbWFnZSAvV2lkdGggNDY0IC9IZWlnaHQgNjk2IC9Db2xv + clNwYWNlCi9EZXZpY2VHcmF5IC9JbnRlcnBvbGF0ZSB0cnVlIC9CaXRzUGVyQ29tcG9u + ZW50IDggL0ZpbHRlciAvRmxhdGVEZWNvZGUgPj4Kc3RyZWFtCngB7drtT1TnogVwlXdm + GGZwGGCAgsPrgEinYEdACwSColBfsdgKQUdNsSDVOJEUtRiqRKIorQQ1ipSIBi0BQ9QY + Nedfu89Gc0+ruHrOp+5173o+nJxk9STL9euz9wbPmjU6WkALaAEtoAW0gBbQAlrg/8MC + a3Vsu8B/9e+f+VOs+/eJ0bHRAv92WWeY/gPWd5bmTxAbG6dj0wViYw2QRft3pCua7yjj + ExIS350kHZss8B4kISHe/ItmUP9G9L1mXFy8oUxKTnY4HE6nM0XHNgsYDoOSnJyUmGiZ + YlGLM8Y8ZQ2moXSmuFypbrdHx1YLuN2pLleKUU02pO9EP/HQXeE0d9PSTHGlejxp673e + 9HSfL0PHJgv4fOnpXu/6NI8n1ZViiZo7ah66q4Nat9O6nJam21j6MjKz/P7snJxcHZss + kJOT7fdnZWb4jKl7RdRcUQt0lQ/dFU7z4nQ4jabBNJK5efn5GwIFOrZZILAhPz8v16ga + UiPqdFiv0dVB11rvzoQkczk9632ZfmMZKCgqLikNBsvKynVssEBZWTBYWlJcVBAwpv5M + 33qPuaJJCdZX0ccX1FxPw5noSEn1eDP8ufmBwuJg2caKyspQKPSFji0WMBSVlRUby4LF + hYH8XH+G15OaYm5oXOwqT1xzPc2nUPIKZ3ZeoKi0vKIyVLX5y3BNrTl1Ov/4ApZDTfjL + zVWhyory0qJAXvYKaLL5KFrlgq411zMx2enyeDOz8wpKyjeFqsM1ddvqGxqbmpqadWyw + gIFobKjfVlcTrg5tKi8pyMvO9HpczuREc0E/fOC+u54Ow5mRnV8YrAhVb6mrb2xu2dG6 + q639ax1bLNDetqt1R0tzY33dlupQRbAw37qhLsdqF9TyNE9bt+HMKwxWVoW3NjRt39m+ + e9/+joOdOjZZ4GDH/n2723dub2rYGq6qDBZaj1x3irmgHz1wzeM2PtHhSvP58wqCm6pr + 65tb2/Ye6Pyuq7vnaCRyTMcGC0QiR3u6u77rPLC3rbW5vrZ6U7Agz+9Lsy7oRw/ctevM + zyrmembmBkoqqmobWnbt6TjU1RM50ftDX/+pAR0bLHCqv++H3hORnq5DHXt2tTTUVlWU + BHIzzQU1P7N8+AK1Hrfm7enz5xeVh8L1LW37Og8fOd7bN3DmbPTcoI4tFjgXPXtmoK/3 + +JHDnfvaWurDofKifL/PeoOaB+5ff0W04pm6PiM3ULqpemuz4eyO9Pafjg4OXbg4fEnH + FgsMX7wwNBg93d8b6TagzVurN5UGcjPWp67qGZ/kdHuz8grLQ1saWvd0dh87ORAdvDA8 + cnn06piOLRa4Onp5ZPjCYHTg5LHuzj2tDVtC5YV5WV63Myn+o/sZG5+UYj1uiyuq65ra + Ow5HTv4YHRr+ZXTs+o2bv+rYYoGbN66Pjf4yPBT98WTkcEd7U111RbH1wE1JMh9EHzxv + YxOSXWkZOYHSyvBX2/ceOvL9QHTo0pWx8Ylbk7dv39GxwQK3b0/emhgfu3JpKDrw/ZFD + e7d/Fa4sDeRkpLmSE1bxdLjM67OgLFTTuPNA1/E+wzl67eatqbv3ph/M6NhggQfT9+5O + 3bp5bdSA9h3vOrCzsSZUVmBeoC7HKp7m89ab9VnRxirzuO3s6T09+POVaxOTd+7PzD6c + e6RjgwXmHs7O3L8zOXHtys+Dp3t7Os0Dt2pj0WdZXvOB+9H9ND+upHqt1+fmbS27v430 + Rc+PjN2cvDv9+9zj+SdPdWywwJP5x3O/T9+dvDk2cj7aF/l2d8u2zdYL1Gt94H74/jSe + buNZUhmu37Gv68TA4PDo+K0707OPnjxdWFzSscECiwtPnzyanb5za3x0eHDgRNe+HfXh + yhLj6V7V0+lO928wn0MNrfu7e8/8NDI2MXXfcC4sPVvWscUCz5YWDOj9qYmxkZ/O9Hbv + b20wH0Qb/Olu52r30+lJzw4EP69p3NXRc/Ls+cvXf7s7Mze/sLT8/MVLHRss8OL58tLC + /NzM3d+uXz5/9mRPx67Gms+Dgex0zyc8fTmBYKi2qe3g0b7oxdHxyXuzj/9YXH7+8pWO + LRZ4+Xx58Y/Hs/cmx0cvRvuOHmxrqg0FAzm+T3uaH1eM5zeR/nPDV29MTT+cX3hmOF+/ + 0bHBAq9fvXz+bGH+4fTUjavD5/oj31ieZQV/69neGTk1eGls4vaDuSeLyy8M51sdGyzw + 5vWrF8uLT+Ye3J4YuzR4KmJ+YPmUp/nrskSnx5ezcj9X8fyXzj++wFvs+Zf/x8namDjz + 61vz66HyL+qav+48NmDu5693Zh49XVp++erN23/8z6ICZoG3b169XF56+mjmzq/mfg4c + 6/y6ue6LcvMLIvML3LgYebL9SyJPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M + 95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonh + vvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHc + V554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7 + yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBf + eeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4r + T7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33l + ifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK88 + 8T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un + 3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE + +7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554 + H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPv + w5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ9 + 2FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wP + WypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdh + S+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5s + qTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3oct + lSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl + 8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZU + nmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bK + k00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M + 95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonh + vvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHc + V554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7 + yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBf + eeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4r + T7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33l + ifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK88 + 8T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un + 3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE + +7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554 + H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPv + w5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ9 + 2FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wP + WypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdh + S+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5s + qTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3oct + lSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl + 8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZU + nmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bK + k00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5 + sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypP + NjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJ + Job7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZ + xHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSeb + GO4rT7wPWypPNjHcV554H7ZUnmxiuK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQT + w33lifdhS+XJJob7yhPvw5bKk00M95Un3octlSebGO4rT7wPWypPNjHcV554H7ZUnmxi + uK888T5sqTzZxHBfeeJ92FJ5sonhvvLE+7Cl8mQTw33lifdhS/8bz3VxiU6PL6egLFTb + 1N4ZOTV4aWzi9oO5J4vLL169fvOW7Y/+f7Hv2zevX71YXnwy9+D2xNilwVORzvam2lBZ + QY7P40yMW7d2zZ/P33i+1fnnF8Cef9Zcs+bPnm3fRPrPDV+9MTX9cH7h2fOX5oLq2GCB + 169ePn+2MP9weurG1eFz/ZFv2v58P1f1DATN87bt4NG+6MXR8cl7s4//WFw2oDq2WODl + 8+XFPx7P3pscH70Y7Tt60PIMBt4/b1fxTM8OBD+vadzV0XPy7PnL13+7OzM3v7C0/PzF + Sx0bLPDi+fLSwvzczN3frl8+f/ZkT8euxprPg4Hs9JX358ee7nT/htLKcEPr/u7eMz+N + jE1M3Z999GRh6dmyji0WeLa08OTR7P2pibGRn870du9vbQhXlm7wp7ut76GPPB1urz+/ + pDJcv2Nf14mBweHR8Vt3pg3o04XFJR0bLLC48NRwTt+5NT46PDhwomvfjvpwZUm+3+t2 + rOqZajyLKzZva9n9baQven5k7Obk3enf5x7PP3mqY4MFnsw/nvt9+u7kzbGR89G+yLe7 + W7Ztrig2nqmreMYmOlzerM+KNlbVmR9Ae3pPD/585drE5J37M7MP5x7p2GCBuYezM/fv + TE5cu/Lz4OneHvPjZ13VxqLPsrwuR2Lsh8/b2ASHa31GrvmFQk3jzgNdx/uiQ5dGr928 + NXX33vSDGR0bLPBg+t7dqVs3r41eGor2He86sLOxxvw6ITdjvcuRsIpnsistIydgPoi+ + 2r730JHvBwzolbHxiVuTt2/f0bHBArdvT96aGB+7YjgHvj9yaO/2r8znUCAnI82VvIpn + fFKKx2e9QKvNA7fjcOTkj9Gh4V9Gx67fuPmrji0WuHnj+tjoL8ND0R9PRg53mMdttfX6 + 9HlSkuI/up8x8UlOtzcrr7A8tKWhdU9n97GTA9HBC8Mjl0evjunYYoGro5dHhi8MRgdO + Huvu3NPasCVUXpiX5XU7k+JjPnx/xsQlOlLNCzRQuql6a3Pbvs7uSG//6ejg0IWLw5d0 + bLHA8MULQ4PR0/29ke7OfW3NW6s3lQbM69P6vF3V02U9cIvKQ+H6FgN6+Mjx3r6BM2ej + 5wZ1bLHAuejZMwN9vcePHDacLfXhUHmR9bg1n7cfea5dF5eQlOL2ZuYGSiqqahtadu3p + ONTVEznR+0Nf/6kBHRsscKq/74feE5GerkMde3a1NNRWVZQEcjO97pSkhA//umzN2nWx + 8eYn0DSfP68guKm6tr65tW3vgc7vurp7jkYix3RssEAkcrSnu+u7zgN721qb62urNwUL + 8vy+NHM9zefQX//603iaF2iyuaAZ2XmFwcqq8NaGpu0723fv299xsFPHJgsc7Ni/b3f7 + zu1NDVvDVZXBwrzsDHM9k63H7Sqe1gX1GND8wmBFqHpLXX1jc8uO1l1t7V/r2GKB9rZd + rTtamhvr67ZUhyqChfmG03p7xn/saT1wzQV1GtDM7LyCkvJNoepwTd22+obGpqamZh0b + LGAgGhvqt9XVhKtDm8pLCvKyMw2n01zPjx63a1YeuPHmiZtq3dC8QFFpeUVlqGrzl+Ga + WnPqdP7xBSyHmvCXm6tClRXlpUUB62HrSTVP29Wup/E0FzQh0bEC6s/NDxQWB8s2VlRW + hkKhL3RssYChqKys2FgWLC4M5Of6VzgdiQnmen74+jR/GWq+iAxokiPF5Vnvy/Tn5uUH + CoqKS0qDwbKych0bLFBWFgyWlhQXFQTy83L9mb71HleKw/ysEvvR15D1d9vmgsbExZsb + 6nS507y+DH92jjHN3xAo0LHNAoEN+cYyJ9uf4fOmuV1Oczutp+0q1/M9qHnkJpsr6k5b + b0gzs/xGNSdXxyYL5BhJf1amwVxvNFMcyeZh+ynONWtXbmhcfOKKaKrHY0y96ek+X4aO + TRbw+dLTvcbS40ld0TSfQiucH/zw+f7/SrQCGhtnrqgRdThTXK5Ut9ujY6sF3O5UlyvF + 6TB307qc5t25bu3qnOaJa26o9VVkvUYTk5INqsPpdKbo2GYBw2FQkpOTDKa5m5bmpzmt + j6J3oobUmBrUlZOkY5MF3oMkWJZxsX+rufKZa4mui4mJibVQdWy5gKGMsa4mvJvv36LW + JV0xtf55c8z/Usc2C7wzWflPw/S/ZP/JfzH/vI5NF/hP/PTPaAEtoAW0gBbQAlpAC2gB + /gX+B05tLvoKZW5kc3RyZWFtCmVuZG9iagoxNyAwIG9iago2NTUwCmVuZG9iagoxOCAw + IG9iago8PCAvTGVuZ3RoIDE5IDAgUiAvVHlwZSAvWE9iamVjdCAvU3VidHlwZSAvSW1h + Z2UgL1dpZHRoIDE4NCAvSGVpZ2h0IDEwMCAvQ29sb3JTcGFjZQovRGV2aWNlR3JheSAv + SW50ZXJwb2xhdGUgdHJ1ZSAvQml0c1BlckNvbXBvbmVudCA4IC9GaWx0ZXIgL0ZsYXRl + RGVjb2RlID4+CnN0cmVhbQp4Ae2b+VeS6RvGrdxARBAERRQFXAAVUQrFUgwzUcxdcVwG + Qx1pMKqRkaPlkilFrpnjMu7jMuo4Wk46TXXmX/vezwuVC1Jzjt/HfuD6Jc/hxPvx6n5f + 6Lmvy8vLI48DHgc8Dvy/HbjwDeg//Y7Ae/GzLp2LPl//IuB8Bb6DGVi9vX3OXd7eAIJ+ + hS+hE9QOZF8/P3+HSNjlvLCfny9YB/BfIHdS+/j4AjKJTA4ICKBQKIHnILgsXJxMJvn7 + I3b35Aj7EkwHQAMyJZBKDaLR6OckGi2ISg0EejKgO8hPGRYCG7xG1IHUIDo9mMFkhoSw + WGzsYrFCQphMRjCdHkQNROTgOQyLa3DkNjIbUdOAmcUODeNwwrncCOzicsM5nLBQNgvY + aQQ5WI7AXTxYCGwY7AAKUAM0EEfwoqKi+YJzED86KooXAfSADuSUADTmrsEvoNn2I4HZ + dAYrlAPMfEFMbFy8SCQWS7BKLBaJ4uNiYwR8YOeEshh0sJzkh+7Ok4aD3YDtHxAYRGey + ORFRfGGsSJyQKJXKZLIUzIJLSqWJCWJRrJAfFcFhM+lBgeC4j7eLSQG74ZYkE9jhPH5M + vCRRKku9fEWRrgRlYBS6XrriyuVUmTRREh/D54UT4GS4OV0YfgHs9idTqHRmaDhPECdJ + kskV6RnXslTZarU6B6vggtmqrGsZ6Qq5LEkSJ+CFhzLpVArZHww/PigOuwMAmx0eJRQl + yuRpGVnZObl5mgJt4S3MKtQWaPJyc7KzMtLkskSRMAo5Tg1wZTjihimhATZPKJKmKq6q + 1DfzC4tKyyoqddhVWVFWWlSYf1OtuqpIlYqEaFRogWD4iUGBMfH1D6AGszg8gShJrszK + 0WhLynU1dfX62wZDI1YZDLf19XU1uvISrSYnSylPEgl4HFYwMvzEoFy4CM9AsDs0gh+X + mKpU5RYUV1TX6Q3Nxh9NrXfNWHW31fSjsdmgr6uuKC7IVSlTE+P4EaFgODwLjw84GhOY + bhYnKkYiU2Tlakt1tQ1NRpP5QZul3YpZ7Za2B2aTsamhVleqzc1SyCQxURwWmnAYlKMf + mQR3EIMdwY9Pkl/NAex6g7H1vsXa+airpxezeroedVot91uNhnoAz7kqT4rnR7AZQS65 + fUkUGjOMJ5TI0lSaYl194x2zxfqop6/f9syOWc9s/X09j6wW853Gel2xRpUmkwh5YUwa + heR7wm9vX1IgGpPYRHmGurCi1nDnnqWz54nNPjQy+gKzRkeG7LYnPZ2We3cMtRWF6gx5 + YiwalEAS3JjH5sTbj0wNZnP58VJF5s2S6oYWs6Wzd8A+PPZyYmpqGqumpiZejg3bB3o7 + LeaWhuqSm5kKaTyfyw6mkv1ccAdQYbwFYll6dn55XZMJsG2Doy8nZ2bnFxaxamF+dmby + 5eigDcBNTXXl+dnpMrEABpwa4IIbHifMsMiYhFQYE53eeN/aPTA4NjE9t7i8srqGVasr + y4tz0xNjgwPd1vtGvQ4GJTUhJjKMCQ+UE37DYzCIicb78rXcou8MJsvDPvvoxMz80ur6 + xuYWVm1urK8uzc9MjNr7HlpMhu+Kcq9dRgPORA+U4/MN3DTgjpMqsvJK65rN1h7b8Mvp + +eW1za3tnV2s2tne2lxbnp9+OWzrsZqb60rzshTSOOCmueSm0EI40XBbqjRl9cYHHX32 + sck5wN7efbWHWa92twF8bnLM3tfxwFhfplHBjRnNCaFRXPlNoYeE80XJ6dkFFfo7bQ/7 + h8ZnFlc3tnf33uwfYNX+m73d7Y3VxZnxof6HbXf0FQXZ6ckifngI/RRuFpcvkinV2srb + JkuXbXhidnn9j529NwdvMevgzd7OH+vLsxPDti6L6XalVq2Uifhc1unc8BgE7ipDa3vP + s5HJ+ZWN7VeA/e49Vr17e/Dm1fbGyvzkyLOe9lZDFeIWC77IXagz3LX22semFlY3d/b2 + AfsDVr1/93Z/b2dzdWFqzN5rvWuAB+Fp3PA11p9CZ3EJv11w/4tRH9xzH/mf2oVLPvD1 + BD4uJSkZObd0jWbw+8X04trW7t7B2/cfMFLDpT68f3uwt7u1tjj9Avw2N+pu5WSkSOAD + E76g+FzycJ/1v4bH77N21P37efx2789Zv+rx+6wddf9+Hr/d+3PWr3r8PmtH3b+fx2/3 + /pz1qx6/z9pR9+/n8du9P2f9qsfvs3bU/ft5/Hbvz1m/+h/89vrC+cm3eu5zOvfr/b// + wXrKBhf75+/91193XnWEmzgf7H76LZwPPu3+uvNBdB57XVvZ8Ok8duu8zmO3Pp3HNlRq + r7s/jz16/j04PrMAB7K7r//ax6y/XsP598rCzPjgV51/H9o3tDzoeGwfnZxdWtvY3sG/ + b9jZ3lhbmp0ctT/ueNDypX2DY7+TdCUrr6S22dzebRsah/3O6sbW9p87WPXn9tbGKux3 + xods3e3m5tqSvKwrSafvd5z7NLljn9YG+7QRtE9bWf99E7N+X19B+7QR2Ke1OfZpxMLY + 5T7NG/aXjFDH/lJbpTfes3b1Px+dmJpdWPptZRWrVn5bWpidmhh93t9lvWfUw7qB2F+G + wt715P7S2+/zvliD9sVtHb0Dz0fGf5n+dW5+Aavm536d/mV85PlAb0cb2hdr3O6LYT9P + d+7nc4ur9cR+vt8+NDo+MTmFWZMT46ND9n5iP6+vLs517ufpLvfzKA8R4sxDaCEPYYRg + QXefzT44PDKGWSPDg3ZbXzfECoyQh4AxIcY7xGUe4pIjfxIpFEP+JK+4CmIz5jZrZ/fj + JwNPMQdQnj0dePK4u9PaBtj1VcV5kD8RC2E97zJ/gnJKH/M+GeoClPdpMd1ra+942NWN + OfDT0931sKO97Z6pBeV9CsBuN3kf+EJI5Kt4znxVSVWNvrHFZL7/k+VnzAGr9p8tP903 + m1oa9TVVJc58FQTaiHzVxWO5AiLPBkEllGdLSFGqbuQXletq9YamH1CgrfUuRrWiONsP + TQZ9ra68KP+GSpmS4MizUVzk2Zz5QUgqRQogGZaeqc7TFpVVVtfUf48ChHh1W/99fU11 + ZVmRNk+dmQ5TIoh02O0qP4jymhQagw3Bx/ikFEWGSp2r0RaVlJZXVFbhDWxWVVaUl5YU + aTW5alWGIgWweRw2g4YCsifyml5EHNmRjwXwBEj1KjNV6hs3NfkFWm0hVmm1BfmamzfU + qkwlJHsTAPtQPvZoLMzLC+WRIbVOBHshjyxOlKVeSVNey1Spsq9DQBirrmerVJnXlGlX + UmWJYpRHJmK9KLl+PK6JuIn8NwpSszmR0cI4cYJUliK/rFCkEQlwlMrGpfQ0heKyPEUm + TRDHCaMjUXAdxahPyX878vYUR96eFy2MjRdJEpKkyckQf8es5GRpUoJEFB8rjIamAIqt + o4aDy7w9MpwoCoDjqN/AjYyKFghjiYIDNBxwSkTUG2KFguioSK6j3+DAPnlXwrR/qsFA + n4QOfZIwDjcikiiUYG+U8Ik6SWQElxMGfRI69EnIqHvkuk/yCZyEmjB0BjOE7SjwQIMH + t8Id9R12CJOBqANIbrC9nDUvoi9FgYoXnc5wFqZY2EXUpRh0OpS9KI6+FKqoue5LfQRH + TS+So592fgU1op5G9NOgWuds1p2CDSMOM04064g+IAn1AYlGILTzcIu4NJn0VX1AdHMS + 5KgU6OP7uYDprEPi/gPql0T/kqiOnmq28wPUWdJFfddzL7wCwse665FU1fHP+s/oyPbD + wtkxPnxd+BmM/Brow78L+ivnqcMsnp89Dngc8DjgceCoA/8DzflMvgplbmRzdHJlYW0K + ZW5kb2JqCjE5IDAgb2JqCjI4MjgKZW5kb2JqCjIwIDAgb2JqCjw8IC9MZW5ndGggMjEg + MCBSIC9OIDMgL0FsdGVybmF0ZSAvRGV2aWNlUkdCIC9GaWx0ZXIgL0ZsYXRlRGVjb2Rl + ID4+CnN0cmVhbQp4AYVUz2sTQRT+Nm6p0CIIWmsOsniQIklZq2hF1Db9EWJrDNsftkWQ + ZDNJ1m426+4mtaWI5OLRKt5F7aEH/4AeevBkL0qFWkUo3qsoYqEXLfHNbky2perAzn7z + 3jfvfW923wANctI09YAE5A3HUqIRaWx8Qmr8iACOoglBNCVV2+xOJAZBg3P5e+fYeg+B + W1bDe/t3snetmtK2mgeE/UDgR5rZKrDvF3EKWRICiDzfoSnHdAjf49jy7I85Tnl4wbUP + Kz3EWSJ8QDUtzn9NuFPNJdNAg0g4lPVxUj6c14uU1x0HaW5mxsgQvU+QprvM7qtioZxO + 9g6QvZ30fk6z3j7CIcILGa0/RriNnvWM1T/iYeGk5sSGPRwYNfT4YBW3Gqn4NcIUXxBN + J6JUcdkuDfGYrv1W8kqCcJA4ymRhgHNaSE/XTG74uocFfSbXE6/id1ZR4XmPE2fe1N3v + RdoCrzAOHQwaDJoNSFAQRQRhmLBQQIY8GjE0snI/I6sGG5N7MnUkart0YkSxQXs23D23 + UaTdPP4oInGUQ7UIkvxB/iqvyU/lefnLXLDYVveUrZuauvLgO8XlmbkaHtfTyONzTV58 + ldR2k1dHlqx5erya7Bo/7FeXMeaCNY/Ec7D78S1flcyXKYwUxeNV8+pLhHVaMTffn2x/ + Oz3iLs8utdZzrYmLN1abl2f9akj77qq8k+ZV+U9e9fH8Z83EY+IpMSZ2iuchiZfFLvGS + 2EurC+JgbccInZWGKdJtkfok1WBgmrz1L10/W3i9Rn8M9VGUGczSVIn3f8IqZDSduQ5v + +o/bx/wX5PeK558oAi9s4MiZum1Tce8QoWWlbnOuAhe/0X3wtm5ro344/ARYPKsWrVI1 + nyC8ARx2h3oe6CmY05aWzTlShyyfk7rpymJSzFDbQ1JS1yXXZUsWs5lVYul22JnTHW4c + oTlC98SnSmWT+q/xEbD9sFL5+axS2X5OGtaBl/pvwLz9RQplbmRzdHJlYW0KZW5kb2Jq + CjIxIDAgb2JqCjczNwplbmRvYmoKOCAwIG9iagpbIC9JQ0NCYXNlZCAyMCAwIFIgXQpl + bmRvYmoKMjIgMCBvYmoKPDwgL0xlbmd0aCAyMyAwIFIgL04gMSAvQWx0ZXJuYXRlIC9E + ZXZpY2VHcmF5IC9GaWx0ZXIgL0ZsYXRlRGVjb2RlID4+CnN0cmVhbQp4AYVST0gUURz+ + zTYShIhBhXiIdwoJlSmsrKDadnVZlW1bldKiGGffuqOzM9Ob2TXFkwRdojx1D6JjdOzQ + oZuXosCsS9cgqSAIPHXo+83s6iiEb3k73/v9/X7fe0RtnabvOylBVHNDlSulp25OTYuD + HylFHdROWKYV+OlicYyx67mSv7vX1mfS2LLex7V2+/Y9tZVlYCHqLba3EPohkWYAH5mf + KGWAs8Adlq/YPgE8WA6sGvAjogMPmrkw09GcdKWyLZFT5qIoKq9iO0mu+/m5xr6LtYmD + /lyPZtaOvbPqqtFM1LT3RKG8D65EGc9fVPZsNRSnDeOcSEMaKfKu1d8rTMcRkSsQSgZS + NWS5n2pOnXXgdRi7XbqT4/j2EKU+yWCoibXpspkdhX0AdirL7BDwBejxsmIP54F7Yf9b + UcOTwCdhP2SHedatH/YXrlPge4Q9NeDOFK7F8dqKH14tAUP3VCNojHNNxNPXOXOkiO8x + 1BmY90Y5pgsxd5aqEzeAO2EfWapmCrFd+67qJe57AnfT4zvRmzkLXKAcSXKxFdkU0DwJ + WBR9i7BJDjw+zh5V4HeomMAcuYnczSj3HtURG2ejUoFWeo1Xxk/jufHF+GVsGM+Afqx2 + 13t8/+njFXXXtj48+Y163DmuvZ0bVWFWcWUL3f/HMoSP2Sc5psHToVlYa9h25A+azEyw + DCjEfwU+l/qSE1Xc1e7tuEUSzFA+LGwluktUbinU6j2DSqwcK9gAdnCSxCxaHLhTa7o5 + eHfYInpt+U1XsuuG/vr2evva8h5tyqgpKBPNs0RmlLFbo+TdeNv9ZpERnzg6vue9ilrJ + /klFED+FOVoq8hRV9FZQ1sRvZw5+G7Z+XD+l5/VB/TwJPa2f0a/ooxG+DHRJz8JzUR+j + SfCwaSHiEqCKgzPUTlRjjQPiKfHytFtkkf0PQBn9ZgplbmRzdHJlYW0KZW5kb2JqCjIz + IDAgb2JqCjcwNAplbmRvYmoKMTMgMCBvYmoKWyAvSUNDQmFzZWQgMjIgMCBSIF0KZW5k + b2JqCjI0IDAgb2JqCjw8IC9MZW5ndGggMjUgMCBSIC9OIDMgL0FsdGVybmF0ZSAvRGV2 + aWNlUkdCIC9GaWx0ZXIgL0ZsYXRlRGVjb2RlID4+CnN0cmVhbQp4AdWWd1gTSR/HZ3fT + Cy0QWoDQe+8gvQYQkCqISkgooYQQioDYkMMTPAsqImABPRBR8CyAnAURxcIhYK8X5BBQ + z8OCqKi5Dbx4/vHef+8/7+yzM5/9zm9/Mzsz+zxfACg9bIEgHZYBIIOfIwzz82Qujoll + 4h8AHGAAMpAFMmxOtsAjNDQI/Gt5fwdAks6bppJc/xr23ztkuYnZHACgULQ7gZvNyUD5 + JMpfOQJhDgCwhAdW5AhQRkpQlheiE0S5SsLJc3xEwglz3DUbExHmhcbcAoBAYbOFyQCQ + RajOzOMko3koKAILPpfHR9kCZVdOCpuLsgBlk4yMTAnXomyQ8F2e5O+YzU74lpPNTv7G + c9+CvokO7M3LFqSzC2Yf/pdVRnouul6zRQ6tKfz04CC0paP3OJftHTjPgvTZPZvVE/mR + 4fM6PyE4ZJ6ThL5h8yzI8fyOQyPm9cIUr+B5Tsz2+ZYnlR0g2bPZ/MLcsMh5zs4L95nn + wpSI6HnmJnp/05N4vqx5nZfD+jZWWmbgtzkAb+ADgtCLCayAxezlC9ARcxLz0T0EwCtT + UCDkJafkMD3QU5dowmTxOWYmTCsLS8mW/v8Uyf82N9u3N2b/I0hJcpT/o+UvAcBdGT3L + 0/9oUej53zsEgOKtfzQDTQA0FQBoT+DkCvPm8mEkDRaQgDSQB8pAHWgDA2CKrqYdcAbu + 6OoGgBAQAWLAMsABKSADCMEKUATWgVJQDraCnaAa7AMHwCFwFBwH7eAMuAAug+tgANwG + D4EIjIIXYBK8BzMQBOEhKkSDlCENSBcyhqwgB8gV8oGCoDAoBoqHkiE+lAsVQeuhcqgC + qobqoCboF+g0dAG6Cg1C96FhaAJ6A32CEZgCy8NqsB5sDjvAHnAgHAEvhZPhLLgQLoE3 + w1VwPXwEboMvwNfh27AIfgFPIQAhI3REEzFFHBAvJASJRZIQIbIaKUMqkXqkBelEepGb + iAh5iXzE4DA0DBNjinHG+GMiMRxMFmY1ZhOmGnMI04bpwdzEDGMmMV+xVCwDa4x1wrKw + i7HJ2BXYUmwltgF7CnsJexs7in2Pw+HoOH2cPc4fF4NLxa3EbcLtwbXiunCDuBHcFB6P + V8Yb413wIXg2Pgdfit+NP4I/jx/Cj+I/EMgEDYIVwZcQS+ATigmVhMOEc4QhwhhhhihD + 1CU6EUOIXGIBcQvxILGTeIM4SpwhyZL0SS6kCFIqaR2pitRCukR6RHpLJpO1yI7kRWQe + eS25inyMfIU8TP5IkaMYUbwocZRcymZKI6WLcp/ylkql6lHdqbHUHOpmahP1IvUJ9YMU + TcpMiiXFlVojVSPVJjUk9UqaKK0r7SG9TLpQulL6hPQN6ZcyRBk9GS8ZtsxqmRqZ0zJ3 + ZaZkabKWsiGyGbKbZA/LXpUdl8PL6cn5yHHlSuQOyF2UG6EhNG2aF41DW087SLtEG5XH + yevLs+RT5cvlj8r3y08qyCnYKEQp5CvUKJxVENERuh6dRU+nb6Efp9+hf1JUU/RQTFTc + qNiiOKQ4raSq5K6UqFSm1Kp0W+mTMlPZRzlNeZtyu/JjFYyKkcoilRUqe1UuqbxUlVd1 + VuWolqkeV33AgBlGjDDGSsYBRh9jSk1dzU9NoLZb7aLaS3W6urt6qvoO9XPqExo0DVcN + nsYOjfMaz5kKTA9mOrOK2cOc1GRo+mvmatZp9mvOaOlrRWoVa7VqPdYmaTtoJ2nv0O7W + ntTR0FmoU6TTrPNAl6jroJuiu0u3V3daT18vWm+DXrveuL6SPku/UL9Z/5EB1cDNIMug + 3uCWIc7QwTDNcI/hgBFsZGuUYlRjdMMYNrYz5hnvMR40wZo4mvBN6k3umlJMPUzzTJtN + h83oZkFmxWbtZq/MdcxjzbeZ95p/tbC1SLc4aPHQUs4ywLLYstPyjZWRFceqxuqWNdXa + 13qNdYf1axtjm0SbvTb3bGm2C2032HbbfrGztxPatdhN2OvYx9vX2t91kHcIddjkcMUR + 6+jpuMbxjONHJzunHKfjTn85mzqnOR92Hl+gvyBxwcEFIy5aLmyXOheRK9M13nW/q8hN + 043tVu/21F3bneve4D7mYeiR6nHE45WnhafQ85TntJeT1yqvLm/E28+7zLvfR84n0qfa + 54mvlm+yb7PvpJ+t30q/Ln+sf6D/Nv+7LDUWh9XEmgywD1gV0BNICQwPrA58GmQUJAzq + XAgvDFi4feGjYN1gfnB7CAhhhWwPeRyqH5oV+usi3KLQRTWLnoVZhhWF9YbTwpeHHw5/ + H+EZsSXiYaRBZG5kd5R0VFxUU9R0tHd0RbRosfniVYuvx6jE8GI6YvGxUbENsVNLfJbs + XDIaZxtXGndnqf7S/KVXl6ksS192drn0cvbyE/HY+Oj4w/Gf2SHsevZUAiuhNmGS48XZ + xXnBdefu4E4kuiRWJI4luSRVJI0nuyRvT55IcUupTHnJ8+JV816n+qfuS51OC0lrTBOn + R6e3ZhAy4jNO8+X4afyeTPXM/MxBgbGgVCDKcsramTUpDBQ2ZEPZS7M7cuRRY9OXa5D7 + Q+5wnmteTd6HFVErTuTL5vPz+wqMCjYWjBX6Fv68ErOSs7K7SLNoXdHwKo9Vdauh1Qmr + u9dorylZM7rWb+2hdaR1aet+K7Yorih+tz56fWeJWsnakpEf/H5oLpUqFZbe3eC8Yd+P + mB95P/ZvtN64e+PXMm7ZtXKL8sryz5s4m679ZPlT1U/izUmb+7fYbdm7FbeVv/XONrdt + hypkKworRrYv3N62g7mjbMe7nct3Xq20qdy3i7Qrd5eoKqiqY7fO7q27P1enVN+u8axp + rWXUbqyd3sPdM7TXfW/LPrV95fs+7eftv1fnV9dWr1dfeQB3IO/As4NRB3t/dvi5qUGl + obzhSyO/UXQo7FBPk31T02HG4S3NcHNu88SRuCMDR72PdrSYttS10lvLj4Fjucee/xL/ + y53jgce7TzicaDmpe7L2FO1UWRvUVtA22Z7SLuqI6Rg8HXC6u9O589SvZr82ntE8U3NW + 4eyWc6RzJefE5wvPT3UJul5eSL4w0r28++HFxRdv9Szq6b8UeOnKZd/LF3s9es9fcbly + 5qrT1dPXHK61X7e73tZn23fqN9vfTvXb9bfdsL/RMeA40Dm4YPDckNvQhZveNy/fYt26 + fjv49uCdyDv37sbdFd3j3hu/n37/9YO8BzMP1z7CPip7LPO48gnjSf3vhr+3iuxEZ4e9 + h/uehj99OMIZefFH9h+fR0ueUZ9VjmmMNY1bjZ+Z8J0YeL7k+egLwYuZl6V/yv5Z+8rg + 1cm/3P/qm1w8Ofpa+Fr8ZtNb5beN72zedU+FTj15n/F+Zrrsg/KHQx8dPvZ+iv40NrPi + M/5z1RfDL51fA78+EmeIxQK2kD3rBRC0hpOSAHjTCAA1BgDaAACkrjk/PBuBOvhh/3n6 + N57zzLNRdgDUuQMgsXdBXQDsQls99JmBthJbiFo6eO0/N6pISnaStdUsQBQV1Jp0icVv + xADg4wH40i8Wz1SJxV8qUa/zDoDzwXM+XBItg/r7/YiFjW9QZ6bb7OvfV38DJafpNwpl + bmRzdHJlYW0KZW5kb2JqCjI1IDAgb2JqCjI2NjMKZW5kb2JqCjE1IDAgb2JqClsgL0lD + Q0Jhc2VkIDI0IDAgUiBdCmVuZG9iago0IDAgb2JqCjw8IC9UeXBlIC9QYWdlcyAvTWVk + aWFCb3ggWzAgMCA2MTIgNzkyXSAvQ291bnQgMSAvS2lkcyBbIDMgMCBSIF0gPj4KZW5k + b2JqCjI2IDAgb2JqCjw8IC9UeXBlIC9DYXRhbG9nIC9PdXRsaW5lcyAyIDAgUiAvUGFn + ZXMgNCAwIFIgL1ZlcnNpb24gLzEuNCA+PgplbmRvYmoKMiAwIG9iago8PCAvTGFzdCAy + NyAwIFIgL0ZpcnN0IDI4IDAgUiA+PgplbmRvYmoKMjggMCBvYmoKPDwgL1BhcmVudCAy + OSAwIFIgL0NvdW50IDAgL0Rlc3QgWyAzIDAgUiAvWFlaIDAgNzgyLjg5IDAgXSAvVGl0 + bGUgKENhbnZhcyAxKQo+PgplbmRvYmoKMjkgMCBvYmoKPDwgPj4KZW5kb2JqCjI3IDAg + b2JqCjw8IC9QYXJlbnQgMjkgMCBSIC9Db3VudCAwIC9EZXN0IFsgMyAwIFIgL1hZWiAw + IDc4Mi44OSAwIF0gL1RpdGxlIChDYW52YXMgMSkKPj4KZW5kb2JqCjMwIDAgb2JqCjw8 + IC9MZW5ndGggMzEgMCBSIC9MZW5ndGgxIDkxNDQgL0ZpbHRlciAvRmxhdGVEZWNvZGUg + Pj4Kc3RyZWFtCngBvVp5eFRFtj91917S6e70vqS701s6+0ICbULShE5IgIRAEBMkmAQS + EiQaMcbBESYqjBIVRQSi+DkuGAKM0oQIDQw8hg9F33PGZRSXcRZHdHzzzOe8eTijI+l+ + 594OEfKNfvzhN31TVedU1a069Tunzql7b3rX3tYOSdAPNNQvbe3pAOmX1gtAwiu6W3sS + vPYClnNX9PU6EzybDkCv6ehZ1Z3ghUcB5PZVa9ZN3J+yEkA13NneiqX0u4h5cSdWJFgy + DUtPZ3fvjxK8dhTL0JqbV0y0p4SQT+tu/dHE/PAh8s6bWrvbscRfWj1mnp6bb+2VWEhT + YhnuWds+0Z80onyvA8FaNdwMMrgReKCQVkMzAP+Z3A4Mtort+FuZpdh2Q3Lpl6ARJP6G + 2oek8mXXL8591X7Rr9gqfI0Vskv9xZILxAIASoLtY4qtky3SfZipo9CQGYUaTOWYijBl + Zs4yQT8ZgocxPYWJhi5yP6zDtBnTY5iYSWovckfJ/SOMEDpG1oGFzA0pGMdindlhkisc + b0UJN/qk433Tx8eJGbX3ETGPJIFslpw8RX4GK8FBngMvuQOqIZ08fiiwxtGCTXuhB1M/ + JlrKCdk7klrgOEmywMsQvMcHqQw57Phzfrbjk/woRUYcp/1RBotfpiIXSnacsj/p+A/7 + KsdJTPsTTfsC2OOwY699jWNbapQ8PuJ4xB4leM/WRHGbHW897OgO7HCszJfa5++IUvtH + HEFsXxJSOIpnuBxF9vOOXH9UIMhn2+c7MvJ/5fDgjdjNiYN6QxqHzb7NcQ02pdor/ddg + Ok72kV2QQXaNeOc6jiGJyz1UE5ixI0p+fKg6Pd8bJXeEiqvTdwSq/d7AfIc3UOX3I73k + FX4jfz0/iy/gM/l03se7eCuvE7SCWlAJSkEuCAIfJT8fKXdwx8l+KEdY9h8SOIGNkhew + kjlOnpcqnz8iMAIlgKCLxv+IxktAFyX7R9UihcRhTqK4KHn+UKLq+ZCDESlGalBTIo0Z + 5kARgYK5ECEPRjnYZOgrN5VryzTBqvB3ZS1Sy6U887t/JmKP7JjX0BjZZ2+KFIhE3N50 + qbvpEvGdZe9t2NRekZk5b9G6Q309qzsq292VLe7Kdkwtkfv7Ok2R/jan8+DqHrHBGaF9 + LW0rOsWytT3S424PR1a7w86DfdJ9U5o7xOY+d/ggdFQubjzYEWoPj/SF+irdreGmQ20V + a5uvmGvz5FxrK/7FXBXiYGvFudqk+6bM1Sw2t4lzNYtzNYtztYXapLnExVd2NVTc2ovW + 6azsmueMpDdEahYubYw4W5vCUTKEleHbgD0FavYEpLP9YGFywQEQfx/TB2IZuzb+KXsW + 1LHu+P/SJajUo2KiYuWlcAoehF1wADgYRjodlsMgvEpW495eBqNwjqRCDvpeBqIwH14j + 8fib0AG7sX8vnIbtcBCUeE836LF1C/HG70A+hHQbbIw/Ax6YAT+FExDEUbfAWHxv/BC2 + LoJrYR/sx/v/i7ipg0xK/IX4eRBgIY65EVvejM+PHwAtZEEF1GPtRjhJvPQH8U4wQQlK + 9wT8DJ6GX8Ln5G4yGu+M98XfiH+EpmoCGzTgtZ6Mko/oA8xP40/E/xKPIRLpkIGztsA2 + eBbHP4DXKXStleRG0ku2ke1UiLqbGmU2scbYOOIQgDl4VaNXvg8ROApn4G/wNfmCMtFq + upd+KV4U/z9QwDxcpbiSdujD6168tuCajhOO5JHZpJ6sJ4+S7eQ3VAZ1LdVI3U79iPqU + rqOX0evo3zC3MiPsA+wgp4h9GT8ePxt/B4xgh+thLWzA1Z2GN+AC/JPQOJaNeEkJqSDL + 8eonu6ij5GlylKonp8gb1D7yB/Ix+YJ8Q7GUktJTmVQvtY3aT52mfk130dvpx+g/0F8y + ZSzFPs1+wnn538baYptjv46XxD+Kf4UuVgAXaqYC6uAGaMXV9sA0+Amu4nm8DqDWzsBL + 8Kp0fUxsMAZfIQpAtMRCCkgtXnVkAekgXeRJcgyvk5Isf6dQEZSM0lBGykY1UG1UN9VP + vUP101Y6g55LL6UP4PUKfY7+hv6GYZkURs/MYWrgAaabeRyvIWaYGWFeZ4NsGVvHLmH7 + 2c3sA/QK9k32HLeB28KNcF9wf0W3OJ+/mX8AtfMq2uwv0Za//THEg9IXwE2wgoRJG+xA + bTxNWmEArWsluQ/x6oH0eDO9gZ5D5aE1nIQfo7U+DuthM70Mno6/R++Dd9FS1uCQ/bCH + qQA7uxO1czfkoRVNXKFARiDd7/N63GkuJ7p8m9ViNhkNel2KVqNOUirkMoHnWIamCGRV + uqtanBFfS4Txuaurs0Xe3YoVrZdVtOBWdkaqruwTcYr3tWLTFT1D2LNjSs9QomdosidR + O0uhNDvLWel2Rn4VdjujZOnCRqQfDLubnJExia6V6IclOglplwtvcFaaOsPOCGlxVkaq + +joHKlvC2VnkaAjhkGdniY4jBApx4AjMbl2PDhZmiz0qIxZ3uDJidiONbbS3snVlpH5h + Y2XY6nI1YR1WLWrEObKzuiIoJ9yvXOleeX80BG0tItW6rDFCtzZFqBZxLE1mxOgOR4x3 + fGL6lr1EVT5wWWOE8la1tg9URUIt9yO4Itsicq0PIDevwYnDUpuaGiNk04QQooyrUVJR + 3ERM8LasdkZk7gp358DqFgQXFjWOWEIWyflGoL5xxBwyS0x21lHThhIXrv5o9qzsWWJZ + 4jJtSJR/vidR/9YpsTRtOPNHLOctmgSAiAi4a1DOiHOFNIkbhZ0hZu0zYGDFDMQJf00E + l9mF8syOUGgztDfCemtaI/0Nl8ToDCeEa1kdHpGZLVIQqmjC/i0D6mtQU9hf7XYOfInR + usU99vmVNa0TNZxX/SWIjaKiJ20lQlov0X1isPTiqjtN7k5Rv32STpF3myovq0BehEaU + OaLDAF7f6Io4m7ACT5NZ86Igq288SMiWpiiJb4pC2H4Uz6j0DcuxOUs0ta4wzo9MdhZW + ZLiQyslyVuHMVaKtOAecAzUrB5xVzk40JsYrldjQPtCUiwg2NCJOsBhnDDVZJ8n2pqZr + cJxccRy8BbsPNOEIqydGwFKqyh3HTnlZGExpX33jwsZIf9gaCYWbUAtovqfqGyOn0HKb + mrBX/qSkKPH6LtOEzAUoc34GthcmRsGzSz8O0TQwII7Z0Oh2RU4NDFgHxP2W4KMEplaE + JiqiIHYRIY+S/nq8Fwu3yyrpwOV2oVhNIqbT0KQvWRSe2b8f4eJJufHO6ShtsYTwjB8I + 4eDVIHzNVSFcMinpFQiXoswlIsIz/30Il12BcPn3IxyalBuFnIXShiSEK34ghGdfDcLh + q0K4clLSKxCuQpkrRYTn/PsQrr4C4ZrvR3jupNwo5DyUdq6E8PwfCOHaq0G47qoQXjAp + 6RUI16PMC0SEF/77EF50BcIN34/w4km5UchrUdrFEsJLfiCEr7sahBuvCuGmSUmvQHgp + ytwkInz9JMIhawQu98P9U9wu/OCOedllkONJidVCBXMrLMLUhw/VJVhWU0GwYTmTnIWN + mDZz+2Aj8mIqofbBZuxXgX2MWOpxiEvvfpT4RFKKfCuYpQdyGmkGWKzF10SYAM/xMpDj + E4n4U+K7FpVEiVnyBDUNYqST/IUapYEexrP3V0wv8wZbzW7hbuJO8ouxF4XPAYB1J/C5 + gIfyxLshIRcDOCYB3xXBG5hEHmn6wygwmMR3SPyHcEySY0nmMRyFhSWZefmFGpfGj6mC + 2RK9+Cf2xD9nR5nab/A9A46+KP6hdOJPxme5UvhdaEZGHpGrFValzV9Yre6SrVbzQUGr + lNHWAt4js6uV9pJMKidQcqSEKinI8GrVPCvY/GlGW5QMhNxGu4P323MUlL1IUcqXltp0 + fCBj2GMpswZsc5P9M8wzy35BduKDzlGyA/B9Qt2F2rELY3Xqv9eeHz+jDeZCefmYeI1p + gxqtMdis0QZzxnLGCJYaYzA/b/a6UHrxdH0aELOXFCe7wJRqdYHBqXMRVxpMp1xgsRtd + RO/CDN+fZRJ1qfi8ftddd0EzafYYCgumF88kKpJMOJ7Tk+LpxUXTfO40nuPdZaSwAB8Z + NDrshFOoiDvN7/OLha9oWvH0FKJaW3dD0w5XZ0F3W34DGS3TK++548ESl3yY/cezJ/pu + M3qVqZqMLF9zhkE2/dd3bj9xbOfA60uzaoa26m2cKsmWu4qsEbJM2csa5mc0vLyrunpw + fKctjaY3KbkKd6h69Yv3bd+dQs6Luu+L/57xsqdBA6nQE8oZ4vfY3rXRaUJyKsUCGO0s + r5Gn2hUKnV+wOC056hwSAI3Z4bzXdaJZArW0dvz8eRHVMUA08U8T1CTQM2kNnNzA6XxE + K8dMzxt9JEWW6kOwiIgTNKcUakQotBodJSGgd3sSIHF6ndFQ2HegZHfLK1///YM7FhcE + h6iOrVsf/PFR35zT7Onx/6ldGBuLXYjFIiXu2s3rPzu59/eH39y5/KBkz/iUS7/B1IEF + rLAnlLvHTAZNw8I+Ez1X0OzS0bSOs1v4JLtOYeWtVqParyW0n9JY7HK/0WzDV3/8Idfa + 9RMWgysrrR0LBtFKJiwGCfWYZB7TwCx4lXq5D1QpalylJlnNm5FjgXYRQjG0wpDkg2Qt + ZjIT5yMM4Vy4cslURGNRl0omI9kLGIzuHDQANJWEVRSK5kAVqaGQp859bDygXrvh53Pz + 7nuk5x7zgdS/Hn/rn0T7to2pi7y74p7h7qee/nDz7e+8RAo/xUf0a3B+qI5/wFjw6dqG + b2K8RBlat1N4zLLHQbMqKpnV6VXaZL0upAzphICFzFMcps+Sl+mz1veE92XnHO+5PzN+ + 5lac1ZzVUssE1uVJftxg9wQ5nje47DZebjcovPxO2x7bEbQVxmtI9tpYs1zJa1T+ZLuf + tfg9ObzfbPb533YNJYwEbUQykbfHg9ogbrcgFrnNiR2IVOl4qXoMayVUq8DNsDS+uiAs + wzl8GrVWnaLWqRlO6U2zenzgBLuPpNplRt4HCr3KR5JUbosLq1jMBBPin6TGTNySiT0p + gZyRmXEXuaUZbmluRqjx0rtS0fSmF09HoHFPcu400CDYxOfHTcrxhBo9N6NYq774Bfvw + zgcX5+kO8gvyF62bteiV2F+I6U/EoUif+/ydwyxxM3NuvHbhmrnPPPtSc/Gckq059TY1 + ceP7G4pUxHy3Vd19aICIHwjQg9twwxnZt/CNT20ok7dzcjtNknVBQxKnlZuNRosqSRMw + anltssqholQXdWaT+aJr1YaEJY43B89IQNVVtoc/Rehw45WWj72NpqidXlxYYDDqRfvh + 9IV6twavosKiF93loxqP0WZWLHKOjI5s385WTFtGUbspcu0LWy6upJ/YMiz55ZmxEvoz + tBUHZOMbvyOh2mJdjVAjaxSaZPcp91qH7Xv9Q5lHrYqQQBvSAqoz8jR0vQwXsJvlWrs8 + OYfPyWFtdI4hJzvAWvKUKn9Smc9vM+fm3etaWzHpeYOiBYyf/xL1fMn3lo9Jak/oPcud + bklVaDxetc+d6vNBugUzjULlgmSVMslrT/MRvzWA+0mpdUnaRYebcLkJnwuo1aJCjY7n + XGk+fyGqWFSv5FU9omZBcr7S7kJXTKg7lxcWDZX2xF59/nPVkST/zHteD/no4sH1L8S+ + IfwxEt79k5NV3m13nl6QFXuTqShzz773YsFrfR/seq7aX/rIkt8tqv8HsZMkkhN7+tTI + DY+/eOLAio1UtuR/NqKySybiaXHIxn/CoPI5Wi5DHaNdBHgaHYdsn6stAU5p7Znx0jOT + ai2vRZWiZ3RrUJMbj+CPyfjmHHviNcmGNuPYM6WxAyE8K9ByFgfFMYE2M+xlQ46XXhow + Mdjm0VExGEtjoHycl5kDPtgUKuEFXsUlGwWjypjsF/y4havNSxSrFEq3V26xu81yijF6 + XXajPYnjgbPavHSKPB3n1ATwowIZsQTEbykhOZAcLyrH7E+PkqRD3y5t/Lz6wtiF8Qlh + jKWi3Y7hXjcGxUArbnkxDOgxOooh0XgpMro1Yqzk9IjCNGlDIrVxJDSt6Zb+uixP6TPt + 79VlHL+xdvVjRyyBno49o0zu4ALPzHJP1ZKGJxZvGZ9OfXZj/Zah8a3U8e6CeU++Pv6K + GOtw3fQY2rkZI8PyUP4R7ixHMZyO8+v6uF6e1SkpnUmNEQ84k0Ju4S0WUAZkFhvJMQXM + YLbisYO7YmWSS0tYM65rTBMMksSCiLiky5YirgB9jIrgKsjG/fP3dZ6vzzpiz9sQCsyd + kW0dJXtQ/uWLfnbdM+MLqWfbSlcmGSqKbukafx2FRV9eEn+fcWE8U+J7bjM8HCocFHao + HzM8xwwLQ+q9hqjwivAu84nqv3XKawTObuKVdq3CzJvNesqfbLHK/HqzxRolMoxqE95Y + OgV9G9Ekt5uFx0+fIkWGnlND+QhvRIpNQkquU/qAqDETDBjEaBVmkm8Vs0wMXh5t0YSO + MHJp0YtSeD5KBK4/bsqbf+y5HTuexY8JF2P/+F3sItH+meslyUM7lj96cWT/efqD2OcY + xsdjL5DMi3hYCrG4VdDGqUfQPjWwIOTz076k6fQchlEJakol08iUfkFUkUYuWFJIjjqg + AbM2JUoqUTUJVymeSOrUoousLT8zfkaMNqKtTViaqJZJX6lxb96v330ja7Krrer7HkEz + Olq8i6JP0tSBteODos1UxN+lDzPz0C/mkpzQQzNkg+wO7WO6Qf1gBpfu8fqLXVWuOZ45 + /iWe6/wdnlW+dcp1SetUfe5eT6+31zeUOpyVQmOYYrOZnBSw6K1Gm0mfrctJT1Z0CT5v + sZfypiXJmcwU08s2ewrP2HMez1Tk8jKVmuIh15VrcZgMJr+xLN3H+9Mt+SqHX10G/hxz + Xv7IZGzF7ZXwrUE1UuJyg7mYozmKAVY84Yrb7RZJy/NJNuXTey0+l8rhAhl+YiR0Fp6R + 2Qyk7Fqss+pMLuJMTnOBK02VJPjlLuLzyuQkm3Hhd2XMUjU2FzEbMJNCrOSEpUyyiktG + gUfgFMkF44HO78sVwyoebcU9zrsTIVY84jmIGIl1HB58/eQLwRseXjk403/rQ5tn9f72 + 6N9unE3tY31lj3V0VabX3X66ouv9339xlidHSP3SvOuuu77Sg6eStIyauwZ/sWVp58yC + OXWhqgxzij03q/LRh954/ynqa7QlY/wLSsYuxZ2z6MWkHPkpFYmS8pCXMQSNNKeSayzo + yvBrSwD0Kn0y7aAp+qLBbLZg3J04AU6Ju7mJwDumHj8vOVYx2opn1UvneF+RGHqHD+/f + 79PnJ6XqHLP9G5Zu3coujb2zbbxyRoqCUFtkwl2rqJe2SbFCH6uRYq+4s/8zdNOA/j7T + HhPNc0ZuhrZa26hdxd9O384/oBuEneygfqdhp3EYhg3qapinn2N8Vc+E2ZdZ6l52CIbI + HnbYyHrSWZPeaMB4o1cqku2CSnQEBiuuEnfWAaPedED5kAH9wduJg4UZn4rOm8aDQfwz + S07alHBotePBAnOuqby0tFTcP/iRNaTV68Fg6NYajSaWkG4tgOnenEz1+jNSIWBJmtHK + biHN+ABUyNEUT0mKLRIPWsXTy8h0Ukho2nXWd09bxRP9T/gCqbkZ6oJcNVumivW+RhyE + yV0V2xr7/IVYxygn7E7iXCbhUQ9Td3GQvlvci9Iv3o7f3f7VD79dQxgqoQq/39XgJ+v5 + sED6hih+qVsC18Ey6SaCXxeJRHH4/xYwp6ZhSU1FZnX7mr723q4VrdiSaBW7VGMSn5BX + YhL/lwPjBzyKaTemUUxnML2N6TymC3gjg0mHyYNpWnzih20wSRN8lr+Sb5vCr5jCS2u9 + 7P6OKe2rpvBdU3jxW9bl80v/E3PZeDdNab95Cr92Cn/rFL53Cr9O5P8fJ4dYIAplbmRz + dHJlYW0KZW5kb2JqCjMxIDAgb2JqCjU5MDEKZW5kb2JqCjMyIDAgb2JqCjw8IC9UeXBl + IC9Gb250RGVzY3JpcHRvciAvQXNjZW50IDc3MCAvQ2FwSGVpZ2h0IDcxNyAvRGVzY2Vu + dCAtMjMwIC9GbGFncyAzMgovRm9udEJCb3ggWy05NTEgLTQ4MSAxNDQ1IDExMjJdIC9G + b250TmFtZSAvR0lTVklCK0hlbHZldGljYSAvSXRhbGljQW5nbGUgMAovU3RlbVYgMCAv + TWF4V2lkdGggMTUwMCAvWEhlaWdodCA2MzcgL0ZvbnRGaWxlMiAzMCAwIFIgPj4KZW5k + b2JqCjMzIDAgb2JqClsgNTU2IDU1NiA1MDAgMCA1NTYgMjc4IDU1NiAwIDIyMiAwIDAg + MjIyIDgzMyA1NTYgNTU2IDAgMCAzMzMgNTAwIDI3OCAwIDAKMCAwIDUwMCBdCmVuZG9i + agoxNCAwIG9iago8PCAvVHlwZSAvRm9udCAvU3VidHlwZSAvVHJ1ZVR5cGUgL0Jhc2VG + b250IC9HSVNWSUIrSGVsdmV0aWNhIC9Gb250RGVzY3JpcHRvcgozMiAwIFIgL1dpZHRo + cyAzMyAwIFIgL0ZpcnN0Q2hhciA5NyAvTGFzdENoYXIgMTIxIC9FbmNvZGluZyAvTWFj + Um9tYW5FbmNvZGluZwo+PgplbmRvYmoKMzQgMCBvYmoKKE1hYyBPUyBYIDEwLjYuNCBR + dWFydHogUERGQ29udGV4dCkKZW5kb2JqCjM1IDAgb2JqCihEOjIwMTAwNzEzMDQxODIy + WjAwJzAwJykKZW5kb2JqCjEgMCBvYmoKPDwgL1Byb2R1Y2VyIDM0IDAgUiAvQ3JlYXRp + b25EYXRlIDM1IDAgUiAvTW9kRGF0ZSAzNSAwIFIgPj4KZW5kb2JqCnhyZWYKMCAzNgow + MDAwMDAwMDAwIDY1NTM1IGYgCjAwMDAwMjgyNzAgMDAwMDAgbiAKMDAwMDAyMTQwMiAw + MDAwMCBuIAowMDAwMDAxNTc0IDAwMDAwIG4gCjAwMDAwMjEyMzkgMDAwMDAgbiAKMDAw + MDAwMDAyMiAwMDAwMCBuIAowMDAwMDAxNTU0IDAwMDAwIG4gCjAwMDAwMDE2ODQgMDAw + MDAgbiAKMDAwMDAxNzUxNCAwMDAwMCBuIAowMDAwMDAxODU3IDAwMDAwIG4gCjAwMDAw + MDYzMjUgMDAwMDAgbiAKMDAwMDAwNjM0NiAwMDAwMCBuIAowMDAwMDA2ODMwIDAwMDAw + IG4gCjAwMDAwMTgzNzggMDAwMDAgbiAKMDAwMDAyODAwMSAwMDAwMCBuIAowMDAwMDIx + MjAyIDAwMDAwIG4gCjAwMDAwMDY4NTAgMDAwMDAgbiAKMDAwMDAxMzU5MiAwMDAwMCBu + IAowMDAwMDEzNjEzIDAwMDAwIG4gCjAwMDAwMTY2MzMgMDAwMDAgbiAKMDAwMDAxNjY1 + NCAwMDAwMCBuIAowMDAwMDE3NDk0IDAwMDAwIG4gCjAwMDAwMTc1NTAgMDAwMDAgbiAK + MDAwMDAxODM1OCAwMDAwMCBuIAowMDAwMDE4NDE1IDAwMDAwIG4gCjAwMDAwMjExODEg + MDAwMDAgbiAKMDAwMDAyMTMyMiAwMDAwMCBuIAowMDAwMDIxNTY4IDAwMDAwIG4gCjAw + MDAwMjE0NTAgMDAwMDAgbiAKMDAwMDAyMTU0NiAwMDAwMCBuIAowMDAwMDIxNjY0IDAw + MDAwIG4gCjAwMDAwMjc2NTUgMDAwMDAgbiAKMDAwMDAyNzY3NiAwMDAwMCBuIAowMDAw + MDI3OTAxIDAwMDAwIG4gCjAwMDAwMjgxNzYgMDAwMDAgbiAKMDAwMDAyODIyOCAwMDAw + MCBuIAp0cmFpbGVyCjw8IC9TaXplIDM2IC9Sb290IDI2IDAgUiAvSW5mbyAxIDAgUiAv + SUQgWyA8NjJjM2U5NGRkYzI0MzQ5YjFiNDQ0MjFmMDRiOTg4MzE+Cjw2MmMzZTk0ZGRj + MjQzNDliMWI0NDQyMWYwNGI5ODgzMT4gXSA+PgpzdGFydHhyZWYKMjgzNDUKJSVFT0YK + MSAwIG9iago8PC9BdXRob3IgKEZyYW5rIERlbGxhZXJ0KS9DcmVhdGlvbkRhdGUgKEQ6 + MjAxMDA3MTMwNDA3MDBaKS9DcmVhdG9yIChPbW5pR3JhZmZsZSA1LjIuMikvTW9kRGF0 + ZSAoRDoyMDEwMDcxMzA0MTcwMFopL1Byb2R1Y2VyIDM0IDAgUiA+PgplbmRvYmoKeHJl + ZgoxIDEKMDAwMDAyOTIyMyAwMDAwMCBuIAp0cmFpbGVyCjw8L0lEIFs8NjJjM2U5NGRk + YzI0MzQ5YjFiNDQ0MjFmMDRiOTg4MzE+IDw2MmMzZTk0ZGRjMjQzNDliMWI0NDQyMWYw + NGI5ODgzMT5dIC9JbmZvIDEgMCBSIC9QcmV2IDI4MzQ1IC9Sb290IDI2IDAgUiAvU2l6 + ZSAzNj4+CnN0YXJ0eHJlZgoyOTM3MwolJUVPRgo= + + QuickLookThumbnail + + TU0AKgAABZyAP+BP8AQWDQeEQmFQuGQ2HQ+IRGJROFwOCQZsRkAQOKR2PR+QSGJxaDtC + TAB+SkABmWAABS8APiZAAETWVy2RTmdTuIySDLigAB20MABSjRuBAB90sABKnAAd1GeV + OqVSfQVn1kACOuAAHV+q2GxWODVcANe0AAU2uyRiNRy2wgA3MACi7XGEWa0Ne1Wy43u+ + imEYCXgIAAXEAB/YsAPrHAAVZGIYC14K8WW4QXKX625vLQZwaEAOPSS6YUt9gB+6sAEP + XZO05XL5ikwbPXjb7Oz7HOZe9bzP2SMtikReHPnkAAD8uYzPCgADdGGXMA3W77rf3zZb + qJtrvAATeGUSpveUACH0YfE9yHdnA+yHPb5AB0/Xz+mD0N2gD5PYAA7AD4Ia9ztwEhR0 + QQ9QCgACcGoYbsIAADEJgABcLQMg8CN7DCDO8bT7hDBSGHrEgAGrE4ABfFTlOZAUNODA + 0SHqAB1RrECKDdHIACVHgACRH8DRfDiCnPIsWAOpqnoO4bioQ5B8gAeUpAACsqpA6jrB + QikhSHDwABFMAAAJMaEGnMzwPEeE1AAC02ybLDMoLLEsIO3KJS4+EZAAdc+AAEE/oYY9 + BAAd1CgBNR4AActFgADVHREmR8K8sEEHQAA00wwbgS3OM7PZIpzyPJIJIZT03rojk6No + AFVM1TaR07V74S9MARTFMiF1MsVdPbWLtQ2uM9T4dc/UAh8mTiiFhypKyHywu0tVg2tX + V/GC41BUSnVIuLQnBYoQLxPDLmzcitq7MYCLwbl1gAEl3XDXz3riel6KEogP3w7kmWhe + Fpt3aq8EFgQAB/guCYMuL+gAM+GAASWHgACOJLHcSxlTi4ACfjSaJs3Ra4+AAgZFCsLr + Fislrffy8We663OJZKxZZaNe39XlqQlChw51SYHAAeef59oCjApQlDAZo+I4nAAO01gE + 603CBu6CecRaOBgAHjrKiqPRwNVLWUB3jAqEsBdAAGbtFvsUxgIbaAFsQsBecAwADym8 + AAhbzpt5NtTZzb+AFKtU1iONIcYACJxIAAfxmv6dmjjX/vmybA3HK5sqnMQzsVgZdJqP + ykeWeIhmSEWRlSFz1uKKdKh+TrCcXYgBtoIdG3Wo3MEd+8jzSeayeMoynpd9I1fi49eq + qOS8EvmNMwy4y88ITd3p/HsvRZygABXt6SCKx2wZXw4zjfj85ay23oegAHZ9m1LFuwAE + z+QAET+vqb76zuS89EQsRBZC3TuRIYYsfyTQBwHdIXR4yd3zIGcE2ZobjgAAngoqxVBS + XBITbonBlRz3quTIg8gvCkVFKMK47ohaghjwleyoUdxCEqgVT2n1qyh01gXhwAAKcO29 + tjhDA1IbuANxDY4AiHrnWwwCVbEd88SXeOVQE+wdjgx+gAhwBd0zKYBMxgUy0nsQEOGo + AAN+MiaHpkThI9h3KQYwJDIKt1ZkMnVkPjgxJ7zjAHxsZrFBDg74/AAHvIFRqjyFs/ao + stWsboRICNXFVdY3IJwVIW7iDTJG5JDkWhwQsmwAA2k8AAIsoQACqlIACPw72FsNjcbS + J7+S4wBIYtg+o6QAAwlsAAYEuQAAsl41tohB3WmzkyVV3pO5ilWja5Z/MKjGmPdCAABM + 0QAA4moACGquY+FkmG5lyr8EnyAkESwDLi3GvbAVBKHz5Y9yuM7Nmbk7JtTJlfFplcXW + Zm+nlKufRO5tz7n9Axf0sJ/0DJEWaghD41RDA3QcirMKGELoTESh5eaHUTIRRGhdFpWU + aIbRijhBaDUfIMjkNwAAo0nAAEGlVFqQoYoEQ6R5N5xxzIdMGfDqEMTHJzTonlLUDG3m + eMSoUFjqnRAMqIHlSTYTwYpRVARt4CAAXINl51FCCQLIbTyflTj4VaJBV4nNPkBUvLJT + Z+9Iq0EOICAADwEAAAMAAAABACUAAAEBAAMAAAABAEMAAAECAAMAAAAEAAAGVgEDAAMA + AAABAAUAAAEGAAMAAAABAAIAAAERAAQAAAABAAAACAESAAMAAAABAAEAAAEVAAMAAAAB + AAQAAAEWAAMAAAABAEMAAAEXAAQAAAABAAAFlAEcAAMAAAABAAEAAAE9AAMAAAABAAIA + AAFSAAMAAAABAAEAAAFTAAMAAAAEAAAGXodzAAcAAAzEAAAGZgAAAAAACAAIAAgACAAB + AAEAAQABAAAMxGFwcGwCEAAAbW50clJHQiBYWVogB9oABgAcAAsAEQAQYWNzcEFQUEwA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPbWAAEAAAAA0y1hcHBsAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAARZGVzYwAAAVAAAABiZHNj + bQAAAbQAAAD+Y3BydAAAArQAAADQd3RwdAAAA4QAAAAUclhZWgAAA5gAAAAUZ1hZWgAA + A6wAAAAUYlhZWgAAA8AAAAAUclRSQwAAA9QAAAgMYWFyZwAAC+AAAAAgdmNndAAADAAA + AAAwbmRpbgAADDAAAAA+Y2hhZAAADHAAAAAsbW1vZAAADJwAAAAoYlRSQwAAA9QAAAgM + Z1RSQwAAA9QAAAgMYWFiZwAAC+AAAAAgYWFnZwAAC+AAAAAgZGVzYwAAAAAAAAAIRGlz + cGxheQAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAG1sdWMAAAAAAAAAEgAAAAxu + bE5MAAAAFgAAAOhkYURLAAAAFgAAAOhwbFBMAAAAFgAAAOhlblVTAAAAFgAAAOhuYk5P + AAAAFgAAAOhmckZSAAAAFgAAAOhwdEJSAAAAFgAAAOhwdFBUAAAAFgAAAOh6aENOAAAA + FgAAAOhlc0VTAAAAFgAAAOhqYUpQAAAAFgAAAOhydVJVAAAAFgAAAOhzdlNFAAAAFgAA + AOh6aFRXAAAAFgAAAOhkZURFAAAAFgAAAOhmaUZJAAAAFgAAAOhpdElUAAAAFgAAAOhr + b0tSAAAAFgAAAOgARABFAEwATAAgADIAMAAwADAARgBQAAB0ZXh0AAAAAENvcHlyaWdo + dCBBcHBsZSwgSW5jLiwgMjAxMAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA + AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAWFlaIAAAAAAAAPPP + AAEAAAABGGJYWVogAAAAAAAAeFsAAEAZAAAD91hZWiAAAAAAAABWWgAAntIAABfUWFla + IAAAAAAAACghAAAhFQAAt2JjdXJ2AAAAAAAABAAAAAAFAAoADwAUABkAHgAjACgALQAy + ADYAOwBAAEUASgBPAFQAWQBeAGMAaABtAHIAdwB8AIEAhgCLAJAAlQCaAJ8AowCoAK0A + sgC3ALwAwQDGAMsA0ADVANsA4ADlAOsA8AD2APsBAQEHAQ0BEwEZAR8BJQErATIBOAE+ + AUUBTAFSAVkBYAFnAW4BdQF8AYMBiwGSAZoBoQGpAbEBuQHBAckB0QHZAeEB6QHyAfoC + AwIMAhQCHQImAi8COAJBAksCVAJdAmcCcQJ6AoQCjgKYAqICrAK2AsECywLVAuAC6wL1 + AwADCwMWAyEDLQM4A0MDTwNaA2YDcgN+A4oDlgOiA64DugPHA9MD4APsA/kEBgQTBCAE + LQQ7BEgEVQRjBHEEfgSMBJoEqAS2BMQE0wThBPAE/gUNBRwFKwU6BUkFWAVnBXcFhgWW + BaYFtQXFBdUF5QX2BgYGFgYnBjcGSAZZBmoGewaMBp0GrwbABtEG4wb1BwcHGQcrBz0H + TwdhB3QHhgeZB6wHvwfSB+UH+AgLCB8IMghGCFoIbgiCCJYIqgi+CNII5wj7CRAJJQk6 + CU8JZAl5CY8JpAm6Cc8J5Qn7ChEKJwo9ClQKagqBCpgKrgrFCtwK8wsLCyILOQtRC2kL + gAuYC7ALyAvhC/kMEgwqDEMMXAx1DI4MpwzADNkM8w0NDSYNQA1aDXQNjg2pDcMN3g34 + DhMOLg5JDmQOfw6bDrYO0g7uDwkPJQ9BD14Peg+WD7MPzw/sEAkQJhBDEGEQfhCbELkQ + 1xD1ERMRMRFPEW0RjBGqEckR6BIHEiYSRRJkEoQSoxLDEuMTAxMjE0MTYxODE6QTxRPl + FAYUJxRJFGoUixStFM4U8BUSFTQVVhV4FZsVvRXgFgMWJhZJFmwWjxayFtYW+hcdF0EX + ZReJF64X0hf3GBsYQBhlGIoYrxjVGPoZIBlFGWsZkRm3Gd0aBBoqGlEadxqeGsUa7BsU + GzsbYxuKG7Ib2hwCHCocUhx7HKMczBz1HR4dRx1wHZkdwx3sHhYeQB5qHpQevh7pHxMf + Ph9pH5Qfvx/qIBUgQSBsIJggxCDwIRwhSCF1IaEhziH7IiciVSKCIq8i3SMKIzgjZiOU + I8Ij8CQfJE0kfCSrJNolCSU4JWgllyXHJfcmJyZXJocmtyboJxgnSSd6J6sn3CgNKD8o + cSiiKNQpBik4KWspnSnQKgIqNSpoKpsqzysCKzYraSudK9EsBSw5LG4soizXLQwtQS12 + Last4S4WLkwugi63Lu4vJC9aL5Evxy/+MDUwbDCkMNsxEjFKMYIxujHyMioyYzKbMtQz + DTNGM38zuDPxNCs0ZTSeNNg1EzVNNYc1wjX9Njc2cjauNuk3JDdgN5w31zgUOFA4jDjI + OQU5Qjl/Obw5+To2OnQ6sjrvOy07azuqO+g8JzxlPKQ84z0iPWE9oT3gPiA+YD6gPuA/ + IT9hP6I/4kAjQGRApkDnQSlBakGsQe5CMEJyQrVC90M6Q31DwEQDREdEikTORRJFVUWa + Rd5GIkZnRqtG8Ec1R3tHwEgFSEtIkUjXSR1JY0mpSfBKN0p9SsRLDEtTS5pL4kwqTHJM + uk0CTUpNk03cTiVObk63TwBPSU+TT91QJ1BxULtRBlFQUZtR5lIxUnxSx1MTU19TqlP2 + VEJUj1TbVShVdVXCVg9WXFapVvdXRFeSV+BYL1h9WMtZGllpWbhaB1pWWqZa9VtFW5Vb + 5Vw1XIZc1l0nXXhdyV4aXmxevV8PX2Ffs2AFYFdgqmD8YU9homH1YklinGLwY0Njl2Pr + ZEBklGTpZT1lkmXnZj1mkmboZz1nk2fpaD9olmjsaUNpmmnxakhqn2r3a09rp2v/bFds + r20IbWBtuW4SbmtuxG8eb3hv0XArcIZw4HE6cZVx8HJLcqZzAXNdc7h0FHRwdMx1KHWF + deF2Pnabdvh3VnezeBF4bnjMeSp5iXnnekZ6pXsEe2N7wnwhfIF84X1BfaF+AX5ifsJ/ + I3+Ef+WAR4CogQqBa4HNgjCCkoL0g1eDuoQdhICE44VHhauGDoZyhteHO4efiASIaYjO + iTOJmYn+imSKyoswi5aL/IxjjMqNMY2Yjf+OZo7OjzaPnpAGkG6Q1pE/kaiSEZJ6kuOT + TZO2lCCUipT0lV+VyZY0lp+XCpd1l+CYTJi4mSSZkJn8mmia1ZtCm6+cHJyJnPedZJ3S + nkCerp8dn4uf+qBpoNihR6G2oiailqMGo3aj5qRWpMelOKWpphqmi6b9p26n4KhSqMSp + N6mpqhyqj6sCq3Wr6axcrNCtRK24ri2uoa8Wr4uwALB1sOqxYLHWskuywrM4s660JbSc + tRO1irYBtnm28Ldot+C4WbjRuUq5wro7urW7LrunvCG8m70VvY++Cr6Evv+/er/1wHDA + 7MFnwePCX8Lbw1jD1MRRxM7FS8XIxkbGw8dBx7/IPci8yTrJuco4yrfLNsu2zDXMtc01 + zbXONs62zzfPuNA50LrRPNG+0j/SwdNE08bUSdTL1U7V0dZV1tjXXNfg2GTY6Nls2fHa + dtr724DcBdyK3RDdlt4c3qLfKd+v4DbgveFE4cziU+Lb42Pj6+Rz5PzlhOYN5pbnH+ep + 6DLovOlG6dDqW+rl63Dr++yG7RHtnO4o7rTvQO/M8Fjw5fFy8f/yjPMZ86f0NPTC9VD1 + 3vZt9vv3ivgZ+Kj5OPnH+lf65/t3/Af8mP0p/br+S/7c/23//3BhcmEAAAAAAAMAAAAC + ZmYAAPKnAAANWQAAE9AAAArAdmNndAAAAAAAAAABAADhSAAAAAAAAQAAAADhSAAAAAAA + AQAAAADhSAAAAAAAAQAAbmRpbgAAAAAAAAA2AAChQAAAVwAAAEzAAACXAAAAJkAAABwA + AABQAAAAVAAAAoAAAAKAAAACgAAAAAAAAAAAAHNmMzIAAAAAAAEMGgAABcD///L/AAAH + YAAA/c7///uY///9lgAAA/QAAL9ObW1vZAAAAAAAABCsAACgAzA0Rky6bz8AAAAAAAAA + AAAAAAAAAAAAAA== + + ReadOnly + NO + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UniqueID + 1 + UseEntirePage + + VPages + 1 + WindowInfo + + CurrentSheet + 0 + ExpandedCanvases + + FitInWindow + + Frame + {{470, 267}, {700, 891}} + ListView + + OutlineWidth + 142 + RightSidebar + + Sidebar + + SidebarWidth + 138 + VisibleRegion + {{1, 1}, {558, 782}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 0.0 + 1 + + + + saveQuickLookFiles + YES + + diff --git a/doc/images/gtsam-structure.pdf b/doc/images/gtsam-structure.pdf new file mode 100644 index 0000000000000000000000000000000000000000..37c2ed3c126960bfdc9dfdb60a37dee28a2e289c GIT binary patch literal 29463 zcmeHw1yq&K);B4g5=zLSJI;2YUcj;2kdG?ukW}ZFs{PxV=d-f)m6BeZhGB6{OcdqWQZsZ-jdf(ZN$O2#j z*cwX{GOEENpCOYh(=I<3n_Gaxm7nMs$Nr zOOSNb6hRL-IZ+)L)p6t5>A`_kHWDd!!9rSz2~miVCKJNGNiSRDbD-Cj^v%blU0GjW z-yT~#d@4^gfotrffbZ<-TK;wKmDL5oqX}sVu0s5jl4IpAwVEOt+&oF;iy9AwTK=+= z$PIqo8;@z13luocow%hHA^Ax&e2K1h%h*c$ul9L1J|EPNt|SjME}BR3wSr3cl+ubK zv|A_AY>v#QzouGi1}R>xt1x`feRY18x#W~rlT@NykGW>r9gxOw$PKsCAu`rJv?PUp za5?a_p(;Ft#yT6JBQs~gD(ls?iV>*kvin@2kbglo-9CAZ+UCa$58{k$;gD3Rf%; z1PQ9jE)IJT+hOJ`rT*f=CdW#51>bvK&G3}csOE!nEx(3!UC&qXtHRRjIu&+NZs#Kp z6r3}6w+E^&Q(xI@&R=<}`6j`px_o^70^!hq#V?Eof3*@d6K|H%&}Ae$(VAdey1A0t z){0xsJ96Q`J_x54u5+go<+`L-Aizcht|{d51UN*!*l{k{8FK+}i=TJkYmKNIr>pf& zPWa4WuyKwL_nt5EfoAU{-Lg%=XcsD#d+WHKK75kF39&0>7sdOQuZ$}RbJZ+R`ZvSo zY%O+iQ3KT8^jDgdj(r#!`)v7XG3TO^g-vS-BUm+rq*!lA1<#_!p!5_9p79x&)m1&C!sP1@DF{rmf1~>7~jv9t8rAu-J`Lj zu4Uq@ICz)LEqg_L&^b+n)6TISIb-FV&Kz_NPj*zt-(p_;;9MyA%+iNWDAQSjtYHOm zQQ7UPN{_4PSYF+tgf`GY~>oFkGh-jI|ZXhyPf@fl6D1;qk z*bck|sV@SS2GrphR(%<8iy7N8YtjH}P4_xjghyuM5unSq`X08~*y+jPlwk($Eeggp zE)i|mn9Ozfo}CFsgq0=<2y{oNg@)q~wRZwP4;e=jc8BmO8^r-v6NV-UvsbUeN zs2|ze&#)0Az=u5JFo$~h!Km$6K}T3Lm0W6XJyBW_UjBnWkUdoPatV_4we$n{=4#7D z9BHK9z6$!2G~-o*3=SwGBSdtwVm;VAim!d7NLx@u-BRMjeGi^)6*D5UiX)nuo3A*2 zmW)EsIo5d57w{6N%i4i1pvsR`mtuqRbG;;K0&|RuPIXpkuN!0m^E0KUd-F{cf~2!D zOaoy|HN=qO4;Cx+cq@Y7#RxNut8>bOGIU69M0B!wx;~8zX4|=owlX;!mEnP)JzqU) zj%&g|e@JB>1?x_jw<9iyw$i7sPmm`mj57aX#d@CvyNNP3bU+}SQen=Un#M`g6Je8= z!hS205ua6b7o+<<=NKKDiq3H*#e2P69vx`Bp2@m&uFuFWtvZpHwHv+h0b{#djg_mt z^ps^4mfKGtD?8KeueaYpf0I8-?smoi zMmc@cyZ;@GZJYqi-(-=3v7@cCgQ2k_fbAPW$kxUQ{JSIIR(^qnm9(*uxxS#S8$go@ zOaQS00W8cwZA7rV`rgiMy&rN;&cW7D(bx%~32sbS6u_ut?B)bu6t@O9EcpFX==-NQ zKpVg)WNT&XplGLWXbiX&lR}Ol0O+n=MDTYYfc>rue0*S03GUTh5m6w+Z7=@%K~2`c z!r1WJZ{pS<0Pwb#;BJdsvjTv3kAw*R&ISN-{Gc-ffVZr>y-oZD(t9 zJE9!_bY*ed>AzMMTknC85D*aUua0D`k%@vI>%V;l34IUw0h8W;`OB~`BF? z8-C%|-*N88oA@2v{N^lheWwU`4d@dG&l^Z{}#Ug_oTv~TK{c<`iFIYSohyp zhy9PI%_TB&rSv~r$o-JDKqhw1A1k@Lb@8wAk9Q56PlEQ#*d#(S+ zDfN?*b}M1WcGQia#~dlA`Y|=F9Fo+7R?-)w9Nq)rOlkfMqE3|2bs@r}+&gk{V}r9x zbDzb;c9Huky9hC!2<94m3<*o=ciGdeGW3h+pNrk`^Q@lo%k|pzI!bZm z)@!X$!~FdIp(3E5%!oyxv9rfxC%XQ8a|s!}rlwe=>LLnrQBx*$D^xuzoLGV3_n%6e z?jsEpVbfS=46g4ZpI$-&E?XcY`^`7T3bC4+n(g5Q>=kmDxp{pTXYBm(VV{Tj58s1+ zl&79YVqe{CFBaTuR#Lw}w47CODhw4B;zrkpa&a-Jp%I91BIGN=(RIjqMLOaJiXSq9 z?0v1+>*mzCvuQ}xM2HwJ;pxOSZ0E!ipVT)vwC0py@Wntf2?5oVdQEel+f|@BVoacNnbmjG+Ks<`BK&? zU$fHY5_)XMbvL)SeF`zqwUgUn;ie{%@e?&igY*ElsVNoOocaN`PSdGJE*k{i4E8tT z_2;Ga_07QQ%4>$B7M`K=mM10P#J4t;%(Qn?@WCVtGUNST?*3yatA z!VdN*sXTQ$UQ00~t_>lcHN_jq=<2>6Tch+&O{eA4eR@WT&WM|VyO!&d%;D3p;AV%@ zVeqiT)ooZ?CYOkB2shLRLZ0pu5x*2AW5xm3VRiACP%u2Xr3;FE#YU_v5l`|Nc5u=Y zv~3xkNP8g$<{~mKuXr)RLeH&qy-x-__A8U0&>l<8H$(^PhQsh4>#$OrHxdg=$%VHq zq58LH<1$2ep>JPGMPJ zDr;W|oUA&nf)RZBSfZ)HN!n36kcSvyVx>5bE_9Fe8pPaGNrc(-D&n^ zq6$xgIDYr*kkn|5p?~;m53_iU5=g-kl@VSnYSMCsnr8{5B+(B#5CmzUMJ3QVC~%x3 zpEc5>^J5>3Z7@&)O1dsTc~C_*&lfreXzV&Nqk9&it-r9jA@{ZI{xbIbcSXq^w%y_# zSit_JD!J3{`~rfY?~18EAovFa|A62h5d2R9!8>gG6$I~8MZbU`^LHiq9}xTlf`35p z4+#Dzf#4ms{R)DhANrTSIS?^_w^sfE!9O7Q2L%6s;C~bd-eTLYAb4j6`*kJwU)c`- zW`p}*)(TDzOOl`v+_OvD>)}Y^$}!;*$T4|NRvhdR?M>W(EBkzrB)!QB;BJPtkvZr8 zHcSuT4{(qE3J8V^d48hnX-YdgmvG{F^MYqVC}C}%hdCn}`5r;~vlki9MyTMQQ-$W{ za99Vk^_X4mAOR7xdaWuXVg@M~+h(j{jA|04vv#KxtaD~adR>CXa;PjN?LwCwxHc<| zfHyTtDbyt#ShZ7YCq2U2N+0+v+t7Mu1$yM;3hC8=#@bsK%Q#(x+X+8hEVvMZJT7)^HXz+M&Ze??Qm1u6E ze{6GaJ9n+6&@`j4YrrxbQb zwNIT#2N!W{%n6^~uM5y@;aWEV6RS~M5I(lk>!vv|gNYh&3otfIFUw>a9)gJ_ezs7x zcKxc9bI4%gWE;D$X5DI0tj)bzJIRg3l(+OB_b0^J{WR-xoOh+ccmC7dA7=g!r%LRN zEA0m?)?@~yVV~nbw6U{;u&IFX2I7ZXT+g#FdYy7FQe?KDT*+({r%G<0`Rv4Lr7U&Y7kH0s z&%fwKi)?5O+WYcm_F9FJkg`36VSTOyz{&P}&#Ge5OxyLsZz*ltmg9?SnP!9r5FgEk zgKTN*0;?Ex$AwOjYAR)6HqB;7^kizo<-D20U>B9NMF9k&XSr zl8eR$D{Ypq@yq%oS*5e|VQD7ndt05Od0h@A*ERO@<5y|yEt8h3%jR5fRuqj6E@ZOB zHJsrD;nq6@E0ju=5*BGz6)NoF_~2nb7RB_Q9(&=5gl!(?XR49J^7gJGWjOl;Jl!Ts z5$_Z%?4j1|JW0FPMpshDbL)g*SA`8Z7mCWQJ{=n>1eI(DSE^s8*e%8b zHOOYR?HaH|)W@#ONws8xv|rMF80eZhJ2!ky&zeN9B3?OTRkRUYLoV_!`V?my9T|8SxKvUC2WF_ zKvUlxw*9)dxpUF@WpBgs$KT-(2>t=VKOp#@2!cO6_5beg!2H8&?(bUe??;dRXu1Dr zx&LUn|7f}YqqN+&*!J5>@SlJn%Xbiz0RRDv0=EGJY`}*D0Y7=N{;NO&0SdBWSn>qd zgKU`o!2$tp!LEo1@zlk|uRgdqtH)bw#*bz_FkNWKu3{cbnPKgUh0)I9aYoBBblQBM znUaw8wpelsPym4EasF~KxcQaJ-`1Ub;o|Dbd%;uKIxTmHn_580Q7E1^C(lMkI?RuV zT7+<1MlBcnblt!{yket1rnPZu(sXpXa=xd=<>HvPCf-<&_$&RJTJ&?`XcGvcqzo$K zXH{BIu9R1ZcpExN=#1y-Z_ z3=5ew=SAlSjoJ;dE2qckIefi(`5`syl}UsFUJx!c{hR2!uwV8n4bawnJ@s!i36eF!Dep@$SYQ6e=9ca-iNo8okQ9lQe^f0%e8 z%9)Duj|y<>cQ|c?_!rJ&!;!* zE7;CcZ}@o5B0N5FmNuv1E9%3$;N0wb`l?Mca$f}7T+y5Ctk*U z73#-4E~8`^0liGUw_mMk6n%yE_~Dhw@4BSBcjETtVQ2bFm2`Jr_?8Afb1W_-B&hFb zYy>`{eCIZ<{o~jI%MWk!zpXM@zB?4jfR94|{(>ny0UucYSMOKaOIIbu8JwWuX7=Xy zm?Qx5Lp%=zz$mvEHjI3T_%k`EKz|AsVOUWt3~Ci4rMHkzf=CQSu#o(o8%!bWqsw)- z$qS3D&V^ed?3Az`%qL&H#_=sv6|mB@+{vCt#oJ@yll3q@;YY?yBQ$hG#~NvvjR;6poWOKG7uXLS*+K5Je`~ zc)TfaSE1q*tGXV7ZeaQjO&8kSkl8A z<>r&gm$JiQGPM%P7frLD!WlO!i6=v>o=}aAou*1bFkvO>4y;jRT7`f_upVxQ>_b7o z$8~ZxIiQA}ahjz=xaFFD3WW&~H^{}9N;F^n^3LRZuS)UE07x6xA-xprCN+Fmjr@WM z_gR_kOA$zNb?YRv=&cfhtu6J*&t_+>GYgNr6|Z>Td0Z&(QEU#U3xubuFIa6BGdANu z9Fu9J5LUIsD??OU-+R2eR4ls#fY^tHsGd(fcob-*6VthjOoxoPDHnPJI5`-S}? zZ z6q?M2-vi2PLlYf{_^zeNtR%Y3F%sl)y>?E7q!ntjBqczi`1u$)(#U~4i|%3eg1=Q8 z6lN5h(&VW-03zMWl?sKenyt!>9$!rz6U3(#$kg@61G9(qJn4IY0_STIVB z3=)IbGMeNyRDnox6zXgI`UtUT`%lpKf-?0JAK-L9TnSPSUoue9pEQtQnn*NERFT5{ z%w~el?0fb+$6%r&SB4>Sw5jmMXB!$ zW<{oijt9R6f8~$S&LZ!dFY81Si0yfQq?R%Whq(?lJAMq@+sG@c~hBpxz8vQSFdb^>c6tO`pEE?*Sk5!UR&<@-ss-TlLfR zvzH7>3!{rhXtFi3xw|97gPy>IfX78H^ah zb=~YT$CYQ}S2Q-x2c)MW)?7NRJLjf(XRhilXwf9mqMwBI#O1}V;SD3{1SgcKMyr<9 z#+(@JSnTBSaq)%lMeyBkacL>?Vm#Hqg1T}!pF5b^T|1w;kcHuZDMt8$_!>qOMg@)! z350+N>kQM;2HDp5oQQE$mrQFM2TJf#$R&UWffZRB``qyX1072-#io0mvYWS?D-6AX zh_Fy+qgdp-(RWY6B5)*eTt$1Ibcswnkrwe3Nf41tP@_|?`Xm~z5e~@Z#UaAS_9Sz0 zC^#9NlMGtfTt-~kW?(4<+R$&yp+w19W2>QLJfW96Whx7vmTE`OHnzhn=~fAxRyE+ z3nxn<_ftozvZ$OlePW!^CqIDk`S4TnC!2o4-hRV5a)2_!lrM+W`Nq06%5A7eHa)V);C<_3=ax0-W~b1qyLUEp0m&aF2b zs3jSw>&(0_UDPgF9oWy>uWeM_Y*EqIwAVv3k2H#`2IW^aOO#nWnaKP4`l~NqWb)_c zub#DAX&-uKr&<@Rea0Xopu6Ds9$^tQ`Mf)kvn&y??$ZCbRNOJVk@dBq)znAVM|ewY zFM9Y%z>}Pw_DJUm?(r%1eD*lD_K2A7iWU1F+pEPRAvGK5^`|f##GHG}J*PxF z>Bu}Y?x9|V>y%d+$8X+iglc3?ew++>^P0`vQ_6E;{n=O=;SeD`f6C3%!|>yzHcB?9>#_3|H@c!R~;)un^oJE>$PKhU!nFX{F_*^ZmXFWjcHH4h6H#7njNjMW&^k z+T31gUd>y9R}qts8q;6uZhD)q*X&p~uiI5!y<91I(E{tWcCLNFIDg#Wwff>F4Iet} z-uX5|i|38bN8WX>`KuAQ0yG`|0S}HVvn#{Rl`Kj`S(@}h{*tSS(bS9k9a%!?dE+qFQ-sTXHwtT$&kHC12N(ZjO?$fxy(#r6FTX8nznvWY$D;N}=#alJ zYQOtN{SOwk0ZPM`_XV)7*=!2llfY|OqE@;^k%+4onTd?EU11nlBF_@N5s5Nl7N4|X z+t{Y4$qD|nJVG-svXu#U^X!qwt`Va|fQAUwd=ZsFCNBNnppDd5!ErFf_WA)se7E@7gnbCHzPS^+}+x0&}ex()k&T{ zW~CqUk*-r5Bp-Y1C&m$XWUs)NIu#Z-MF?kZW77Q&y;(LYw{c**$RIOS<`^}qIqlF} zrfQzAowyz8VF|xzT}1j(_yqs5{?hBuoq@ar4_FUR^{{L43Qk$uv2@X;DYKO9XBbfS z5=*aC_9dR%MRD{Q=|6MS5R;vfvN>%Cg7u=9x?i^Jsv^JS9(mt%etd36jwYjDBLd+~YtVJRnP@13zieJ^WZtkTaP@qmzMfg@7m9N8Vcb*K<7AR3!Fs zLN)L)mjc%`WxcYi?q~g4<pYDgcZpSf^0L_7 zqbYe4kAG7&0r>ejYhj9fcK?~)p<743J>GmUd>97~~aTSvTh-`H4YdvjdEsPPoxlqj%f0Gc2PT!K6veW6Yq zd--yZQz3{hBer3^&p=^7ZdOP^VTydpSQ4iyN!eiCWjbk$(1swBQ}CoSPr^9%ylfAn z{Hk2x?5tQ}##;t&(l_DU_HEOZ$Uk`le|RXcGqeAA0e`$&KW!?%h2;3_{rkJp=9{Ye zHo%tS|1D(JZAd3)aF`~rI!Dsn$PpYP>zl1l`}SDz_gGpifA@>{c26OFCw(hh({Itc z9DjuEQZaULG`F<@FajA^{#G9xO6nV!{0$Po5xee=P=AY!0|ama!Q1G6xwUQ9aCcJ@ zdBg8~qBFX_ec1B4aZHozLJ-PYaMWK0UQ!ScjDRTxg@Aw=@nB^U{yw&7NGJ)E{3U@r zGUPpTLH~RA9(4p|?QpJuLi;(wNV!_vKReFzq>e;8wL01c!JmopU+<>06cjoZepN|3 zPg7hQZ)WGU+&1$g`vQ&k^<}kFt>2;K1|(o9t!vq) z#BTcvgu_MOgk{f;tUBZ?ysu`KZ3^ew?M-#iw3u{B&vWv!i`JeX=x{$bHajZm@0nE; ze3$23b7}U}`xM=Mjh>UBZVo>qv!*AVL8vT>=G;(7bvAkz=G6T0TmEcc!yz zoS=Q5)!oI2>A?^`4U~f5t?B-HQ>5#jiVme2Y|Sgo zxaV5vFnki;d|KO!GErA@FUmLh>Fl8J$r<&?9iJ0K(V!7vKk&tT{9a_mM|g$&Randw zsYSHlGCZZcRvZCGYCadb0~1M?7>b3&YhVWf6^R@Z9Lc98DmZ+U=G9yW>m&*_?Ca8E zb&L8`Q}2^u;mznR#|?avi_M5=sOaEXd`4GxZHktv&3fpR4>Ta=H3luux>`?VPvexv z${FpMzyi*FJ=-Aa(W$Rak2EIe**Hk6%j%uogVf$si!{txFTJC2op#SxZLn2vY@GhM zflBoJxK9Kn=!1~;($c(~ZB8TkN4L5f1L-kkN9*K7OX;rG#3Dfgs|XI&BBzDd^~s%| zRqRVC?*2~76|p4Lo%Ri#ht7Jw=SquDb4-gqJb$+dD~U%k^s?J74%xu?6je{wFPRr% z-HJ#pQOgdZbD`(ZSFO7=(x)#S+PRqay44AR<|r{SU(KC5H84n@k^lxZFiIxKmdgGI;8b@RC`>{KvYRxSMjT!`h1=tbD6NV4DCO}^r7{9h{zQRvKy>l}z7PQv6H=MQ zVILX*s%Mez5~YPgSB^qM`s6)hSJ?6m9AaWv5ti!cy=J$$$SD)8F@*ML9#HIfwDTwX z%81LrzE`Drc=_A~MDiJH{E(WqikuB}q-q8!vt&r&(|{ z{_yLR6J>LR_w#G$D{{qdg-wRz`$PRVY?FAiSQpMsWY_YSv`!UJb#lzua!Bj~NTqM^ zbKlC^VZ-fm1#564F}4+r9sw)bsGbH;L5yG`Q3F`rCSuNBr#Z#s_1ZVdh*w^w35v*p zB!nJP<15S7C}=AY9idJ<(OgINKyCKt3!b7qbU(*G#}71Cc)-gXmV|-^)E>JinlA=yJa-xfIGzQynq!33+q56-oRk zt_8xzca=;^L!aBi5ZBz-ySfzn6J%!*{^*MIp@#=fe9)vFqIdY@Ia#rv^r6Buwol|d z+)h?baX0aW9-1Pgiwm5^n$9~RTD(?4-|)u`3u{MpV_Gs!XKY1XRv^5?2CNd%wAV`S zjG=}rkfkx+6*{T1a+9`vhF@`1RW%K3YJ{cLD9tzPF4+uM(w?JS#@exL%PsN?@yGwdmw3)|h_gXk_XvDktM6SKr>e+-3%^ks?xPY%b()V;(LyxU7~u z5IjQo;=#^&=OMjkQsL7tq22JSB^KrzWugAbM8b9=Z`40&JQB3AX}%wn!^XxY{I1)c zSooo8=IgAwkiA>IXp1|ZV5Kt)J`5;{maD_4dG^_}p_JGG zkG{47!*f+uEEKbBgC(M0>ltXxRL@i20E?&ba0xx)>S{Uh2*pPAlao(tjqXQV1U?Bp z2NAO-5<~-BjD4#0q7KgryT;-eR4p6a&e#2-0`*OlQJ1(NVZ z{B2Voa~MUujrXpzjhPJ~`UqrfhH~JcuF%NWvk3}F^w`U6fa$lOfoG%3i*+oA9HX!y zvU;o|MLy0q?SDm69*H5zi)w#17m1l6CJ}85S#|hWhI9}jtmZTs{{AAT&OL{xBp5yt zPp7hCsDP4>@^T-CJ4Ln1k+QrOayz~bUDu!2E1DVnNdJ-A8{;@@mlL9Vn~V>4S1#R+ zo$QkVL=V|wBZ(Vy>^o9vp9iq_Voy;+ZqQ#yI?xUAyvQyu=U`@Rm0KA-1u8S8WG7sA zreCfNP$?duw3xmf!R_Xclez3YrBg+0MUw7+N9s`1URZsGR5X!RscgYVWfl+mpz+qz z$fagfCq{e~M&iXwIda&CIwi@buqph5W??bcQL|>QyWXBJo>$^hOPq}=q`W{gLUyM! zo_uC4Q|XiJ?lHso4)y7KPSH2eEwcH|YRn$?)hbsf$w-E#HEmi{j6~RF^44M#mDWhR9`Fx%P2{WJyyM3d9{{f&?;`+wvBcOMaw|SvC*rR zeN69iug|xwDI<5j_;`s=Znn{T;O9wHu9lJ&1<)xTkDj|fJYw7_E`9W1R$nrEJwl?i zov={nXc>CeB`*poYuj_B)wF5z;rqulPC*X$&UoLrT0132rAkylh;sK^ekyPY5M0Bh zlaYME6$JCx(1l~iHO(sKF@4FyMmqsvXDoE-%P|;MghMF}Xi9cFE~1e>;MjpEk$7~@ zIXWH5GK@5J03HTniRcq?_%CzmFk-1XrYu;;kLYIRF8ii@ZWc>LVA})=z4~7U`8*w9 z-$3>>+4Ql%=@d1@HLMT|X*3yY7?#<(x{79ZrQ;@>Vdh&MwPmW&gQVR=SltH3LXJh1 z4+{@tuy8xGl&oyx@b#7|s<{_ULRb%K3B3 zkrr!13(_5iR@?lIByA#_hJ&;Ov8BAzU~j@9w23{m2S|L{v%Ava2~kHOx3Im={RE zs}K&Xbw|{Xyq%cr%p0FKaEsFqHXRvRv4?49ViZjk@3XhGW{QanxIUR^4!Q_A^@ZTA zLt#&i_Ci`X9rp*hb5quik*VXdklAb0&zM!`$FM+Vznr2dBA}6Q7B^)}Vysswl~r3- zQ`{|vQL;AHJXQ2ZW!Eu3`!Z`5`k|mJ0QO$CPBoE?ZoaGKE)5Nx$A~sx*4_halP}xR(iZ){h?50WmB!leGlB0tfewyLCUexlJJUM+CN}msA z2kPBV8Yh*c+~!}IK^o$=2=nS5H?L;Le7Ns1?2xCafQ=Way5*R6{xr&_O)6Wi9-y8h zwf|x4X{Rm9qPK#Dc8tr&5`~sc`x=x*O}C7&IGNya%8@GRBBmu<9qD; zU$>0|MEr8*Dpb*)mU1P3%J5#;ASTl0Dc=s5X7}fpX>as#DC}!I+GakeGOz_<8*e9_ z=+d~AocN^;t6oSFXrv#@T*|C*Vp5oq`v4Ek%_6ZsH{~f z&r}%R>)jTqS@)qytwJHw$#WG4Y>Cf%kUeG0{vnp*5l7LWWZt_mdl_j6ewrwK$;X#3 zF=L>6_p%%Yt`Diixh}UxyBYEsU+56v<94gjeAuGeb~cnlu3mnL+wtsCcJ>3zhy>DX zP10@&nMf+BXf`qh{6HZ^Jll<;!TmVC*<&5+?vNBq6<+&s%r7ZkB^{ZSmI4IPA*~Xv4%uUMtaG%MCTuLJ zr^SpWjX&6X#!USQXWjtP__0YvG=btb<@TJeKrul7kdjcAYvyYpOGT)|}&rD)e!maAQ*)?V7;ePYXqqN3JBqlTK%bTH! zDS5TSRr0-)hq&F$nt-fYVGBu$C>nc)rrzK zERuHP@lJBD&ga;xC>lQ$dM^T5vJJbqsn4;b3AMmcAwEcnTxy@gGvi(vF!Unuf~48r z+D!3f;=e~TvRi*t);g`cn!K8{s=Ha=wy>?fu34m&QmrzvvAuWb=K0jGKuDdMC6Jme zrB@s>Y~G?e>2RhY_0UKpZ}9-fliF4zCbd@z*lbmmw;Rs8)+;5#z^GV2{m4PP9w(?* zZy&#Z)T@bqE~d=kbi#OX7`V2ICfljfCR&T>(U;2>EnxBTh|0&6CTi~frp6vyX{Iz>3pZD|Yib zylyn&{fS<~ZyDJb*AsP^irAFm^<^s7OqBVq-{J4@3wcGnF$(t)=$$67bHr&$j3ebQ zA(2;jv=0h=75!PsAp%zWp|>@{Go2jSTtXHRT~Oj6PI%)AT*c69PLo%-zImZ6BPow=Q6*JpN`5q|Lap+} zuqtPoc6;*%d2Y1K=WTV5@Ih*HN^Z#{o0;mq>!|BK+WI{`IPO;q`qTOZ&x!pS@IHSv zeW*LZtbc6$vLS=eU!XFG5LB7&H2Inxk7@o(e5g_5D@;P)w$P%^H0SsE?1V~u29JGq zU6%FqyYsS;ax3)EZw6vw*~ker2Gz>nrdrZ4($iy~pm`gim>+pCJ!q&F%?=@dEs3Pp zz)z{zyj`pWuNFg5T{$aupAQ1tfu&0^#vrWIPi1c$1d7MPOm;~-n48krQ(91Ld2C@5 z*Z@!+d|6DHx(kpp9<>uieKuYh7;{_F#f{RtOtA8akNUIoUdZz04d9Zxc1J zvx74}2&;P&Io)g?GJqrgAoR9+S z&jtj7K;R4-w@t|CTZ0`#73C!aoeVb1F>`5eS&j!+=UGO_Q?VE_Wx1#wj}fIHMq`gY4A1TU2X97 zUnZ8jL?5?|{+XxXhy9UMLkXNL;~TSYJ^${~g!~gu{5%kdcS8kE0CM-(j)1!-0bh!m zJ2*NCndv(KIKd+#rT_f`2#yTTC}IOn(`9Z0w!=v48!FgZ>)ZUG{4Fa8>ksE%DsUly ztRg@SoR5To4Q!&3ch+}s@&JI7qTJnYufy9O{5a$0xmsmVb*V!Vn%6OqrYGOW9-}< zj7`AYW@STU`s)vXjg=J~c+CXxjRs<8zn$i{e*iY$X-q&i4zRiUCmM)}lLI^xexiXd zZb$uR8W60g`i;iU2_EyG%7O340yeb$L}OxRz4hSyna08ao}j3=XBsQ;_jXxXZe!N{Tn@y18>r+L8ryBMg(AwwS#P}pex|W-{9cX~_**$3J9spIsS9EUGw@d$6VvT${&O2_?6-kRf2Of>a{ksA zPG+WG%K@2Ke;;#Jmfy#hjr}%j%uj6qS%GZ7jt7|XJMTG|!1(!dT_#Qt7$$$Ff&0So zYdIi@mHk&fgK3<&#OI>#0?LpL^@5j#k`+Q+%`|UZv zGmYtQeRgut2a6AfI{;TS_W)xP8-P*4*47DdXX^$dm$;3IE!ZgjEhCdK*euS&X#i%0 zp#hKud@Cjv0}zl2oIL|%!pR9T0VAX_J0Ie|E&|Rj1%^9ECot^ZfgM=HfY=bp$wg#E z5pNs&2BeGv&Q4}v$xJ2cpl@Rd5H_~5(l>T+qW&39e?n#^aGx~37r3n{Yi(l=jw^0r z0v58Y3?K#&^$Z#Wd%u>F(Gimk=`I23 z2EX-Z>pe~pcX6^=+gIYR4po|g{M6PZwP;&<&4=fI? zyIRk+c<;!#D$C*t$TA0i)e3eF7SCdQedj6G1Kg3`dZNpW`Vb=S3#pd@cVMI>79!u)RhtV zCqdT9(G64Y%J_Fa7~#QCh^@JdlLwc3U3=Hg_j33X#M#LQ1lfssei0W(XPf2FejN);I~GU%yV*g-Ab82=hb z(SeUq_#YFLkoaqhe=+_``Zwc$*-+#kt$6;a!GE*h(R^p&_79!@V>m`0U0Vpo-U9rh z03*+9sI9e)8zaAv5FaCttP{-1Mbp{b5=tccPfjwnZmw!j7g;95NGS;&8VPIWJi-2iO!qqeF2BqPPIvA)r#(eoo+ z5&!J&3cB*_$l7#oNu81p*DgR%t?8?QJURNK7nK|k3$CNSt6RA#{5KPtDo-p&oEDF_ zDJrx+F#Q1iky!BL>-3q4ooKBR6Wlp$uU&h0SttV5-h_)OqQ5N_xgVs;1K~-nVeHhy zLmAsNO#^ZDk`cSyW9^rvrx>nL5-d~CG^eQKE~cqNVPD>CygOn;s9UTE9jR2*2!~%- zy1yh&%R;GC*g$e@c!PF|V7F#!x|~H;SlWQysHGzXu^hlM>1qfd-rAc|Y{f=}oy;ai z!DgqY}~g)9@ek zH_UKnb@~6HpCyE1$KT1%82`X)7m|Wdpgj<+FH}!F3RzAxluP8gv0tRiR7BDcAEQ=H z*rO6&>oX!^`Nx=2KES9)mS#C7ZY1r*C)lZR#~&z!Jy) zq}fNq+H*l@Ibg|v(Fp1OFMBMRV8?BcKQgT;%|pTV=3vo` z{1AKtwID>CFm*9x~_aOWlMv8_dbedt`NbZ`Io+a{c~i=%K@JM`f{ z2Qfq1v^E$w*kRm7SE>NE9HAf1gb4G^u?yG~Ub>88?{^(g9jZ{b9?k1vG5Y-9rMUdJ zIREdNuT~@2|EJ%Qz8Ou1l6uZ4X0CNfG8lt=v=49=itzovXO#b8$$z-9r?tiyxbk=V4Kw=6!0fI&o+$NPhU0u(l9PZNfye8n|lbOTTY6_JL zOP9+?hSFhtxF2PlH`!w~ptPkISbLscn>wkZ-cZ-x_*3YvHdaHO#nv*t99|daeRQP0 z)x~*_l_$O>y&Pbfs4wAL`-4b5h#bR%IfRf=3_*COJ(MUG8ETFls)958q=>Ob3c_5Y ze77PNe3!CQOb)PU{CK~SSURjAXc#*-YM4`6P63cMyU$LJzKeVy2Z2!F;%7hj&x&vK z@G0p{Z#JcGN~AueUtU-Nl~Q&(;)(7y0qL@6^{Ny+CXm2YJtqUYuIhWrPEXf>FSqh5 zfV;`J(a&i|!Q&AzMgvFUJhxJRLTfae_%TN0Wr zDHJb!Ih}@C4lo%g(N=`yKmnd$CJ>L+WYJT^2tPbYCN_#jz+U?S+9n05oZZtEky6dB zSglkc!*d*QsMynpkx;#(x1M#>w$ zAtua1M$Ol#l^YxNC55_|63uDhUZ}(jViVwsV?*e7?r0?JeRKKwMp=&$q2Ipk@=gJ8 zaW`PnZIH{YP+=q9`LF6Al^-Y8wj*JyJ5_Sud#nhH`zH!}*S$oy_>#i$e0QMpCxg#a zuPmNM{Df&zpJyl4{Yvj1bH=#K$BwUMiqkQn8*P};2=RYP#m+IZD15XC5Tum<`UnT( zH8}A$3Xs&bu87^Pc#H5jj1`}`dLpmqKR6V=3scYH!ZfMjv^744;LNh3TK_`DewbnP6D>G1q<8zG?s9e^+s6dd$4+$xHn@XyhsTXsr}vtoF6YhTuc(uPiSy z^M4tH>qd{p#m&iAf{Y2gmdcL>OYwdv`kyQMQYw1AkcKB)DHRoeuy^scGU(v9sytja z`bR}Wkx}*1*m3v&&m8_s)*iu6P_?vw(8oP2hy%L-XAX*UWF5jyoGp(N77$@YaSrn0 zNd+%DHAKUx_v%=RT5JFccfu!Z2*Q9sy-z&~u%!DI%<%iqL*IqMIx!WeBxuy1ipyXr zd4QPCv;>RLj!uGFyB3bXWHucGTbCEwL0zRf|aNONlUfGSfB z{hx=PC&+wPZ?-qR)wmPxLcu`rCwp|2Ft7J{s z39>RZ&t5GLuumSsg%Jn#P6^XYAS(L{BnW+8U902}8x>w{F>izAh(%9IUV;Zfr6Gej z+BEKSuyiOG@pm=UNX3BN$fxjiKl4Cbb(}&qc@@m`y6pB3}^7~5B}7;wr$DwDUYIig`!;3~b49xJ}F7#$-YF98Id(1-3g!$MkJk&AtU0z;qApG6Ufu>Vvr7fUQ_4o6C3rT)O#Zm=51)y+}xuuuhZpS})32Ie_#7&#_V_!zwy~t4X-2g)HedalR zsq37TSg`Fu`iuTwN-FP&GYspEJxG;0G}-L5FzYzsnZ|#AZH_qoeSemhSUIs4sj`kv zW>VgEjK(6x%J>5oewbJ*%Ncz7EzDF}TvsJ#BQZ6XmB&ylsieCQc;tYAT--AWm7X-; zp-3S^QTWt42DrBOq0>%&1k)PFFLyGU$Y zs;}p)A&gv7LF4S~!PHqJBy9$aq&k%av{5W~CovGB+-BK>f;-jKocT6Rj?sO}IHy|z z`BG|*$4MU8LvK#rM{gPo`qcMyHATI%4~4mLZ8RG}R_41JgyevRL|0R8#9JrJIeI3L zaeqAz4LTAf;-9$@g+UAC#GRXj#KU1#$yFtIOmOI~q_!7C0GbXR`+q1@MW2IRJG{SJ zYD`g;sQE%H38wG4cjB@I;}<6U(0FxGQrxeooBvjKsVC1q=Ki2dUv;RD!Ck=yvCxHr zS!Cs@K*K1$mT#rTN$$7_2R!SsN)qDQJI@qp9VSYRxMN%}uebXH58I-0`3!$|owPKT znGxU-8khXVMAOD%$lC6YsuM7StPIxV#pyP9I+Oca_PJ*t#v)}xk_rGsEbpj{J`+5c zgh$(hMyH3uS#c}PR> z-Sor}Z*7cZM`EM0u^6ahU=Qi1)Z8GJHd3E{GJ`&K2~jejY3YZ}4|=+?-;&C|`v2(y zMO{B8Gjx;qnq*$tq~9J`mQ*mFrDCV1(_(`d;VCvfto9v|SJGIhUOwW?hoa6Mi)?+y zwfyZoy%l|Yj|vQS9vo>dL@5AtqUCnFml9H@EIG~WMcWr-WYKJY!am6w{OnQ-Utz^ye!s@dKsObS4zX|8n#nc<2Nx$%W$4`PwbmPbAn1N`06IkTZ} z=0X{g!eM(v*M*;C-`4iEW8aEUa%c zsOjNpyisHqs?6|3)VDNbZA&Oj#xi~+4q4Xw#f~OZ!N>5qVD}2&$-l~YfHy^h2L_nNPnrgja!WoDfBE?Ni%`E#>U~FsefW#-ePfziQWi*y zoj};$-lLqGe9m%QxYzgLxtrZDR(uZ9z}eZ<$gL)|ULd%>!}E{g>~@-rCTCmTY+?PM zr;g~4U3s%1+_$~2AR5&Xs^6Nq_O;UPmK|k!r(S;dHa<~b*al#?m&Cslt{hABedduz zT3>3N!dq@9z1FO14vnW9J^jIbpo^)6M1pI<+g(HdQ)Z*gjw4mJGRrHjC4z%86t>pG zUG5t5cyG|gaJ;*TKRD4PDo)eL3%@@v)C(}L@Z`2@Vf)Ua-FPmyJ%jB47%n7~6-!9M z3`_&-$UMc{WO)CH|IYt5r{eq?R7E*(*P0jV}2obtu1ZTQZRici= zn18F4k1O6nQjJcBDA89F`UK(hDa)pNq$-u*CasoHr2?9!VnaZUuAEI83+`j&qk>wv z2j8y9Cj%|U{Zw)A1d#DI`?H!`ocpn?U~A#*)nFEN$z8{cMOR%MH;LH;DdN;Q4_ zJ(-M;{<<69o=mGnPu@BCpZ)tSx_bH+`-%j7(M&Z}sFk`usQApEy;4I=C$1J>@E5qUg)H}Q^aY$~7XheO019SKqI_-M|DZ+ERnBRY5$hl%;+_1ma&6T5QhcP_z ztr^xflIW8gvs>&T7sLFqo~ryU3X(Z19L~UjG$b}^8v1Gi0bd=AFB6}%`fAGveQCguGh)@dJ(KGgGz`-L(evd8MZD*k>eL zDaG!iv}V1^1wF*i1vb4TvTbqF9DL6z44UFKyl{lE;b;^Z>F}pFhu$M%ryJ#fn|6H~ z(ONu*9IfRO79}oc(ynt!ZB(NA-d^&X-y_Pa!OduVxLp>IKNQas*0McmN^yevI23;# zB+R~k+PhwPZ}hVG5xba)ok=E4;*uSzI%`r?sy(wCkL+H^`=q7aMm+dC9!X$27U6m6 zX}y$s*lPu++;_7kK~V4aTKQ>Hw!eA-O{h-&U8-%%{ZZXBoAsh(IgP+MHAp7dg0044 zYH&T&*^avB^<(=lAj1RMGEVIL2&G`}&XM)tfX zniIG0SjWaHmB@{%Qd6i{sDn@pZo58-SJvgQVm3BnV?Kkg3%ze|m%MAq!yoqnCS)ye zg!puxJCxdk4Xb&#_BCizxLTXqjABs7%^{fg9<^C~EH9WmO=mnuVa-E8fNsA)ZBd)6 zHSYxbx;3h@{DX3N*gctE>9gLv%Smk`pOEgnhfd*D80-g=0M(00%bwy6Gu_c%KMq@6Y zY9G`^{6kk!q5JcpT1=myFAh%h@^nv5YMWLy38;>T0X<-XvxgQG67&_g{u!z-&%-Ng zDJmQ_WGIz-z#{RD#nNF4HZ4|#YK1U{h!PLilTeQt!j^TvJ>A)k2N!$6Jzs-m4v2e} z!b{ysBcty%g+5=8;O~~~JnRI%@aOG=HnI%;L zu+fh41@f7%ywb_ZLPSN_SuU%12rF0D`U8SAefl{P33Szzu>236IlLz#N4;+OO80RRWwnEPEtX(s!e2Ag*DCBiPt0 z>cj|)INcTHU!I{mOE+yrlo4TNdudj(`SGQBr|ZM=3MJu^FU-d+BQ9af+m-g$Q*&cK zGb+vPJ|15Rn11ozbNUP(;r$xi)*68bD;`qRaO0nFTyAw*_SsUz;pt1QDm(HwqQPIrU+VV+4% zkj4hMv5&Z<`h$O*iJGqjqaXHubWF;q;sw1wlkhW=)GveKCj8tTJg|Rl_WfWWgsnac z(Zo1do?6MaHzvr0!4@D*1E;&y+;5Gt%rdB3w)q^tLw}cMo4jqM%awhlxx*TIofmq~ zEs}nk1Edap8%)6sde4zI0+cFb(7rCE@Bn|LQ93d=)JxfACoKC^4yly7Ifjj@QNMYYie9I;&gy!wiU*<4 zr^pPyds62NP@J0HDi(;$-{sK{HS(oqKu1>S->#+8%;!f12H+0y{Ju8N>JP5W#t9N6 zKdju$i)8r3RXk0XA0N7S)Y{*%$Wh8Zo_ffk8Z$9p5a9u)TODI3b8f zJR%y#g5tcc0z(Aa^7Kw^;XPL2NJPwg1wa$V&!4a@#x6Ykr=3~!bf+lZJ?j)sYGUb6lpb15RW;kwYb3#svWfPQ1>)_a8;ixh-E(-lcV zu8WZ3Yk-^iZrpV)-SF?hRNM@LO^OWmOw50dc>*jrgUa#_m*~G-KWyL|+Hvf|O)NK5 zwv6y2wvK!?cfx*Nj>~!OgM@;AG(Wy<^qiwMS~3Dage~MRKPa!qDy=6!jNpMIcYNuS z_4bFQ*ljN^V6n)8C$FQuGFoBhL9|348yF*3(I1`+xZF9ro9w}zTLJ4qHI~|^_z|vRr zs)lQTMIqM4S2V;07A%S5K{vBs?Y_bz-P;l`@i7*yY zIqp=M$qMQPks@HHE(N*YKS}3(l72%~p#zi^<0pIfA$mgvY5|0VpBpC|MO3_wW6IWu0;`1|(KT*@;fe2ZQs z>a;?@(#S-xe|l&^1ng4X+qJJcr`|%Cp zymiLX4qXG7T{bjEEkgWYt^6^aU zdTcn}qfN$J&L{d52?N$o;6(69y#h6`oQID=(d3=@S$3b)-Xxb3H*xYN7c%8sGU%CH zaru_yaO@cbElK*Bw0fbBFO105#=}r>E0p~9yBF)HEky{kgY@r(*al~S-HU$yuh%J< z58==L(wY9r34NNlilUI+4NHyxCP=gIckk1{*6)|;m&NK)QN8w`s;1?tlnBlJHsgYOUWtP=InT`m~0@@_cgRiw?)gJ*U}UVa35s=R~-2KxQx2vu1-ie8QMnGQAoIATg{85~RPcqRwP^he8`*1UM-Qel(e zDQl==?{(FV7OzI~`<3kXH0;SXZ~=HJQ$4O^+hxsfV!>~@O5sr(=ukI@W_}G*Dym?9 zcvF>QnA_k;d+F`ixy1Bg< zn@-QGS&N#vmc|v)&Z0dz_zr8kAyAR* z?s3zb5559^eq74=d&d1LXUw1zjwQjyZtpijz&3t(XMJny(}Gaus(+$?OxR6%XYZp2$V5I_n74=$06ZH!RMOF73ir{`A2|1>^HaOu{utq# zO+wdS zd{G3m?thHcYV#knif8Se74(vGej&ySlt~LuPY&%KfQ(yG^nI*0dhi|A;-l7$vXbjt ztUiIwTmwE;m#5r{wecx(MhXX1U!}W(d4+& zqm1srrQS_v>tY_$VQr3asPz7i8j zKW3+9JL#unI(wBnHT)9j%Ts<-UVPDZNX`(@s!ttyk2HUahG})d6Gu=>;}kZkk~;O; z3-%OftwgV4$@w?mol{F0wSfeyb5FGI(WpOi0sO@Q^}5M*^Bw%Pt2g==DE`1|`{px` z9nRzYhGzDuyK9@m2?1XuS#?CBDl(Zt(2hfF7N60mD^*PpzlV!iQPf`wLP z%h7dbxY|`biH+)UdGOY11-W_87l=?eZx>7$mQ8zh8HM83sIXk|wj39C5K#<+S;yT- zylWgdK4{!pz0eZN{Ha4G+d^l!BnabYKMF~RT}N3T*?nW#vSCjj6Uli3ziy$nAErIA zY42)X>-<1P)0u~gaBwcjxfdL;fU?&7mFp$-j<_hvOM1M&N;#55WawSS2Gdm8*DZQ` zPvysIeni)a$rC4!f7(w8SC4mpt$wA}t@KC^hzogOW$$C&F!x>vwr7M8&6UYDQqV|h zZ$$WUH19R0unZc^q&onr?_#go7qP0Xl+^owJxmh?joOx6Dhe!yqFV<8ByQ0XQAHdu zy>`o}JlBA)A8>qis#>_TCAs}oDtq7U^7Sj|miyKVRTMswd;#l1+o%R_TnhS7*e4lL zz%|=bQ=Ux`j0)E6btNyz0Z~xO=ruQ&R){(Q!b zQ(o-0=6TINf56Lu#NuI#AoXdMNp3whi$C$xG@>jc*zlLZJSAhxY87Z|`Co4Xup1hF zciCk|#K6`$1>=365~LL~6xGwERiRtoV{jN9MR+{dIoP+dC8X@0E=*-nRH*r%-GZS0{pb$sW0%ur)^)PS-d1d7s{A)lw{tQ#ZnWm=RR!F z^#g4jUw}uZ?M36jBdKkL6Yfhe4I%q57um7|R+06}&wlUbGLjj_kUPXr9HK=L+F0O0EWZl8Ds7Btv+?`sx> zq#8(#ud;~G^_oTrwuD$qnr;I*u{j*(-_kZy>W?5eXU;Vre-|&k7rdv7bQszZW4cmW_$ow4vvv?hHrOeo< zxO&`_C59m0MWX~ZvmwhBk#1GSN7Uj`tc19c3Zj;pq|rG-G0)OA^}=sFK)yH)Tr_{e8&$gyjahFeFz*HG8gTWjfTC> z&|2-Y>5ZX=>&D5iB8daYT#sD^0O->HHyRsfHu;r??r2&BRMnf5te7a z0e9g~el^#@8^IV{FO-dblb)wYEy4K=0w6Lw{X) zT-4Jt-t@+}qPIC~*?pkfjwX#}ZYaCQ>eyj>MiubZ4vHbV1OL$(>q87{uG`b)@O;Dw z*V1@*1Y^|(EVUm=%szap)YUBHUwhH-$azKWxaTd~6^`s|v~az)%3D5IbrbJ(2^RwD zqRrzg9)9T#_|s~QMAMXK9tllo%}~LEZe^K<#Z{M%6LK5&EBu)+i4bj2!dZuo&(hui z|LY2pct3+*@Luntuo#-3AuszXf>lT}m%L>RpZ%fzv)-dH)A{{+eGh?J%&GO-Pe?`H z#>65Csl`%i!m5caCMe7+iGa+pFqVR+OOES=_zbWU3hLFeN3E=1qy5y##|QgytC=|& z%7T!(;~K6pBF+9Qi{guqpoj0>SKgDI@Mye(9fEukG+^)~XGBlPA~JxoI}rfU1|E|h zbVZT#e=XD4R(KYm1&6iDE~*O&ZV>BGs0BEZg*@3Ulv)Z!@-=Y+9!C@m8-%ym_wLSm z1wv$bB9SW@i!S(0cw~%Ok1LW~Hm^tn-S3~`&%w5(9#_2f@|iwT2KZ(IGrue}qb(BX z__oF#R@65M0>6oN#`*W*hj>65*kDtVtn`o6a~pp0#cVUNSn-rEDtXgysy2kPCK4AP zY4XUHt}`?`zG|Eu9tMsAyVJYla^NwWX{(Q?o|bXS^^}_mQj>+Y$~SDzK{y8#n3Z@ z@YxuFtaWyjH*rlR^Y=JMZf2fX~frMd;C$EdmEM2+p2-u{y9Ug^OED3DgzrkN;#ZaqNIaKNjI38=Q zlxcQ&P7`-2ZNxCQU;%Qk7&v9$5wj=t?;-+31>7vJ>)YbM^pD^_<{Q*%l5_!6y8>Zt z+|$8*9ah}tA04_26#)b}UxGj_SVDac&!E9S5EnYKO@&N#Op4Ff7Y&;N5Nvmg3MdLx zo|N*}69Zm(e*)NWO@%2h!0h>@0xcug->GfDYl5|(`^7+2ESa)LFL2I@MFSL-(D3ErY0s8bb1^vsI#Q-e2_h#^`~GXex0j{}{zzc-FAf!VDRSDd8G4gmU`YfA{+b zQV-VKC30nPwujiN|0yE)@xfn}>`Q`XGVyZ>Qd7qZq}{Pyau8Y0!=HK> zK+r3Gcj%lsp z^$wzl|CO^%;G)p~=IQGzhyA9)DUFNTxOvrUm) zKGWu?LgEXHi0-9o2$^eYlO8o%XmaF#r_|>8s^1R4ld=eYBe&N-Z3@?>t_NCZwG>z= z&cOC%7Wf(Z3~{ATZA%~PYE?~nmKQcM-_H6YNc92?LQM`TG_H#aEDOgD+{Dlp+arfY zcXU%`o$M;SJE8f6i1bf(It{A4%%OG#^|tAh{@cK-;S0`07d@*EAXEQUC;Cn?GoP9^ z+NlAym`)H@;2xBl-+i!t&N*r;%^AACt4!#44zkR*^o`cmZ;1-TE)F+ zxu|4wUC=#{1Z0d8Ey#-WIIDxIoZO@iQ3S7OtDf;?F0g+Fo4>0y74_kYU_Dp}?hqHh zlJH%S)4B`4x>xQb!lSoH5h_5x@nRZs6y2m9Drpt;=*!ac31H2K{sIm& zsW<};&_`H_BKwtciZT$<&_jJQ=Hv*in87f+w5Xg)Q5dv*Teu7j5^)LallF6&emGV- z;%qsYpMLv*ihL*Cm5a2ctDt!I4N2?VGg-Q?^)tLlA|c^9 z44noHPIX)$z)c@OXYvIRX0$1hkigWmVl#07*iD$K`9tCr31pAcxx5AhViwQEAgB0> zmNMackag8Sh`(0yOId$%4^s$k^qW9ZATVq?W19o2rd6TQxI$_;y?@J4a%ppHLvJ5S z4%%z|3a9*4=VzHj3YX~Ep_>HEv^_Yi`Z!DeYy|tN?`V3`s(b|>e=TCaDKNgh4O+853h2#pKke8vw(99wodxZ zh#fTVxH-44+YIh#Eh54Oy{Ge7_=(82kxZ@yrb+{)z4R4-8?Ctof}Ln{yxVhc)7D5|)Ee_zzx`;Aa@N_hGaemi^Ur=rMzCH>mMay$H8n>iv^!b znveO^ydVuHZvP&ZgUnuGE{36|Qax7|HDIuu1^ln3lu3F}+5x-|_u%c34>E178~v_| z)HaS9ME|zV5e9BTDzMn^w+7MAY}N*B(m32)fA%MJAeOiT$IVFZdcAZCyJ~Dqk8@y~ zj44H!o4&PXJ#?8?JD}QC*PRQN+~?dH(q6WEDy7lF=b+#x2t|U^8M2%{Q9p1M zXFMzJB%U9UHS{sKANTC>(C`I{=sFkj!}V25_IhAgz+H*`fIDp;D~9k}NZTK$?Ny?e zIRixF-vdr2v{lWzlzuKvvmsqC1I$o&DYq&;<$$c4#oE`Zyp-g(%*hu@oi@p7jGzKY34C)M!UYsIlc#Efn}%&a zo}dlRiS;4`k_&Kd*@;Yl=!o_%}} zCT(Q7^6u1Tl7s?44tTb%7q+ZQN1vOv;u~U>wsE;j^yXQCHJ&?Uf-8anGt-bMbV49| zUbRIE2yav7qtrUs)|4PQC0Br0Zy?%EmQ}mHj zIL^-@v4L_d^-sdu1mIs9-|xXH+qlg#Kff6FQl_xTYas;fV?7efaQ6T87%)H8X8PkD za!-q{&&@?vOVo}DG@woS<>usI1KGNSwELOYRw@Itsh;G!FQNx~-c$4{g>2CWn`y6K zS8r-`csuzq`j{k;G;lJ@x-^}XEI0onZ%1p>J&gF9$=d2_$UGd62!U&w8&Rd7>u-DT zL2lfztSw%uxz+_H%YHTSQBoFIGLhcfPo!6l9TB$=@si7%tjxyGKoFed*hi*(>LP~} zuoz)j{?k8rzi3e}?Q*P=%L}hqjE;4m{JBr{!}=bs_S^k17_a1mg8nu>Tue8+w35o8Jj zR^1zzg#wV?#k<1$cI?=`9fdnfp9vsAtUdTrRXCS)Mz)*6C92PDUQBFZ@a`MK_+L$P zMmWIcWAXj(p^qOwhrf5w6rYP*{{8&X_!X7~AcAX7M59>YpR^yRSGrDBgT>wc#fSC} zpSfo7uvMk?Z5zudZ~Biy6HYP;J}Zwjww6shQj(-XN}v=M2S7d_)7fh1xyxu~spO8+B12|*W7lmB$Tw?L4bm|n z!H1>Nwe~AK*-WoF(bs78k?K=X20XE?o2b*s;ovzp5COiAK}Q~Rhtt8`e(_4>y?1-p zq+qgNB&l(i6UMm1=7uDqdh!B-FawG*%kZ-v4}Twc<8CJAl-^ffKbCzs&g1Zb%c?KB zIp=3Ev|tQz6?)iV7sbmu!wTiD`}!HV1Uesc5vY1LaOk|rZy6Lg9s~t$jE&v}i#;Q` ztg>34by>riZ7yI(#RrzTGJdrP@(+ReEB`8%uX?a}JqCa*v@K^~8AmSr1YBnmVg%93 zKnynElsuG%1H!Qk&!UeMt}CjC@+&f55H_o5;`KNe#3=!)IWSty1=r05?QLy#xX-jz zyj?L)aViB)8)xcUQJ!BWk-JXKJh{5?6efU?Ahe?Qv=1%FA>oiyLri~8iW0PBK(XP4 z8I^f=2xsY2Il;r(fwN8F(j`JyXW$c$O?CPmf{gax8pTw2Ki6AzZX&^h2A-FSW4YDv zD3I0A{U;W#-PcxsNR3~D((DXKtb8l~g!*%rI-Y)XTDXr3arHlM9Cb3OJ#4KawK($_ zF|YZ0PIY_mfb)tJ7_{Iu!vVk&PqLIhfy+ABwdJQ|0FimKKlspJ<>s(Qu~EOTG7`~d z#9a8yK>lhiuAA+y22d;2#-*YX=HpNZXo}(ziwvkIcsI zH9u1;s@GQ|TbEU&f>V^YSw0dW8Vqsx)5=eY{ddu>7{E8M5J;}L*o0Gl@f>?T?vl;& zAiA7B5kKcoc6|E=_GfS65l|v7YeqX=rKry->Ga!FB+fKlJ+Gf<+he(oI`-BH9hE12 zUYadM8fkvh(2nt&5Q|t*;&Z-=qaN=cr9#6@^t30_E3SEx?;m353{ay0ov(^WvHh0loOdh zH`dsZ1Q$o;fpjig5bW*?E4Hx=J?7ju$iBa6=F9GO2uFcjlC@z-B^)h^3K)&*GRM?0Eu~Sgr@k+_fP@_<%h8fG$!Ts*N0_pkQQ#Hxh_jy!?V*y}lC4g;xbGailY5#GHiCPnWU(Uj{J<)^# z@m$-aQ3*Bty&lgoI1TLO{5uo}@Oxb!4vUF@EP0r`?u5)Un)iTMPC1oS+QPnhe6;rj zhLhqsb$%Qj{VH8p?|J=Fo%;oMV$-dw|1ndC7ejEJ$Vd^bE{w zrG?PpQ=lGg7UQDVPX!sg#OQA`F*W_`y@NcXjFE@KAS7$*1u9m}B5AJI(*2g?ksduU5!XMZ=In^8YOq&~xZF<{Os+L?R) zNsi(ihzC+L9}{0&Dl*yC*Nb|1F5d_vJ1TGZXZB26_d4qb}U#Q(|W1!}wrWKzR1{N_M zS(p3Wqv!8dt#ehiC&XUb;h}&7Opxg(Aw9H5*|fy+Z54`PR(aXm4R)2H0eBaiwN{ud zO%RXy9NBbqXrpBsa;2`}1DjS^vO;00Ldpo!%C`K$i}21G6_nuzA{}%&_yIh;wizeuIduk=b4S-kMwA7dwbIZ!XIJ>A zucjD-o1;5UHHV{2>cm0UsZPFcW(beyk{L5dq2)b+?{fHO@aXR`vyB~|3hFB{b^W!d zBlI!o*Ua$l@3g`iN_U~hS&?}%fh}DT@OVMdrdl+M$emsCZg4pOcvp05)gHfU zQ4J~^Z66!lL+RNqexrr^YA*PumZ(1)`AFIx24lB>?`WwVtB|PxGudlIKgxg#xp+ASQY(0DVi^?+h82zv%qu}(o zI83flk@|*()m0oDb2h1Yy=7DMf@-Ts?9}se6LT$UVH?&$P;Duh5+8@ujxC>! zze;lO+;{cd*bqLg6^lZ*5~n@tpX2k~WrCmPiha1Y5`;=*?^tB^oe3x8AFVA?$zxiM zHidlj>Em37&6`+%B!s7VB}^Q|d^>SGQNfnX4iphqKTH}kx;Yfc7F7f{5W-n0UEcs} z?mt&QAPUJd#2ZsRaBv~tb_Y~q=-}JIgbG4vKbP_&6*uUd5+M9asiNfiyF4#UkNC?B z7yF`F@t6&F>)tVgnb`(xb)u1*rKRt+eAN2~)-h2*rGuw0MiLB%(BCFNBE`C5gZ=2V zCm^wfo!E!J6_%q=<%NW9Xs`RXI&0Y{S4@w`2v)YVzD@{w`7*ymk)2p4o%2q^ewe@S z2_TIwKq+-8X@yxl)E+3yOh@7!N7O3yscIMopD#s7zo9#@;*@5}sHk6ql_yL+fI<*z zDQ|QRQAcoVj!U;-+RFMB3D+%H`Atm_7N~g^8`zI&q9T%Xz_pVN{SwJqXvCkgqiAR6 zHTJOR(FDwycc$IXaEeTOLheP&%ZO;Q&FO}BzPhiqiA;$W4n(D}b4j~8ROT?p6An8c zfeeqb-0exLR_wubW>P$-96?VIo;Jen&amOj@0>I`Y^p*8XzOq??Cl&P|fe1VAN&=^YLM;k_(s0;< z`On8`x3QGjEzU%Z(hA##BVN@0RiE%qttQI*G7ybQ{p$X`{%SB~l+Y3<{?0=J^i9A? z1)q)2l-AW=VY)z&M3gbdGZ3I^&%$BVpkBF5lv`R+QT=RmWX>NcK!p7qmB|Ox?4@W@ z?mW}8v~*as6Q02a?euY{M+x;LqIf0oP0c$<=KJf-TF_MvcE3=qPLArI;*bZaj}6r$ z3}Ts>JEzwM9R>Qv3*x%{Nq)%q>nfW-lWJaGO<}(J&ZNt+9s$RZfO= z6Vl2R*l%TNUt824LRSZR=GAqnw>kV7iT|RmKb=@`#um{P-)r56|D6`%8U$NxRS;1J zX?%lVLNLq=r0}G4F)fwz^KSI&#|lO5zL<66C-B~~l1RXfyX_0<4{6HTXUrn=iyx6P zdQU(#@)p@!#^jeKNU!o0zn`dU3mnWX#_tZ`p*LvAR3uWjr)v}j4fZ{PgiGt0WP%mc z7_D8eg;b_Fo1SW9l&c8MJw zN7t|f1EGXl%0L}mzt<6PfoHqhWR;bEYmR@Vh27MDVZ({a@3Tu|>+*DUhnCrcp84|) zJc1_kD;A9?580vBhzo0xx!V=;(|Hm7ohXoqlv63gqj!(_1fdE>UG&UfuvZSxJ#)(0 zn>~tg@kd{uXqZe@ykE zp7YT>9@OvZ9QH{I$xIGbIY!AEe(;85a6tcNDvNw)K?>&E4cA(+tPc5f0*!&sg4^Qp zkMD1TrguU!8A(4&8=>rS`(H@WA#mpSGW}_{No2xN+wx#uEX|MaW>bDkYwH#AfdcMg zB9}uSI8p{y5@M2gXUCG&ZPYJDK*1|G?7PR$=N;1;Ehpf zW?9LQZ6}|1d$n>hX4Q=}l8}7q2#FuctHts5M6$ITT<*<=RKN&+s4ou(I>VZY`p>(# zx3ff{|4#j2J^ds41e?%uo(_cb7^` z+V31ojsXEreq8P=LUW2^Vv1A}d@^wx=ft6PAW$jCn>^jadxPE-0~6IkpvjceboL6Y z*oDM{jd~%_Koz7SyFMVKl@_=kH#hlQ_-=7Q0XBMQ%i9lmT-XYRF0@6NySc`&K{q!V(zYIr9VIZioR(b757`3FA=RN0|P z5AIQA`?pbWUW3izkoWE~`+It~bQcN-q(|Pv7yDhE@|ie@u^cp}ZM!1r*pY58*6X3a z#E%!$+doi+;~6_u#NW~f8)aH*r+)WAF(T^4Z=j^lWtV%Qy9 z8|QC3$o0&}9Y=wzEHE!)TA;5ns4m#Z{4eCi4Smp?Ha6g4*fdrLv?pxhwQ-L{eN$GP ztXa!Ou=ra{JwMPCv|U8ZdA3LK=H!zSsQtZj6!3Xk2zs2%lw*n!jCfei1EK^gi(o56 ztso~A@RIceB@k{YrVa2&9i$m^jpfyyn+k9P_nOi|Tc78{qt~@RYNh;~s5ANiGgW-9 z`qt*KyVEb&x{fSUD2fAm`RB$zH2RpLjd(z}1ntOzr9X9~Y<{NifWXppZ8UBK_1Ya? z7}5fTf`6yxY{2h4>UzE~_fr77c3NL{aZ&bF{o}(~x9>f*EWowac!2TfPqbrt$$Eqy z(oyi}C{5Ok2dMe!=LA~;gMAy5{orAR9VuHx&fke;@ODIo7ZJO#29klAFe5!|?nM`O zio`bUU^zXrVoX=@SJa`OaJ0@5#$EG9ha}JI*GO>ty#hmH{^}aVp7%@sX&pOOSqKiG z0BL7>MW{*(xd!Ly)o5`^a^TSOq%XoYZGl*{;E&JqRRkLPe3ajut^UeN|8D+#bQOv0 z>A8bx$xV4UVBaKBz{G21?P&-uk6{7I?5!^U%&B=Azi?YoPCMRCVzk4z247%%VsU<& z4mi`uFhUQr0j=^YP$h+7JS~cCG^c8mTt0sw#jijx6hs%TmCs%5V^dhsF>94ygCCDj zi0O0!*lK*T+$y68xC3N#D>~;C|>QE&|6b-^Zm}Nk!UE|ggdYzDPFjtY zHs0lLuEojI1Jg6$mrf^<9mnOvX)7mW(U}|NmYUd4%AF)L5z_8~Um?9J!!`c7IH^~Qu!M*iG}iwRJAXg(diq;OK~vX0iIK&lUX_HeWFCf9lOvWoC?;Nzq5Q-KxBw%9 zfS=%Cjf^O)R_yajt_Y$LYFST-g`1lzMZNV9Xt{##qmb7H5S22nrnIpo&MMbSJ)=2r zJl(O6)T$Gv=IRsaFQq7TZ#FvYJO+6!dR0L3G~SVMye;w<$QyA5?a}qHs$7&;^f#h0 zSd$ui@?78#O+6!sZi-JRo)X$S@fMV~`Q29G4M!ziUK=cJ?C)*p+%j0~W2uA$MVkK} zl-U4{uV8yWp_}A;l--7_qWN4HX598zCQKdqI^@yV-$$!qD58n3cy+X05>91R&pvTx zI%z~()F#o42U{ z?ShcDCRKOaH_ROEM9_DJ3ZRLTNxmOBt+3hrd<8^g8*T`iuuX!cc>!)s`tiI}zFUj34Z zZn(T#{rlzoUYzPu8)r_pvL%0U1fXihHox=uk6(N-t~7{MsSWol{vWQ)us9;7W2I{7 z1OT)|Jo!Lm-m)_6yB9X0LHTgYgObJN3d{%cs*sMYCcbA2%7ZQ^et;BUXr?MKaaD5C zPx(OW4n*z^-VCGItDi2zSsJ21cUPuBNJM41KVoeDp*SN%`B)hx+HJFB>FVuIWd4j< zdpzKXTlC@A30PlNKgVrQHwn%3`*)8FHk>W3i%`}u9s5H)qtaT9%DGT?<31=Y99}z3 zx2SEGcwJ}J7L;rBvGKv%i7#pfOJGpSl)Qptc{VN8(fY=FE)(Go?7?Z@VZMB@0gfVU z){}h=*U18fV;gpei5o?JnHz%5W%tgP(@UR1F^O}7f1Srwp%T!g?0V8rX6Uw@3k6f6 zy+~B2i(lTWT1`or$AOdY))hu1;GQ*)n*W;vqsDKP4%|g`^2bSP(o#~nN8=IS&()@` zyv0KG(BM-Tvt>xbBalGAVeI}Wb{Z*a&%bPiRpXZ~s*kHos-QG0NS2sAWR23|&x`-a z9I_O&UND?Db5-`bbwI*!qLstbg~S`5Kdu*bZIi%=na{43t2_fXfLvzPY0Ni!J;Sb$ zulah+wj{1P&kq!5+z#%#0mJ~C7E3|?e+M{J(+4*VTJ4MB*i^PX*`U8)fQwK*-3n64CU5A9*Kz36KLrERGCH%Qkrrn`s z&%-pE=OKJ`^{JrbKE4pz;IyclaIUoBb34X0Jo>NtTO_($gQidHW9XfueVM3nEXb#+ zSLdU@cQVhv(e9n!D4;jHG@si~^NStJfW>A_w8fI8|KI-3wxf1gV2lhu+eQ=Yy}ZBW zmL(bA{IIX)tJ?EQvz^@s(NY%%&M%~D7!?iU_Qf>+*7Zt$Byie-_j^PH-w%^nb)1Au z&oyeF0HKiAWiz%05zYQarKnDYIf0OL|7o`%HBG4t^^91sw?xNz%%fxcjnF*CD#vT! z0@%OBt`^aV7#f}5`DgEE{f>ZRxC#9ug!GT`F%@QfOL16CoU`unzx@}|h8D8w8;C8N z1CN+O1pa)#2PXSCiJvd=>zpf`E#oJGBfOuM)(TnQ?ulGN2S`@L_7b#hox8I z>w0w!Uke}AWr~mSVll7E8g#ikWJ*#c>ZXxonK7BRW;_w)y`yT(ramX`iZ6s@u(K=NVk?hDH#)$;wsT^tD&$kvx2i)18Q@Bu zrT6{Bytlb~rNs3sZDx9gr|xfsaKfbcE*hL?fZt%f#BhFT1}KrD86Py@?dY%0)&xc% zy=~KK$f4gb#KiQcX^Rs?=-n3hb`W)|O9Oc~KVM0uRzH7PfsYo2tq6;P=KC)160S7g z_jrloAMwAd(XJllkf?d?N^2$Su{x6cCiana2bw_XWqIH#AWs@*_=j3NGF};sI0sE&k@_PL|FGAh7hujFz%t0Ebj#BlV<{v};%FNol z{`)H6&GHqA?P?~q*_$35BUX#W_S~%-!ekozjG`CWBh!o{3?(m(0sG>Y567%kIu$3AHgdv!cq{BxC;!JCO+eBcMO%(rKIAfbzug?iJ?)5Wh7q3lDPtxPiY) zAp@n;!Lcyt@xcAB@f#gwJA-4O3j7nK7ZUqf<=pH^U%*c(=;o?#!^sa6>J4K5q?`a_ zl!m(XH#L1c&v#Z?3H+rr;h~rITQe?1fmYOK^gBgmydC=L-9EGZp``=loh4BoThb{p z)A6D_zb$r|+{;p`VR>-MmAu%aP^>;PASBU=D_dgr%nz36VrFG*gS8=d6lKngoQ&#( z zI-X+Q73c8wR^g;RLIVo81=g?ODIhXL{7sHVc!Zig4d3rI_<)61i{eVvXA3NoW#hJB zH#}@JSNPtd@b3pZTWjJqr;L2i0b-}Ted>417#rxbY<_Or=6c6B3`~>~*B01l-$eo4 zWLtD#oW$S7t*-%(0kr0l;eGPyCEpqgDIvj>`lc?e|50ZDXzwjzY9?hNM2^g=h^K$F z%aKejJwGLbL^JqxoA-|dx_e)IfKaZ7>9VJ33WH+OTeb5cz0eGzVCFa7a4dR2H*1u5 zw_KdO1y@4dN|f!i6f@_TwtQiC8RI~sYs=B}2nwHz%M3MYykGGL2--M>pL*vBokLd0f1>tr zt@;$X%gS(Z5Y-1|a#0iwzN0@+C>3}xDtt}=;5Oxd59t|J#bd1bR&Puhj^)hh-CaSt zJgBA}KsXu*rc+f4zn4kgKvyNZl5}tEq{M6?g$?5&rL(<8V;VBe5FtV%H=O8W7h_b4 zQ1{a%aMS8>Mi(?X^!j4>^=7nurla|zA=X#k41wYRcxRgbKn&)%EIHrNI?X%ec)KdU`ZBh*A2f0ef7R^&`SuayN`u%e{N3G~ zLE_!;EOU_NPzX85Si+ujYW=l*R{PaE`ET-c&5#`};VlfT?dpr}kRy3wL0MFR4gFZ$ z{?%O~UDjv7)B=KSsK&yT<*$_ce=lAl0vWGAT&&Vz`b!}-K4P=eOHU~!5?e1zLr49V zK7O)VxQXEbGI?=?&lM2pM5yt!Ke~2KYR;JG)u23r0=`*=5B%)E*8Kw&5fU7~q?tVQ z^Ynbnej?$v3b2(VO?|u;d~Z7e(D3NcD||5TUvtlVu;#;xr%Q~DD=M?T*{vpJ{$o40 z`Vc!-))Uz^4Fos;(#LzI>1HY3lDDDKKpYr}hpT&f+(j&pwVar|3~&V#CbifJzmeN*|1iyTDS`=JSLdi+_6ViQWfzWp3D zYm?JG;OQ zh=#6O!Mfva2Ln_4g>|^OB$mTw=Or)|cz1kz=nO>F)|cN<=nB92xzM4@i)*l+_A& zKH(Xn4Sd!3==#wi#K~>HN3r=84|}$7+dl4fVp)$(?d*3!j>Ab+NGJ4Rs=8+S?Mu6T z#NA_&Sx6#aAlm~Jj~Il@s`l%#cS2#DxGBa#>x-%A({>J(QeoIhwuyOMrDbU!kk_70 z79?4eYj>CG)P0ltub)?oY-uKj@V(#xsQ}o?Uz< z+2c2(P#&IYVn1t*byc_Sh0?A?f3>7`hsr6d#yKWS3KOgUxGu;4+F!ddh)NH9n%w9| zgvmt1pKkSZnIoXN7{OrfFV%?7^y|Hca5IR zI3cum1F1cC|efZv?%08fO?YFw5gP|o>ULJdFq!QDRXDMvvQ8-KHP z9+2#|#qa@P{D{^RPdl2MJoiPhe5p*kmdIyNoKd*OD;m1m)vw?B&r$s7WVp(9`BSyU zBUZuFaRjf{V*MX~*$pyioAQ+xHDAsEd?9298q?#)=0Y=mwEHdK_TyH<+GpkO6;O{z z^;+^TkaF2J&Ml#L^bx;bJ0{7f%TK>fjxM2i(q?>BVy+zu{Yw#%%3Cq5Qiu&r7Tc+z zl)?VgS?z*HGIzqrN@KKa(4s%VNfMBe^=F`W_NDYdy`Mt!fp>#iPu|<)L~n*{bqvp_ zX$;t5_ErGU^Q9T%E%d?Y*JsSxHyF91v%f=^3FK?sVIViif zYd)W2P65Cdo(wRouIi#>_x1hTqQ$7KV9w|I?W-Jqb4bwHmS@qpvQqE_IHt83GWGe7bCIz7XK!>Pj4g zdGso$EWbd;<#JoEfW)V+-)*ON77Gsu!IpQd>K}3B2lWWJjJW-9Dpg*Ye%$Z-OD#7J>ma&OL^Vv!_5n z-t%>M&-^;+@QNspJh+t=m`)mvF!V|W^^mYE3viyQ`KOaSf&NG-#pd>&Tep>}LpTC& zO7o_(8QlW+Gc-7_aA#QXXJ>7A*y@wP7ywk34XWV(z1ro}#owiBNs2|YTs#P>T}oa* zMjnD}Yy#GMIvd!23_+Klqp}p<*Qi1n-6-dduqLgq1C~oKF0fZ#^UnicrJRhoDsbki zpP@p`T?TbSJOR{q#+%i@Rm86iy1mD*J{P3|h@1h${s1&Je)Vf8wazkcs-QYSWD=5s=3 z)Hf6fc1UPsrHc@9AOqE@{N#=uQo&L~WNzGb=xiYwS(@QdJHgXNyi&+87;WCo+K2aE zf&hNmR*v(WHWG=NKtGu=D(FN$G_GY5j}(}>sG6AZytQ9~94s$6>GxcbV5C|ff5pUb zO#}!mf*tep4Cmq`3d}TSqsM=6lD^|W?E2jKdA$&XrD+s^;PF3yeUK?H25^3rnp2Q0 z;qX(A-??)y*dUHmg?)o}VP=~Z>{D;C(Jc>y9BIpPoy<&g#m{L@9VJP<;WEGBSl=Ah z$3X%m?`)>sewdr+rD9N=^j<<=YKxwkhJ3@;d8Ws;qV zDGuKABQ8K%U@jE*k(q1c;X2k$LLmGbQ=w!Nb4gHUG+g|-`7uWlvD)1%`%Q^NHt)xF zM7~SRqG~Ez^iUU}vkW%t2x;i$lUCg8lKfU2VQ@3KRRsgH+kuU6jZz;S0R!CX2g6ee zWNS4a$pghJyUd($sKeF?|5TGl=_vvdYo-YGMd~wI5}^Y@9xOix*Pisg`g|9tTA7UJ zWSX+=(tnwX?$7Q5Ukv<2-PBp4&80-RGvYEnAIHebd`yNk@ftxWE!9RszyCt{MM)k< zmp(x1=d9xSTTVKcfFp<3s`i%=vtM4@HQMHJ#i7LpAsOFcf0cU;6eV3U)7`V@m{QCF z8dG#;$Mux?#E~l`zWCrlK%#wJL6M|sENsn;l0CM2reYBf0`G^{_8?r!u(At(F8bMPIzT!{O3GPIptm7860>2ZyPLYPwaZ}JJ6wq z8|Xh39H%2f#>&CkM%0nqCVR;%VB*QNi3lqrBYqik)P+N3Kz9?VWY1T`pw!pZ9j8*( z=cnO|gZI+z88*!|OF!?)E7{V&!c`cCXcA0q#;C808cfB>UOj&rtaFR33Nx;9Wexds z`Oggv?zo%__NctB`>o4jE?OVH7}#^|RCHK6XJcTj-kBsNnK_GTx#WLw)yRK^r76?= zcr!(Hd!zK|b@@VJZ*#YC9|N*>H41V`TP7EC;|@P^{l?R%*Pr$b{*VpXuhz?+;fv1v$<`&? zKc^pYwmNu=5-j`JMEkS(=Azku&CX@uph7%DHozmx7B*)-@x2_;8CR9rl$J98OzCFQ zWW)US$dvnT$e{**P$$x@>DEId=ClL)@%ZGl`AU;=!k}5T?0eYXquwIZ-Dcb0m}Wu6 zq+1dHN@x)xuXVXV*OxuX5s~)iAkqA7981l_xz3NKWlEv%wsir(f~n;}bK2WBE`|*E zYwX<7=DRvV<^7FPu8_0G)h5$0L5RC+m^ugz<6sEczf=&b*LE6_vn72vrKsd{G}iS| zU+SvJ`e5PXtZGdN{rF7){a9>RmqF8x%0gbnZ&fcoyT2kt5svDTSK7g^8s=tQKBl&a zeOg#rKFnO?4VVx8LSraYdJt6VI1>DYjkl>;kh(W+kw0k&)HM@Ppf%;F_KO%KOViA& zcQ)^wFhbSfI=v~CpmT6O5?AK#oz|?$Ph^&N%cU~eTxwz)*yytIsm+|@_DRV|WM-ZM zxOxxb17NokE>?erGeGDqsiDNyR_gv{^I8Lg;QJBA)dqAkw0f~wmTDh z=d3p~c`fSnO&T)wH%GXD%g2(*A47Iqp8@rk&RA^{^YV%yCjks8+6}*z(aIY~5-WsW z!pEWNAh0FYvTsqF}k-v2ca%bj;U~^10jf+Jt4XEBB^xg$ys|EyJYx&b zcl~S+q6v67IcAZKJY@pxTBxX!C)E#Aoy)4b!%4zi6xn-74Q};)VkD-*&TKvJf-KdD zPx`Z`oBK+{@ujo!FJJ5Zjn6 zbi?SkcE9OCa;@5GprNP!TcC>>C@NB^nNyfBtzKK0AtrHOwRrH&&C8d`He6XY=wzW% z>Uy6k=%nxV2gR;1cvxop^)E)zZutf23-!r|qtecta46~a1Ubf9cq;Gw5NHxe2!;Ce zJr<9I<2IU%Jtw7Ies8~Y)Nt(o%W?zy&ApTolb2#PSiw;C!xb;}Rf6Q_XzkPCBuZ6d zR=skONPgFOX{S@}n2Yw37q~{O*Q*-AOX5wy|0%jrNhwRS#GPmnV_? z4kbpH({R4MIsDnfa=R1<@LC>=yZt0_HDl0icdp_+Y}v-2%nt4Pm}ruuHA#`~Vax-& z@|4hNVFj+C3!9j{7MaBnsi~O*Yi{hdHf?oP2S#C!VKQ`=K&=OXGaoSUcZU2nN}CG% zVFsX*r%C2thmJN#*E%-Nzw%?t7s{EapKd(l=?ddu%S~ykMZM^Y+;;V9m}*Z z;3fLt4~OsGEy1nFPl#iz%BQ`z55UZoP>o2(Z4(mb^?7hfHn9{52dSSS$KJ<<7A%AT zimRON#xdM1UH2q+#jO<%;4ELiW8RKK!O_laz}~bguwzO8JJM)C1JCEN+xL!P*Yp`o zW*=?~7F~j6`pFNvI5yQ%TCGC?AZ9LpW{u`2w_rZIQ1$T-4{gG&2mbPcykIkUaZA>V zu-FD0>K4M)Bic}v(yS%I-*UqE_KDljBFNbN_ zO`?-!ntU*C_1XEMp!(O!a8v00+!Zg?bCCmo(m}}KeMmR~?dwX@@`W+AtK%gw#?*`T zP86A+`|opr#&|M7ykp@3^9sY*V($y4ZjvM$jrOJM>*IF2OQpSkG?PyH-vMfIbd=q= zmMy9Y6>niu?CABRI1;KTj70aCz!)gp|5*v8WDwg5JsJA!P5|`i0!}Bk?183nG*+(nqfL zAiE7Vi5JpWdxaA^Js2roIa&tqjrI;|uR5LgU>-C%&3`PZR91L^sI{kn+H;xun2Q3( z_y3)(NuOEiY=wkYjd_Z0@g4k77k$ZC!R-3%jJz99V!!LY#rx9cL65F+bWHPQ27}0D z{DU)!FeIL1&+6?Lv|8o{((?Zf;F&mbya*w(62ZTt=S@~^9QmK!Ok)tkkRJgrx1?M# zjf__ZfPT^!^9rAf>urOl&ygx2Z4zW5uQFWEw*37;^CK?^7T+hD8rp}aAAd4v?kRPr z3=K1lXNU5{=JD-6#y-FaKJK^EIVZD6+CP!EJp4Ry{|sv{4QL-US2C0cruc*++Nd7To`5*jq;8HK#O1SJ#N9t)wp1Z{S83B0967I0p3L9 zE0;Yz5P$P4(5{5nR|cVGs84aQX81*?MxZ3NL<- zvND&5zV^|qd>>CD&3C0BT9soL9{$use$O_JCN_C!SP*za#|II)vi~g^BD0XmPUKUa z4*0-zDbh*u=*Qzpke zhGq#`tdtd7Pu;KDdA)`S3d7ihK{?}(%IKdY=Q6bKa{}kl_In%P%Q{m zhz-JJoX8I+IqZdnwZvj@1X&J$9?yT$13_dooSX0HirurNIqf&yGVL$Lrr7Ar)R0G` z*yO@mFgYzGW3Odq!zcFt>!@Mt47KbIJoJxvfeDo-Bf5rlkd!ZT*ZEdXv>ygu)aT6U zs^9;DQfgWFx*3rl4`>yXNSB3@`~%L0+@!cXs$dIZ4WA=;aOV5(7$6@O$~u&^0&F09 z@7?@sp5N~n8VSH;lYd8s)e^+Z{dU(R&z5T$<50VEmZ2`{V#(cf(=c~lNY1IyoS*E@ z40-`H0*OGXvbseLU^Y7C_AKW!o`XhB_>c$phpsS?_mC`2qDNw+a-fytaLC@T?QRfD z96aOS;w8z{KkRgycmy&F+wdkhhOoQ`>m&I#4FBP=zfaO+76;+loalXwC)fGr zCS&IOsdjxo=owj}gE%EbKsB76$_t!4t+fk8gdeG%pJ|8n9e#TV^P~7L==y0=A2@^J z3TBCRbjIgB;dhvMLGvm>uAzO=1C^i2W$=@>;eRbO=Ky-HRc2EM85x!jdDLVbn7V?> zecNU59(>}-d1jOK;-9@=b7FCfG7gA}glyQ#uS%HMSWb*1Z9GwnPR#rFPn|7<%KLq5 z=XT|YQsaAV(s~nhW^<8Jt?*jHN-=0~{lhJUN(xqkS84}K0NetZEmmT-(NAoL2|^M> z3DW_59%=DQmPRqJ)EiR%o=OUi$+2VdY+G=kr;Tu09XdRbXs2IHbTe{honkU(-}9tx zKvTMfnCD*zG`(zK&D;jp& zKqWZ&!rva_dTfM zO7YlLZbQp6E|}2;aO*pibNAVMvTrDb0$l>u8_aUWSl&~p`q))nUeU9lk5$*5zBAOv z+;D%%rw$-)M5?H^Ail6!^Q}O7nS3<=@su}26YQ4vco!TD+QRGN4c#2yZv{r1y|FBB zjm@S0c?HvXcl`O-v4W2{qzyA4gxAtv>*$MWDErhbju-ec5bBN$74Xd;WVml!q@IS=CfRJMkXdDq)@x0W7m(!Q+R-6hj5j9 z`sEi0N2tFIkEO%;WOB;d?dNWVu*9lHoSHbg2AEw_&tNVg{oI#$*Jb-@HjaL<}~gZ6#oeo z3pQs1p2gk4UInz}-SM-w$3DoP^GjFw2q55L4Ljwrl_dh*UF0!0iq*6^Ty+86HM!1JNkk3@dCbPLz(kDR1S2dYNZNSQPm5WyI*SkSawfxw%qp$0g`Q< zb3W;exCnu|8RvLMgk8iafyig$V7af{<7;hqTi)NCsJCWZm8cMV&L^NI*5}Gk&kF3<0k{Nf&ai z-tBdpZ8IgjN4(*-*p$Xol2)a|{Q#Te;`zIj>P<+*OIO#2Ta!sBX42lyB`N;xUu!<* zrCphl!{5_C_u8%YG0w=8VDvq!R;neICXrpRi)DbHH{*AQIpgV-JEr1?0){j|90AJzHI^Xn?1A=w0kOoB|ngd3@9`-p7!^&1egr*gV-swofJ z#Fh;*Qu~2rypvU z!34Ul)x#T@L7SjTpgYLyU?a=)Kqfb3dVUtC1hl1ztldQ1p8Eh+$}hh_Iav3PPSkzi zA2v++efy=fHRzi`ynVC( zO#W%9xXBrpZu7!Y%;Tj8`RrM4ETS&45Ub2_6TkqAf8L>mZO&@qdPVsMi5pKU2KhuH-UdGdo~bu=NBRkeE#d-ta3$dD=e!cC z&FivEV%Fb(p!$W%ZbjCjwJ3TLVj!8I@BzZ_O<#~UXt(A5^V~SFqjo$4wF>7{ll3=< z&q(EE-&&8`2|2tAmuq|Y1ZZUl19;40rZLWVqowd5erqUX3to_GBq7&K{xbgz6%#__ zT1_6DZ9eVNbBq*k%`Icz`TjfxLWAPm1si@S;i^x%e&g|ks^l<>GVYZlnu~3atx>+{af<%rg;v8rF(;jOBh{_xKS{3 zQz7kb7or__2xM3Mb+ctm`JmlDklv5a3+#v&j=Q|6EA|;fW@?*9J6f4i<4P&ZVDG6xQ9spGBH;Ga)LB>BGG?K$L$q~_-LUK!5oeB2expK-S|HU{FP zqs+1~;uw*>WkF{~UcBKKS?FUjU3=oeGz?!#bj`V1O z7>^>%&|+1zEyVB0^a$Fk`y&$(Y!s*dagwBxS>-zlZx@8_R(zx=2o(X2aC2E88w+rb zLwPRTgOukV9$~#8oWalfI5?RT2thsS+8T<&0dIS!^VAa(Bz+!TR>TssYvf>am@R3c z)!ti(AO#`l>F^(-RF)>-6)DfEyk*2wQtvfE7J06vUzRQHAafnYr~*F#YU* zxY6lN8%T?A#s-OKwL}<6KM5tDFhV>DBEN%9YpQh}Iv^c^kTobVC?*I!0W$5e7JXTi z+iXi`K`%nTey~Rr)={dGC%BIhjUB$&Hd9B5H;X0TF-K zdx^*w?)M$o-~SrTe6jb>%r8NWNp2-7%gBfV*duH^E%d}XO`2Z~Ioy!bEI8Y$^t|VJ zYQpLZcMYN0{f<*>Df;_AUgXoj`PA$cxP%y~CIOv9!pLkVhsz~j8->FNXSGfek|cTQ zI;-;RSlUhn(4F^8yXgGSrPp2zZoe*4-V<-3-L+I~gGZwQii{g_ppV3mv-<<uS7Ul(vJjh_DxP+G|z*cPwv!pi`q`d>Cla57YjkBA}hqA z6m3`CS_nx>CE<^CwiV0f74deDfc7c5(b}1;*}7jsP*VjfoA5@%142Fv3yv598ff5# z`bU{r6+HFsnIRo_d^(nkxUwP%E5c3$ssMk_e8kw%iF1#KRB0#3qf@aW>tndN2*A6q zGF|4AuKMm;6X2kB(q_mjtk%zNJH6Kwdl{D^TJoHDxd%my8pD7+imr}WZ;!Ps#S(AW zcL$2FXw)6oEt;ocTu>^$KY`6Jo=7;>Aq?Hf#@Wmf3rdxA-f>S1yShoV>5O|x>P4a^ zAf;bWfulCq7QgV`$QTAOwosoo%pOB%+2B2^AEjBtTp+R!cHt6hc21M()IbxY8aZ&) z5=UIoE+azqlPde_n&@S*Oxrb)i7RgvxP?rS>BUZ|x0!bRIg6+vNRANuT*f-F;Vx(% zp1m)%RuS5%l*|=bz%ZXhG~}bRe5Zf3r62MuVDfgn0y^3LN!`76@AFm zHVOQ5#ep!eu!vHY8O!vo{()z6l(fTh_7}2>hffbY-mDTFhST8gw{#kpGc!H?XDml> zUz&Aq;?3dgn`}9l0ECcULsMm%sk6;0*uXFj7>TqU(%%W zwGK;sPec1EtKZh-6E9Kqlf5G4K}8@}*;M^Tj2$IFsPnrM;o1V%I_EaJKTD!~88LMOu{WOlX@a$k=qW>V(RL?Idm@pkY6o z&3Z|;3RqXv!$qs~lq?@i6^|-yf+<{7xq@Z9?8<8yD3!zJbcw#dFnaDWPOSD=DC#5SCy&o;PJYGBBkZGK@+2OgV2_ zO~${0*V-N{HsxsKkJD6^(tG+-u1*|oM~zInq)*p#??quDfqD*CuPY%tMJsPXwchgj z>Rdr~AbIMNxJt;gv@4Cl*9et0T{$Wzd*5Fu(PPI<_gn@rfdk1-?n~=wP4u&LghYSm zm`sVC!vfL$MsWZDIL`L zuyNeEARfR%M*IbaXfd7 z&S0xM66|l8f?AgN&`8b1%{hBoS4}COdTzqNbMYroAj1xtvrc~WwW8&py}O;IbQe@u)g|ew zN{`Pt#{=^#m~jTDHZi<*r3}itgL!UR>h=NpjD)J55LA6OPU67h^(&i7=4%*fMM6eV zf(B%Ozu5TV5bMQT<^n01@pDMtqvIs}x=s`>46SlvVmC_#G=RPcI0s-dzfv%l7pBOb z&{(^If79lnh_lA7>R&btgdq%{rlhLd2UDiXSyKm4_=Q@(noCSBOZfi2;m+pyHq1{p zXIcTbvf=j^p4}Txn(6*6xkOfeyW^9{`#f7}xvyvj1FXYRj1~z(rKewUZOKZhai&F& z)9m#^N!Vyt==Vyf zBcOG8W??N&dOzPX+yt}TnF?^a@Fgm&*U=Y-{`uwFu>Ki_zv2>U>g@z1d9SdMT>Wrr zLB_>}Y$LX2Y7t3%uA2i2bH`+Dv$6A*@t3C>PlPg^{ zCpO@0s`!jjxsO@f97kk+M>cKdI{*f;ew;)nFh|Z{ml3B`*m^O%y zykb`@&QC#0BArwVgvndUI2AwXV#e$#6}>2Wc71t7AWMn#sGJ!+a_o-$s*2^4^|DFi zC#I6I(q8RXbj-~~*@V+L)F(jpq`B9)s)2ObRS&Lnd7S8W@HylEqv@-o+WLZSi(7Fg z1qu|`BEc!eN}(z4Zoz^SEACJ%xCf^=ln|`AyL*DWYmow_{XM?#z4zZ)H#v7@-8H#q zX7--FPnIi<7v~P=kVJr-;t?6bl9isIENF?$BS2?iw09g^2Q`uj!7Wt;ayJ|T@?|uM zZ;Nk@MpID9?=)oedIo24%Cn8T!Eg(AJBSb^@M|gLlz^)=-*sSv0AMC0U9__0wId9u zqyJR*UPh_ys5i3I=G_e>@s)}U{~a|j7tgI zPo>8H0wdH@@dMJ@FYdf2sI(}K$kv_l1#RFNTZalhQp^af!(~9w-A6ADp2+iOO8%7f zHOAl1j<72>$6*%_7eQaVzxXsEP#NL1K6-60Uamh4O5(Oa)&*hsgBIhC{aK{Qn=JjH zRdrvt*hy@ec67$1-r%`E5@h80T*cQ6Lrd(z&yJOGr*0LBaWS zd5diSf$m{Te}P*Y-gNysMEHUx6As)L02JY!CO4L@y^f3;RsFj1=4L(HT%O%@Fioul zC;`Jn!aw9PGQcjlMHrFA(V*Zxb&|TC$nE37NLKNQ(u1?MYf8CCo2yPU#9aj)a{Bi& z3+xFmkjL=W-aqu^S7L_=BLA_o$a=ib3pQXaO?wQ$C!qo8tZTckc2`ZhVRFihpSWWB;Rar-qzQzyH&qHV*#B*W*(xl1qUM z28Ac!nGY#K|6bOgGRFUCIK79l`Qx z(`Q2v(NNGGI0E$=Hszmfkw&N`P8gn_$W~%zj0J1}^cT#lg;K74pDS8B6&S#J*&>_e z6jN=R(pi{|1KbV})V@t*x>(tCpCw@NOXwZ%M4$SpZjqJmk7Fi`zCi_1pj8?q7aPX3 zx#8@6;=x^*#8&%S=|hBm-4PMAY83oIz~*^a>6+`g;iuR_!p}0&Ci0izWE}f;@qZ&0 z3;2jA=;T_Rz%Q0tLLAB=3UsW1Lm`XAFAHL6k}j1X4F1b8~n z#SEcEgRQd6a^FrYOomTmr*&R4)#b}6fd9SyX!amnuMetLEa3jI9rK!1{1Xr<0blF> zRYwdwR^Xq+UPY|E1`Lvgp@eIcJ2A{Aop9DKDdDFjYPGIlU_pX&Y2*aGa~lYE*9uWM zXFr1dHLv1JgvlRyv#3r1Q4HryvAac-9$Kz*GmXpZ9>td}$`xeY03E?bMSP_|Nf|3NP$*pda#y-vkGK0n=JJQ zU+`fylS#FO5_S;Iv#8A$XU`zEo|xFp_!;)?bPvsMT;u?oaE4e^^c6%HQ7EjxScr4M z`lN4}!m~J?Sn#{8jbEzCoy&*?MnXOT$vl>L0>ZCc-6uLmaR7tZxy|!aMv#lwnWjGr zaB@ZZ8Quc}zfd1Az)TMaATrOjL&M}d5r{c{;xyqa@5yILod(l!BglEdh9(3(iaG!k z%-G)^JEy2(i=+56_(k@V)Os*mYZe<&bvUxu9A$&1^|q|;o;{Axq7b4)9jJ;*+~)IX z>%PMO6#ihol68Py9_~D7-X}~RDNDKgKEkkvtt&pk$hw3 zcf)}3{XI}P-=`f7^h_**#00!RL3DII-bP-I2m%ZH=s$HG-n?X)LEWKKt!}?Kq}RM~ zJvo9F}v}Hm0KVczO^} zTV=+16yoN>iL|bgr+CMbRQ?iiwf+J|68S3XF1FS0^*%9C{mdhd1`~VyU^by---B`W zaG=@8%p#FcQy%lcb>?5Dq=)^PAMqfQ0ayWgG_u#Te}r&tA0|$wjrGomu>qeW@;{(z zwSlRGt1}dkUd7W67BckeFG>s^J|1|%rY@Dwp4(F27PV(54TrENgM?8*{qgr>N>nba zN||<9JP3C0tKOFof_t(IAJ^7bAFX-fNV`;ke!5`Zopfu;7{_*?vWt$Cvm_LE3e+T(&82~RSF>t zYg&Zrr}+$~r4xrypHQenVud?l=bbVqQ0 zL~lim%L!7x@5Vz^PUK7q&Qb`kxrTS zO$Dx-1DT0lT~tWl&561$LG93LYJ^~mm1LxZz;?AA)wk88by3egpx@U8!$qdOmVh?>Y-A!|Rvh^f8mR-f?$@5oS=iqv($DEJlV$Sd{XZ^# z4*>~xpi}riclleax6%TheJ4n`X;mc1HIj!2 zVL?E3<1-?}1vH)IgE&u;?o4)gxu-!62W;rW#Ip?(V_$!-5wtb)gP6^XWbnqD!!S!ujKr-ksr2+ zb>Ru<^>XKh$cS(`ZU<+9Y>58Spk6`OF39u4nzo~OFGDTJn_#*AfJv+qBR%1YYmaUh zIpA~R)xk`py+RT~!}s+SFRFSn-8*b4&)J~|RAD$(_|3dt5_X|XI}W+L3x!4gCpy^{ z$WEb6$WXa9ydAx&!m0o{Mt@QK6d=*nJj!0hX(wc(%VbIx0NfRPP zx2`l{zHDv2PMq^W8^ZkGcaA;W@26W)ZNxCsqA5RdiK-fUz!}rj57udViNr&Jslv8O zXAhv|&ir^OclIETohmJ@dx&P{ns|NP$q?D{kF}e&E4gd0Vzoc!8a)c+$}r4Z3trTX zgXj&t7Qpn}=1)Twh(2&&urj~(JI15I*tzF6A&0S+F7FDVy-LvR1|e``Ww+f8_;)8wS?=;589d-L4nB|?BFeyw%!ZU5+ z=#OYu-|?NZX!3+Y!19h|7&q+i5(Eqkn50VI_h>7;inJ4Dd{h;89$ilZ=vB`wL3UT9 zi3YyxR^CjmKNEcp(7(G3hydFkwNThCQMbiS-_*`Dx49-X^Ct&mr>4uRVI; zqtB3;^?ZF%%Z89eto6yYf}@697l&1SG`6Ks>7(+y1!!KS2;jO8t7b1oVPFa(T0?M3 zsu6``IV%4+2quq-VH}jYp3+JpxoS6#RFf8jJ-KUK!GsRb`}9oqITTVE;`I&d?Kv;H z-tMrf;r({agwl|KX814YvY|+ZZbz!1k3T0YfXx|0>fAlk5V`u)d+{v>(aH7nuU_uD zlE9iJiLHPU0U(ETC*G$*kFu{9vz=BULW?=?ezxI)5x%&OiGF|UJ%2L zu8-37MfUsG%%bspalziD!^WmKM9;Bm7?a)33Gx*N{;1qsMx_d`D|0=3K3&_?(9Aai zo=;-oQqMHXkNIIbJ(F8(zYrGJp#W$^;>)_u4oNs*_uvda02|@Yxvi`H#Y80ihp{Uq z$wo5Eq<@KBFXPOi(5;JPtAk{LY@RjLuuc#!wf)*|t^bkim|{?ub`PzY2?#_imHoY5)`$^2?T%2Fz#ov z2wb$bA5n_VfBdh~!>3{|{STuG_xV!yzHU{B>f$6MdD|?FkH7JF^Ek_3E(=5 zyLZ;vH3ICYOhT{(h5!62>}T({&$ zcV`aW1lKa}EzyXhpsVQWI&5&xq-(MSr;fKWdxjvNkNMwvu_c57fUe=FLNIY$g3Pb| z=gwbw__FSFdfG;7~9Ob z5uFi$de$~2}YV-y1n^Xh=rUdK>FZ-4sz)uvN=4MVaPKxZ$zmuwKGfD(*P!(7|E!cMGL6$lAm|9UIO zg8pz$kvH-B+uzqM6m1rWqa=dyT%J-P*v~?=ewp-SLW-xC% zl&$+fn(+8D{=qaJo20jX;gZc6=29V$TB@&-E zFvc?KWh`y!lO@&(%B1nb@p!&0*R^mbXF(NXrNhXAXn-eqduHzi-8gA?WNo#42tTxW zU3bDeueLNj0p+V>bsDv1ds(&A7 zpTFZip+qS|s~H`iBJV=!)pdbqcLd&^+e=X@U7`j%7fpI=h6isT{*o}=Gi;gRg}GDT zQkbwoZlczWy%-Xi-n(3PR8!gN@Ou(c9iBlZ_?v%pUo2hb+xS;eYcTyUIiTm?iebxL zFP4}uk3YK-J%+)KoPJ;}u@Guk4EqIoYcgkbc)#8`&7iSr%@`=IFTEpGA8?Igtk`C!Io zK8=pT(N*F!jSTGt|NnB}1eP^ncP!0qwL0H|I1p(5-+fp> zF?x7b78E4O64~>cwwjn!c18$Bdh0Sq_s&NSLJ9_IN`A114WhdQz-1b+HOJ2)i^V>N zDWr!&OjmGnvY_+2SMLpmnwemF&n?iHymZjpdV2!!vG=8J+v(n@A=lX)x?`$1ybL?A zp~P`)Fn#FNq7lZT4H$`=>%+SYx|lr(htdU4G>Ae&NM39rN)z%fJ*acaOyG8~S#10; z(Jzrr)tf!f{fQ=;jP_2SONbO~KLoV(aQik8yq-%bJP`K#mP~T*BtMxg1Z?q49PKW} zeWIkxMfo>S-h1~xY3YE>V<55h5#1%catR`^mNg_Lmt4y007~2s6JM|bhlecf+E50} zX17%YGa&Fp#yRFr_wYKD^<#N*62Kq} zjYlru+xbl1>R5b}hwzQ-)sg5yVjyAc^mGkse8*Yz1I%HPK-E$bKukS%N}Znon~3UA zBBO5dN}2Y1ZqZ-U$xh85ZDYb-2u1=RRM$UOpo(t~uvt}4aI}+y!mvJ#?t43@F?{mP zWL)_njl#jds9Er=Si9H#Sj%&1QP-pQOXgL|kD9Z{MjF31+ApQQTyIv(*f_;uP}KlK zMoQtbmdmf)=IBlU7bMSXXDUWH@N;bl+QCETD0+(D@QQ8Ky^S=RX1_e)HE^Q7#vbTP z?2`wK`_Z;v)I~Ni7+E7b1!+D0opYa5t2qTpS@h3=v9XEAGn&J6TDJQ`_y+{*Y9maRwkEZ?^gA)kjUx~LQaSzGRA&G zv9Ld|yy>QKaKE@DJr3&BJTyL7)G70Rq>2b~`t|ug5%5BPwtvF`f^7X1a0)!z|MU30 z-sK&k0#fzNXL$~C>T;Bgx(S<3JjOR`N7*RwGXKJXC!5ikDrR&~G%^0MKk#kM)K`xti4Bq1C`{ni{?%Y9Jxetf z%=0}9ijlY=%ei1j72U6&Sm~<1uP7u{AKieYUGN1Tms$XTY=_|mbGs#!)$u+TCH!nN z;M5iJX=elB^1d;Owny}fkYIg9WlK%Mm;GfNoNU(qjbK*RODj=QNc!kflF01u#pxl2 zpC$O4jskZn#^v~^2AV7~bFFFtxBBO2aH7;c*Keh(j1POXnVwo3OWJ{-ggS(~nw_iN7rbr4xi8Bx(LnDnF6YnFx<{g2A6FRJWLjqahg z!0dfPqYxsB5!h|$XLtTd=)!7aD7Sba>;L`2#JG}L})`! zknz{9>rDK)C-6*Es+i8lGBbko>|>12pbyX7d3=x$5m|R{tI)vr?)h66GH za&@z}lMO#95WCEw{{uPhlTJPf-?UE!Pi03mWYSOr0&V6jExLJrEQ-`u=n&kF=XC^D z(y4L-FBgS{IYaX6pP?ax2-L|}ehL^lhUf&CmjAF0w7T!6I6SUoSLFN2tYoTCe#}4_ z5Kw#Hs15__^46ZZdqTYS=;99I&Dd(A$7OVMkMt0`Cy5j2krvm5sU6poYaV2SK_o${ z)?aRV6)f#*J{q$MypVcM2=c-2w<=tF5;oQlX zkZgIYAN1%lnO}n5=BBh2ng3!25Pa$kxGfR^_%bs6XWXAa=g#|UQO6?=TK4#Re;G>p zt1jFA>242@pd8e}x$E6*Ci>P!%bU5gBq=wLu5dG}ZQvP_2sOR&UwuilD?zr0tKDx zAO#Zcm%;~JI%z6P(^yk^o$K&2s$Do##eikAR1_qGwdr6#BME!rw0f$2 zNSREOgt?U7S>#xz_`KiEC;92(ssiD>p8D(N+8HByb-=Ztq8eP^7j=?`7jqzEmSPI zFoUt)wP3y->^$a#E7IOp_cod6;swwtFYQ#v6(VhJ)e%`!} zf-6nZS$~X!!AzZLZP2^Vb!bdBwbO50&Hj^ASE-M_+Iv^}@mEG|m;dMRGLn}_o=Q-n z8O{hpOV-4lFRFooqdvQS$*X8B?Hg{Php&`2YSnhVd8+bxhQuh%7F}`jVDdP*KGcu` z$M_=RZ~xUF@~spcqc#Rmwmy%Eec*=))27a5hut5e`+T?N7Qs>e3aT%F-y=b?JGtO6 zls+rzUeAnIrTt84edSSN<2b)7zYq1bOw+&*i+T{%$0uIW3QX9xy}Hv%%TN&~aN2W$ zF7vzrECg<=sK#AXG5XcuB`wHT?eAe@wT9Ei>uj^Wiin|pEAub}mH8Orz9CF&i$QMf zO!v&(AA-F_^{+cJIs7T+hHQp(J1JI5+)7GkC0L|{~ zMC(jUc^fKJmx>N`xdECMDIHhsWhYG#s_HkL^mMO)Kq&;Dam`=(nhTP=>9eRK)r`~S zdY=teqd!7#Tg+^(bAM07igY=LBsZklI2~>=M>Q)}HgAa3g&a3}^AnAEwR>rGAI;po zoM~9igQk~57t-JI05bkG+&pi*roM$Jw@5W%;lCKg7p-ggb~0}x?i1#x0EFis4@GM7 zt{;>2kd08yYr6vgnbI|?KBX1ZUA{Go61QIRDqjdj2FaN~5Tb#gi$;2m57uFG1Lyn3 zK&W)2Q+tI)3Ty1)S+hfp7GGM=u-fPX8AO{s&@8@pjkJ0wO)V_4-0BB`ovoqPk;uOT z#7OosG!5!Y+e*P{p!Bh*4$oSd7vQBQYwDj3na3mV-Axz|%Z~fR|7IBl4SoaC&uz`lSYD@*5G$LB;E4BH7@8;pri(~Rn z#>W~C^pC9EU2{?VD;<8ijoKloDl{2c|2qtA#ZT1MIOyIB0CS4NYsfg&F(^i=5NAUmM7mEex0 zDx3TB#$k}E=~;E%+O!DC$7#D)-H}aPKbs6TVqU5-mYJs{&$$iL@S>uw)l13KE4RI) zN{vbN7#xwi>thR}W2Vt!%M|T~m^M4|+O*d2=sg{8PtMP~X72v3klie!AJwI+ZY1rV zO|xn?roXH^hC9i=H13iG<8oU2{&kP%~E}R z&;&5x0@p5m*80I=zz_m@O+TK@M|LqF$74yC;9dUs)J>jij!{<>taLWtaWZ=y8Y!X7 z%N{f}J}XwXX)N@}o;CVO%Zt|jMmB5$N@ZyqHgMj6gg=ofPGwjYJ`07Ge@ufGupvHW zmCQ;hdar#U1DfF|&3Mdf%k2N?OouFTb=b#ZOsqvieHOBLT#A;e$RU_6*7eS%B-Ar1Bqu**vI5etq_tsj!vtyqivHsq_`q&Q z;lXJ&OLJAf0NSpqQ@16brV;3l-6yL!p=Ow$b{-e>UM=l=26}4IJMQn(Y9$HWO`2F> zqoxejEK_#?eMQoUTx+Xw=9tq3U-CZ=eqMwyBnG*;3G){y0h#B}PtASF;GDb=LmBBFyilpIN z+W)lgsj9iQGrAH!h+VTQ=wBg|K#!}+gk=J|qy%o$Wg}kh$xswr^I}4f%QEW^9*}{8 zK&c7FeKgn4=fWlp5qdktX+Tf4o&@?eXyl6m(O``sJ<-&@CU~{Z>k<=%Tj7ZG z&hOaE*TUQ#!XarhyBl2to?$5)p7iGX*Crw6RD zUaAWw$1-j!J#Jy=Pq|YBhxaiX)Zi!BWh&D3>=S|4t682bS-H4(1%^EB&rF&YjWQ+~8Fn9SDaW2I75 zDG!nj8mnhLH;{Iv?@n0=#TXpHXtLM5M*~-f5L!Ozt(|x5a-IL>S9D;~ zNGT74Eems6SXy}`^yI}NjYsY`NAo@J)%}-3McyIV&L+%h)jFlC z;8{+_9o%;l(N(#3?S+v*AqZ69HW=XFq*sXjJ!A=ptbhOIa3pDL+|7LTHh%>8+{-|s|1uyhgFTZVYY#tk&?m!sg?C|^TY{B`o3Qy zo{>L>nSttd7NRM+L+$G32vP;g-4 zX1>4UytAhREc`d@y&!dQNFSV_B>RikfMNz#>wn&+QOKnhNSW(%;-8j`{*MkB)z1RI zQd~EQ&jI;}%x3n;2I_0w2eybUOels8{`yHo6k(YX7$4iKYR*!2^hgb>fe66+*{-M+ z%hOxVAi4u|_z{)bs8_cVaoyO*t81>ny%iCGuY#XcT=`y`Va-D)Ky?`s-%K`LBkIHX z^HqR2jq?@!tu%XK81G&igUN?_5SR1&?oeoZUCx*n#u)h~fk|)7!C%vK3n|sN=l}zC zY69C7e{z}%4p{Cl6+HU5KaGIt%x6RE5HbL8xE>+ASJ|88q^k2ca~a=ZnZ{obySuNX z-{7-+;r-uB_uUt$Rc>I>-*WBweHwrm8X+1dps4-w4G#UC6^8H|fG-Q~3N(9neNKeZ zYu^xMe#8c|ORBvtv6LSGYw8UGGFh~MuVcywNg$oiN8|F~3P`(8iD*%sZE|{Bj*r3P zWG)ywEAC-0MjhNUcHr4krV2bgb)KdgT%Fa4CWF~vON!6;(Ru+l?(;jCU9*Q{L{j(l z+ghU0tGk5tKZ;vn`w=}tWB;%ubhqK1J4nG>i@8#%{!vE}LgaEM$ex(9V`KD2JXCQw z#7;!WYi2$1=lHiuB2;c(iwdn9{roi)-JMn!()KN~=W(;fRKv0QU&r#`EMg5}m&XRU zDS~*%4*1ulCJwI6ZY<~XE;N+}L{Zj|TeCcJ)cA1SSc!p zAp&7;5kL%8kC`CXA^Mag_Bqoq*uHj1@~v`8dl)XmQ&?Ri!0<3xiTqs_BN@_`#eHZl z8sOB9mq{(N^IlSz_RU+vFHar&g}*t*f94Q~oihO)=&8F(`yaFSY$?!^eA+oyml`|M1Pkd`Ffxcq1fz08#eYP{JNBV@vV_HPdIIWb5LQ5^N6( z)uS4r@^HIbU7$@;M8n?BAw;f5RN1^Tx++`SZE-I|%JtWPgUt7%0-maKU5Ni00NEb! zhfW6sih;m2f|Crvpa1^mjI0Eg?VPhG?M`v?W^NQEc9VPG z(E$LAy(xM$s@YCYgGRR8SsA*Y31Mo&CjG6?Ntr_7TTOHvJ!JR&&qB>DwR5K}YUfH! zR}#oN3*d06sk&l_WWHCpKIC8^APJ36C+2Im0n(f1-2;$hAH4IOr$kfl`)!omjtSS_!O%|2X6y<<(TKlbDX>Fi?6;pMN`>{-*)zXmi08shUv zez0XZ_=wmQ6F_y-q`pW3VY+>_bx(W{B={sUel57&07J?06GTc=-6YxK>6BV;_$6csM~}%tdyHb zdEoOd#zH5D47-3cmPR+fu>~d*NlF$ENz-8QaOo>FOx_30bg8etkL4|&^!qS*1P4q~*^Jra9OX2^iq<7}lt z;OyzLXV^JG8JaTbL#bJ@qXJNFj1m~mrP~0bpjsun46(q0Dlc%nB`7fHrn?&~UmC=MCOUR#+p!C&&?kEhH#k8) zK~$$-HF0C%@w%w|qb+Q}g!QY@0CX*qDpSi(ce`D7*DKsGx3GaS%e)Xfh6l2|&NN$G zshGAn>dofF2NL_@*va031lJ=rmSAe?S_-_Jv0uyTA~82Dn1I#>jv>G(m~#r54v|67 zg_9=fR5W*k^%>=PAcxQwNId&itAd7n1pt6$YE-W{dlz z5>JYH<*fmzAI|@EOBH~Lc{qdaukh__U+>B%?Jr+|ZpB|%Lw}ifBt;OKOn(Y_=5&;c zg@ZwpX-s}B{BY-DsQ9Zftjsu3sA>-j=f`Ff< z!DDJyrQg#bV)w|yy@}B9lQ%HH;TV2FFoDYU$$A#GZxBfeO;|apJKpyfV5TP&X={V1 zI*z@y;87oMQm`3O`4_cGY^9|Iswr+Xv%%jFj%}4E@)0Y>X#x|{6v;EP!3l(C z>G1AB!~mTVvzkYDc7Dam$8b0kAgT`Yt(AFSSyxNG|DVOMZ=%+pjmy43-7H8fGSZmc ztSsP`EZaFU@xw~Oaby5S=bP;jyrB8&O*z6zp({f`+pJB*>CByAUW0HYL3&Nn1b(2a zL~WB|S*>%jEhP}|-8bt&^JtR7^#uD^7vJ{yJ3Qnic{~9X4*WOmP~aBSF=cq40I0m2 z#^<;sm>pN^70<~J4jUPf&b#emg0BhVJ+b>ulQPx1kWQZ9bDq$qHd8x^PhmRccSPyuQg&D2w-NjhCl|Sq``dI< z)FnCL!BBRKJaDT?8Sl5T1CL$>59tfPMh@tj`WGBB^G}Lf4vZTkN?&Gs_xWC+_ue7RV>*({5wQ^RlSeew&B*c3J6oE_F@1ibhme5J@H+Sg_BnQGf0ftaX?I@o)lq)J*+s}+Wf;Cz z0Mx8;kXAN%XxxUOV!S99qoF{Rh253q=XsUInKp$~$fop|p~MtR_r9d3oP&jV2QEMh z^Zb!E-tZ!o>^$gkx-c3g2*`ux0Nw(b;(&u>N)5Q1Do?ETi4Hu#$d`mRdL5052qI{Y z#6>yP?5>a$fai$%$pUhG5mr*c*Dh{kt z>7Jd(LEW>h1yq`KbXr#`c8&=Ibs86)T&l-B01-dV*q7&w(7-kudWTm zBy#-=$sgwXAwG?KJT^DFcr?UygZF>A1}5U=6~wd@x6hI zUub}h6CI2I7Z;TweXftirM%#{f}^k?B$(j)R5ORuLKsZlq#kNks)f}5g3=esNWF9+=~x9 zE49h@3h^qwtI=}=)PJRz4o-MXt)Xk|n0kFy8hEi(*+F4AUia9L{@{?DT64?&ibpp` znw|OIhn4O(%#Gqiy``O`?}UNJ;uV#a#7BSXX87sA;(Jz5?>`7xOk^7CbOEy zmr6hL+r5;Y7HzEC`~$LTa7JT67<^3$ANnz8ai6b)XvGAGfPO@|7uSVMeC^A8j~s67 z$mN?ihvfAIoXJkno;I`o{%A{oof18c3j{8&ByT^)%-xy^^^yO0{;ng=PFw}`Rk)N0 z!0z%)BklaV5bSpuz6`xH?M{XSpbJ=~T5oWynQN`Z?R5L3Buoip7g}O{?|1MSo`YuW zuiFtmwO`;xmD5!@>Mk9#Iwh_Wz;|Q(x$@$xFT^6l2QOim7MQ*_JCVC=bFa#Pi<**T zm{Oh8R1Jvqb!JB$CY6}%4+LDImR|p|7HdvK3~~N`aW<&gAJdVYJK!2Kp`=WY)eDA% zsppkBu>y}of3|_zZB<#>M;(wdik(~O@n297J@F((@d2epNuuw;k5rU?23rq2YcH@;q|CXzc>XUnQW|(V9hTl#6Ly8vWIkUccM1NoWsIdEJ6#;!487&OW znj89~!1EVb`)$D;j`}Y(sHIyPh**Doo-TWYcvi2PK#+-ZnLY~N1tJPL_MG^;%nr$W zo3>~a@5WS0B)A-dVAajp%Dvw5zBU{~eCc#~%V~OQf?ZP6d7ep~^JK}tXIavKaAjK0 zsh(3caafOFe_Xun0d}ol`t9OxyjyE62I^2cVA960lK(D6l?`MoMKI4~tMz5)8|f;e zjI2vZeAU_=i*Ic$B6aCpfC)XHyr#5e!Z+on@qXX4pm(w(;gGyPzFz}d(`zhW84Wl@ zh5xa)xK%E8Ew*&%9KCL+5vC5tqy%1ag+59uU22#8i)0HU6gRn{eVf-Zh|Q1GW12y| z(*8@Q=0sUCxflwWaJ zFP1VY6(w4k94u4k5;YB+(R-w1K26&l$v4xQuo*rXkqtf@ZIrfe%WgzYXc{V5-4)>) z29cF=@Qn|Yx~;%i{oxf&C=7e?S%v1AoJ&VC;aln8>m8wR8&3pL+Lj+7F3h7ieJf?c z)v>8yaq;vb{|ZH7aIT(SoHz6NYYv=!+S2=5p~kd!!9(8gDDDpgie_swc*)KcSa;m5 z|Gm6FvWw8k19+*zphW!Q7icwS$9Db28vMdO!zqnHb@pUcFd;<^%7zNTyNiL zeT2(QTIDMwvJHfkjw%_^9if~J;UN>XMQhb6+kHCEo@FD_Hilt*thBv&F3sw{7wsZ5 ztap6;S_Unc>-R_Eju1{U_!nEgZqxMP_lFeT zTA>n0oxD|1GnEkSbSW5aGHu#Cu|{UW#YO=y(tfZ2sfG?P+~4%y&U zKa`kW+FL4tDciPH_5%4*3oPHpAyFndpu~e2DKkN`SdYPSpehz`OJQh9ZmH|gS20+s zN}G#(r6T@;p#fm#y?@FU_$qja(;gERMJU{@1ZF`vitQ8rJMd$i8ZPROYyxXSy z6`aw@D*5Y|@zLh>XiFb>|G1)Y?{r=cE30&W1}t&f2ZLUG+0tpo)Oz!1q&@Q= z*}k_@VI#yp$%2b#EuIp1vzp=ans5M&$G2?kBW6SHilbgqQ^*RC`4PdL^SRr-*|i-m z{yb$tWA-5aaRs_*bEJ4)qgeEdP|F5`&emtz@k=fghiJk1mk7NBQRZ5O7x{z#dmij{ zra=Bm<|rl|>Y+|mYudcB&vPVM;&#^%gUELgc={C;s&w(k<0>FFBMM(>;%r7o-)=l_N?WWd5dt(0=Qq%X6}j zXZtg2af7>y3y>*Srw^xdhDQez`ePZEn()70*l4t@M>!oDMc!Ybsmwp2klgAeFZz-sj;XOQcUZUt;tN^tj%2LBEA>?CAXTj{oo;AQ z3$swN>YJULCg~(D`kEAk&#s~hta@iQSI@=~<<8T-x9_Z~({s@JzptW2e4BVe&Bi8NenF zAeZGd=K$#Pc>YI)?0?1SyJ=&$nhc7$7U%K8v!(o@l<#2Q(612`Z{kjD;XCrIEb{cd zg?|O~sKi!qwCg34M^KI?(Id9`xzxd5>3su$RE|aVbervt6>z%neI#i@Q$if}Li%&# zGaJj-@HF83{T#O(htWy9PJGI8yoqWt4BMcH4H(^{RNWaHx@j%?vRuK|-8>|ZpDvgq z;(-OG$c&O@nMcS2f9i66q6ls^*zgSnDG`a~hp|q&EGZ@j?bi@=yIZ)Q8vm<(?+gxK zydQS^5U?RnNc{6k=NWfXywtvA;_RER56Md!A}@g}(D-GMtvlb*+E=MrFUXpd;+PK1i+`i%GHm<*v-s!XS|7jKo#L_zQDxL z>=?2}uax#s&QM~riIg)o13GU1E#3T`K04v?y?>ctKl2vRzia~0Y&21NR`7eYsT=IW z_HvXb2fgl^1vO*WNBY77cc^^^iIi2tU{@l;1-`4^ zW_`D2uzh&pIH$ay_V3`vJBIL-_wp@sOg#4vgf*J213C3We&lE7otfV{_m?A+73W~W zHXyYM5QbO%2F8#&(L@h;yt$CT({xiE_^f-y#yUS5Sj0a4Ls(S*Av506;1fD@X2?~7 z?mUFpvv6u}yiR^*dU|Wzq~|7|l?)<=wWzL+=XzB^7aU#0p}YTj4Ap%!8Yj!O`skhF zeMxaHaiwK!hL%#@E3Yy=2zq+fYAr%U?O~JFy0xo$0MjB9+FGmyIwP!c%!UCxB2ca(K+P5nrR==awnTs^mx0!I#{v>9ry$I8P}7@aS_ z6s@fep}C0eXY~oSjBgw8jG1UU zjCO_*Pt-~DD=(^>_v1A1#;ASGzca?-r8YKl7@Nc2piO$g*;x!`$v$iH&-;`OJugk2 zP)@7SK{OSrwlkN%3l$T>yH;3Rn}LqaPb47(o)%UJxy5hrd$9S)FeoXP?z#U@VQ(GP zM!3Wc<626AqA3vE9YXO^+`UlTDG=OUixnv@!Ci{G7I!TL65OS@6sNrDmG`~hy?=ar za?WmMXXlyc**Tk;?96Y#IzI`(rk>NV1#aiwwnO%Tgc!VJQMRIwa&(`L>8Z<;w%hRm zn#F_kAJoz-N6|hk>QIpC({943acWE^B=5VILl%p4bR#TdHiDFlT!c(k+)|Koa<#`I#dqyk@7vOwmPli!EC?1VyC*IP;iOS;&g-Crd>>9<7ipQ4GkV}6Rb-{>q7 zw$O~Q4}rxv;Z=kijQbzyJIg!T;m7Qw!k<5LjKG6=jX1Ujjqk zJ2KvB%9GO1&j^5(NcXN{7x-HPcJ;9Xj(t&gb|GvsD5s`6W+sUvFO+o*>?mdduQ>Xn zd#wxtHPaoOOR>`>;{T!=U`A!Jvc@gIYDqhWmYC0!+_7?%Om|z-DZ7)A65oDgK8N%M z<_1_JJ{@SWYuCrb3?s+-Gyqt#_7M$5Mf7PPxN~+rQ){&=@_D9vW{m%AE!Zdfu8C_4m zI%e=hSa#c{F5|Tnvl{-%VQA6dCh=~MYG`&xZ?##$EYThB8?Sb+wO8M~0)8AR>%_S; zx$mrFZ~)cccMj;X6(A4;_S^Hs&uE~_(~ab{N2pV+x727tn{#GJ`?qc{B=EctJ7*Bo zY+y+j@O~!xnG^G89WRGw*msq2(JFiMhx3D!mb=kzHiN=2$1v^n?#Ai;X_gZ&oBGj^ ztxw%WA%R3!2(W4I$Q&@@g8N&AotSr5tlvIMM#pFdf8s|k-%hI0Umr+W9$cx zbC^s&9?b0gBFrkYnl4|$IJ{-JnV@})&AG0~_pX(_u1f3^;9r9&$BT72kQ?O@zJ25>>0BCB76apCj2kK9*pf1iqb7KSh?sY~D&uyS!o(gHl&XjW&09O`IZ=Xuf<)>j+;6+63ld{^X_WkSQ0#6{tE-DYG| z5(Yp-9W+24F2nbE2_w~3tnGAMdLhhG8+ZDQOR@nVe8~c~$GUcGF()8k;}DcWn+M#1 zrHfRANM_OtgaELj`R(2Eh1z!G%^hlI!*M8zD<)a>v%{zCpUr{%Qz=l%E;U-$k7N0_ zz#QxH7nff)3*r&TO{?ALa%Z;UYw$FJQozF-M1wvv&$Z#4e1u4V#X@6Zd_D_M`VjH2 z23`^98GV)2X2%oM;5`>%X-&^6x^|lm%Dg?kgIfRuKPJX1#WSw@9bzJTT0lC^H(#Gn z)H0)#X6KwH5qyw-WG=3uNjXzsuuO*mQbnF|+Mo58f8ZtWwWWb-(-#>XZf~-32y0^*QL1$)Gq_@S?ibE`lJ^?-SxnN_-J@Besf?kVGvI`27;;S!We5k-# z7H2T28I56U41Y8{eOsF$t_IAihy%#96mJjWimZ+NA_Tor`H5v!7Zn{->*y11>~H$c z6fBxYOcwD7F9jjZ#B=A7-?u+tCw+jnI`R>6F5)b=z9W0v{+ZZGGPGVGZ~;sIA{HA= zm8geUb0mR>FB}y%0QHSC{1m8^JHMZn)5Ik1nJH{Y3BesWH?JJUgUYJ-{dPxgO9sns z;He6dnb)Hp^CX9$ce=IZnq2LvdW!1yPwr)!V=?w&?#D(JhzJ5D^As`datASw^vxKH2Qp!lMsGxKB< z)Ge8Tp8GQiH56+!yW@-q+)&RL>nxTk`LQY52eTjESib^o!e zB~tQgmhCWAP-!EZy?_SzrFBiYy8<-?Y6hyM;Cu;TdE?*>|G5nMrBR1D?Ii>I){O>U zPn8Nqa}6P=q?0b=*_@Neg1VmMRV7SRDI0;ryauX@JHeS^e(VYq{MBkspAKTyNKxt6|1+vAxyv#3SKtKBOWvG)9^9IK3V~!>2GB%n@+yc;-ftWH z<9CXO3)mKW61ty(ow+??4cbI1Rcf#OM3y68%9Zk(ua^8=Fqqz{XZSNB8}q6UI=zsP@*Q2RL}VoF=jRN6BBiwm z0_j3y*hlqph=dmcTS)me!bM{QJ7(D-XEWJmo2Or#Bu=9Bhp4e zKWGKk+JwZgYeio@aPC(evG>v&!P{!L_Lx~EqHgAgA^jQ+(-5g%K|t>1F+~^UCrOM^ zTm2flg^+GdXhmR^VI>2~A80fs;FZI1!7~k&%8RpClB9uJ4>@5R{483Rwpd73>P~1f zDVTVx>Gdmy!4CXNro_Ld!gUF5z( z6g;xjDlj7fIW;VkN`YZ43X10m}<37cpc+Hngs*F`a@}zfFtk`)6GS_x4TY!=&o0Q&R8$uKy3v6qb13e z@NUe|(5r&i-c3vD*du=Tl~oDV*}WzY_NuTetCSHvC3s;NU-Fv_ALp z?Wy7ZoI2?T^?|k4JW;iZpib~{)M{b~f* zbNGXYMr=hed|x2;W1 zW-;{Av`fIrd0k4f6E62P2DithT}=>4&j`f!!wKYZW>cMjsX+NLNC-FmbP6nQW0SX~ zjY27yKKrkmS9K*=Yl0T!H97-Z+KecOISW$^_Wqn0& zEpHRDa=jcwZ%7Q1Ow7jyh-9UFu0w+7y(#;6C1bg+G{Ikwox_$(wv(z{`)#DjIR0k% z_Hzh11oV2LCP+MUfD9dkbLne=_OAh!AE7{ z4nRdIJGl2<;-+CezYc%4j2NuV0YiIrx;xFxvLH!)@iZUxr%roa>VM^^CP{ z31J}_BF9!EpaROyqVu?Hncuy$$wY7-`%6<8gP1t$joO#jCz7xjI(c-^qg}av0tl?E zf;2kk9H#Uk2?Vuz=LlmO*rE|XnGaW~3W3yZRa5MgtwB0}QwoDL1@M~XvIvwIG z=Z2WJ;sMq(Lm9(38J1gO{C+@_4m2g})tLxU)4{!z$jM?;_GRL;p z7HWdun{v>c$Moddwd1)QM>j>1)NVIs>0*F?mBDt}JooKcF<(O%80G^H6uu{u*b)2e zuhPp7p7_^k?=867V6c9cyPiv5(ZOc{9pXch(k!HRD;(PDOe8RUe6RwL3*!TnIedD% z&pNP%>{*%kKzaqyA-95|XPpNl^tq&k-zd!vC)`f+ln;QfqkdHFw*VAAaJ}h{d6TGg zi%+EETE9OsSdxBLoPhr;s{FDxl!(Fm9oeD0zq{E86O4A3_XWph47Z6!Jy*EBPaiKG zFF;gimj?r_cUbIV=B|FjgFJRc$8?mSaeTM_vsVwYp0RhW3CCvi$5eXCp32xeezQ5p zE8iQlWFV~HvVG(O09N=3#(50^%WH(wBOag=xGZDSjia&R;j#Pw>{`*ra$0SrRCqsN zX;&)xJ3w_7h4qa$jb=G-WiyM(!lz}DZlYk~j5awZ+n(f%Cmm-6Q21|g4jLT%#^7kg zcjc6juiZD|R}V;UiCK;rLT6%(skE)H&E(i%p+y$E>sFVel-@0s?2?D>1Z+{M(iOQ2 zoP&YL3U*<797BE&{;YU}0GD)u;?A@W%#ue#XoPUjT+lTCVo)FtL{S!aSaUptPe8(X z+5g6Y8Qfi9loOU=6sf+RrU6<^W?TJnC&Jd-`0>UJ)0czW-=+>Rz=eIfeWe@zR_=B1 z&|`Ys_a9Tv%{T?^4%cRpjL>bB37=R_Yo5Jn>orjvOC-ruQJ<3n9@^V4U%PLA+B}mU zFTKAuRS7>)kvSknZezBoBew0_>aitF#3>z&nD%B@?SiW05U{F^=Lf8~e{*slF^-!f z?UMyfX@~tX0msjxs8!+RAp_#G$!8Z(*p9Nrvps$J!cleoDJcOnB^FaTWZD7U(#DDR zWDyfW?_CNBLP@4k>H-fNj)w5{YUI{BsJuz_{%qHs@V|g;lM7)|$91CxHC0Nd_Hn_N z%8M32Ni@!j49-1B8~mix`OuIi_ExsqXPkwyzQxuFzEYYsa!4+b#bGgWeXee=IPjSy za23NttE5-r=+aEh*k=$RT4joP8YgxQ`RbaGOX=+poDv86CZyt*OL1Dc<{BB?eG6}- zP3vESjT=73YE?2_lE=iPMbi~A@zgNo%Iw0rKU%M7i{`1b;J0lL$2oYogZu<@WY zKf*PhjRvjJ_0D2R$NB8h5OY2Q;D>+{PUoyJz#u7cY5%Lev2K`SA39m!K~!zOn; zr{0!=+Jia!$udvP<*QC!!4fFmtmqriSw?VZbZOZ^z5iP7)>>26gVXVAK?28gAE&ek)DP>XyRC?4|=2KBfm8`Gux_>{2wg&WMA-m>kCD(;|X$P30+a9w$D?_0KaIlE zT7sltknez&Baz~VyjoaX(Kpw{KQAiIYuue*Z&gaf4J;>A8`n4Yw-)DytKo8V*W z`uy#I$f=4>-jyx5DamDxdzDYJLR7>VN1cDH#o?th|F#Z??$N@7QN^j&2N@r=(5f5s zCK0<1H$($#i6sCuX|2%8?S&1>WgxE18RS&ff?{NcRBQuD(>Tk>`3w~;zCv|T-vYRUv+~Y$821nKR70K zAE?TaPvzDJiBrNIJ9r`DuAUq&=S9beIus}n^hJ9R?)u}8@^#zmisni1vea!i^k`+y z)nkML8Z(7Huscm&GR9;HI{A?fhaRJ!=|(=BeUwWAsZsq(@XkjXVjHC7f2eBp@V5&- z-z}X4#~SQFc)P@`tr@Tn$9IWE#?oV|aGH-gS7Ey!2wkmxSDcQo(_`9EC`lll?HMQR zFl4hWkA=W?rs9C`$PNn!eWYbHD-x6~gpBy{5DPBSP;|6DE>74!F zflbw$v#$^Eb;*mz!}~3rGzt>2>+cL=WbHcPY=zef1H_hzO{i)Fr--#&Vq$c^?hSQ{ z1<5L^rQD@!|BzafD`YG*LBy|h-OH@Yh_TxW`L^zhFUt*x*D4H4I&&xMvvSth7v1{F zJgaYk$)XZHJwT-KbY7cohZh2*uQH>#WZo(u`#=8_e=c+x1(Cg#=&_=;qk+BIdx4r0 z?>g^;jgw^glTE#pF{o~`36Iy zwm2`waEJv3zn$JC_ty`VlBL0-%UA2Ub6}Z8UG)T~Yy#t3F;W5qC@`oi1ClOPs)L2#?e&jME{C}~UQ(Wy>^WdU4N3lD4RZ5Bjpzi3U(|Ed}a zd60GW;Z>f@nT`AczVbf`66yUYg2yJxUN-%oh0hiqTC zJZ{0grR>mnr7dDx5YYI3y66Kg&B^$nK`aj>U5OZHe`~_*WcJzsZh87y6Ylxk2CRb~ zs-@{TA)A7bAzzP0DbRi6-eQ(}rMeX6>yg3JmzA~E@P?T}LP+Qp#Ue>L-o}~w0BBBi3yW1E5VCV; zLn0cE2+hQ2eoMH4zfqp|_{w`s#^>pP7BHuJLPKIVOgD*(KI)nZddZIpV6iNGp&%yy-2y|NEth2lk2M zyaBhmm41J`J<)RSFJf_hx5+kWgp}yQ_(i*IQa{8Nw~-N~mK{9JI);a)UyyMP1qv zLeG>?oeCuGa@%*Ry;CbdO!k;Y0JO2-tnr50?VXeC!HyCGkBM`^6u2a%WryGkH~c~h zM7j8wLx%$-JQ?mD*}LpSyEb{Grq?n0`7U*WV#geNRx|wJxemQ}vve#oAI^s79i&+& zvwu%ruX9O+aPgd`dnm#Y3|H!{EcfUkOEGypoUg!+e(#pYxblUuWY&$@M7#|`f)N47 z;!NmLl@YGm=Le^FS1N)ZMt!OFET{dej(%L`)qezl-w6A#TJ88K=qv!yZL{&RCO(%; z8~ncWTR=& z_)(_=E|VUi6>_SOzQ6657?X+MX-+NDq7$76-sYhg2=PPLgt+u5fg~f?i7-MR)X0%< zY<#r4qZYxLzOm~kiznF8ZWO3y7RzF5AsvnLVsYs4+>X^m9*^XzCvu=#N#(lMIvGb z6(Qh@&tgTf_9d*}G(L)#KxbtprN6gc4=+u0@z3V0H~uR0_{E|^qDb}JWkof^;=9w? zkv_|lTA@UwNOjj`L?w{mbftm!Wb>0vYntu8u$G7R(nG}I$9r;SR!7;CI>zB*Mt@R2 zkShBEp~rd@kk5I0^#{6xr{2{TukylDiQ*aRtGFNf;+^#}m}ty?s9*|~jP#hk?LGG` z_RRE&bg*bv`f7r&rJ0&CBsX0Nz$Vi2wkM=wrmt+8#%k*%hVSiwC5XL==lY^-tY*YO zEu!FfHy_OIBH!XH-H^1!EuWwB3hpv)#kiA#;sBmX#ANqU zTMb4AT}JI{x5PyQd72^8k5(v>Oae5&8yRql%e!yxyFDo~Xq)(30o~g=|K5rT3$0RJ~#A5IvvNn;F9BG>^D% zW8nFd-_~b>YAew<*Ltw7bJX*m=bIbO{Kin3aFSL6)=3!da1Orn>lVEyvw>{Ik)PZGt zL0h{Fl)LI;^Vvi8!L%rh!SToCjuMN@Kl)DL%9Jm%Hoo5VXrJ$jPE<|*Kq?fe!=USR z9^}#^x@-$H2>6RHHi(5YIO-YUo3|poDLQfNgK}2eC^KH{*uL^@_uMk#k5#nrMfwDZ z4LPlfaXmS0!QnWq<45qV^vs~eopj2C9jLH{wDk|W)#)3+QIK~8fWOm$N0^g$~T8&sdJzf*~w32XQ;w~c27 zO04K`3!3cEDQ@hSka4w74g9t~E?wR$Fg89YK&zfRG_dRQ@zl0Pm>sn6&OGHDjPtf8 z<;rmv+AKy0m3zEs&p*2f=$!Ir_I0!@Wc0rmeLi8RTVm)rnF>(}$bMdR=(>||!1JE! zy4yXi>Y(!v-Lsu~z!f>we%9N6idzl%<&{&A!-;*$@x9~WF|v7`;#u^KSOER|2g=k` z-A*K&ygSU%=ariQO2YR1TimA8=beBH*oMmU%q8x#{@lLHDSyD>Sap{=MJ&{?lge82 z@hnbZ)0b)mc=7$l;rVxt*Yo!CpORwNtd|BaD^^J7U^ZWtO@(D+XEa|uJhrq_lQMFjD=Gc&qViWXAZ(88d&r0(Ou z-gp1^-{I)t&tf;vD>=sTYsAm{?E!7*V=6u2&jq)49EPu-7gPo~#GX>c9;eoxaQ`@n zy-pQ;P;H8zaCn}6C>YRg=lHYr{mIJcQOKxb_I>G?I||6?i8z4eHoWH~PV~uB@AXi; zg`X$v`S~gLo({{x-rU92*}}x`?~#M44c1#AC-Co{?=3GE=f8n|J{^q^=-Jzp;wJZKEjB|=a6&U!!iS{R zXdKI^5%0)`kqL7VT>}w0Q9pDOy+yEEf7uZvhJl6$L}NvK^A$xsh=dj0%b1)IWx$vR z`jWZFP!;=^IL%uu-EKKYB7FqyZoX;slVEX9r0gK4GcrYLjQ7&!cove#Gg8s7u=|Nj zfK?Iv_z|I0T(ZIm5g75Tw74JRUej2}(y7P%q!FWL_*y?qS4i9%^Ma~iIA_==DNtRF zP!qr>y_fqUDH1IgZ{L&`Pf5mQ2FaB`H)uXLe8%#M)f@F#0)5769|iH1Iff02NHAfL z_!%tauu6*_X6p z>Mxkm8xl0%FDltkHzs<^^%Y`rr+*V~0=9n*838-fw|?zN^iA^(^UV@|@6SR!$mw?Wb9pTolqk#HJ)>u_Kc}lDa%wQH*mk_xtpu4@sbS_xRYa z$|;5n22?AIeunqiS8zyWQa@6ebXC%>aou#RbQ*4Ai!k$5wdB%WO%dhcJ*i+lj`eeLSaHERs~`CYh}h4jEaoREQ^e2EXB+zj1=k}g}0KC-^{;lSN3Z$ zt1ec%DqHKM=Yn&O%Er|UtMw~<4ZS2k7n^*~`fw*+Bx9kkCFhoHlk^K~j(JX_ zJj4ct&x|i6<6WiZajEY2#fOiJ^=b8<^`J?cOgF!Iz;D>ElV8HWsejY|7X5ug#*5<+ z^E!r&jE(Guk4wpALUm#%!-sduHg@7e`mr#Cr~T9Q49ufJmCdD+vocxtp|P!zzQL`* zuTg4IsBy|V?x6Ib<&gFeJS$MiQ(p1yuzYM`rPxRMhDj-Tun_YTVT1BwOLj_jj$w*n zqhZ`?VOOMop?{Zu;vYX`YveHT;2u!O%Md3CgFe(SuP~f2k7!2e7X`Ehso*Tt?c<5Kr44 zc-SR@AMGye7QufS_?ma1A7HDQEJ6!bCmF4kE=J?^X+w}^t5r53i*{6Zz>(mQ=%Ntx z%Q4_shWrKjCb_%73rRBX~2U$YaTU$$8m|z9Mntw7eBl zlDNk_<<1eDTCE+g9oL-TQRq>0gG}j{BbkGi<76bXmfUshFZmteJDWc;s~u6e))d)| z$C=U28tFS64BXNeo+O_r7+-?*0@=@uYTSA{fdxPlRRvBAOH>D(E=p7U1d0n6MkZd` z2IecZG$kEF9qkt9+aG5V8`U(z)bcbZ(izg0Qtpx?G6Pa`GM$mvQS4tR^xs--lz-MX z%Xu>9~yz{JO?%v6nIlHQZjX!zbAEG=?HU)3jR@j zM0e+G4-=`4ZUisXImI$qq3@9{WVOc#jk;_kpHncj&?eCd%el%eXS~hWPSMQf9lY7r zzA&PFpgUFaPsGo32JX}Yb*GbE)?mKc=PP?km=JII zV}%uP+XSq*hfzFW!0 z4V>+Uvs%%1;jSmcJwCk+Uhhw z6QH&9TV(6uUT~sqvn>ui6desWjQr@EM`^WKp<8JKqTR3!iO3s|+eKVMu?CPX-v|CO zK0-=FnYvivC$2w3e+m#~gkrg3`Tm$+%~oxV4t>dp-_6`TPbp04nNOQvCHTW2xR|*V z`wV`%3`+E7s8BA;W)@-dYg@nC<7u^`Uz9pFvm%&!>A`y3;$y$j3dzdL64^tZH0oG) z+0ZAhKOC1z{ldT@U?Av}?$o*y^_0A8-+r?79s1Lnf1D`n0>iw?XrweplTpNGB zheqpZ|FfT87gTTh&cZ#y1>kKP#%_=MWP4~}GCOf@lnY|De$LK6t*#blrBr0HBeRua z3I9~xK2+@$PX*lfJ;j}zf8L_u=;si9{&=CjwG*U$Y3QaHswnK4b?<$lG@}>OjK0RT z>ediz_7XeUH$CT8{&r$lrCIs zQ_4?ksle;VP$=Q1#iQZ}l>RgNh|pl5ue(dQu>M9}u5m71d*5rhVu!I*f5}1QsB^ABR zTg*I^tPmXag^pq9PyV*pVd0aK*dye}yC=bp@l=e^#uj&Bj zKb?T$q+1{U^{j1{1GG0vzk?af3FM(AJ|@Lvo|H;%^F|`~+E$pxm2aoUSGxsD;3h7g zwEpbQ&2#hY8vL7w=RX{O zO)p2df3Ip{W#IzkP_i($HhJ&h3Do-=8-TdDf&2p820#u82RD1yzafEwwYdvW56JzG zD8b;b+yAc!1J3%-5aVw!@lTl&Caxx62djSz|2wGqe_ru#Ef|$d%z!EyKpnWA>>ze- zpqiVBv#U2yRZ?2Q!QR!v)0OG}j>7w|Q5Yo!xjDHwIe9pFxp_GGczAU=IT_%e|Ht_s z>Zm$9n7f(5Ll&-o>cAlZkBwZd9qc9l#x`7kWx_)qB?t5W{Qm!@=ILxWpkeI|UuQlbhq{9U+>GE?{#|f6drJqnP5tv&5^hz(W+0F`r#Ua5 z1 Fe*mor1#kcW literal 0 HcmV?d00001 diff --git a/doc/images/n-steps.png b/doc/images/n-steps.png new file mode 100644 index 0000000000000000000000000000000000000000..988fe5dfce89e48f42763c1d4398d6816f5b8f4c GIT binary patch literal 1427 zcmV;E1#J3>P)600002VoOIv0063u zBQgL0010qNS#tmY07w7;07w8v$!k6U000Sga6xAP00B<`008j-Kn&ja000DfNklGb&ajO3TYOW;f4gIfD`WHK(-pC4E88vHVT^(0NY57{MqL^#b6sK!sC7iC2 z_1dVp?hgF_sKIIJrT$~$^xR9yN6+xAFY&B1oF3uS;FNK?M%K%#m9C<#`FWUT2>n^O z-&2Ir6Zcy}RKqka;SQumbQ?odaEw+!)bl-()zsI=t$)piu0YB&RiB{|M}AseQX)5K zPPRErT?JfmrF7I(m$V&vPV<_&d!a1U!w{{9>Vf@9(uq5arkS5AN6XQ^yBP72JwT=C z<$}r%wY@Fm?b1F^MLI~y(L70i|HRUfrNscXaTas7%SR@*R8x>nZ4G|2t+AzPO&DFmS{<;=`pxG)y6?RY7FnAco07br2YYG4zVK23(}H2Da7s9pI8AXH z_nsI*Y8P2FKpRn>Y^E7T3l>5R(8fHiS&VaxDxQorMu{gCP7O#Co|G6hF`M%Oqlqcc zu&mV`GyWr7EZv~TRu|YM_|(0j0eac6=RRzZ5UocFM9UEeVnLVH@h%1YH2i56A^mq3}xs)=Y>t9#E1!f2vj6bhrM*4>pr)uC!ptK72^@Y0fVtrbL{ z+LgenzFz$Ko~6HJ5Z$%(86ng>vg?bd5~8;`)89eV?XqSad^gZEa<4bO0bpZDD6+AZKN6WpZJ3Wn>^?c_2qnOdv;SZ*z2W zV{&P5bRZ~XWp-&}Wj%0iZE|6EDGCQC&hP*L05o((Safh?W;#e|Qe|^OZ*^{DX>Mmi zZ+HMRGc_(SH!*lJG%zkXIWa3VG&e3eHaIIXGBPeWIXJyna+Cl702FjZSafh?W;#}7 ha&u{KZU9h3MlCTeGYW{kWoZBa002ovPDHLkV1mwvi){b^ literal 0 HcmV?d00001 diff --git a/doc/macros.lyx b/doc/macros.lyx new file mode 100644 index 000000000..1e57e1675 --- /dev/null +++ b/doc/macros.lyx @@ -0,0 +1,294 @@ +#LyX 1.6.5 created this file. For more info see http://www.lyx.org/ +\lyxformat 345 +\begin_document +\begin_header +\textclass article +\use_default_options true +\language english +\inputencoding auto +\font_roman default +\font_sans default +\font_typewriter default +\font_default_family default +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\paperfontsize default +\use_hyperref false +\papersize default +\use_geometry false +\use_amsmath 1 +\use_esint 1 +\cite_engine basic +\use_bibtopic false +\paperorientation portrait +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\defskip medskip +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\author "" +\author "" +\end_header + +\begin_body + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}} +{\mathfrak{\mathbb{R}^{2}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathfrak{\mathbb{R}^{3}}} +{\mathfrak{\mathbb{R}^{3}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathfrak{\mathbb{R}^{6}}} +{\mathfrak{\mathbb{R}^{6}}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/math.lyx b/doc/math.lyx new file mode 100644 index 000000000..878a7b167 --- /dev/null +++ b/doc/math.lyx @@ -0,0 +1,5746 @@ +#LyX 2.0 created this file. For more info see http://www.lyx.org/ +\lyxformat 413 +\begin_document +\begin_header +\textclass article +\use_default_options false +\begin_modules +eqs-within-sections +figs-within-sections +theorems-ams-bytype +\end_modules +\maintain_unincluded_children false +\language english +\language_package default +\inputencoding auto +\fontencoding global +\font_roman times +\font_sans default +\font_typewriter default +\font_default_family rmdefault +\use_non_tex_fonts false +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 + +\graphics default +\default_output_format default +\output_sync 0 +\bibtex_command default +\index_command default +\paperfontsize 12 +\spacing single +\use_hyperref false +\papersize default +\use_geometry true +\use_amsmath 1 +\use_esint 0 +\use_mhchem 1 +\use_mathdots 1 +\cite_engine basic +\use_bibtopic false +\use_indices false +\paperorientation portrait +\suppress_date false +\use_refstyle 0 +\index Index +\shortcut idx +\color #008000 +\end_index +\leftmargin 1in +\topmargin 1in +\rightmargin 1in +\bottommargin 1in +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\paragraph_indentation default +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\html_math_output 0 +\html_css_as_file 0 +\html_be_strict false +\end_header + +\begin_body + +\begin_layout Title +Derivatives and Differentials +\end_layout + +\begin_layout Author +Frank Dellaert +\end_layout + +\begin_layout Standard +\begin_inset Box Frameless +position "t" +hor_pos "c" +has_inner_box 1 +inner_pos "t" +use_parbox 0 +use_makebox 0 +width "100col%" +special "none" +height "1in" +height_special "totalheight" +status collapsed + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SqrMah}[3]{\Vert{#1}-{#2}\Vert_{#3}^{2}} +{\Vert{#1}-{#2}\Vert_{#3}^{2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SqrZMah}[2]{\Vert{#1}\Vert_{#2}^{2}} +{\Vert{#1}\Vert_{#2}^{2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rone}{\mathbb{R}} +{\mathbb{R}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Reals}[1]{\mathbb{R}^{#1}} +{\mathbb{R}^{#1}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\OneD}[1]{\Reals{#1}\rightarrow\Rone} +{\Reals{#1}\rightarrow\Rone} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Multi}[2]{\Reals{#1}\rightarrow\Reals{#2}} +{\Reals{#1}\rightarrow\Reals{#2}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Man}{\mathcal{M}} +{\mathcal{M}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Derivatives +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}} +{\frac{\partial#1}{\partial#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\at}[2]{#1\biggr\rvert_{#2}} +{#1\biggr\rvert_{#2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} } +{\at{\deriv{#1}{#2}}{#3}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +Lie Groups +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\xhat}{\hat{x}} +{\hat{x}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\yhat}{\hat{y}} +{\hat{y}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Ad}[1]{Ad_{#1}} +{Ad_{#1}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\define}{\stackrel{\Delta}{=}} +{\stackrel{\Delta}{=}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\gg}{\mathfrak{g}} +{\mathfrak{g}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Rn}{\mathbb{R}^{n}} +{\mathbb{R}^{n}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rtwo}{\mathbb{R}^{2}} +{\mathbb{R}^{2}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOtwo}{SO(2)} +{SO(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sotwo}{\mathfrak{so(2)}} +{\mathfrak{so(2)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\that}{\hat{\theta}} +{\hat{\theta}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\skew}[1]{[#1]_{+}} +{[#1]_{+}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(2) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\SEtwo}{SE(2)} +{SE(2)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\setwo}{\mathfrak{se(2)}} +{\mathfrak{se(2)}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SO(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rthree}{\mathbb{R}^{3}} +{\mathbb{R}^{3}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SOthree}{SO(3)} +{SO(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sothree}{\mathfrak{so(3)}} +{\mathfrak{so(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\what}{\hat{\omega}} +{\hat{\omega}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\Skew}[1]{[#1]_{\times}} +{[#1]_{\times}} +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Note Comment +status open + +\begin_layout Plain Layout +SE(3) +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset FormulaMacro +\newcommand{\Rsix}{\mathbb{R}^{6}} +{\mathbb{R}^{6}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\SEthree}{SE(3)} +{SE(3)} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\sethree}{\mathfrak{se(3)}} +{\mathfrak{se(3)}} +\end_inset + + +\begin_inset FormulaMacro +\newcommand{\xihat}{\hat{\xi}} +{\hat{\xi}} +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Part +Theory +\end_layout + +\begin_layout Section +Optimization +\end_layout + +\begin_layout Standard +We will be concerned with minimizing a non-linear least squares objective + of the form +\begin_inset Formula +\begin{equation} +x^{*}=\arg\min_{x}\SqrMah{h(x)}z{\Sigma}\label{eq:objective} +\end{equation} + +\end_inset + +where +\begin_inset Formula $x\in\Man$ +\end_inset + + is a point on an +\begin_inset Formula $n$ +\end_inset + +-dimensional manifold (which could be +\begin_inset Formula $\Reals n$ +\end_inset + +, an n-dimensional Lie group +\begin_inset Formula $G$ +\end_inset + +, or a general manifold +\begin_inset Formula $\Man)$ +\end_inset + +, +\begin_inset Formula $z\in\Reals m$ +\end_inset + + is an observed measurement, +\begin_inset Formula $h:\Man\rightarrow\Reals m$ +\end_inset + + is a measurement function that predicts +\begin_inset Formula $z$ +\end_inset + + from +\begin_inset Formula $x$ +\end_inset + +, and +\begin_inset Formula $\SqrZMah e{\Sigma}\define e^{T}\Sigma^{-1}e$ +\end_inset + + is the squared Mahalanobis distance with covariance +\begin_inset Formula $\Sigma$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +To minimize +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:objective" + +\end_inset + + we need a notion of how the non-linear measurement function +\begin_inset Formula $h(x)$ +\end_inset + + behaves in the neighborhood of a linearization point +\begin_inset Formula $a$ +\end_inset + +. + Loosely speaking, we would like to define an +\begin_inset Formula $m\times n$ +\end_inset + + Jacobian matrix +\begin_inset Formula $H_{a}$ +\end_inset + + such that +\begin_inset Formula +\begin{equation} +h(a\oplus\xi)\approx h(a)+H_{a}\xi\label{eq:LocalBehavior} +\end{equation} + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + +, and the operation +\begin_inset Formula $\oplus$ +\end_inset + + +\begin_inset Quotes eld +\end_inset + +increments +\begin_inset Quotes erd +\end_inset + + +\begin_inset Formula $a\in\Man$ +\end_inset + +. + Below we more formally develop this notion, first for functions from +\begin_inset Formula $\Multi nm$ +\end_inset + +, then for Lie groups, and finally for manifolds. +\end_layout + +\begin_layout Standard +Once equipped with the approximation +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:LocalBehavior" + +\end_inset + +, we can minimize the objective function +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:objective" + +\end_inset + + with respect to +\begin_inset Formula $\delta x$ +\end_inset + + instead: +\begin_inset Formula +\begin{equation} +\xi^{*}=\arg\min_{\xi}\SqrMah{h(a)+H_{a}\xi}z{\Sigma}\label{eq:ApproximateObjective} +\end{equation} + +\end_inset + +This can be done by setting the derivative of +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:ApproximateObjective" + +\end_inset + + to zero, +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\begin_inset Formula +\[ +\frac{1}{2}H_{a}^{T}(h(a)+H_{a}\xi-z)=0 +\] + +\end_inset + + +\end_layout + +\end_inset + + yielding the +\series bold +normal equations +\series default +, +\begin_inset Formula +\[ +H_{a}^{T}H_{a}\xi=H_{a}^{T}\left(z-h(a)\right) +\] + +\end_inset + +which can be solved using Cholesky factorization. + Of course, we might have to iterate this multiple times, and use a trust-region + method to bound +\begin_inset Formula $\xi$ +\end_inset + + when the approximation +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:LocalBehavior" + +\end_inset + + is not good. +\end_layout + +\begin_layout Section +Multivariate Differentiation +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +For a vector space +\begin_inset Formula $\Reals n$ +\end_inset + +, the notion of an increment is just done by vector addition +\begin_inset Formula +\[ +a\oplus\xi\define a+\xi +\] + +\end_inset + +and for the approximation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:LocalBehavior" + +\end_inset + + we will use a Taylor expansion using multivariate differentiation. + However, loosely following +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + +, we use a perhaps unfamiliar way to define derivatives: +\end_layout + +\begin_layout Definition +\begin_inset CommandInset label +LatexCommand label +name "def:differentiable" + +\end_inset + +We define a function +\begin_inset Formula $f:\Multi nm$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)\in\Reals{m\times n}$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\delta x\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f(a+\xi)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +where +\begin_inset Formula $\left|e\right|\define\sqrt{e^{T}e}$ +\end_inset + + is the usual norm. + If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then the matrix +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear map +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + When no confusion is likely, we use the notation +\begin_inset Formula $F_{a}\define f'(a)$ +\end_inset + + to stress that +\begin_inset Formula $f'(a)$ +\end_inset + + is a matrix. +\end_layout + +\begin_layout Standard +The benefit of using this definition is that it generalizes the notion of + a scalar derivative +\begin_inset Formula $f'(a):\Rone\rightarrow\Rone$ +\end_inset + + to multivariate functions from +\begin_inset Formula $\Multi nm$ +\end_inset + +. + In particular, the derivative +\begin_inset Formula $Df_{a}$ +\end_inset + + maps vector increments +\begin_inset Formula $\xi$ +\end_inset + + on +\begin_inset Formula $a$ +\end_inset + + to increments +\begin_inset Formula $f'(a)\xi$ +\end_inset + + on +\begin_inset Formula $f(a)$ +\end_inset + +, such that this linear map locally approximates +\begin_inset Formula $f$ +\end_inset + +: +\begin_inset Formula +\[ +f(a+\xi)\approx f(a)+f'(a)\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:projection" + +\end_inset + +The function +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + projects a 3D point +\begin_inset Formula $(x,y,z)$ +\end_inset + + to the image plane, and has the Jacobian matrix +\begin_inset Formula +\[ +\pi'(x,y,z)=\frac{1}{z}\left[\begin{array}{ccc} +1 & 0 & -x/z\\ +0 & 1 & -y/z +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Properties of Derivatives +\end_layout + +\begin_layout Standard +This notion of a multivariate derivative obeys the usual rules: +\end_layout + +\begin_layout Theorem +(Chain rule) If +\begin_inset Formula $f:\Multi np$ +\end_inset + + is differentiable at +\begin_inset Formula $a$ +\end_inset + + and +\begin_inset Formula $g:\Multi pm$ +\end_inset + + is differentiable at +\begin_inset Formula $f(a)$ +\end_inset + +, +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + then +\begin_inset Formula $D(g\circ f)_{a}=Dg_{f(a)}\circ Df_{a}$ +\end_inset + + and +\end_layout + +\end_inset + + then the Jacobian matrix +\begin_inset Formula $H_{a}$ +\end_inset + + of +\begin_inset Formula $h=g\circ f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + is the +\begin_inset Formula $m\times n$ +\end_inset + + matrix product +\begin_inset Formula +\[ +H_{a}=G_{f(a)}F_{a} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +See +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:chain-rule" + +\end_inset + +If we follow the projection +\begin_inset Formula $\pi$ +\end_inset + + by a calibration step +\begin_inset Formula $\gamma:(x,y)\mapsto(u_{0}+fx,u_{0}+fy)$ +\end_inset + +, with +\begin_inset Formula +\[ +\gamma'(x,y)=\left[\begin{array}{cc} +f & 0\\ +0 & f +\end{array}\right] +\] + +\end_inset + +then the combined function +\begin_inset Formula $\gamma\circ\pi$ +\end_inset + + has the Jacobian matrix +\begin_inset Formula +\[ +(\gamma\circ\pi)'(x,y)=\frac{f}{z}\left[\begin{array}{ccc} +1 & 0 & -x/z\\ +0 & 1 & -y/z +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +(Inverse) If +\begin_inset Formula $f:\Multi nn$ +\end_inset + + is differentiable and has a differentiable inverse +\begin_inset Formula $g\define f^{-1}$ +\end_inset + +, then its Jacobian matrix +\begin_inset Formula $G_{a}$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + is just the inverse of that of +\begin_inset Formula $f$ +\end_inset + +, evaluated at +\begin_inset Formula $g(a)$ +\end_inset + +: +\begin_inset Formula +\[ +G_{a}=\left[F_{g(a)}\right]^{-1} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +See +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + +\end_layout + +\begin_layout Example +\begin_inset CommandInset label +LatexCommand label +name "ex:inverse" + +\end_inset + +The function +\begin_inset Formula $f:(x,y)\mapsto(x^{2},xy)$ +\end_inset + + has the Jacobian matrix +\end_layout + +\begin_layout Example +\begin_inset Formula +\[ +F_{(x,y)}=\left[\begin{array}{cc} +2x & 0\\ +y & x +\end{array}\right] +\] + +\end_inset + +and, for +\begin_inset Formula $x\geq0$ +\end_inset + +, its inverse is the function +\begin_inset Formula $g:(x,y)\mapsto(x^{1/2},x^{-1/2}y)$ +\end_inset + + with the Jacobian matrix +\begin_inset Formula +\[ +G_{(x,y)}=\frac{1}{2}\left[\begin{array}{cc} +x^{-1/2} & 0\\ +-x^{-3/2}y & 2x^{-1/2} +\end{array}\right] +\] + +\end_inset + +It is easily verified that +\begin_inset Formula +\[ +g'(a,b)f'(a^{1/2},a^{-1/2}b)=\frac{1}{2}\left[\begin{array}{cc} +a^{-1/2} & 0\\ +-a^{-3/2}b & 2a^{-1/2} +\end{array}\right]\left[\begin{array}{cc} +2a^{1/2} & 0\\ +a^{-1/2}b & a^{1/2} +\end{array}\right]=\left[\begin{array}{cc} +1 & 0\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Problem +Verify the above for +\begin_inset Formula $(a,b)=(4,6)$ +\end_inset + +. + Sketch the situation graphically to get insight. +\end_layout + +\begin_layout Subsection +Computing Multivariate Derivatives +\end_layout + +\begin_layout Standard +Computing derivatives is made easy by defining the concept of a partial + derivative: +\end_layout + +\begin_layout Definition +For +\begin_inset Formula $f:\OneD n$ +\end_inset + +, the +\series bold +partial derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, +\series bold + +\series default + +\begin_inset Formula +\[ +D_{j}f(a)\define\lim_{h\rightarrow0}\frac{f\left(a^{1},\ldots,a^{j}+h,\ldots,a^{n}\right)-f\left(a^{1},\ldots,a^{n}\right)}{h} +\] + +\end_inset + +which is the ordinary derivative of the scalar function +\begin_inset Formula $g(x)\define f\left(a^{1},\ldots,x,\ldots,a^{n}\right)$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +Using this definition, one can show that the Jacobian matrix +\begin_inset Formula $F_{a}$ +\end_inset + + of a differentiable +\emph on +multivariate +\emph default + function +\begin_inset Formula $f:\Multi nm$ +\end_inset + + consists simply of the +\begin_inset Formula $m\times n$ +\end_inset + + partial derivatives +\begin_inset Formula $D_{j}f^{i}(a)$ +\end_inset + +, evaluated at +\begin_inset Formula $a\in\Reals n$ +\end_inset + +: +\begin_inset Formula +\[ +F_{a}=\left[\begin{array}{ccc} +D_{1}f^{1}(a) & \cdots & D_{n}f^{1}(a)\\ +\vdots & \ddots & \vdots\\ +D_{1}f^{m}(a) & \ldots & D_{n}f^{m}(a) +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Problem +Verify the derivatives in Examples +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + + to +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:inverse" + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Multivariate Functions on Lie Groups +\end_layout + +\begin_layout Subsection +Lie Groups +\end_layout + +\begin_layout Standard +Lie groups are not as easy to treat as the vector space +\begin_inset Formula $\Reals n$ +\end_inset + + but nevertheless have a lot of structure. + To generalize the concept of the total derivative above we just need to + replace +\begin_inset Formula $a\oplus\xi$ +\end_inset + + in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:ApproximateObjective" + +\end_inset + + with a suitable operation in the Lie group +\begin_inset Formula $G$ +\end_inset + +. + In particular, the notion of an exponential map allows us to define an + incremental transformation as tracing out a geodesic curve on the group + manifold along a certain +\series bold +tangent vector +\series default + +\begin_inset Formula $\xi$ +\end_inset + +, +\begin_inset Formula +\[ +a\oplus\xi\define a\exp\left(\hat{\xi}\right) +\] + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + + for an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group, +\begin_inset Formula $\hat{\xi}\in\mathfrak{g}$ +\end_inset + + the Lie algebra element corresponding to the vector +\begin_inset Formula $\xi$ +\end_inset + +, and +\begin_inset Formula $\exp\hat{\xi}$ +\end_inset + + the exponential map. + Note that if +\begin_inset Formula $G$ +\end_inset + + is equal to +\begin_inset Formula $\Reals n$ +\end_inset + + then composing with the exponential map +\begin_inset Formula $ae^{\xihat}$ +\end_inset + + is just vector addition +\begin_inset Formula $a+\xi$ +\end_inset + +. +\end_layout + +\begin_layout Example +For the Lie group +\begin_inset Formula $\SOthree$ +\end_inset + + of 3D rotations the vector +\begin_inset Formula $\xi$ +\end_inset + + is denoted as +\begin_inset Formula $\omega$ +\end_inset + + and represents an angular displacement. + The Lie algebra element +\begin_inset Formula $\xihat$ +\end_inset + + is a skew symmetric matrix denoted as +\begin_inset Formula $\Skew{\omega}\in\sothree$ +\end_inset + +, and is given by +\begin_inset Formula +\[ +\Skew{\omega}=\left[\begin{array}{ccc} +0 & -\omega_{z} & \omega_{y}\\ +\omega_{z} & 0 & -\omega_{x}\\ +-\omega_{y} & \omega_{x} & 0 +\end{array}\right] +\] + +\end_inset + +Finally, the increment +\begin_inset Formula $a\oplus\xi=ae^{\xihat}$ +\end_inset + + corresponds to an incremental rotation +\begin_inset Formula $R\oplus\omega=Re^{\Skew{\omega}}$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +We can generalize Definition +\begin_inset CommandInset ref +LatexCommand ref +reference "def:differentiable" + +\end_inset + + to map exponential coordinates +\begin_inset Formula $\xi$ +\end_inset + + to increments +\begin_inset Formula $f'(a)\xi$ +\end_inset + + on +\begin_inset Formula $f(a)$ +\end_inset + +, such that the linear map +\begin_inset Formula $Df_{a}$ +\end_inset + + locally approximates a function +\begin_inset Formula $f$ +\end_inset + + from +\begin_inset Formula $G$ +\end_inset + + to +\begin_inset Formula $\Reals m$ +\end_inset + +: +\begin_inset Formula +\[ +f(ae^{\xihat})\approx f(a)+f'(a)\xi +\] + +\end_inset + + +\end_layout + +\begin_layout Definition +We define a function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a\in G$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)\in\Reals{m\times n}$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f(ae^{\hat{\xi}})\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then the matrix +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear map +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Note that the vectors +\begin_inset Formula $\xi$ +\end_inset + + can be viewed as lying in the tangent space to +\begin_inset Formula $G$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, but defining this rigorously would take us on a longer tour of differential + geometry. + Informally, +\begin_inset Formula $\xi$ +\end_inset + + is simply the direction, in a local coordinate frame, that is locally tangent + at +\begin_inset Formula $a$ +\end_inset + + to a geodesic curve +\begin_inset Formula $\gamma:t\mapsto ae^{\widehat{t\xi}}$ +\end_inset + + traced out by the exponential map, with +\begin_inset Formula $\gamma(0)=a$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Derivative of an Action +\begin_inset CommandInset label +LatexCommand label +name "sec:Derivatives-of-Actions" + +\end_inset + + +\end_layout + +\begin_layout Standard +The (usual) action of an +\begin_inset Formula $n$ +\end_inset + +-dimensional matrix group +\begin_inset Formula $G$ +\end_inset + + is matrix-vector multiplication on +\begin_inset Formula $\mathbb{R}^{n}$ +\end_inset + +, i.e., +\begin_inset Formula $f:G\times\Reals n\rightarrow\Reals n$ +\end_inset + + with +\begin_inset Formula +\[ +f(T,p)=Tp +\] + +\end_inset + +Since this is a function defined on the product +\begin_inset Formula $G\times\Reals n$ +\end_inset + + the derivative is a linear transformation +\begin_inset Formula $Df:\Multi{2n}n$ +\end_inset + + with +\begin_inset Formula +\[ +Df_{(T,p)}\left(\xi,\delta p\right)=D_{1}f_{(T,p)}\left(\xi\right)+D_{2}f_{(T,p)}\left(\delta p\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "th:Action" + +\end_inset + +The Jacobian matrix of the group action +\begin_inset Formula $f(T,P)=Tp$ +\end_inset + + at +\begin_inset Formula $(T,p)$ +\end_inset + + is given by +\begin_inset Formula +\[ +F_{(T,p)}=\left[\begin{array}{cc} +TH(p) & T\end{array}\right]=T\left[\begin{array}{cc} +H(p) & I_{n}\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $H:\Reals n\rightarrow\Reals{n\times n}$ +\end_inset + + a linear mapping that depends on +\begin_inset Formula $p$ +\end_inset + +, and +\begin_inset Formula $I_{n}$ +\end_inset + + the +\begin_inset Formula $n\times n$ +\end_inset + + identity matrix. +\end_layout + +\begin_layout Proof +First, the derivative +\begin_inset Formula $D_{2}f$ +\end_inset + + with respect to in +\begin_inset Formula $p$ +\end_inset + + is easy, as its matrix is simply T: +\begin_inset Formula +\[ +f(T,p+\delta p)=T(p+\delta p)=Tp+T\delta p=f(T,p)+D_{2}f(\delta p) +\] + +\end_inset + +For the derivative +\begin_inset Formula $D_{1}f$ +\end_inset + + with respect to a change in the first argument +\begin_inset Formula $T$ +\end_inset + +, we want +\end_layout + +\begin_layout Proof + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +\begin_inset Formula +\[ +f(Te^{\hat{\xi}},p)=Te^{\hat{\xi}}p\approx Tp+D_{1}f(\xi) +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +Since the matrix exponential is given by the series +\begin_inset Formula $e^{A}=I+A+\frac{A^{2}}{2!}+\frac{A^{3}}{3!}+\ldots$ +\end_inset + + we have, to first order +\begin_inset Formula +\[ +Te^{\hat{\xi}}p\approx T(I+\hat{\xi})p=Tp+T\hat{\xi}p +\] + +\end_inset + + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Note also that +\begin_inset Formula +\[ +T\hat{\xi}p=\left(T\hat{\xi}T^{-1}\right)Tp=\left(\Ad T\xihat\right)\left(Tp\right) +\] + +\end_inset + + +\end_layout + +\end_inset + +Hence, we need to show that +\begin_inset Formula +\begin{equation} +\xihat p=H(p)\xi\label{eq:Hp} +\end{equation} + +\end_inset + +with +\begin_inset Formula $H(p)$ +\end_inset + + an +\begin_inset Formula $n\times n$ +\end_inset + + matrix that depends on +\begin_inset Formula $p$ +\end_inset + +. + Expressing the map +\begin_inset Formula $\xi\rightarrow\hat{\xi}$ +\end_inset + + in terms of the Lie algebra generators +\begin_inset Formula $G^{i}$ +\end_inset + +, using tensors and Einstein summation, we have +\begin_inset Formula $\hat{\xi}_{j}^{i}=G_{jk}^{i}\xi^{k}$ +\end_inset + + allowing us to calculate +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none + +\begin_inset Formula $\hat{\xi}p$ +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit + as +\begin_inset Formula +\[ +\left(\hat{\xi}p\right)^{i}=\hat{\xi}_{j}^{i}p^{j}=G_{jk}^{i}\xi^{k}p^{j}=\left(G_{jk}^{i}p^{j}\right)\xi^{k}=H_{k}^{i}(p)\xi^{k} +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + +, we have +\begin_inset Formula $\hat{\omega}=\Skew{\omega}$ +\end_inset + + and +\begin_inset Formula +\[ +G_{k=1}:\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & -1\\ +0 & 1 & 0 +\end{array}\right)\mbox{}G_{k=2}:\left(\begin{array}{ccc} +0 & 0 & 1\\ +0 & 0 & 0\\ +-1 & 0 & 0 +\end{array}\right)\mbox{ }G_{k=3}:\left(\begin{array}{ccc} +0 & -1 & 0\\ +1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right) +\] + +\end_inset + + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +The matrices +\begin_inset Formula $\left(G_{k}^{i}\right)_{j}$ +\end_inset + + are obtained by assembling the +\begin_inset Formula $j^{th}$ +\end_inset + + columns of the generators above, yielding +\begin_inset Formula $H(p)$ +\end_inset + + equal to: +\begin_inset Formula +\[ +\left(\begin{array}{ccc} +0 & 0 & 0\\ +0 & 0 & 1\\ +0 & -1 & 0 +\end{array}\right)p^{1}+\left(\begin{array}{ccc} +0 & 0 & -1\\ +0 & 0 & 0\\ +1 & 0 & 0 +\end{array}\right)p^{2}+\left(\begin{array}{ccc} +0 & 1 & 0\\ +-1 & 0 & 0\\ +0 & 0 & 0 +\end{array}\right)p^{3}=\left(\begin{array}{ccc} +0 & p^{3} & -p^{2}\\ +-p^{3} & 0 & p^{1}\\ +p^{2} & -p^{1} & 0 +\end{array}\right)=\Skew{-p} +\] + +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\noun default +\color inherit +Hence, the Jacobian matrix of +\begin_inset Formula $f(R,p)=Rp$ +\end_inset + + is given by +\begin_inset Formula +\[ +F_{(R,p)}=R\left(\begin{array}{cc} +\Skew{-p} & I_{3}\end{array}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivative of an Inverse Action +\end_layout + +\begin_layout Standard +Applying the action by the inverse of +\begin_inset Formula $T\in G$ +\end_inset + + yields a function +\begin_inset Formula $g:G\times\Reals n\rightarrow\Reals n$ +\end_inset + + defined by +\begin_inset Formula +\[ +g(T,p)=T^{-1}p +\] + +\end_inset + + +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "Th:InverseAction" + +\end_inset + +The Jacobian matrix of the inverse group action +\begin_inset Formula $g(T,p)=T^{-1}p$ +\end_inset + + is given by +\begin_inset Formula +\[ +G_{(T,p)}=\left[\begin{array}{cc} +-H(T^{-1}p) & T^{-1}\end{array}\right] +\] + +\end_inset + +where +\begin_inset Formula $H:\Reals n\rightarrow\Reals{n\times n}$ +\end_inset + + is the same mapping as before. +\end_layout + +\begin_layout Proof +Again, the derivative +\begin_inset Formula $D_{2}g$ +\end_inset + + with respect to in +\begin_inset Formula $p$ +\end_inset + + is easy, the matrix of which is simply +\begin_inset Formula $T^{-1}$ +\end_inset + +: +\begin_inset Formula +\[ +g(T,p+\delta p)=T^{-1}(p+\delta p)=T^{-1}p+T^{-1}\delta p=g(T,p)+D_{2}g(\delta p) +\] + +\end_inset + +Conversely, a change in +\begin_inset Formula $T$ +\end_inset + + yields +\begin_inset Formula +\[ +g(Te^{\xihat},p)=\left(Te^{\xihat}\right)^{-1}p=e^{-\xihat}T^{-1}p +\] + +\end_inset + +Similar to before, if we expand the matrix exponential we get +\begin_inset Formula +\[ +e^{-A}=I-A+\frac{A^{2}}{2!}-\frac{A^{3}}{3!}+\ldots +\] + +\end_inset + +so +\begin_inset Formula +\[ +e^{-\xihat}T^{-1}p\approx(I-\xihat)T^{-1}p=g(T,p)-\xihat\left(T^{-1}p\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $R^{-1}=R^{T}$ +\end_inset + +, +\begin_inset Formula $H(p)=-\Skew p$ +\end_inset + +, and hence the Jacobian matrix of +\begin_inset Formula $g(R,p)=R^{T}p$ +\end_inset + + is given by +\begin_inset Formula +\[ +G_{(R,p)}=\left(\begin{array}{cc} +\Skew{R^{T}p} & R^{T}\end{array}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +My earlier attempt: because the wedge operator is linear, we have +\end_layout + +\begin_layout Plain Layout +\begin_inset Formula +\begin{eqnarray*} +f(\xi+x) & = & \exp\widehat{\left(\xi+x\right)}\\ + & = & \exp\left(\xihat+\hat{x}\right) +\end{eqnarray*} + +\end_inset + +However, except for commutative Lie groups, it is not true that +\begin_inset Formula $\exp\left(\xihat+\hat{x}\right)=\exp\xihat\exp\hat{x}$ +\end_inset + +. + However, if we expand the matrix exponential to second order and assume + +\begin_inset Formula $x\rightarrow0$ +\end_inset + + we do have +\begin_inset Formula +\[ +\exp\left(\xihat+\hat{x}\right)\approx I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat +\] + +\end_inset + +Now, if we ask what +\begin_inset Formula $\hat{y}$ +\end_inset + + would effect the same change: +\begin_inset Formula +\begin{eqnarray*} +\exp\xihat\exp\yhat & = & I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat\\ +\exp\xihat(I+\yhat) & = & I+\xihat+\hat{x}+\frac{1}{2}\xihat^{2}+\xhat\xihat\\ +\left(\exp\xihat\right)\yhat & = & \xhat+\xhat\xihat +\end{eqnarray*} + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Section +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For matrix Lie groups, if we have a matrix +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + + that depends on a parameter +\begin_inset Formula $t$ +\end_inset + +, i.e., +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + + follows a curve on the manifold, then it would be of interest to find the + velocity of a point +\begin_inset Formula $q^{n}(t)=T_{b}^{n}(t)p^{b}$ +\end_inset + + acted upon by +\begin_inset Formula $T_{b}^{n}(t)$ +\end_inset + +. + We can express the velocity of +\begin_inset Formula $q(t)$ +\end_inset + + in both the n-frame and b-frame: +\begin_inset Formula +\[ +\dot{q}^{n}=\dot{T}_{b}^{n}p^{b}=\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1}p^{n}\mbox{\,\,\,\,\ and\,\,\,\,}\dot{q}^{b}=\left(T_{b}^{n}\right)^{-1}\dot{q}^{n}=\left(T_{b}^{n}\right)^{-1}\dot{T}_{b}^{n}p^{b} +\] + +\end_inset + +Both the matrices +\begin_inset Formula $\xihat_{nb}^{n}\define\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1}$ +\end_inset + + and +\begin_inset Formula $\xihat_{nb}^{b}\define\left(T_{b}^{n}\right)^{-1}\dot{T}_{b}^{n}$ +\end_inset + + are skew-symmetric Lie algebra elements that describe the +\series bold +instantaneous velocity +\series default + +\begin_inset CommandInset citation +LatexCommand cite +after "page 51 for rotations, page 419 for SE(3)" +key "Murray94book" + +\end_inset + +. + We will revisit this for both rotations and rigid 3D transformations. +\end_layout + +\begin_layout Section +Differentials: Smooth Mapping between Lie Groups +\end_layout + +\begin_layout Subsection +Motivation and Definition +\end_layout + +\begin_layout Standard +The above shows how to compute the derivative of a function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + +. + However, what if the argument to +\begin_inset Formula $f$ +\end_inset + + is itself the result of a mapping between Lie groups? In other words, +\begin_inset Formula $f=g\circ\varphi$ +\end_inset + +, with +\begin_inset Formula $g:G\rightarrow\Reals m$ +\end_inset + + and where +\begin_inset Formula $\varphi:H\rightarrow G$ +\end_inset + + is a smooth mapping from the +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group +\begin_inset Formula $H$ +\end_inset + + to the +\begin_inset Formula $p$ +\end_inset + +-dimensional Lie group +\begin_inset Formula $G$ +\end_inset + +. + In this case, one would expect that we can arrive at +\begin_inset Formula $Df_{a}$ +\end_inset + + by composing linear maps, as follows: +\begin_inset Formula +\[ +f'(a)=(g\circ\varphi)'(a)=G_{\varphi(a)}\varphi'(a) +\] + +\end_inset + +where +\begin_inset Formula $\varphi'(a)$ +\end_inset + + is an +\begin_inset Formula $n\times p$ +\end_inset + + matrix that is the best linear approximation to the map +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Formula $\varphi:H\rightarrow G$ +\end_inset + +. + The corresponding linear map +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + is called the +\family default +\series bold +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +differential +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +or +\series bold +pushforward +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + of +\begin_inset Formula $ $ +\end_inset + +the mapping +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none +Because a rigorous definition will lead us too far astray, here we only + informally define the pushforward of +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + + as the linear map +\begin_inset Formula $D\varphi_{a}:\Multi np$ +\end_inset + + such that +\begin_inset Formula $D\varphi_{a}\left(\xi\right)\define\varphi'(a)\xi$ +\end_inset + + and +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit + +\begin_inset Formula +\begin{equation} +\varphi\left(ae^{\xihat}\right)\approx\varphi\left(a\right)\exp\left(\widehat{\varphi'(a)\xi}\right)\label{eq:pushforward} +\end{equation} + +\end_inset + +with equality for +\begin_inset Formula $\xi\rightarrow0$ +\end_inset + +. + We call +\begin_inset Formula $\varphi'(a)$ +\end_inset + + the +\series bold +Jacobian matrix +\series default + of the map +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + Below we show that even with this informal definition we can deduce the + pushforward in a number of useful cases. +\end_layout + +\begin_layout Subsection +Left Multiplication with a Constant +\end_layout + +\begin_layout Theorem +Suppose +\begin_inset Formula $G$ +\end_inset + + is an +\begin_inset Formula $n$ +\end_inset + +-dimensional Lie group, and +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as +\begin_inset Formula $\varphi(g)=hg$ +\end_inset + +, with +\begin_inset Formula $h\in G$ +\end_inset + + a constant. + Then +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + is the identity mapping and +\begin_inset Formula +\[ +\varphi'(a)=I_{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +\varphi(a)e^{\yhat} & = & \varphi(ae^{\xhat})\\ +hae^{\yhat} & = & hae^{\xhat}\\ +y & = & x +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforward of the Inverse Mapping +\end_layout + +\begin_layout Standard +A well known property of Lie groups is the the fact that applying an incremental + change +\begin_inset Formula $\xihat$ +\end_inset + + in a different frame +\begin_inset Formula $g$ +\end_inset + + can be applied in a single step by applying the change +\begin_inset Formula $Ad_{g}\xihat$ +\end_inset + + in the original frame, +\begin_inset Formula +\begin{equation} +ge^{\xihat}g^{-1}=\exp\left(Ad_{g}\xihat\right)\label{eq:Adjoint2} +\end{equation} + +\end_inset + +where +\begin_inset Formula $Ad_{g}:\mathfrak{g}\rightarrow\mathfrak{g}$ +\end_inset + + is the +\series bold +adjoint representation +\series default +. + This comes in handy in the following: +\end_layout + +\begin_layout Theorem +Suppose that +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as the mapping from an element +\begin_inset Formula $g$ +\end_inset + + to its +\series bold +inverse +\series default + +\begin_inset Formula $g^{-1}$ +\end_inset + +, i.e., +\begin_inset Formula $\varphi(g)=g^{-1}$ +\end_inset + +, then the pushforward +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + satisfies +\begin_inset Formula +\begin{align} +\left(D\varphi_{a}x\right)\hat{} & =-Ad_{a}\xhat\label{eq:Dinverse} +\end{align} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In other words, and this is intuitive in hindsight, approximating the inverse + is accomplished by negation of +\begin_inset Formula $\xihat$ +\end_inset + +, along with an adjoint to make sure it is applied in the right frame. + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Note, however, that +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Dinverse" + +\end_inset + + does not immediately yield a useful expression for the Jacobian matrix + +\begin_inset Formula $\varphi'(a)$ +\end_inset + +, but in many important cases this will turn out to be easy. + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +\varphi(a)e^{\yhat} & = & \varphi(ae^{\xhat})\\ +a^{-1}e^{\yhat} & = & \left(ae^{\xhat}\right)^{-1}\\ +e^{\yhat} & = & -ae^{\xhat}a^{-1}\\ +\yhat & = & -\Ad a\xhat +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula +\[ +Ad_{g}(\hat{\omega})=R\hat{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +and hence the pushforward for the inverse mapping +\begin_inset Formula $\varphi(R)=R^{T}$ +\end_inset + + has the matrix +\begin_inset Formula $\varphi'(R)=-R$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Right Multiplication with a Constant +\end_layout + +\begin_layout Theorem +Suppose +\begin_inset Formula $\varphi:G\rightarrow G$ +\end_inset + + is defined as +\begin_inset Formula $\varphi(g)=gh$ +\end_inset + +, with +\begin_inset Formula $h\in G$ +\end_inset + + a constant. + Then +\begin_inset Formula $D\varphi_{a}$ +\end_inset + + satisfies +\begin_inset Formula +\[ +\left(D\varphi_{a}x\right)\hat{}=\Ad{h^{-1}}\xhat +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{align*} +\varphi(a)e^{\yhat} & =\varphi(ae^{\xhat})\\ +ahe & =ae^{\xhat}h\\ +e^{\yhat} & =h^{-1}e^{\xhat}h=\exp\left(\Ad{h^{-1}}\xhat\right)\\ +\yhat & =\Ad{h^{-1}}\xhat +\end{align*} + +\end_inset + + +\end_layout + +\begin_layout Example +In the case of 3D rotations, right multiplication with a constant rotation + +\begin_inset Formula $R$ +\end_inset + + is done through the mapping +\begin_inset Formula $\varphi(A)=AR$ +\end_inset + +, and satisfies +\begin_inset Formula +\[ +\Skew{D\varphi_{A}x}=\Ad{R^{T}}\Skew x +\] + +\end_inset + +For 3D rotations +\begin_inset Formula $R\in\SOthree$ +\end_inset + + we have +\begin_inset Formula +\[ +Ad_{R^{T}}(\hat{\omega})=R^{T}\hat{\omega}R=\Skew{R^{T}\omega} +\] + +\end_inset + +and hence the Jacobian matrix of +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $A$ +\end_inset + + is +\begin_inset Formula $\varphi'(A)=R^{T}$ +\end_inset + +. +\end_layout + +\begin_layout Subsection +Pushforward of Compose +\end_layout + +\begin_layout Theorem +If we define the mapping +\begin_inset Formula $\varphi:G\times G\rightarrow G$ +\end_inset + + as the product of two group elements +\begin_inset Formula $g,h\in G$ +\end_inset + +, i.e., +\begin_inset Formula $\varphi(g,h)=gh$ +\end_inset + +, then the pushforward will satisfy +\begin_inset Formula +\[ +D\varphi_{(a,b)}(x,y)=D_{1}\varphi_{(a,b)}x+D_{2}\varphi_{(a,b)}y +\] + +\end_inset + +with +\begin_inset Formula +\[ +\left(D_{1}\varphi_{(a,b)}x\right)\hat{}=\Ad{b^{-1}}\xhat\mbox{\;\ and\;}D_{2}\varphi_{(a,b)}y=y +\] + +\end_inset + + +\end_layout + +\begin_layout Proof +Looking at the first argument, the proof is very similar to right multiplication + with a constant +\begin_inset Formula $b$ +\end_inset + +. + Indeed, defining +\begin_inset Formula $y=D\varphi_{a}x$ +\end_inset + + as in +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:pushforward" + +\end_inset + +, we have +\begin_inset Formula +\begin{align} +\varphi(a,b)e^{\yhat} & =\varphi(ae^{\xhat},b)\nonumber \\ +abe^{\yhat} & =ae^{\xhat}b\nonumber \\ +e^{\yhat} & =b^{-1}e^{\xhat}b=\exp\left(\Ad{b^{-1}}\xhat\right)\nonumber \\ +\yhat & =\Ad{b^{-1}}\xhat\label{eq:Dcompose1} +\end{align} + +\end_inset + +In other words, to apply an incremental change +\begin_inset Formula $\xhat$ +\end_inset + + to +\begin_inset Formula $a$ +\end_inset + + we first need to undo +\begin_inset Formula $b$ +\end_inset + +, then apply +\begin_inset Formula $\xhat$ +\end_inset + +, and then apply +\begin_inset Formula $b$ +\end_inset + + again. + Using +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:Adjoint2" + +\end_inset + + this can be done in one step by simply applying +\begin_inset Formula $\Ad{b^{-1}}\xhat$ +\end_inset + +. + +\end_layout + +\begin_layout Proof +The second argument is quite a bit easier and simply yields the identity + mapping: +\begin_inset Formula +\begin{align} +\varphi(a,b)e^{\yhat} & =\varphi(a,be^{\xhat})\nonumber \\ +abe^{\yhat} & =abe^{\xhat}\nonumber \\ +y & =x\label{eq:Dcompose2} +\end{align} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status open + +\begin_layout Plain Layout +In summary, the Jacobian matrix of +\begin_inset Formula $\varphi(g,h)=gh$ +\end_inset + + at +\begin_inset Formula $(a,b)\in G\times G$ +\end_inset + + is given by +\begin_inset Formula +\[ +\varphi'(a,b)=? +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $A,B\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $\varphi(A,B)=AB$ +\end_inset + +, and +\begin_inset Formula $\Ad{B^{T}}\Skew{\omega}=\Skew{B^{T}\omega}$ +\end_inset + +, hence the Jacobian matrix +\begin_inset Formula $\varphi'(A,B)$ +\end_inset + + of composing two rotations is given by +\begin_inset Formula +\[ +\varphi'(A,B)=\left[\begin{array}{cc} +B^{T} & I_{3}\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforward of Between +\end_layout + +\begin_layout Standard +Finally, let us find the pushforward of +\series bold +between +\series default +, defined as +\begin_inset Formula $\varphi(g,h)=g^{-1}h$ +\end_inset + +. + For the first argument we reason as: +\begin_inset Formula +\begin{align} +\varphi(g,h)e^{\yhat} & =\varphi(ge^{\xhat},h)\nonumber \\ +g^{-1}he^{\yhat} & =\left(ge^{\xhat}\right)^{-1}h=-e^{\xhat}g^{-1}h\nonumber \\ +e^{\yhat} & =-\left(h^{-1}g\right)e^{\xhat}\left(h^{-1}g\right)^{-1}=-\exp\Ad{\left(h^{-1}g\right)}\xhat\nonumber \\ +\yhat & =-\Ad{\left(h^{-1}g\right)}\xhat=-\Ad{\varphi\left(h,g\right)}\xhat\label{eq:Dbetween1} +\end{align} + +\end_inset + +The second argument yields the identity mapping. +\end_layout + +\begin_layout Example +For 3D rotations +\begin_inset Formula $A,B\in\SOthree$ +\end_inset + + we have +\begin_inset Formula $\varphi(A,B)=A^{T}B$ +\end_inset + +, and +\begin_inset Formula $\Ad{B^{T}A}\Skew{-\omega}=\Skew{-B^{T}A\omega}$ +\end_inset + +, hence the Jacobian matrix +\begin_inset Formula $\varphi'(A,B)$ +\end_inset + + of between is given by +\begin_inset Formula +\[ +\varphi'(A,B)=\left[\begin{array}{cc} +\left(-B^{T}A\right) & I_{3}\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Numerical PushForward +\end_layout + +\begin_layout Standard +Let's examine +\begin_inset Formula +\[ +f\left(g\right)e^{\yhat}=f\left(ge^{\xhat}\right) +\] + +\end_inset + +and multiply with +\begin_inset Formula $f(g)^{-1}$ +\end_inset + + on both sides: +\begin_inset Formula +\[ +e^{\yhat}=f\left(g\right)^{-1}f\left(ge^{\xhat}\right) +\] + +\end_inset + +We then take the log (which in our case returns +\begin_inset Formula $y$ +\end_inset + +, not +\begin_inset Formula $\yhat$ +\end_inset + +): +\begin_inset Formula +\[ +y(x)=\log\left[f\left(g\right)^{-1}f\left(ge^{\xhat}\right)\right] +\] + +\end_inset + +Let us look at +\begin_inset Formula $x=0$ +\end_inset + +, and perturb in direction +\begin_inset Formula $i$ +\end_inset + +, +\begin_inset Formula $e_{i}=[0,0,1,0,0]$ +\end_inset + +. + Then take derivative, +\begin_inset Formula +\[ +\deriv{y(d)}d\define\lim_{d\rightarrow0}\frac{y(d)-y(0)}{d}=\lim_{d\rightarrow0}\frac{1}{d}\log\left[f\left(g\right)^{-1}f\left(ge^{\widehat{de_{i}}}\right)\right] +\] + +\end_inset + +which is the basis for a numerical derivative scheme. +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Not understood yet: Let us also look at a chain rule. + If we know the behavior at the origin +\begin_inset Formula $I$ +\end_inset + +, we can extrapolate +\begin_inset Formula +\[ +f(ge^{\xhat})=f(ge^{\xhat}g^{-1}g)=f(e^{\Ad g\xhat}g) +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivative of the Exponential and Logarithm Map +\end_layout + +\begin_layout Theorem +\begin_inset CommandInset label +LatexCommand label +name "D-exp" + +\end_inset + +The derivative of the function +\begin_inset Formula $f:\Reals n\rightarrow G$ +\end_inset + + that applies the wedge operator followed by the exponential map, i.e., +\begin_inset Formula $f(\xi)=\exp\xihat$ +\end_inset + +, is the identity map for +\begin_inset Formula $\xi=0$ +\end_inset + +. +\end_layout + +\begin_layout Proof +For +\begin_inset Formula $\xi=0$ +\end_inset + +, we have +\begin_inset Formula +\begin{eqnarray*} +f(\xi)e^{\yhat} & = & f(\xi+x)\\ +f(0)e^{\yhat} & = & f(0+x)\\ +e^{\yhat} & = & e^{\xhat} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Corollary +The derivative of the inverse +\begin_inset Formula $f^{-1}$ +\end_inset + + is the identity as well, i.e., for +\begin_inset Formula $T=e$ +\end_inset + +, the identity element in +\begin_inset Formula $G$ +\end_inset + +. +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\xi\neq0$ +\end_inset + +, things are not simple, see . + +\begin_inset Flex URL +status collapsed + +\begin_layout Plain Layout + +http://deltaepsilons.wordpress.com/2009/11/06/helgasons-formula-for-the-differenti +al-of-the-exponential/ +\end_layout + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +General Manifolds +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\retract}{\mathcal{R}} +{\mathcal{R}} +\end_inset + + +\end_layout + +\begin_layout Standard +General manifolds that are not Lie groups do not have an exponential map, + but can still be handled by defining a +\series bold +retraction +\series default + +\begin_inset Formula $\retract:\Man\times\Reals n\rightarrow\Man$ +\end_inset + +, such that +\begin_inset Formula +\[ +a\oplus\xi\define\retract_{a}\left(\xi\right) +\] + +\end_inset + +A retraction +\begin_inset CommandInset citation +LatexCommand cite +key "Absil07book" + +\end_inset + + is required to be tangent to geodesics on the manifold +\begin_inset Formula $\Man$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + We can define many retractions for a manifold +\begin_inset Formula $\Man$ +\end_inset + +, even for those with more structure. + For the vector space +\begin_inset Formula $\Reals n$ +\end_inset + + the retraction is just vector addition, and for Lie groups the obvious + retraction is simply the exponential map, i.e., +\begin_inset Formula $\retract_{a}(\xi)=a\cdot\exp\xihat$ +\end_inset + +. + However, one can choose other, possibly computationally attractive retractions, + as long as around a they agree with the geodesic induced by the exponential + map, i.e., +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|a\cdot\exp\xihat-\retract_{a}\left(\xi\right)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + + +\end_layout + +\begin_layout Example +For +\begin_inset Formula $\SEthree$ +\end_inset + +, instead of using the true exponential map it is computationally more efficient + to define the retraction, which uses a first order approximation of the + translation update +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+Rv\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Derivatives +\end_layout + +\begin_layout Standard +Equipped with a retraction, then, we can generalize the notion of a derivative + for functions +\begin_inset Formula $f$ +\end_inset + + from general a manifold +\begin_inset Formula $\Man$ +\end_inset + + to +\begin_inset Formula $\Reals m$ +\end_inset + +: +\end_layout + +\begin_layout Definition +We define a function +\begin_inset Formula $f:\Man\rightarrow\Reals m$ +\end_inset + + to be +\series bold +differentiable +\series default + at +\begin_inset Formula $a\in\Man$ +\end_inset + + if there exists a matrix +\begin_inset Formula $f'(a)$ +\end_inset + + such that +\begin_inset Formula +\[ +\lim_{\xi\rightarrow0}\frac{\left|f(a)+f'(a)\xi-f\left(\retract_{a}(\xi)\right)\right|}{\left|\xi\right|}=0 +\] + +\end_inset + +with +\begin_inset Formula $\xi\in\Reals n$ +\end_inset + + for an +\begin_inset Formula $n$ +\end_inset + +-dimensional manifold, and +\begin_inset Formula $\retract_{a}:\Reals n\rightarrow\Man$ +\end_inset + + a retraction +\begin_inset Formula $\retract$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. + If +\begin_inset Formula $f$ +\end_inset + + is differentiable, then +\begin_inset Formula $f'(a)$ +\end_inset + + is called the +\series bold +Jacobian matrix +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +, and the linear transformation +\begin_inset Formula $Df_{a}:\xi\mapsto f'(a)\xi$ +\end_inset + + is called the +\series bold +derivative +\series default + of +\begin_inset Formula $f$ +\end_inset + + at +\begin_inset Formula $a$ +\end_inset + +. +\end_layout + +\begin_layout Definition +For manifolds that are also Lie groups, the derivative of any function +\begin_inset Formula $f:G\rightarrow\Reals m$ +\end_inset + + will agree no matter what retraction +\begin_inset Formula $\retract$ +\end_inset + + is used. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Part +Practice +\end_layout + +\begin_layout Standard +Below we apply the results derived in the theory part to the geometric objects + we use in GTSAM. + Above we preferred the modern notation +\begin_inset Formula $D_{1}f$ +\end_inset + + for the partial derivative. + Below (because this was written earlier) we use the more classical notation + +\begin_inset Formula +\[ +\deriv{f(x,y)}x +\] + +\end_inset + +In addition, for Lie groups we will abuse the notation and take +\begin_inset Formula +\[ +\at{\deriv{\varphi(g)}{\xi}}a +\] + +\end_inset + +to be the Jacobian matrix +\begin_inset Formula $\varphi'($ +\end_inset + +a) of the mapping +\begin_inset Formula $\varphi$ +\end_inset + + at +\begin_inset Formula $a\in G$ +\end_inset + +, associated with the pushforward +\begin_inset Formula $D\varphi_{a}$ +\end_inset + +. +\end_layout + +\begin_layout Section +SLAM Example +\end_layout + +\begin_layout Standard +Let us examine a visual SLAM example. + We have 2D measurements +\begin_inset Formula $z_{ij}$ +\end_inset + +, where each measurement is predicted by +\begin_inset Formula +\[ +z_{ij}=h(T_{i},p_{j})=\pi(T_{i}^{-1}p_{j}) +\] + +\end_inset + +where +\begin_inset Formula $T_{i}$ +\end_inset + + is the 3D pose of the +\begin_inset Formula $i^{th}$ +\end_inset + + camera, +\begin_inset Formula $p_{j}$ +\end_inset + + is the location of the +\begin_inset Formula $j^{th}$ +\end_inset + + point, and +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + is the camera projection function from Example +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + +. +\end_layout + +\begin_layout Section +BetweenFactor +\end_layout + +\begin_layout Standard +BetweenFactor is often used to summarize +\end_layout + +\begin_layout Standard +Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "D-exp" + +\end_inset + + about the derivative of the exponential map +\begin_inset Formula $f:\xi\mapsto\exp\xihat$ +\end_inset + + being identity only at +\begin_inset Formula $\xi=0$ +\end_inset + + has implications for GTSAM. + Given two elements +\begin_inset Formula $T_{1}$ +\end_inset + + and +\begin_inset Formula $T_{2}$ +\end_inset + +, BetweenFactor evaluates +\begin_inset Formula +\[ +g(T_{1},T_{2};Z)=f^{-1}\left(\mathop{between}(Z,\mathop{between}(T_{1},T_{2})\right)=f^{-1}\left(Z^{-1}\left(T_{1}^{-1}T_{2}\right)\right) +\] + +\end_inset + +but because it is assumed that +\begin_inset Formula $Z\approx T_{1}^{-1}T_{2}$ +\end_inset + +, and hence we have +\begin_inset Formula $Z^{-1}T_{1}^{-1}T_{2}\approx e$ +\end_inset + + and the derivative should be good there. + Note that the derivative of +\emph on +between +\emph default + is identity in its second argument. +\end_layout + +\begin_layout Section +Point3 +\end_layout + +\begin_layout Standard +A cross product +\begin_inset Formula $a\times b$ +\end_inset + + can be written as a matrix multiplication +\begin_inset Formula +\[ +a\times b=\Skew ab +\] + +\end_inset + +where +\begin_inset Formula $\Skew a$ +\end_inset + + is a skew-symmetric matrix defined as +\begin_inset Formula +\[ +\Skew{x,y,z}=\left[\begin{array}{ccc} +0 & -z & y\\ +z & 0 & -x\\ +-y & x & 0 +\end{array}\right] +\] + +\end_inset + +We also have +\begin_inset Formula +\[ +a^{T}\Skew b=-(\Skew ba)^{T}=-(a\times b)^{T} +\] + +\end_inset + +The derivative of a cross product +\begin_inset Formula +\begin{equation} +\frac{\partial(a\times b)}{\partial a}=\Skew{-b}\label{eq:Dcross1} +\end{equation} + +\end_inset + + +\begin_inset Formula +\begin{equation} +\frac{\partial(a\times b)}{\partial b}=\Skew a\label{eq:Dcross2} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rotations +\end_layout + +\begin_layout Subsection +Rot2 in GTSAM +\end_layout + +\begin_layout Standard +A rotation is stored as +\begin_inset Formula $(\cos\theta,\sin\theta)$ +\end_inset + +. + An incremental rotation is applied using the trigonometric sum rule: +\begin_inset Formula +\[ +\cos\theta'=\cos\theta\cos\delta-\sin\theta\sin\delta +\] + +\end_inset + + +\begin_inset Formula +\[ +\sin\theta'=\sin\theta\cos\delta+\cos\theta\sin\delta +\] + +\end_inset + +where +\begin_inset Formula $\delta$ +\end_inset + + is an incremental rotation angle. +\end_layout + +\begin_layout Subsection +Derivatives of Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + + the vector space is +\begin_inset Formula $\Rtwo$ +\end_inset + +, and the group action +\begin_inset Formula $f(R,p)$ +\end_inset + + corresponds to rotating the 2D point +\begin_inset Formula $p$ +\end_inset + + +\begin_inset Formula +\[ +f(R,p)=Rp +\] + +\end_inset + +According to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + +, the Jacobian matrix of +\begin_inset Formula $f$ +\end_inset + + is given by +\begin_inset Formula +\[ +f'(R,p)=\left[\begin{array}{cc} +RH(p) & R\end{array}\right] +\] + +\end_inset + +with +\begin_inset Formula $H:\Reals 2\rightarrow\Reals{2\times2}$ +\end_inset + + a linear mapping that depends on +\begin_inset Formula $p$ +\end_inset + +. + In the case of +\begin_inset Formula $\SOtwo$ +\end_inset + +, we can find +\begin_inset Formula $H(p)$ +\end_inset + + by equating (as in Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Hp" + +\end_inset + +): +\begin_inset Formula +\[ +\skew wp=\left[\begin{array}{cc} +0 & -\omega\\ +\omega & 0 +\end{array}\right]\left[\begin{array}{c} +x\\ +y +\end{array}\right]=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]\omega=H(p)\omega +\] + +\end_inset + +Note that +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\strikeout off +\uuline off +\uwave off +\noun off +\color none + +\begin_inset Formula +\[ +H(p)=\left[\begin{array}{c} +-y\\ +x +\end{array}\right]=\left[\begin{array}{cc} +0 & -1\\ +1 & 0 +\end{array}\right]\left[\begin{array}{c} +x\\ +y +\end{array}\right]=R_{\pi/2}p +\] + +\end_inset + +and since 2D rotations commute, we also have, with +\begin_inset Formula $q=Rp$ +\end_inset + + +\family default +\series default +\shape default +\size default +\emph default +\bar default +\strikeout default +\uuline default +\uwave default +\noun default +\color inherit +: +\begin_inset Formula +\[ +f'(R,p)=\left[\begin{array}{cc} +R\left(R_{\pi/2}p\right) & R\end{array}\right]=\left[\begin{array}{cc} +R_{\pi/2}q & R\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +Since +\begin_inset Formula $\Ad R\skew{\omega}=\skew{\omega}$ +\end_inset + +, we have the derivative of +\series bold +inverse +\series default +, +\begin_inset Formula +\[ +\frac{\partial R^{T}}{\partial\omega}=-\Ad R=-1\mbox{ } +\] + +\end_inset + + +\series bold +compose, +\series default + +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{1}}=\Ad{R_{2}^{T}}=1\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=1 +\] + +\end_inset + +and +\series bold +between: +\series default + +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{1}}=-\Ad{R_{2}^{T}R_{1}}=-1\mbox{ and }\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{2}}=1 +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Rigid Transformations +\end_layout + +\begin_layout Subsection +The derivatives of Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEtwo$ +\end_inset + + on 2D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{3}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +f(T,p)=\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +To find the derivative, we write the quantity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + as the product of the +\begin_inset Formula $3\times3$ +\end_inset + + matrix +\begin_inset Formula $H(p)$ +\end_inset + + with +\begin_inset Formula $\xi$ +\end_inset + +: +\begin_inset Formula +\begin{equation} +\xihat\hat{p}=\left[\begin{array}{cc} +\skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\skew{\omega}p+v\\ +0 +\end{array}\right]=\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right]=H(p)\xi\label{eq:HpSE2} +\end{equation} + +\end_inset + +Hence, by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + + we have +\begin_inset Formula +\begin{equation} +\deriv{\left(T\hat{p}\right)}{\xi}=TH(p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +I_{2} & R_{\pi/2}p\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R & RR_{\pi/2}p\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R & R_{\pi/2}q\\ +0 & 0 +\end{array}\right]\label{eq:SE2Action} +\end{equation} + +\end_inset + +Note that, looking only at the top rows of +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:HpSE2" + +\end_inset + + and +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:SE2Action" + +\end_inset + +, we can recognize the quantity +\begin_inset Formula $\skew{\omega}p+v=v+\omega\left(R_{\pi/2}p\right)$ +\end_inset + + as the velocity of +\begin_inset Formula $p$ +\end_inset + + in +\begin_inset Formula $\Rtwo$ +\end_inset + +, and +\begin_inset Formula $\left[\begin{array}{cc} +R & R_{\pi/2}q\end{array}\right]$ +\end_inset + + is the derivative of the action on +\begin_inset Formula $\Rtwo$ +\end_inset + +. + +\end_layout + +\begin_layout Standard +The derivative of the inverse action +\begin_inset Formula $g(T,p)=T^{-1}\hat{p}$ +\end_inset + + is given by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + + specialized to +\begin_inset Formula $\SEtwo$ +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\xi}=-H(T^{-1}p)=\left[\begin{array}{cc} +-I_{2} & -R_{\pi/2}\left(T^{-1}p\right)\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +We can just define all derivatives in terms of the adjoint map, which in + the case of +\begin_inset Formula $\SEtwo$ +\end_inset + +, in twist coordinates, is the linear mapping +\begin_inset Formula +\[ +\Ad T\xi=\left[\begin{array}{cc} +R & -R_{\pi/2}t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +v\\ +\omega +\end{array}\right] +\] + +\end_inset + +and we have +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial T^{^{-1}}}{\partial\xi} & = & -\Ad T +\end{eqnarray*} + +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{1}} & = & \Ad{T_{2}^{^{-1}}}\mbox{ and }\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{2}}=I_{3} +\end{eqnarray*} + +\end_inset + + +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}^{-1}T_{2}\right)}{\partial\xi_{1}} & = & -\Ad{T_{2}^{^{-1}}T_{1}}=-\Ad{between(T_{2},T_{1})}\mbox{ and }\frac{\partial\left(T_{1}^{-1}T_{2}\right)}{\partial\xi_{2}}=I_{3} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +3D Rotations +\end_layout + +\begin_layout Subsection +Derivatives of Actions +\end_layout + +\begin_layout Standard +In the case of +\begin_inset Formula $\SOthree$ +\end_inset + + the vector space is +\begin_inset Formula $\Rthree$ +\end_inset + +, and the group action +\begin_inset Formula $f(R,p)$ +\end_inset + + corresponds to rotating a point +\begin_inset Formula +\[ +q=f(R,p)=Rp +\] + +\end_inset + +To calculate +\begin_inset Formula $H(p)$ +\end_inset + + for use in Theorem +\begin_inset CommandInset ref +LatexCommand eqref +reference "th:Action" + +\end_inset + + we make use of +\begin_inset Formula +\[ +\Skew{\omega}p=\omega\times p=-p\times\omega=\Skew{-p}\omega +\] + +\end_inset + +so +\begin_inset Formula $H(p)\define\Skew{-p}$ +\end_inset + +. + Hence, the final derivative of an action in its first argument is +\begin_inset Formula +\[ +\deriv{\left(Rp\right)}{\omega}=RH(p)=-R\Skew p +\] + +\end_inset + +Likewise, according to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + +, the derivative of the inverse action is given by +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +\deriv{\left(R^{T}p\right)}{\omega}=-H(R^{T}p)=\Skew{R^{T}p} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:3DAngularVelocities" + +\end_inset + +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For 3D rotations +\begin_inset Formula $R_{b}^{n}$ +\end_inset + + from a body frame +\begin_inset Formula $b$ +\end_inset + + to a navigation frame +\begin_inset Formula $n$ +\end_inset + + we have the spatial angular velocity +\begin_inset Formula $\omega_{nb}^{n}$ +\end_inset + + measured in the navigation frame, +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{n}}\define\dot{R}_{b}^{n}\left(R_{b}^{n}\right)^{T}=\dot{R}_{b}^{n}R_{n}^{b} +\] + +\end_inset + +and the body angular velocity +\begin_inset Formula $\omega_{nb}^{b}$ +\end_inset + + measured in the body frame: +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{b}}\define\left(R_{b}^{n}\right)^{T}\dot{R}_{b}^{n}=R_{n}^{b}\dot{R}_{b}^{n} +\] + +\end_inset + +These quantities can be used to derive the velocity of a point +\begin_inset Formula $p$ +\end_inset + +, and we choose between spatial or body angular velocity depending on the + frame in which we choose to represent +\begin_inset Formula $p$ +\end_inset + +: +\begin_inset Formula +\[ +v^{n}=\Skew{\omega_{nb}^{n}}p^{n}=\omega_{nb}^{n}\times p^{n} +\] + +\end_inset + + +\begin_inset Formula +\[ +v^{b}=\Skew{\omega_{nb}^{b}}p^{b}=\omega_{nb}^{b}\times p^{b} +\] + +\end_inset + +We can transform these skew-symmetric matrices from navigation to body frame + by conjugating, +\begin_inset Formula +\[ +\Skew{\omega_{nb}^{b}}=R_{n}^{b}\Skew{\omega_{nb}^{n}}R_{b}^{n} +\] + +\end_inset + +but because the adjoint representation satisfies +\begin_inset Formula +\[ +Ad_{R}\Skew{\omega}\define R\Skew{\omega}R^{T}=\Skew{R\omega} +\] + +\end_inset + +we can even more easily transform between spatial and body angular velocities + as 3-vectors: +\begin_inset Formula +\[ +\omega_{nb}^{b}=R_{n}^{b}\omega_{nb}^{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\SOthree$ +\end_inset + + we have +\begin_inset Formula $\Ad R\Skew{\omega}=\Skew{R\omega}$ +\end_inset + + and, in terms of angular velocities: +\begin_inset Formula $\Ad R\omega=R\omega$ +\end_inset + +. + Hence, the Jacobian matrix of the +\series bold +inverse +\series default + mapping is (see Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dinverse" + +\end_inset + +) +\begin_inset Formula +\[ +\frac{\partial R^{T}}{\partial\omega}=-\Ad R=-R +\] + +\end_inset + +for +\series bold +compose +\series default + we have (Equations +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dcompose1" + +\end_inset + + and +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dcompose2" + +\end_inset + +): +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{1}}=R_{2}^{T}\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=I_{3} +\] + +\end_inset + +and +\series bold +between +\series default + (Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Dbetween1" + +\end_inset + +): +\begin_inset Formula +\[ +\frac{\partial\left(R_{1}^{T}R_{2}\right)}{\partial\omega_{1}}=-R_{2}^{T}R_{1}=-between(R_{2},R_{1})\mbox{ and }\frac{\partial\left(R_{1}R_{2}\right)}{\partial\omega_{2}}=I_{3} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +Absil +\begin_inset CommandInset citation +LatexCommand cite +after "page 58" +key "Absil07book" + +\end_inset + + discusses two possible retractions for +\begin_inset Formula $\SOthree$ +\end_inset + + based on the QR decomposition or the polar decomposition of the matrix + +\begin_inset Formula $R\Skew{\omega}$ +\end_inset + +, but they are expensive. + Another retraction is based on the Cayley transform +\begin_inset Formula $\mathcal{C}:\sothree\rightarrow\SOthree$ +\end_inset + +, a mapping from the skew-symmetric matrices to rotation matrices: +\begin_inset Formula +\[ +Q=\mathcal{C}(\Omega)=(I-\Omega)(I+\Omega)^{-1} +\] + +\end_inset + +Interestingly, the inverse Cayley transform +\begin_inset Formula $\mathcal{C}^{-1}:\SOthree\rightarrow\sothree$ +\end_inset + + has the same form: +\begin_inset Formula +\[ +\Omega=\mathcal{C}^{-1}(Q)=(I-Q)(I+Q)^{-1} +\] + +\end_inset + +The retraction needs a factor +\begin_inset Formula $-\frac{1}{2}$ +\end_inset + + however, to make it locally align with a geodesic: +\begin_inset Formula +\[ +R'=\retract_{R}(\omega)=R\mathcal{C}(-\frac{1}{2}\Skew{\omega}) +\] + +\end_inset + +Note that given +\begin_inset Formula $\omega=(x,y,z)$ +\end_inset + + this has the closed-form expression below +\begin_inset Formula +\[ +\frac{1}{4+x^{2}+y^{2}+z^{2}}\left[\begin{array}{ccc} +4+x^{2}-y^{2}-z^{2} & 2xy-4z & 2xz+4y\\ +2xy+4z & 4-x^{2}+y^{2}-z^{2} & 2yz-4x\\ +2xz-4y & 2yz+4x & 4-x^{2}-y^{2}+z^{2} +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +=\frac{1}{4+x^{2}+y^{2}+z^{2}}\left\{ 4(I+\Skew{\omega})+\left[\begin{array}{ccc} +x^{2}-y^{2}-z^{2} & 2xy & 2xz\\ +2xy & -x^{2}+y^{2}-z^{2} & 2yz\\ +2xz & 2yz & -x^{2}-y^{2}+z^{2} +\end{array}\right]\right\} +\] + +\end_inset + +so it can be seen to be a second-order correction on +\begin_inset Formula $(I+\Skew{\omega})$ +\end_inset + +. + The corresponding approximation to the logarithmic map is: +\begin_inset Formula +\[ +\Skew{\omega}=\retract_{R}^{-1}(R')=-2\mathcal{C}^{-1}\left(R^{T}R'\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Section +3D Rigid Transformations +\end_layout + +\begin_layout Subsection +The derivatives of Actions +\end_layout + +\begin_layout Standard +The action of +\begin_inset Formula $\SEthree$ +\end_inset + + on 3D points is done by embedding the points in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + by using homogeneous coordinates +\begin_inset Formula +\[ +\hat{q}=\left[\begin{array}{c} +q\\ +1 +\end{array}\right]=f(T,p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=T\hat{p} +\] + +\end_inset + +The quantity +\begin_inset Formula $\xihat\hat{p}$ +\end_inset + + corresponds to a velocity in +\begin_inset Formula $\mathbb{R}^{4}$ +\end_inset + + (in the local +\begin_inset Formula $T$ +\end_inset + + frame), and equating it to +\begin_inset Formula $H(p)\xi$ +\end_inset + + as in Equation +\begin_inset CommandInset ref +LatexCommand ref +reference "eq:Hp" + +\end_inset + + yields the +\begin_inset Formula $4\times6$ +\end_inset + + matrix +\begin_inset Formula $H(p)$ +\end_inset + + +\begin_inset Foot +status collapsed + +\begin_layout Plain Layout +\begin_inset Formula $H(p)$ +\end_inset + + can also be obtained by taking the +\begin_inset Formula $j^{th}$ +\end_inset + + column of each of the 6 generators to multiply with components of +\begin_inset Formula $\hat{p}$ +\end_inset + + +\end_layout + +\end_inset + +: +\begin_inset Formula +\[ +\xihat\hat{p}=\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +p\\ +1 +\end{array}\right]=\left[\begin{array}{c} +\omega\times p+v\\ +0 +\end{array}\right]=\left[\begin{array}{cc} +\Skew{-p} & I_{3}\\ +0 & 0 +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]=H(p)\xi +\] + +\end_inset + +Note how velocities are analogous to points at infinity in projective geometry: + they correspond to free vectors indicating a direction and magnitude of + change. + According to Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "th:Action" + +\end_inset + +, the derivative of the group action is then +\begin_inset Formula +\[ +\deriv{\left(T\hat{p}\right)}{\xi}=TH(p)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +\Skew{-p} & I_{3}\\ +0 & 0 +\end{array}\right]=\left[\begin{array}{cc} +R\Skew{-p} & R\\ +0 & 0 +\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{\left(T\hat{p}\right)}{\hat{p}}=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +in homogenous coordinates. + In +\begin_inset Formula $\Rthree$ +\end_inset + + this becomes +\begin_inset Formula $R\left[\begin{array}{cc} +-\Skew p & I_{3}\end{array}\right]$ +\end_inset + +. +\end_layout + +\begin_layout Standard +The derivative of the inverse action +\begin_inset Formula $T^{-1}p$ +\end_inset + + is given by Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "Th:InverseAction" + +\end_inset + +: +\end_layout + +\begin_layout Standard + +\family roman +\series medium +\shape up +\size normal +\emph off +\bar no +\noun off +\color none +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\xi}=-H\left(T^{-1}\hat{p}\right)=\left[\begin{array}{cc} +\Skew{T^{-1}\hat{p}} & -I_{3}\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{\left(T^{-1}\hat{p}\right)}{\hat{p}}=\left[\begin{array}{cc} +R^{T} & -R^{T}t\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Example +Let us examine a visual SLAM example. + We have 2D measurements +\begin_inset Formula $z_{ij}$ +\end_inset + +, where each measurement is predicted by +\begin_inset Formula +\[ +z_{ij}=h(T_{i},p_{j})=\pi(T_{i}^{-1}p_{j})=\pi(q) +\] + +\end_inset + +where +\begin_inset Formula $T_{i}$ +\end_inset + + is the 3D pose of the +\begin_inset Formula $i^{th}$ +\end_inset + + camera, +\begin_inset Formula $p_{j}$ +\end_inset + + is the location of the +\begin_inset Formula $j^{th}$ +\end_inset + + point, +\begin_inset Formula $q=(x',y',z')=T^{-1}p$ +\end_inset + + is the point in camera coordinates, and +\begin_inset Formula $\pi:(x,y,z)\mapsto(x/z,y/z)$ +\end_inset + + is the camera projection function from Example +\begin_inset CommandInset ref +LatexCommand ref +reference "ex:projection" + +\end_inset + +. + By the chain rule, we then have +\begin_inset Formula +\[ +\deriv{h(T,p)}{\xi}=\deriv{\pi(q)}q\deriv{(T^{-1}p)}{\xi}=\frac{1}{z'}\left[\begin{array}{ccc} +1 & 0 & -x'/z'\\ +0 & 1 & -y'/z' +\end{array}\right]\left[\begin{array}{cc} +\Skew q & -I_{3}\end{array}\right]=\left[\begin{array}{cc} +\pi'(q)\Skew q & -\pi'(q)\end{array}\right] +\] + +\end_inset + + +\begin_inset Formula +\[ +\deriv{h(T,p)}p=\pi'(q)R^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Instantaneous Velocity +\end_layout + +\begin_layout Standard +For rigid 3D transformations +\begin_inset Formula $T_{b}^{n}$ +\end_inset + + from a body frame +\begin_inset Formula $b$ +\end_inset + + to a navigation frame +\begin_inset Formula $n$ +\end_inset + + we have the instantaneous spatial twist +\begin_inset Formula $\xi_{nb}^{n}$ +\end_inset + + measured in the navigation frame, +\begin_inset Formula +\[ +\hat{\xi}_{nb}^{n}\define\dot{T}_{b}^{n}\left(T_{b}^{n}\right)^{-1} +\] + +\end_inset + +and the instantaneous body twist +\begin_inset Formula $\xi_{nb}^{b}$ +\end_inset + + measured in the body frame: +\begin_inset Formula +\[ +\hat{\xi}_{nb}^{b}\define\left(T_{b}^{n}\right)^{T}\dot{T}_{b}^{n} +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Pushforwards of Mappings +\end_layout + +\begin_layout Standard +As we can express the Adjoint representation in terms of twist coordinates, + we have +\begin_inset Formula +\[ +\left[\begin{array}{c} +\omega'\\ +v' +\end{array}\right]=\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right]\left[\begin{array}{c} +\omega\\ +v +\end{array}\right] +\] + +\end_inset + +Hence, as with +\begin_inset Formula $\SOthree$ +\end_inset + +, we are now in a position to simply posit the derivative of +\series bold +inverse +\series default +, +\begin_inset Formula +\[ +\frac{\partial T^{-1}}{\partial\xi}=\Ad T=-\left[\begin{array}{cc} +R & 0\\ +\Skew tR & R +\end{array}\right] +\] + +\end_inset + + +\series bold +compose +\series default + in its first argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{1}}=\Ad{T_{2}^{-1}} +\] + +\end_inset + + in its second argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}T_{2}\right)}{\partial\xi_{2}}=I_{6} +\] + +\end_inset + + +\series bold +between +\series default + in its first argument, +\begin_inset Formula +\[ +\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{1}}=\Ad{T_{2}^{^{-1}}T_{1}} +\] + +\end_inset + +and in its second argument, +\begin_inset Formula +\begin{eqnarray*} +\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{1}} & = & I_{6} +\end{eqnarray*} + +\end_inset + + +\end_layout + +\begin_layout Subsection +Retractions +\end_layout + +\begin_layout Standard +For +\begin_inset Formula $\SEthree$ +\end_inset + +, instead of using the true exponential map it is computationally more efficient + to design other retractions. + A first-order approximation to the exponential map does not quite cut it, + as it yields a +\begin_inset Formula $4\times4$ +\end_inset + + matrix which is not in +\begin_inset Formula $\SEthree$ +\end_inset + +: +\begin_inset Formula +\begin{eqnarray*} +T\exp\xihat & \approx & T(I+\xihat)\\ + & = & T\left(I_{4}+\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +I_{3}+\Skew{\omega} & v\\ +0 & 1 +\end{array}\right]\\ + & = & \left[\begin{array}{cc} +R\left(I_{3}+\Skew{\omega}\right) & t+Rv\\ +0 & 1 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +However, we can make it into a retraction by using any retraction defined + for +\begin_inset Formula $\SOthree$ +\end_inset + +, including, as below, using the exponential map +\begin_inset Formula $Re^{\Skew{\omega}}$ +\end_inset + +: +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+Rv\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + +Similarly, for a second order approximation we have +\begin_inset Formula +\begin{eqnarray*} +T\exp\xihat & \approx & T(I+\xihat+\frac{\xihat^{2}}{2})\\ + & = & T\left(I_{4}+\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]+\frac{1}{2}\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\left[\begin{array}{cc} +\Skew{\omega} & v\\ +0 & 0 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left(\left[\begin{array}{cc} +I_{3}+\Skew{\omega}+\frac{1}{2}\Skew{\omega}^{2} & v+\frac{1}{2}\Skew{\omega}v\\ +0 & 1 +\end{array}\right]\right)\\ + & = & \left[\begin{array}{cc} +R\left(I_{3}+\Skew{\omega}+\frac{1}{2}\Skew{\omega}^{2}\right) & t+R\left[v+\left(\omega\times v\right)/2\right]\\ +0 & 1 +\end{array}\right] +\end{eqnarray*} + +\end_inset + +inspiring the retraction +\begin_inset Formula +\[ +\retract_{T}\left(\left[\begin{array}{c} +\omega\\ +v +\end{array}\right]\right)=\left[\begin{array}{cc} +R & t\\ +0 & 1 +\end{array}\right]\left[\begin{array}{cc} +e^{\Skew{\omega}} & v+\left(\omega\times v\right)/2\\ +0 & 1 +\end{array}\right]=\left[\begin{array}{cc} +Re^{\Skew{\omega}} & t+R\left[v+\left(\omega\times v\right)/2\right]\\ +0 & 1 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +2D Line Segments (Ocaml) +\end_layout + +\begin_layout Standard +The error between an infinite line +\begin_inset Formula $(a,b,c)$ +\end_inset + + and a 2D line segment +\begin_inset Formula $((x1,y1),(x2,y2))$ +\end_inset + + is defined in Line3.ml. +\end_layout + +\begin_layout Section +Line3vd (Ocaml) +\end_layout + +\begin_layout Standard +One representation of a line is through 2 vectors +\begin_inset Formula $(v,d)$ +\end_inset + +, where +\begin_inset Formula $v$ +\end_inset + + is the direction and the vector +\begin_inset Formula $d$ +\end_inset + + points from the orgin to the closest point on the line. +\end_layout + +\begin_layout Standard +In this representation, transforming a 3D line from a world coordinate frame + to a camera at +\begin_inset Formula $(R_{w}^{c},t^{w})$ +\end_inset + + is done by +\begin_inset Formula +\[ +v^{c}=R_{w}^{c}v^{w} +\] + +\end_inset + + +\begin_inset Formula +\[ +d^{c}=R_{w}^{c}\left(d^{w}+(t^{w}v^{w})v^{w}-t^{w}\right) +\] + +\end_inset + + +\end_layout + +\begin_layout Section +Line3 (Ocaml) +\end_layout + +\begin_layout Standard +For 3D lines, we use a parameterization due to C.J. + Taylor, using a rotation matrix +\begin_inset Formula $R$ +\end_inset + + and 2 scalars +\begin_inset Formula $a$ +\end_inset + + and +\begin_inset Formula $b$ +\end_inset + +. + The line direction +\begin_inset Formula $v$ +\end_inset + + is simply the Z-axis of the rotated frame, i.e., +\begin_inset Formula $v=R_{3}$ +\end_inset + +, while the vector +\begin_inset Formula $d$ +\end_inset + + is given by +\begin_inset Formula $d=aR_{1}+bR_{2}$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Now, we will +\emph on +not +\emph default + use the incremental rotation scheme we used for rotations: because the + matrix R translates from the line coordinate frame to the world frame, + we need to apply the incremental rotation on the right-side: +\begin_inset Formula +\[ +R'=R(I+\Omega) +\] + +\end_inset + +Projecting a line to 2D can be done easily, as both +\begin_inset Formula $v$ +\end_inset + + and +\begin_inset Formula $d$ +\end_inset + + are also the 2D homogenous coordinates of two points on the projected line, + and hence we have +\begin_inset Formula +\begin{eqnarray*} +l & = & v\times d\\ + & = & R_{3}\times\left(aR_{1}+bR_{2}\right)\\ + & = & a\left(R_{3}\times R_{1}\right)+b\left(R_{3}\times R_{2}\right)\\ + & = & aR_{2}-bR_{1} +\end{eqnarray*} + +\end_inset + +This can be written as a rotation of a point, +\begin_inset Formula +\[ +l=R\left(\begin{array}{c} +-b\\ +a\\ +0 +\end{array}\right) +\] + +\end_inset + +but because the incremental rotation is now done on the right, we need to + figure out the derivatives again: +\begin_inset Formula +\begin{equation} +\frac{\partial(R(I+\Omega)x)}{\partial\omega}=\frac{\partial(R\Omega x)}{\partial\omega}=R\frac{\partial(\Omega x)}{\partial\omega}=R\Skew{-x}\label{eq:rotateRight} +\end{equation} + +\end_inset + +and hence the derivative of the projection +\begin_inset Formula $l$ +\end_inset + + with respect to the rotation matrix +\begin_inset Formula $R$ +\end_inset + +of the 3D line is +\begin_inset Formula +\begin{equation} +\frac{\partial(l)}{\partial\omega}=R\Skew{\left(\begin{array}{c} +b\\ +-a\\ +0 +\end{array}\right)}=\left[\begin{array}{ccc} +aR_{3} & bR_{3} & -(aR_{1}+bR_{2})\end{array}\right] +\end{equation} + +\end_inset + +or the +\begin_inset Formula $a,b$ +\end_inset + + scalars: +\begin_inset Formula +\[ +\frac{\partial(l)}{\partial a}=R_{2} +\] + +\end_inset + + +\begin_inset Formula +\[ +\frac{\partial(l)}{\partial b}=-R_{1} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +Transforming a 3D line +\begin_inset Formula $(R,(a,b))$ +\end_inset + + from a world coordinate frame to a camera frame +\begin_inset Formula $(R_{w}^{c},t^{w})$ +\end_inset + + is done by +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +R'=R_{w}^{c}R +\] + +\end_inset + + +\begin_inset Formula +\[ +a'=a-R_{1}^{T}t^{w} +\] + +\end_inset + + +\begin_inset Formula +\[ +b'=b-R_{2}^{T}t^{w} +\] + +\end_inset + +Again, we need to redo the derivatives, as R is incremented from the right. + The first argument is incremented from the left, but the result is incremented + on the right: +\begin_inset Formula +\begin{eqnarray*} +R'(I+\Omega')=(AB)(I+\Omega') & = & (I+\Skew{S\omega})AB\\ +I+\Omega' & = & (AB)^{T}(I+\Skew{S\omega})(AB)\\ +\Omega' & = & R'^{T}\Skew{S\omega}R'\\ +\Omega' & = & \Skew{R'^{T}S\omega}\\ +\omega' & = & R'^{T}S\omega +\end{eqnarray*} + +\end_inset + +For the second argument +\begin_inset Formula $R$ +\end_inset + + we now simply have: +\begin_inset Formula +\begin{eqnarray*} +AB(I+\Omega') & = & AB(I+\Omega)\\ +\Omega' & = & \Omega\\ +\omega' & = & \omega +\end{eqnarray*} + +\end_inset + +The scalar derivatives can be found by realizing that +\begin_inset Formula +\[ +\left(\begin{array}{c} +a'\\ +b'\\ +... +\end{array}\right)=\left(\begin{array}{c} +a\\ +b\\ +0 +\end{array}\right)-R^{T}t^{w} +\] + +\end_inset + +where we don't care about the third row. + Hence +\begin_inset Formula +\[ +\frac{\partial(\left(R(I+\Omega_{2})\right)^{T}t^{w})}{\partial\omega}=-\frac{\partial(\Omega_{2}R^{T}t^{w})}{\partial\omega}=-\Skew{R^{T}t^{w}}=\left[\begin{array}{ccc} +0 & R_{3}^{T}t^{w} & -R_{2}^{T}t^{w}\\ +-R_{3}^{T}t^{w} & 0 & R_{1}^{T}t^{w}\\ +... & ... & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Section + +\series bold +Aligning 3D Scans +\end_layout + +\begin_layout Standard +Below is the explanaition underlying Pose3.align, i.e. + aligning two point clouds using SVD. + Inspired but modified from CVOnline... +\end_layout + +\begin_layout Standard + +\emph on +Our +\emph default + model is +\begin_inset Formula +\[ +p^{c}=R\left(p^{w}-t\right) +\] + +\end_inset + +i.e., +\begin_inset Formula $R$ +\end_inset + + is from camera to world, and +\begin_inset Formula $t$ +\end_inset + + is the camera location in world coordinates. + The objective function is +\begin_inset Formula +\begin{equation} +\frac{1}{2}\sum\left(p^{c}-R(p^{w}-t)\right)^{2}=\frac{1}{2}\sum\left(p^{c}-Rp^{w}+Rt\right)^{2}=\frac{1}{2}\sum\left(p^{c}-Rp^{w}-t'\right)^{2}\label{eq:J} +\end{equation} + +\end_inset + +where +\begin_inset Formula $t'=-Rt$ +\end_inset + + is the location of the origin in the camera frame. + Taking the derivative with respect to +\begin_inset Formula $t'$ +\end_inset + + and setting to zero we have +\begin_inset Formula +\[ +\sum\left(p^{c}-Rp^{w}-t'\right)=0 +\] + +\end_inset + +or +\begin_inset Formula +\begin{equation} +t'=\frac{1}{n}\sum\left(p^{c}-Rp^{w}\right)=\bar{p}^{c}-R\bar{p}^{w}\label{eq:t} +\end{equation} + +\end_inset + +here +\begin_inset Formula $\bar{p}^{c}$ +\end_inset + + and +\begin_inset Formula $\bar{p}^{w}$ +\end_inset + + are the point cloud centroids. + Substituting back into +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:J" + +\end_inset + +, we get +\begin_inset Formula +\[ +\frac{1}{2}\sum\left(p^{c}-R(p^{w}-t)\right)^{2}=\frac{1}{2}\sum\left(\left(p^{c}-\bar{p}^{c}\right)-R\left(p^{w}-\bar{p}^{w}\right)\right)^{2}=\frac{1}{2}\sum\left(\hat{p}^{c}-R\hat{p}^{w}\right)^{2} +\] + +\end_inset + +Now, to minimize the above it suffices to maximize (see CVOnline) +\begin_inset Formula +\[ +\mathop{trace}\left(R^{T}C\right) +\] + +\end_inset + +where +\begin_inset Formula $C=\sum\hat{p}^{c}\left(\hat{p}^{w}\right)^{T}$ +\end_inset + + is the correlation matrix. + Intuitively, the cloud of points is rotated to align with the principal + axes. + This can be achieved by SVD decomposition on +\begin_inset Formula $C$ +\end_inset + + +\begin_inset Formula +\[ +C=USV^{T} +\] + +\end_inset + +and setting +\begin_inset Formula +\[ +R=UV^{T} +\] + +\end_inset + +Clearly, from +\begin_inset CommandInset ref +LatexCommand eqref +reference "eq:t" + +\end_inset + + we then also recover the optimal +\begin_inset Formula $t$ +\end_inset + + as +\begin_inset Formula +\[ +t=\bar{p}^{w}-R^{T}\bar{p}^{c} +\] + +\end_inset + + +\end_layout + +\begin_layout Section* +Appendix +\end_layout + +\begin_layout Subsection* +Differentiation Rules +\end_layout + +\begin_layout Standard +Spivak +\begin_inset CommandInset citation +LatexCommand cite +key "Spivak65book" + +\end_inset + + also notes some multivariate derivative rules defined component-wise, but + they are not that useful in practice: +\end_layout + +\begin_layout Itemize +Since +\begin_inset Formula $f:\Multi nm$ +\end_inset + + is defined in terms of +\begin_inset Formula $m$ +\end_inset + + component functions +\begin_inset Formula $f^{i}$ +\end_inset + +, then +\begin_inset Formula $f$ +\end_inset + + is differentiable at +\begin_inset Formula $a$ +\end_inset + + iff each +\begin_inset Formula $f^{i}$ +\end_inset + + is, and the Jacobian matrix +\begin_inset Formula $F_{a}$ +\end_inset + + is the +\begin_inset Formula $m\times n$ +\end_inset + + matrix whose +\begin_inset Formula $i^{th}$ +\end_inset + + row is +\begin_inset Formula $\left(f^{i}\right)'(a)$ +\end_inset + +: +\begin_inset Formula +\[ +F_{a}\define f'(a)=\left[\begin{array}{c} +\left(f^{1}\right)'(a)\\ +\vdots\\ +\left(f^{m}\right)'(a) +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Itemize +Scalar differentiation rules: if +\begin_inset Formula $f,g:\OneD n$ +\end_inset + + are differentiable at +\begin_inset Formula $a$ +\end_inset + +, then +\begin_inset Formula +\[ +(f+g)'(a)=F_{a}+G_{a} +\] + +\end_inset + + +\begin_inset Formula +\[ +(f\cdot g)'(a)=g(a)F_{a}+f(a)G_{a} +\] + +\end_inset + + +\begin_inset Formula +\[ +(f/g)'(a)=\frac{1}{g(a)^{2}}\left[g(a)F_{a}-f(a)G_{a}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection* +Tangent Spaces and the Tangent Bundle +\end_layout + +\begin_layout Standard +The following is adapted from Appendix A in +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" + +\end_inset + +. +\end_layout + +\begin_layout Standard +The +\series bold +tangent space +\series default + +\begin_inset Formula $T_{p}M$ +\end_inset + + of a manifold +\begin_inset Formula $M$ +\end_inset + + at a point +\begin_inset Formula $p\in M$ +\end_inset + + is the vector space of +\series bold +tangent vectors +\series default + at +\begin_inset Formula $p$ +\end_inset + +. + The +\series bold +tangent bundle +\series default + +\begin_inset Formula $TM$ +\end_inset + + is the set of all tangent vectors +\begin_inset Formula +\[ +TM\define\bigcup_{p\in M}T_{p}M +\] + +\end_inset + +A +\series bold +vector field +\series default + +\begin_inset Formula $X:M\rightarrow TM$ +\end_inset + + assigns a single tangent vector +\begin_inset Formula $x\in T_{p}M$ +\end_inset + + to each point +\begin_inset Formula $p$ +\end_inset + +. +\end_layout + +\begin_layout Standard +If +\begin_inset Formula $F:M\rightarrow N$ +\end_inset + + is a smooth map from a manifold +\begin_inset Formula $M$ +\end_inset + + to a manifold +\begin_inset Formula $N$ +\end_inset + +, then we can define the +\series bold + tangent map +\series default + of +\begin_inset Formula $F$ +\end_inset + + at +\begin_inset Formula $p$ +\end_inset + + as the linear map +\begin_inset Formula $F_{*p}:T_{p}M\rightarrow T_{F(p)}N$ +\end_inset + + that maps tangent vectors in +\begin_inset Formula $T_{p}M$ +\end_inset + + at +\begin_inset Formula $p$ +\end_inset + + to tangent vectors in +\begin_inset Formula $T_{F(p)}N$ +\end_inset + + at the image +\begin_inset Formula $F(p)$ +\end_inset + +. +\end_layout + +\begin_layout Subsection* +Homomorphisms +\end_layout + +\begin_layout Standard +The following +\emph on +might be +\emph default + relevant +\begin_inset CommandInset citation +LatexCommand cite +after "page 45" +key "Hall00book" + +\end_inset + +: suppose that +\begin_inset Formula $\Phi:G\rightarrow H$ +\end_inset + + is a mapping (Lie group homomorphism). + Then there exists a unique linear map +\begin_inset Formula $\phi:\gg\rightarrow\mathfrak{h}$ +\end_inset + + +\begin_inset Formula +\[ +\phi(\xhat)\define\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(e^{t\xhat}\right) +\] + +\end_inset + +such that +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\Phi\left(e^{\xhat}\right)=e^{\phi\left(\xhat\right)}$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\phi\left(T\xhat T^{-1}\right)=\Phi(T)\phi(\xhat)\Phi(T^{-1})$ +\end_inset + + +\end_layout + +\begin_layout Enumerate +\begin_inset Formula $\phi\left([\xhat,\yhat]\right)=\left[\phi(\xhat),\phi(\yhat)\right]$ +\end_inset + + +\end_layout + +\begin_layout Standard +In other words, the map +\begin_inset Formula $\phi$ +\end_inset + + is the derivative of +\begin_inset Formula $\Phi$ +\end_inset + + at the identity. + As an example, suppose +\begin_inset Formula $\Phi(g)=g^{-1}$ +\end_inset + +, then the corresponding derivative +\emph on +at the identity +\emph default +is +\begin_inset Formula +\[ +\phi(\xhat)\define\lim_{t\rightarrow0}\frac{d}{dt}\left(e^{t\xhat}\right)^{-1}=\lim_{t\rightarrow0}\frac{d}{dt}e^{-t\xhat}=-\xhat\lim_{t\rightarrow0}e^{-t\xhat}=-\xhat +\] + +\end_inset + +In general it suffices to compute +\begin_inset Formula $\phi$ +\end_inset + + for a basis of +\begin_inset Formula $\gg$ +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Undercooked: What if we want the derivative of +\begin_inset Formula $\Phi$ +\end_inset + + at some other element +\begin_inset Formula $g$ +\end_inset + +? In other words, if we apply +\begin_inset Formula $\Phi$ +\end_inset + + at +\begin_inset Formula $g$ +\end_inset + + incremented by some Lie algebra element +\begin_inset Formula $e^{\xhat}$ +\end_inset + +, then we are looking for a +\begin_inset Formula $\yhat\in\gg$ +\end_inset + + will yield the same result: +\begin_inset Formula +\[ +\Phi\left(g\right)\lim_{t\rightarrow0}\frac{d}{dt}e^{t\yhat}=\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(ge^{t\xhat}\right) +\] + +\end_inset + + +\begin_inset Formula +\[ +\lim_{t\rightarrow0}\frac{d}{dt}e^{t\yhat}=\Phi\left(g\right)^{-1}\lim_{t\rightarrow0}\frac{d}{dt}\Phi\left(ge^{t\xhat}\right) +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +Let us define two mappings +\begin_inset Formula +\[ +\Phi_{1}(A)=AB\mbox{ and }\Phi_{2}(B)=AB +\] + +\end_inset + +Then +\begin_inset Formula +\[ +\phi_{1}(\xhat)=\lim_{t\rightarrow0}\frac{d}{dt}\Phi_{1}\left(e^{t\xhat}B\right)= +\] + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset CommandInset bibtex +LatexCommand bibtex +bibfiles "/Users/dellaert/papers/refs" +options "plain" + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/math.pdf b/doc/math.pdf new file mode 100644 index 0000000000000000000000000000000000000000..ee50857ce92a23fe32b13454bd579266748e6c90 GIT binary patch literal 118509 zcmbrlW0WOZ+oqegot2rDwryLLwr$(CZL89@Gb?S|wym!B^t<=2@0|C1-J|=*8u6?- zV?@jmKi0agc|SocDJyor{SvZP>PXpw* z(8Y$uxl(6=tfAyRyzfWIPiRamFDaj$_VI8z*emGIRKH2o2rdo*faT@+;l%ioI87A5 z%OnT$X*}`@AhXrq9kRcsbbEAV+Q$%o#HD71EJ3X27JrB-N1 z{DT`6dX8FwBwSd{W__aFJc8F++Tyf};%Vb{tNf{kSMn#G=6*}JeBdn6LA+`6hl`b( z&;8kiw@!Lf^O*dPa02l(5;bemF4{AN6`uCe+o<-sNQN)8Y*}H9r03*BbLo~J@-1Y| z@3@k&D348JpO;IafspyK@zg&FjX-CDvN~7Oz&4#)8OL`6#2nMmglnH|&&vfLFdgUS zy~99+;{}3=sYugTh`XtjYU%KT#?fLHys!3Kp9s&2wKJMnwDV$=x*c3X$_7;w9|D$I zGjv#;+N#YJnyg)IMkjG=-#}KONX#$43>Hl}PNa{LSv6cPTm~oBST1^V_+)aDJYww>dU!TN+a$aVTMDoDtI z>q#n0OEGb90`xz@Iq--~l8NViXt>ai?6@5GbZZDLLdQdYy(xHd!uC@!gn+B8z>LUT3L@CEyLjnT>8M12C8PLLj0in$rA`WF^GwITATa$lw(jFmkyCc zw?0hnk8~=N0EI8Eyo@J5`}y7iOcaV8=l~>^sKuH>!f|YlP@mc!3NiRhPh!IFDr*di z-;*>Lx+6gyEv@u)iRQncJ;p&$0EYPiSDTvcD%n;FSA2>0IM%s#ExWkTv|_V9hjW~# zezo4;#vXL@mitY_Bp*Exbj2t9xm|=;kgbye^Sb&DAtxjvkFFvPQS}ijd%#9%FOc;!b$34M(!Owp7~U0Te!+t$ ztD4UDMZuyc((7DIai2)RM3=>jFi=!>g_XYOh$!WVBd3!O`J3bG&`)_^p<@-!8_J|z zS+G#?LHgc3M5}0ktWe7`WY!w)1&fTh3x#gVkLOzE4D$^a`T?`BjHyn&%Ozl2t2L5j zinMP|Zz!N}JW-LE8m}lb^awf7Ox^L-QkI?A2QBe1_ojYJ#K2N~?4MUEoe={D5{Qzw zJ>Rzm=f^`6kLt=XlQ4uef*?IFb3J#ld39zHgD&Z%QVr)zk#6Zr=1e7W087I}AAFz`n6`x z^jktjw5CG+%{JLAzTW-i@PwniSyUR=$U!aELz*$w3(*3uaDG1}5G$Pg5h6mxnDLaM zv}!cgWeh`5k-9X>ZrUXTi&TNy9`-~p4eo(DAHTEpNuLN33J7msCMC^4{7dzhESX;t!ur`7_UUzM%lP%T=NKgrl_tj?lUUl)ug=9{=Pp z63WQ4O)o>pAU8M!QPy*x8Vrtty~ zbI8HHE@l^SqwD=jn+9#dr^)mvR{z0-#t zx(x7*PPNSPrg9}@K9tn^o|KoVvb*0{s#P>`up|nzo%QVy;~w=GL;AP;sTmWP!QtDp$N zroM~K7P+O7K&*_#%uACofudDVs3Md!yB7H9ZvJrQoF5A}rjSTnZYa)7ceNq@FdG0wV(3t2zj2{fGAs`Gg6{F1%{eR1NyO+GE|@>jB_;n}RgUzUtD#rbxHse4W-YglRm>N4qf%lg~Y5GrV@{G)8vDdo{s z!OtZOJrY0NLN}2a4Q=6?+7ITmuSY1aE>r{1KXh@VLdQFtj-MOoZ)LaffIdRfdfNU1B#$|9nK0f4hSN-+n{Mbhy@@2qE@CfM zd(=n##YX7K^I?~31#F$=Kw{X`rC8?=sta;?2KGJO7`f%!PV2`tmuJVoPIpzj51dZ_ z#{+yf;EA`pHk6UI;lKIjcl9qUqG$Y*k8G?R{~u1G$7A|EEdQIB82+vp@tFTT#`Jf^ z{P!#y9?QRH+3{HaUC}e)vHexD{yk66_Rk6b+=reHkNvN6+3|jV`}ghX@#yLQ8fX0b z6qdg$dgi}N28MsH>o>&F%G%o)C>S|v(Ei3jJX%E~S4TWraVtF&Bf)R^eu{~%UY#dslj|3w~{H~OWLX4UuLUsO6wt} z{Pb$;I^4YPXGN9uj-E7mZCP9T7nj~#I*T;p%aWa&s?^24%X8WVTD>4=Wm-)_bHv)3 zGi#CiY!&>qYpt4$Ppdn)AOnU10*xX@0&CzKK4jM7Vqg136;>Tq$41DLQIO{FFp_}~ z!_z0L0tHD1&Nywx$heO8kjceFFE?1z*LbEtMO75pX}$^z^0B5_ho;=i}8m0 z?Ag$5pYh!b0b-pvMtyn@*rF8T30ua%L6K1U&zAQmsad{!B&ZVdKnhrwNcBETB@Kzx z(kf+M8J=JK8QR8j%^2VeN(&+_l|ZM>aq2|K^R_Ar;iebM&t)|z9TAq35(Y$L&+qHs z3WBV+_$2f*J&4BKAjKXa1(N2uPMLtz8iP742ar-wC{Yy(5v~`bW1fuvy(t zHD6qMH^HuYYHscNX;UXhsL8H^dm^B`*4!+)y>*!_bHFf(Doj(;(V($!bcYS4!omO% zuVN)Od;b(>a~0|TfzqUkDPSg>{+0W#A(LqflwNt(APGi?YAj2_J+G$_4N}-o%lY2o4&-YNrC+k5cNTih#OYaW_))|2 z<~4g+Wie)vEt&@AqtZv{^@K)o5r>)XchK`0-4*UJ?ly1*J0#`-L)_5(QoTL_O-Pjt z?$f&JEVS-q5j)w(F)Im2zsL|6(ryWa&En83Nhi?N8j!PvXNQH@ySvJ~155-mP66}1 z!)t#?!;;3Ul!vnpD?I6{eJFk$D+F5V4#LnQO`%EUF)rY4i64pvtK1WFj#QdZOVys1 z3Q_NwN2zYap@hVl)`tWX z>M^Mr0Xr*sIIw-=m=idc3JIsqg1=@l%dp}ce~|613b?rCvS>#8eK^3{&;DqAN|W|xcd6Ag?BRf)46k{a=1Y`UAn8A z+8FUi>ku%rY>nkNj>r;xd%tNFCX^!`cs5K};-B%qGMnp40wA3D5%9AujP3?p4ymg? zjhi%^?!422=->nOX7NsNg4OCXCLa2TTLljF#YvgUT~0DQ2k;Qk4tcrFE0$`^=?+tqKcwONJDB z>Sh3W+QqJ+fvK{1bPYq9j#taHAe^ui^mxSGCJhq;`>n2szzu^XG2|TZxxnE}rQS%| zwk@2i05qN=OI3$~lqt#s^m_X2dJqBk({b?VM7|mH;G&0BpL+ATBrAEi8Q)5bcEMMq-G)FLMx1Z=d*U-m>2s7v{oVf3yM1%-5gxBz_80i8rUUU429*mLA6lDM5Xt8gq%4AVa4S6rQc-9aml>4(3;nPF&i47d7?_ zEncXJWHGl$6=|Tzvh^5UwAIlO8{R_6;|BqyoeLs^$|7{WIir>7{!n$r>Pk-O{16R$ z+JC4mm|ZY!YvAGa^f$e;8;imARHCwQ?AnisQU5e>vvzm4zSG=+9aXS%rrYQiz^Hpl z=e|S#T-0gK7H7`Y1uJm)Pt56X2gt6`!+Xz~_uy3;NhEPja zE*!~k2B=&a`LN^#fY>B<&6~LClLOBCwzS?S&B%n%B>SSUdO)BlsYxN<9SHg9fb}wB zDKvpWoy@B$2qHkzh0T|v>{l}ZZVcq+w_c_+kopVA{+UZ2PM3~KGy~R~xQ97TJUIka zL{Um)`h;7dO*7wbxwvUrZKt&Y_UIs;vc$`jM}FPGN)lb|5qd&$)PfolF|Cd@TZ5yo zl6$PeO->_qWGg?O@7UBTvOHZrBpZ5tCrX{7g8Eg2`w;8F+ZNV4!wUMus9nZ=?N^TJ zZUMeP=(c{X9t{BhK*y(Jw=953mDbnLp7(SXdYPzeJ130{E4q{E+~5;y)i!tbJz5&q zGrgA1#(vII{lKci9@V8~-^Wu8M|7ufkz@QLOD9Clu(v-iq%2>BBmY$FG^ugz&+rX| zqSH_j$Ksp;D+Vf@Gjlw_bEw_6D=7P|*2IW6IGhf)AwX6a;d{~%`N4f6ndN2 zgT=Dy0qd2p<#a9**+7bl2 zYQ8odchj6wih{Mh%Ea%KZ-Kt)CF4fMfF-*B>_v8mC@2+s34@pS*3@OY z&q3NT*dkaY1V_NHC9vmva~8gj6MII`K7Nb)F!2fACfT<_*M&~bZ@g6H2%xSRG~<)F zbiZMLf(tj8aJB1%_S$;Z^)YQmSFBKCIo>GscQRPF6Cd76v}$PbF+<`Q*8;1*V+0Uh zvgU@84V6qdHppY0YbC4TUbah=&PzBK5Bw3KREiWUZvJ5Ux5kDhzRXTD@Vy_;k z1T=ne;IpkFfsg3_SPA#Fm-a!L6)T@>%Z_yQ9%*`M++y1hi& z%cU{i+ZuMF;2fpip9f-5;kS)Yw^Jq=wbGUF36o-Ss!STuSW^(jEYmV$$uLqkk98Rt zhfZeD2D8BZuE${?>@W_+dA$DlAW9a}hu2&9BNSWu0%}rz9r{TZ1%|PTRR$8#FMt5U zfDXx|YV|F>r^aOW-G?5-_zPE8wTZ+^GpCUW2L+A!VCeG7xc|ZC3)tgZ@8*9{!GFox z-}3X93jU*g4F8n>cpt-`g7%N({iB0_=-waJ_J{5LBZ+?t9IeP768Vqd{WihBw3HR^ zxA^^A5t;Dl|8h?Tx_=wz|G5JGzQi9-;lB+GSegH8U@)Pf;jqSn_CFP{9zPrlk|3?a zal@6LcP9a7#LQr^x3F1^TOD#^)|YZjw;*{n>R4|+}=>ZW#fh57;aY^X`& z%<(U-F8~K98wnb565af?8?#4mMs)W_quPwK74I9fO)1ar%o6$9mD!1@_m^ zKCZwaUX%pf_u84&nVM6UthM#3XgjzFgZGQA*|FUb5^&h^fYnDxle+rBGR|BAEebF z1R)>1Y0U>4VKl!U^`g+4#k+NJb_h9auPCfyuxXVt(crGM_<|#6 zl5%@kRe`QD(c`>laeml>K%|hho2NOUF+fp^%Fyq`>JvSM?x$Z|F$_7();y}a*^MPH zwp}&buR&SQ$6A=gaS2Z^!!Sd%RH+-rKXM|{DSSKvDW*RvK6xISoVKojicmvvSlAtS z+?|3vceJb)m=|wHuv#!I$Q>`T?<-ZAlP5+Fo&`uP!Oxby_vyi!V&4Rs27E&h`hiM^ z?;`1~$(Hva_-PjMX`lU`Bun7?UL7{hG;&KsU9nx+zC}T(W}o0GqafFz zhg%rF5jelZG%MU@td>GD5`Usm5(9r>9UDw-vJL}%m&K^D3}lh86%+^c{9U^;Oz}V$n^?z{#-;kd9?A4~{TN z*GqE*>FTu%rh6_i?RP#TWG#g;)Nh0IV?Q7n)gsN5=xf{hZVI(%Wzq{49fVz947yE| zjcF{(gGa|rH~IwFa&J5&X2V0%8Kc;P0Zl36Np5T;k3dy3LtcL`Quqq&6qEkLR^2Xs z?t5N&+}eS;A>=O$9~TFd;bIn;{Y1l+p9Sbl^@yS(u=4bTTT6Nk-DFP-6M}c=T(%Ek z@|%OFEFHXtvC|}+#(nhQAl39NfXGEFys@nSHK_)_e+mrxy@GTW0u5SSCF<}<<)ui% zx_S`>zs?zN&1M}VeHKMuj_gm1yGwkWiD0xEPpdf&GV`p#8zjCp_k(r92@SaE*(0Sx z>^Y?Z@g}>_2Cx6%tjs0p$#LW~@4GO)Y{hw(SH$)B)Jj2W$;yn*UVV+%uzYRQ6Lzc6*nTx0J=lrbRFZ!XYpPGBetAuyZ_n;sG!1|FP3-kUQZlw}SZ zHpR=APv}dTMzng<6G)73Q-|=YOJp?QDhBE@865%O(#tDl?3&qEo2MVact|ybv6$RC zUz`6jJgi#w)-weItr{kgb(C_Ab(SU;V-XTG8-y5J4P;WNzZi%rrTDi0Yx=$XK)k>8 zYZB7{%!V2_Us2SpwowT=VraKPs)rxK=(`q`T#Jk+kGnn1!skgSq~k>2fN=*G+?Wv? z^GmHNO@IA_VK$VA3GNpwIE1E7RX+5x%7d0!g7o9jLsf^CQp$mJMB-Uxxi0l7OHgBV zm5P(cfo5u9WUO0)H6zPl;Q4h4KdLTT)JCD>WA(-BV^tN)(ga8M=EnTOI-gyvzn0Qs zbS@)8!lM(bZmlSs_=Go+MW4Bk6W-HkMIU1-%ooGivI(K#8{J70O*NX9=k}!M%`}bv zZh*9?{ZPZ$#i6~OM#urbie?A3i<8nO(^l|^YY=$`dz>Y^%b~MN3b3SuzsibrkBA(k zkyepsm zoRK`&JBUEh;1nKQw^Rt2u^pIB*prn0AzS@WvuSw^tV8wv*HIKj(|ho{pj>V$I6hAi z3Sj*91zrPm64>Aq@@G<#uLj!0iegP7ftP2%XNV6y*V^8yQ2{C5AA2p*27T=new3gi zifV>r1g*Z)J52s^Qcxm@kb`C~WyLRLh+V;I-~&?ZNU@~M)<&>1jnr%nv>g?KeAtl; z^&pH^nq7)Uc0R(^oVwUqI)GOdU=((18%mAjF7OJQ9dI>@Y(5k(D@A?=r29!5O}xKb(oW>W~A;%M2H});g_=TSEB31 zm^S{73(??O+sFF=_Al{X67ZX+Mft4rqBo7B0F4NZK4=iIF3LNtT(_b6#vUqRiFZ~u z;odLkJs`jt0x(T$;3EKlFDfuLr62@XiCKQuV1t43O{>;~LPVajv-q|oEpf90wQhtG zn?t;3ubbzt@7{eF!WII%K^Q=R0IMv~msvQ1qU9q-pL|a2UI>m;!Nprpbxe})2&uQ# z>xo`N**uI|anh4jq#yHVorj@{-v2U&RIyS(vq^A9$W=HY_S{Y~_i!Y>w7_52TYLwN zABKB#)!K>A6XrEqD=avUffXm{@AdB4PY~Dt`2p56vw5P1j>V1tDf}pMU@7MRYOw)R zPo}(x8zAiGG26$o(}$IULRd-WUm zN+-WfViGoRv_a(;%y}V4O#-HR55hH!DQvzdvSA)5%;!DOpkw|Dv5nSHo5z@D;c?wr zRX`TG`P@-@6PjAX&W+86&)vc2=ib+}xrO5Y*9U&1{U0R!mk;~_>Hk3f|I!Ekuz)|4 zo`2Z?58(fY@)`aU+S7{s0sp_r{~rjlj35IPnAHRv3{|Apbnv&ISZuPDl&M3@DU#pHT{7g-CyW6}1gg6G2EMF(pwlynrYxy$GVe6vP^m$Nw z@{aXYL?M%NTxIdzSUC!vds*=H;-f4;TQ0rSaPR3(#j3;>6)GDKX3eY{O!l#lAE>p@ zC*`u9iP_lG&lzg4tH?eV;RJ8jjWlq3e#4EIBkRrw|UNW zs^ziic+{kCebw0Dn*r)=QEWEWo1hTxrvB)mANN(&9aoJZwB&M+&sdp#15Z5~Mp7bX{qyb~r zYkT3cpYE(llRD*e=hX*EjM3Uc#$A`CN||a`Z;J6UCR4fS*a)DeQSB{yx6&=5UXp%m4WBuNBWn8wDp>VofX_#sKIc4x=KNf)b)mzt9 z=8HViRQ#x7n~c|IKKQ6P%6EyBkg^r!5_dtF42LynVjx^maMtYE%SYMoXIk}JuM3Z` z=f0xb^n#Lg!C2Glb#USE0t_{Ll*y7)0aaZ7mrjPDGrRE*t<+@#_JfSeC=>Zuhxt+*T@)pbS6TZ0DV1{bdjb z$(}Mm^ade7MpY;6nYMZ)e{g|lIs&CQ0R$xxzi5~QlU&chsIVgZ{*PlhfV5N`Z29Il zmY9M97nkuvUWP*))olca{SZ4!ppQ_D#9zAzZ47LzWphzi;)gD4CbJ)^mu6f-SAutL zpKYt`_~?o!C}fi{4{;GvB)XaWDrKRkn56FWc|qE-*uiIBn~kKqujwuy8u)h>={052 znstr3R=!gXrFI6)F@bTDM}AaP_KCHkOW!=Ux}-2obk%ka`+G(LGOB0cbuip%kT9SI+c(bu zo=J@*OKfc4lK$;&Vs3j`U1Uq=(3il__do%!2C1Kt*@8Tbk0jYgL9F#b*~p8Ka6AZk zciUufr=hl?auIgX08Gx-6)`j9lka|8+~itC700bGh#0XMKf&PdyEBzpj*ow z$sa-b6NzLH{Fc10tUza)$0E1$xTG(johKs~-P#(h{%l)3fWC$}5z*j%D|n3T-O7n4$h1fX z$MoX0!>HuL8-Qpp+0XAa@SltE^SS96(1k%AY(=15>r+rHSLBk%8}ayQ2vN5fjQkd| z-zct6I?bnJdSO~h-pJhS$ntuFW#gaKBQT3v@gS(^%{E)|CL^wxbVr78y`Ar%O4ReH zHg6sYU1x>{d4?2+@p;!$I3$-Fx_mFqV9>)EdDI&28ph1j%fN75+5ot#%!dpF_r;hU zk5sBUOLMBP`Z+g$t9yu7 zVVlXga(~N*ebA#djEJi%WD>C1WU|A|kg>}+3}dH&e?+Jbk(iG$V;EjHiGO5k1l)Wo zr75(-;Hrkf5?WLY^%*v~v$ zPL&i*Ihh7{u;@PnzqJtSc*$EC>HJ7}c2+tdyC(sbfR+^2t!yUJlgD1OG=O7H1tu<7 z43qwV@u|K+?6HBN?W@(pB+oCe7k+}b*^)0Ec^rG_4!#q=9;pBj5N)8S3F3?JQS>9! zt*}k1Mx>WoME(wXip78dYsX`*fGjj?z~pA9q$>n*X`LwCC}+PjN7o;$8vgi~l&eJL zHv;5e)-d1Kv&Yf-_{K~5Z!&!l0K{Z zQ?EBFx~i2njv3=-p(>Gg_qmr))~)rC)M92#@`5gH%*NhB8u!fi;`W zR;g73syHS_h__u?axx@zCD8rA1Ks&~i4DO7l47kcviR%qtpB;%uBfW8rk zVBUh4E3B)89)3wbEefo3-Lv!+@O?2G!9=VLPUixkygI=SJTUPwmWpz@{!n@cn(Emw z)6#8Rd{_~wg0aWF&LuBpQJvc*L=Wqcn^K;Z1=6%8XOBr|Zg=#dIZu$!icEw4_};AY zOow%?B;U=#Wsv%f)?{TVWQ0pnx791l zF5I6GSiU3jS{Mv45QpC<>6&|nO@g5^IFSPdodHYUJOZcU*O=$~?JN;rF?^;Q4ll=; z)4t9&hc^FkiDpRF1xKP&l2#UU!?!sti>QGV3@!@TgFU*@)1}+PY6a=oCfoG9N`72= zoYj3yxQt&WT16l$df_u;UsRJ@o7CRGOw6G-$oqKV9qhrO5&Z&a-xkJsuh4mEy$jtY z?G9oo)N&Jn;KRngI7U38k7s0zrKwa|XOWxOU^F5vp0OY3hmg!Q%O|Vm$y#ja{j3J$ zTgHL$yJegw7bf0waW76dO}G1qK!~=xJEjI^Gnl)Yxy`S&9`sa0M#obqn%qDKCQTlh z`fun7p+EYk%eq5lrI>VYfjOS+=hl}F==l>6D`At*-{8#sO%VXlo70F%cQe0NGjPu* zh;HCngghEe$>qSleJ4q+k|W5Pj48_C^C)`9pceFfb{D|yg)G=K86B4wg(#QRA+UW@ zvY!XB$Zr-}dhhj&-zE?bG8{qIjxs~z@ax=vI~7yE1vXkosNYT*=u2EK-TAq+{~2`D zF8`~A~QZr4$G~HLpVY4(J^+pPtXg zG;rxaq`^u0!)XX(@927`?Q7q}nUVJeJC74)G@UL*<|-rcR)W>lnX!FjAaMn;dBldW z-XPr6f9w9l)+h7Q0LPfjen~LuTtoo@47JNLYs~){den)GiCi@O7Y!Vw{?}9|4NYlmc76H_AiP2-TL@X`M>nre^mGn)BPv!`a_!kv;O`U(`Ci`ee3@jZv7E? z{n6?8k1YQkc>P}PKYf*q41Yyp{}(F!zuyYUO2_hFS|KkqB^}m8kh-p_b**(*dh|Da z6{=P(SKJnqt#*&m4*0}le+5>@DjI&hU1VbdFzN;X5RXpkjoCr?2Vma6on?QQ`OK^l zhx1wfW&2E;?4PW zTy@oS76RMoKU^>HLf%EF>`O`badoG~X7{?3I8xZQS>62k*sssKMRmAT@7wWO$qr4r zfCqhP^06&S$4JgcrYs;_d;oH=AlWK3I%hm=q59*_Fk5NG!hc**B6|dBpN6sY9J%>d zVUN|$)+sE#WY0yq5|zGj_RTDO%f5VU;gPLVroEk*TSFxOVMC#hFbyH&MD~DgLK2DU zfn8TODRaZP>&`O;VHX3Y9nBK60h0c=uIL z)sGflrdqx;&EX`#ZUJmE)TquDf@WZM<-)N?gaRZ3is}Qy2|it|Uk%(Y?Gx^pm?QMU zj5#vBp5=i?iX0*G*bBC%y88(bh(Uzpj5&0kDI6pk1v#ihrV0>Fn~KP)yJkV>T+p_Cv23;1Q4cKtO5QU#&{R~*Gi zh!0YCEW~)LcuiLaA!iI`;BH20zm4Nd%_!a|M3y0#&le`9%Qp(#0?+d>R2mC#yQFf* zp<|lsnk7kwdv-Ip;Y?xV|Gd6gT^}&bIRvGajLAp~UgBTklfTHC<_eX*D=xjAosNnW zM?(C}fHC8!RERt#oCtO>vhiL$I`(v$;6-$h8w*8^gpiN(My(9^zF=Y%ElQ)5pMcfNiFzGvsJ`M~gTAMBvFVM6Ds2EVA%)pH2UlC<^pt;m z%iQOX4EVE*GuxaV7Q2BWGQ9{?(hL8nST8o4%beE$U8MF*tYASM;@N=WT`R>B{s|~p* zhNvm<0!a9s?KuJM9W`LP`nXaV)e5I)4XWd?Y1OLCf_C>~wLUyv_IFEX6w=Lo)aC+W zb@~O5bfc6x@y#gX))k!I6I9B`MO>KC#|O}b8}LzwL$2E4B( zjQ3pNB_ZAvwXhpXP;hXR8|LnA&Sq%uLN&bi3&|<*dcoOINXr$god7w^_K|OK9l^R* zsmZ_tRkdT}dw>2s{#k?Ii)9tN3WLTB9ZW}gkUJM!5Uey&QUYVZT`g;ppXLz87nPgl zSnbdLW@WZ13&CVtow7dMn|VnUw|^qS);Dl6Lqh|8p@Y6pL6z>8ORvdWH(*(H;TIN*x_I)!x%yxn5Z=lQrVJ4PTCPfNi*0jDZ?A zyZjMI680Jl*GnMP;Ev>@HB=J@N?ZJ5ELG(q=WCtqQc^(Qy}hPfkBMOS4Oxdp#Y|B ze+y@@tw@i|d8Bpf5368-S~lanwv9$NVMwS3IHjvtxy}~=GSmu$S#Qq_abF#!8P_@{ zR+N$uhTxkUsT9&;5sJ@^woGIUWpmF!eT=YHeDAdQ`ARnI7dzO(&n|z{`&Gi8HZCPS zQ4t6QmnVxz&KPEfhYWNsl|}0OA+!Q=VA?cEm24nZW(e&X)3W@Xsib>_h+%zCXV!)j z^Gs*lIzB|ISfpGjOxSKIp}}_!vkwoA<1;g#Z9v4FD99{xbuH3jjSoeQD2_#hggcj=mpC{l4%kObh;`SG?AEfa@zz4H{MU z=wmC!5E%mVV0RKhi;I4NT?zM~U1P);U#J5R8r>WNq>xmnVz2!*$~+w7Z?z?m1VyAy?X%^GCbLs}j3)c4xYi zzG@hH(iel!%RUyHsA4R|ylKP@pXmz&J;DpiT3f(s#HWB1CLy7cOd~TZKrTPW$o6dN zDqOVs&IGdMTz2W)*<#|-ajjxD1hk|YJ1z|F8V~w4xwUu%IfUesZznqT)Wa;IC(e2c zs^%Dc#n>K%_%{pY7+4NtZ?@0D?mB0xh~A59Kh=@?SVR5f5iwmzf0%)5ymQ%*vy#xu zW)kohCt6_=nHDP|yLb@&EEWPE5=)>WOo&9}>R;r=y<#Oo1{nggTd`TBptNMr8I@}} z3Dru$X-~#!R}OHVxa<3NDt2f$O>0eX_%Q>nstz?ZRuZ6$fLdOR=Mp%xxvFQfV-^{U z=Y*{4%oVjAim^7OG`~q#Q}^i@WTfA5J=$jtgVc9+UUOp~=sikP2%Fpx+SETbe<()H zIMQepzJ7f(pa2A7_2T+~F41N>bC6355QYTJC!f@`iw8&v;IG-l8rV}7S`IL<7xjf{ zi8u)CNNMCy;KDUtEyT9D!G=+t_1b);um!O-grl^3<3>=5>AZqRyXBKf%?h1UPEi&G zh;5N&ETkc_oAtI{^@NrzH(jfHA(sn}GTxNM<#x4+mE3XqzL#QV9{&{&3YvyPq#nLW zi6|r9;D5w9@&Wkhc*J_)zv9naZ(Y6LX;j_2-%AX z3UMH+m=A%R`=^_;d_Ih5EP?b!l^SIhy?vzUt%% z%ZlS-+h7h&8)F7%sO)~2t>+?IB<8Sz3+yYS>Me|>{=yJk0(4|xVPbuQ*_EVTUX3{u z7jEM3#xCAF4oz!HW932BN^}|$1?J^-+yl3q8&+HL9XZ9TL{Il>rikC&JG5!PCzogW z^sYUko(szsJ6yRpiX6{e9%E*CrmI9?d3sQEnK#1&on+6`t^#?Z$fTjoEBWxW)E~Ij z=_H^#mV!`SqCS@-vIffo=Bg#B2tT&CbcDW0>s#C_3I2d#q zjj-@~3LhS@>rd6==b-m6nytOlV4gQ5lH2Z!RUI5=&W4A2C4V+Op>r|>B zSB=|?(Z2P@pbt?YFs+2FA%;<=%q`wY)j*JExdX$p>fsRI!UYJSsp zu_)m=)aT9ej5-A;gH@ut`CHZT{J`#^Ywx7O6$dd)Y{j4wn7vq=}t0l z^(wc&N=tAp<9F>3K3r{T?dxByB4#+)+81jpFMOC;(tbY`!$$%b)I0|ZNc?arx6sM^f54TndUzgv-?;pi)=9Q#;*s?mJC#C!oZ$&k1G z2gU!7Ev^4i?Ef+N|DTrDKg9lz7aRY~qW=i4|LQ}f75Ouv{*N01f2#jKV*iKjGt&LL z?e+g$=6_$}kFAdXHrJ-3XZSBNzkxMkzc&1kU7c&A8@0lJwejO%JM03py_f=1BMDoC zhYv+4Prx5LzOJHs>I{}I02Zl^Ej-~C2+8%>`{OYxVT;r?z8{w>4&?JN;RUMe1LO-W z0hgA<$6NFmgi$ChRdc;(19MQU|LAOsA$-}fxN&kbam~D}p7y$WIYj2bQ6zP8k@Zr2 z{_?deTOPhPT`pLasjYsjJud}}UffoJJ==vQ(>3xy43AcHfiiE zi`TdR<*@29KCiuwK#c6`kf63s!2flq8mZc$Pzk>Jv$yXoB~T7tz!oMyE#w7bF}9`_ ztd`RzUkvN zvy50Fowm?Kk>2gZwnz#^FhL&#fEogAM8rTnsv(8w%?IwB0}PZZ(Wo%Qi)cNezMV>X z0Pl1~Fo~XCN}$Mf6pw4C7DF9GOkL~#L6A`0%Rey37G1Ew*BUXzm66N7aRs|d=lrsG zr0PJctb(~ykKSg6?QkY~47QN-BG>4**vyX0BrN9ega-r1maG_H)UVJJ+Nmm5sF#|; zhalu%57wDz=B`nd-zgIR3Y>G%_EqIn#A4`_E2=ca=uoB|H0Zj zcvr%Ad!Dgv+qNpUZQHhO+qP}nsn``;6(-8FsRs(1S7o;!VKt@9t`WS{-nU;K7H zXfa@@nC+Z=W!=$46Bc;ru{rC$-^RVraSe(rkavi?w#Udq`-z#GEKn2|CX9}B(gw1c z)7;dmrwqv3vB~tSUUtLN*{$TRAf#~8GYoYIPPXg!f47+A%bo#y+vXp6&+k7bfUZMV z%0*TAXbhWdfs}>}13>s>E~xmh4jeFk7ezSm9bt#ub8>~oX2ggD9H2dy08WTq#)9mv zduod%+jMNBJn@SA*x0I0EXe2Aev;O*d%59YD5Y_QR~l$c#_uO zc;+9j{+>VQ13qlz={obhs+f&BJmY)JM31@v zLKac4+y;YcxY(SZw|D{m)I3B=|3baw6D(q)^+8?IgYrV>Zo|V;q1@+nd_M91t_LHFR0+kpoDO*T?%aKvB(W(LW)9Cqz0Tk;ubX*3Y33 z>6maQ#8X)s1YWtEi{vVffJEryflX?aHxUHkk-iec7`#J}vz^Q@tL}+the-5fQ5k?n zPA#@vIJAm1S3AvZOGU-TQu<)4h=AI7uh3MPGQ<|UV5_0@0a6UH-`K>;I``f}d3;R3 z_yJt=+hwjcvakh1O*82esT-)Z3c*xamOELh^yyBfsAYNg6as&=h(R%5QS%8y%& z9S)N}f5Uu+3)zTt+Vr{#84+KuB;fk<_G;wNEnb;y`4I0xgTO!%Mi`Gq^;a6ob!KDg*_A@^NnoBf4tWId1hg|$`~6nZDQN#sA33+CQCd2N3`wcvE2ne z6);VRpujI)2-qm*bx=2UxZRK_D=p)}7&s=|SpVS|A9wsCI&+V=7Im9cgfsmarUa^| zNSxcb1TXdxZY?`p7N3LK&BtB_ogQT_GFHWIJ*K!#`eb~Y%eSz+Qs$Ho9*e;Avzv#d zgt8boo*Y6_h&kTA=ipA-Qg!&WCJozW65bX(D8kWidAd53WjS}3{)9yj;(bJsV|0n+ z=*3NAQ_Y`uWzDmAT3HDmPD>n}z!9TirgdS^kUGUXiKbb*3FY3r##AjCP@8T8ti+TUSO4N%Kxm z8}~^rKjsy2$bV*&yq1w`vPa2|Rq`?o0^!ZKE{VBp-ImwBjXAICd^G5|aakbXTz1}% z3y`HuyZhSmaN#Yn%%M7F7Co?tovpXDsNIARkO9PuHp{UtqS{4T(ztV4UQDc==yQpI zC<^C>T~5Y5_td$)6^8a5y?%#2<}2fvZF20$ReK8y7~nxXC%uk-#|o3-u($&C{w$%| z3LA0tXrrP4v)M!8o|n6tS_ zK7@pW2Yz0JRN_s87zQa4S4SU{|s3HiKmlTO*$)}pWNPgSjon(%ONIH?~Vb_6rQHU`JG0H}sm?67Ny zAF(%>3)k(v5(46oe5JlQA$7U-@~*W(kxK${=S56MjmPCiWhlKVqmbBGuDPYhPzFZz zL2^HBLs{91MA-I`+Kwv0Ml0iqyuvt9l-RoIQ7Y(f4Ylzd3poI!UP-bi zsO4A0b3%=`2HsiXc&cm~?k+x|D(6Hf8`GTmu>=JF4c}~_pF$xRK!Vk3=94(oFxDcm znFc(R1#G7u!LZ&dy4Zj?yNDDPIGre=T!$yA{4wgAHo24`v8MJ;CTV;SjR8p6auR2a z4VmQkeB~m!$pcaOBp6gJyKUF6RzBAdhy&kNFZCKpqpKgpYCD1OBaRBXHqg%{+No8I z+i$PHj0f(OS_*C^_?bzUoj+#UQYvufaI}Ilf7Rqz`Z24GgmB#_eiU5kXMB(T7Fmib zpeH-itkg=0<|`Guwft^40>|GLW{Q2%5An8!X~nX_8ga{!I8e5jksW~ zbSqnvH1tE{wEc7A9d1MK>j7UB560qu#vvFHys{f$NcYN7d;r25|gq<^cy`QHK(6BF~l0n!NeX5(h-ZI2#d zp9C|S{|_>uUieWT{$MLtGzSY_pR@`J2Ri}Zkz|0$l9|%*=`OJolFwh(eTxXx;w=oM-UN^(#ly9>~0j`>OCLM-!aI$M$@Xd$6xG*H(Eu zcsbj;?9WWp6_HIQ)H-*emT;}4 zU*Pw#(s%sv%m6Hj&>z(gunjIhZ4Q4kTQA7QTwh}pZ%~m<*o8C98)z_T&8F2#VBMgs zJ?lqciH2)&9@2cD#*avS5(obhVXkD$wXwe;RY5Do0a0uisXCnlVl(R%F9eVZ)PYP0 zinFX;QmpXlvOdRkR6*&A-B)TvCw*SXdHpV$;+L^lZ#ROA$K?%|NrN>rxG+01=ls+V&Y5-Hy))!p^z*Iy3n2ih$b0K+qCo0)1zPS%X z6LxeF##9n2wPKyAN!p+5$}i^&t-z|DS(0=bEmk3ix;0!SoHk6WrAiUN5vK@Cp<&*(g>gL4SX>15Su z&3|lgc(qx&PpFRnX2HX5PK6j2vj@k=&S}3)IfB@00p( zLw2Kw4tx&Ir)y+B+-Jw)Dm#J%KS+IqIche809E63;({=&D^wid{!r2wB)8*ozA>j; z0TKg|k6i;byoj#SB_PvU_rtu9&_U_ORrhAx8QdzR)Y}i(@l80lnM4?xz><%|^c=L) zmNeSw5AMd4^YrwwmD7m#51`ra1IJy2o!Rlz=@+ehA26Hr@gV#V83pV=u}c9H2bdrs zIu-yqcHg5Ne~#}2J04>m5p{!!mC*Tw{hTn*!=XIInapUW!F?4BuL;W|a4%)pI1Oqe zKdTBbp484R?#n*cZ9Bv^&1Dj@m-Sl^BLTTOE z=K^#Jawz;h7bKgl<^V<2V!R=XujV^)kSTjUr#clZG>)Kjnp`23=3X#IW`n9Zksb`} z1WY$(ez+hy{r0Y$mIs0B2*Lpk(YcF3jvqPN2j#l5=f}OWT;_P)#QH4aa!b0lPZ^pC z!!&>)WYiGfOuzzs>h4Q2vaBxdEQ|*kTHX6I!sH}ErBZuTA{UYfRQ$@b*H~paUK^)s zsBT<)QzXmOH?8&h~kZ*S-{=FyeloVkG z)MghqTzn~soXh-~Fi4?L80}j#a3NnyB^-uR;+0kk=`N=e_mxI88%JllJC~B@`)TYf+a+uG1c*R zszpuTYPc@)%#<)0m1_ZtT(CEMd!aY2^#$;D>H{(QC2jJrOeY8Lr_a5`JE-sB%= zroq30>Ip`KT9)jHqZDY8`A>d~?Ju?fXbbL}TmkgP@VYOQ)c`0rTJuK^L`u=X(`cn% zmm+|Eqc%>~PT-I>6+qwf`nUpam{(GdSvQUTp`ZjmEgQP4{*+<={dBK?3u?V{lPxT~ zAsN_&RFgA0Dx!!eCd32tfNs_PE^G;68{=JX3~&MoFhAn~kywt*5f9Fld8l5yUARIn ziKADwFctPzg^}1m0oD^@N2r%2BhGRXF&Ej6gfN6<3vRbhlBKTewY#oNSi*R&_yPV0 zlcPB%qoHPJU?Ff|3biwsNq$f`iFGY|_s z>A43H4MxoJQ6AR}Zb5_sFU*F5=Of8wDT79j+uQ8xNo2I&woSVYf9Fe>P$*4*@B>Hl zTA4$LcweFLHE=(~kv=Op(sVrt)~{8frX@2bIVX1?6hOQwotH56j97 z4F0j8S>4K9J$ipH0e79t&e)QIOxoyzst ztBZ>aRrWh5EQ&R20oAirL^KEFvxVMmOfj6WVfUZFE)&JqT@vDQkux6XZ03=nF{}x! zsW}xm-y9AM)+qY(w2J`9H$4kbp5_?g5AH(MfiJvvC5ojp zju)9S0hTWTybIHrR;;8(W=4_$Q3YGupM)(+nVb%L!|@of;3$mqaQfviYp!TZOyaW= z78+qOzYjf?xUuVVBnmhUOc5A&!!vqH1|+c75E*un=-@r3u1xqij7~8XQDYM{=$?~9 zi&Kf9!@MSQaWFE$Wn4T^cjn ztX*LdZ5V7Un1DolPw8Dz@FG)`j#S;n>Vt_fJ)cH}i19HUg-;yn1}p&Rtz>LuwuMU* zNK`1WmMzKa%y}D96rZuTxJ-<`5&k7`a}F+tBS}KXx0K|Q$)>X1#X$xC6F#brt~br* z_>Nmoy5V_=lAm7Zk`ZXQu|`JBBRIhd(7)RVd)SXPJbg>yL4bgUNMe#&8J zIl`P(w7}^sBL-vZHV`Hyq5)~2TNsBls934C>o&}uKenoTgn%)FUvwvUn$!nOZ1u+@ z1t{vcn8M1|V;H5gMONR|3~wNeMEtL@jKD)sDbPvB;+x(#z(9j~kFNE%b$axh3_nfnJ~Fu1#xj*$sU+1mI?ch+>utKTe0sih4*`x3DD_p zpl5F2-L_$B6j7a&p>3=OZe*lv?G9zvgysNxkLvBNfYYB&`N{kIabulaXsn%9-h(*~ z#rmjZ&cLz9CHNK4YkBRwz}wsfdQN=6Fm7_+-@3^Aj6BqrL3O{Tctoqh-s?#@N7%HW zWSNqsxh8P>R!p^D zQA{eO4BJ+(Uw>V2xIe~=7OS3R+TX~(rg6f$iYz2R~{U^?V*!%`G9*yd6; z5!c;nq=>GkM&-_(AZ^t9apb6vErh!MkV*IY@YeIBW$+Ol0*&I~L_Br8*l8J8p-vSi z#6e9dbps-Gyoz*eX_+&dq z`gls`_@@pUZXYed4^jgBq8h)d$)LJz`I;kfp&(uT!(%@1%<^V8#zgY?*H9a^<=&e` zgw3E9Ek4+xkCgydbkG55q_b3@5>LnuRmsWRklll{r>~lugWqmfFv@_>e_+0Ui#Glj z-LC(K^!JC?{(`?hJuZI{-#;5;|7O3x9I#CPGRFQlK<~e7Yh_|*{P%?C^6z?=gH}}E z>pJ8R?PxZPDZ(O&R&P7cH~`%e`Qjtzrr*|K_|FlB zJ9f2ug=T%T<~6{+<}*xh=(D!!_RhV2eK|a>Zm#R`GO-mUt5ce_!P~QsK(lt~cuU%* ziL_)X<)B=6OfsiZFnt|8fxC}7<0%BnL&NVQ^YPiV{r*lYg_-z5JX8u@w+fXnFceKA z8D+ZF@{#t1k{{k8i_=m}Sf{;iuK7Zo7<}6a%d>cPOQ%GH_{8zZg)($$@;@m4@#diL z!vu2^1==s;+Da67?83W?mObus-+&#Rs3P$6E(SkJrGbv^_ir!-yo&pb0shla7m(2c zl0uWR?ePz?uMDLGlyC75XP-&~oQP1vB;oNt3&!|O&A>>?;w6!+OatxrAbzIjw^W-; z70ZAB>|wbh3$QAlA=;T%B5Nup0sR^4&0OdO2*02)iGs*8qlBo?V=U|%ah-VTi#5VK zisr=qwsU=4uaQc6Z3w0h`AxTso|8w!@zro505>3o!JtQE&-krbk5{?t#GCzuOT)br zo;cB@KLCw!{@gXJ#TZjw19BKFj#2R>0oLj;49RB8_xYvZ$AJRH6C-C3Xd+D7q3y&- zd#5PpBuRi;@gS1Lm_{KCX_lm9JErl(S-!y;sV#$cE11)Hx_i~pH_@gwq<-U`;VwWs zW09uNa7^fQqbt1~dP8d`5^-$RyK!06fQEuo>(&!aiUd|ZdPctL0mF+PGJ2iW6xtF}0nigT@~; zPe%uL@^#HyKP%H5VMWip>$IADN>Av#t|zXqs~%ldex`}6O`WKX$sgyG@nvJ%n<3!@ zi0^`;;>i;yoev;ZMjOLS0|;IuXot~gSQZW>V9H>)mA*KV?NZizu8@j~8F(btQ5~YN z-)ZBe`lg1}97X9>ArZsq>YEQZ-~!QSfrbtM&Pn6MA`*j|X$zXg_2MPNv>YPwG-v9@(B{Q~A}S zT^A*ifgibC)px6jRuz(W?CZXP4lhT|=Z1J{(nbB`RmRi}Zo4Gc?a+T1_TKxdeZ1#Z zpQrP}gx1`T7(l0(DS%esl{=oxMFc2@Oyp+CdQ2jY^N0vDWQ`3wnr*_1w<#-AdC!f9 zEtNFuWSLZ^*_&mb$SD%GJU@?h2rTIfJK)n(;~MrO13kFx%{#90j<5=*>BO-G>N(dH z`%627-jT8P?%-rFPNdf_hguw+hN_qD_lDwgHlwbWwy za)4OO_KeW?TO6bqlh|W~A6F1^p-80$Ns&m*xt$8YXI63VmSDaQ-ZKt}GUFh}U8>o_ z7qM6b0E#}}nY@+7vs|`gj%ec{IUnVaQG=pK?xKWI4^S8I3&Gg zD-whQ?+t&KZrlxM4(Spb!9{s{pfWos6N!sYC-bDWOPD>wE@Qix#5#}2I+KQ{KKiOl z!?xp!V)z8%Db8pE0jmVD_{IM|yef<=fxJ$hjKJWhv1bPzWNJMf=5-_i1SDKE80+Sw z)C$w*>PR&Pl|*3D%PbWy6#D`6cIAA4`KAUjsqK)w`Nt?IkO>$Y^U#IjKoh|>pD`%2->eSc#AO# z1_|>Tu8lsR5p#X*j_J7AgHG`h$%gNis$R)RKex6BqDciX6{^R)%qZo&TkXEH9XUAi zk{|Vvmo3|j^CgWwOqYXw%M^4;T<0AfGGd2}Vk(aS1dGVl##Ow41~WxroHhZNHA4=K zE+FcBz*{dY8efsA{y9AtrqgIJO2c)#7Aj-i7Z2vNOxzbSjz3wlBDXyXqMsAUl`wGo zPWfbM?{pr1B4FE0b_a9@tdsYwC!53TMqxJA2Z`r&F>OjR)GjFzj-TcKL>o2Z!w3K^ zD3f;$v?X)}fK`cn18lc~@u>4HB%~Go z#71NnwXCk?NPqv45KLb1J3tPTz(^@F2Vl!VHbFUS9D}P342O|OjEg{mn|SCR-52rN zu4&{FZ-~RghfbwGP|KG*sNbU%!0nu?X_b`aPae?zb=%C9ys6@$XJid0WJR#`XUZgPJv*H=#Z+kZ=t!QAdC}g-~cJ!n(dZ>Dh|a6c)~n1N?qH* z0M=dko?~x)2q&mP5)RMt-c5qaNuzii(R!ZqIalye`9ro2f50@-vl9_S83B(Q0_&c= zIzhc#_$Ytw^XRSb(!f)%9@*Kogm1JjUETIZctwnIypJ*bnja}G?*sIY9Cqdl;G}U| zUOc#i(9H}bQ3$3OsF9e^p2n8(uiw2|jPoqNAdt8&Dnx33tA5MS4VsQoHkb~IkWs`F zBKL?|j5ZxZ`%Z(^lqySago;6;6fPrC(-0_l_pI=1z+@~{_AVEFFU#lA^w*V~&=c9t zT9cKn7jNAGhTXxm`GZ%Wtir@KGI$oyv*nRz7VM8V#GuC#S{%lO!Fgg@oQ+odX?y6f z-iELu`m;TPU7y~tAsAm<_J$BA5v>m0FmP_!O8$GLZ`_4)exSxba)n0sSmT2u&v*#v za>C;3QLX?9i|2}ZBi!7%B9=t9a^__h2#7;({I)Z5u9%QHUj+PWwzDZ5G7@ z#jG(Y$fxTzG~9g-j!uT0+;|5`cJ$f`?Jv$HzmXA=n2-8-8=Y6bmmSA>4*n|p0_xlT z(fbd3{y$sZ{^%`#cKSbS`k#E;Un&nX8^Q0-|D8koYmfgU;{0WUWBgP7`1kVum(%X= zc-ns&+UP}@IseDI0RQJ3JUXMbwP*UC1nR zpzr1K9Ie*}{!3?eTX*{N6Ze3b3Ig5I^%l{0hJqBWHtqT(aa_c-Cg;n&Ps>M}fpfHnGq&dwjmB$r2zdBHH%z3Xm>rRfu=wJIdg_euI4!z$1DFH|{w;b#u&L6ZkM8ZSM0~g(|Ql`@wT+yi3@yj2V zKey~;Yy<7?!#&q+c0t#kNYOvbZ~geS*=4AA#mn1?ZZ6U+r*F^eF}81kl|A zKtuR6unrI=CGsi75!fsa?J0z>-Jq(_&I=%%Em@=4mk8Lr*b5Cpq!L1 z@M%Tja3>52jeVK+t@<1b&D-2b+9|%qtPe$^y3?eX6d68 zhM6HOxj`00`q;oaM%zyB5Zx$&aJyB?(-ML`y8`a_seZO>Un2|zMWf%L^E>d<;Y}&qxdgL{U@l^nv?UAn5E(CiYoFF>r$m!FfpK^Se zRO;kXJ|8R$_qHNgcxgJdO~xDK)OTP^K6F?^?FbrOW|E@7>eC-~za^T;)4xqN$L9Qo zIfCB3XGVty)T>qVaRMH0brvQvlZtN{*-eGEw33O(!{g{?t8kRFsLn4?LP(T~4^0_K zQr2vWRo0CIPYK7XN9LU?7zfZEMLs5&FKQp5jL$~%E3;*&8xQtJbd+c*(MB zQd9{{(H&(~3wR(vKt`Nx13A@IKK}P+5_1g%2zNCFZL(FPc!xphUmY65^Nm^VjWxujLcaA`BAy+0BtmRM zq1nyKi=e}GN**l$Flo&%&cBmXV9cy91MOPf6uK2&?F;15-EBQ4EC5ErM#cx}^W#-Z z%(!R7{gbmm)m&(6_6Tma&88rB)$=pK@g!{q_OG@vmlD(L`~YpAcLu*F)0HDQOn}k> z1>UFjkF724m9$5pbd|0h}zKOSdCQG3ybrGS8sP0K@}Kw!)avW zWM@^_esNoSP1=_cdMo{i&q|H;56=v5#9?ZiM7Q7|u4?BTFPJ$l01)BjXxx6nHJlbQ z28ycXal{~hA~y-SuYF;(0Jn_0DVEC_Fv?o=dVfnDLFdJuCfNPIe$86C z<+^D0m?N!qApwF2);G^n0=ODT1B*C%9&Jo>`NlZJ*TC>IXOi)5idT*S*mJR=0F zCNnUBa|pwu^a|J;*wsE zIWwa3C(c^8xe+HQ6PH_y&`QoLqv4;-b{~1PpH)+>s%XS4nVC`+h zUza?Kx_iCydQ}F*T}DlR-yuVKtQ@-jLKl2~|X*1hLW3CnN%G>LoS;JsU zIv&=>z`ZhRM*Yqtfrkmd%x_XurxG*~ElP+63O9#vf3)dmGUv$x)T&u?ndzt)7JJF2@fNV zr)`9jfaqKjRGUOANxTc+KYp)}`>|Zkp6(pQY_TH(XpvucEVKPOF1<3TU_KP{>1Ya8 zCAwaq-EwZ(=Id(4{#crTt;izjFtqCKHZnT(`rr3*J9pjv0D;XzEQJCH_A9G}VCdu< z9K!c34&XLp6cPPoCIZ>)>5p{tPU!AqFQ*Ww;~V{UN4}qXS-Lcj4Gza6rggyb%PRBh~2V{ z9@x|r;TpMb(gRk<)usN&i;q#9w?XnDLu<$|F%{dJ#7IjW|Jld@$sAlBm7*y7prM}pU z+A^QWF#27#HF9H&Zw8RcIfygv2WVsGU4LC+V!s-c;li7$v5L%e@kmg03stQw?i@ni zS>Vw;!CuzR;IY?)r$|UOAh4KB(q_`I$)ZuSWxheUig9Ezn0dU!k?oqlph61#!l!*e zPkhCn5>-hK3`;YE6Tv)l0$c%1$LFNu=%T2zV7`hot{IxLUFInXDlJ#%U-Mn6JzMcE zN=`S85khV|Ae0UFL0xBPz#+HwErRHYL;>Y#ts$ApUbOnGi&F;uch7Ct(nkCq$z-rI z#SxQ#?nw5IK$^ZBP>tFxjIxi9=i?K`=HrRL7Q^CIwvg|&o5Y%og1Gf#tPQ@!W0isY ziO}So$YA` z`CZ{k9*$9NqghU~6%T^Wg#dls64N~$HcA_HmvcP-Ao7S`LF>oBI>+WRGurO{w%o-{ z%I*3_6})~$QH~@NznbvDy#5krNH@&yEEZSVpcx0JrlF`LxGv9&jTSg(5ygECH%gt^s?9>s;~~#s&E#i3BHg!&DYqf zPqOrhw=?)mmXc!12DM{F=dbWH%*w8Y+ZN(I7h@(^eSHQ!7@}G>OTJP)E`d!7g_y|ApNKG^51~0|FS=hk&%t_ z-~4gQ>c5|`WkdK6*(8q&5OM0wJRz-6CZLc4%Q=8|*dyM}q%NK(QOD-${S8h;5s7_C zvq1+~1g=ivyS?czA1CW4N@C1VJ`yFA&wcBTkR9I;zqWO`sLMC@WRqaxQIpp8faOF4 z-n%Tf2x8JUr90t!!ri+aG^RrmJ5$N~8PA}*FPmK1p8y$sZZ<&S1tL1ZDVjH`@;Ijy z9&dfjCjvqaqJHV}?iVh4%m7Qn-p>+I&wOz$sL{n0-g2=qR9nM~a$wTdxxUkxQuS`T zMYC$#vfeTBakk4#Q&oh{v2=A-|BWnAs6sS7+dxKm-pJrBMX7bOO=N-vFN{KQ0`cgc zMHiKlC`FWjmOva#fk!5=Ar~CMn~!i797M>1geO5*`3=m?dKcMFmLzeQDYmmZV=^Wl zHNP6hOt;#fO#B6a{K!O>OHp^9go80CnTv>YfL`yDix>k5&R8a~yfjE+f|4d=bYlME zP^)al_iMnXazj~TE<8z!116MwK&<-27QgSVEjaVNfft~r&giKwQ>e!pyIdOpzlC(oDfybZC~-1;u0ilo&&ntB2X4E!6_yU|yb<`*WJKUa4b4qq6q z3PM0?ys_xueF};diAC$0CX+-)U?#pD#Bpk-QA8Qpy$YApB**PX<2Y}?vi8{}ow|(| zQL0SuzaVUQh%(EpgL)&SEy+A~tk}zp`j~z#Q!UMVwj-Q6 zsGC&rl5?TH5ZDivP3PF)g2tuR7Mw7~N_ev3FgxT9b@)@MWgn9Zf|Oas`jZ~U%Zv7# z;1B0{LU()n$w4RJzQo*DAgG99IAOpr6rfQNsIY`(&GvyoVhbwnYHUrG!b2j-rKuv4 z+&Tg=Sbjpi(1^(IlM3m<4Rd}3(miWw23R|G2n9m%xhr!Gn6S8Cc5j?)MR{4wMml&6 zVDyB)B?AWWr7h79oFWH4@;we0b~#7Mz5~r6)N6 zeBA1j3AQ-E;e76tY{IMNkO8Pl6Q_qE_4K~lDkJsZJ_&;=M?TlvG{?n|6~Byn?bS^z z7c!S3bu-}B(+gb~aL?|mKD-CMz8Cby`-0PdnD+mujQ@4I`g0xoGwlBw;eQS2zef1q zXRtq0`L7>=Ki9W^`Imo>>c6J?ze=3`|2dQW$0_e$ZCC$0hcgog%m3qD6HSSv&34q@ z6E%BVbgqT>@(Rh3jetI<9^ zc$+_WU&BGjk!)2ZodjI+JlIATc)pjKE%1%Kd9u`W+DRYGt+V$vKh5au;&ll*VQhMQ9za{CoY6jgTUS`AU1VteCgr)={<}v{r)hpu z*!3>ksi$F+4+fllCaf?&?8zRy&m(0eHfqU8g3?j8fY0?(O}GRZn3lDI+j78BMdREJ z5ezvsYQfhJ6PKVa`Qx+dt@a&oGFwXOCcyDHRoXifNHao3oOjbN-j8!pTGLjJi(-^eHF4Q{L5n-J*lcjCnJN-$C(1{` zPrM_<=3kf!{^h&m(Ii#&ZJ)v>-}$>^4~0A}x`0|I_BW5Fc*XTnIgbE8!c>HFGl+}x zgFGp})J>unoAYD@zkKC*Gey5~1kRSVf-5ccjeh5zmwmi`wFfW7^X<0klwoeR`WA@o z+1-|t%@@g-6G4=AnQaR6m18Qp96zVcRa8d|?5>(w$5deanwL_o*u{30TyKCYT_iT1 zu4pc|fe5*U&elLgB;uw_5f>BW(QxItSUz*`BR7KJKC!Mrl*ph1fhQWAm&O$5x~qV3 zCd{?F?cS}&hduhkf+zPC%vG+6$tNgi+J`m;)03wYeyBm0oiR*=6yov)PYMJN@W=jT zy*+H^84fp7mG||v6*X;i;zD3ap6rmh=3XZugAE()f>o1EW{|^0*29#O6uosWOZrLeVg~ZC z%X2B%$LdPJ^)xUlrf3_bn$IeGOhJpU$O+I>iqq?{n%7$P3I@wf*wi}N#+U|CcXMmM zj}`!B!GdWvN5RjHo<+{*gvR zu<2w#p6YmEqwNrG^exSoqNFOM^r`*L2r{*NY>bDGt7^lA6N=yVltcE5{)?c*>v7K$w58q@)sGZ>3jz@4jlR^g556)8lZlj?K|yVIs? z>=@Vt-}%^>>Os+XITEC@H1$ z4kr?$r&5erFoA9Ln-RaHtr_O80lI(}PQLPsj~TF1kt-I)JB?i@T-M`p z5irO~KaRXXLxO;kQc|I$gvNO*%wrt(Q)$=8eaZW9F&AP-IYb~`){5j?J-mWxg$vKIqIY z1iNTlN3&w9Fjy$*LGwt3dJJdkfm{qW?3C)?XL)ZA6uBYANiOODi0BFz7S_n0JF-XG zSx>}2CL{_Sy}T-@$tW5$lLlBCGDjiYut_%Rc>ZIobjy|yP|zE`sbf&R6cZ&I26*f&(K$q;8O% z2%wYmWxYt95PKjn_D}V9O2JY@Ve?Gsk|6u)_LcEdk`g1-C1o76X0k=#kz$JS+Mi$Y zQD!txNdAgP!G^yO)X>&;e^mN!3(2RB;YjJy^dt77NI=lcZoZoW9A~sMsemvhQm_{S zL|3wK?>QN<-g@sX%tdgKexLxV)I;nA5=`(Kgy=+gI6x{2AQ#OFDm%mb@)R1HxkJeZ ztU=+uWcW+|e#EvPS;OR3IHy4eXu`R02DO-4je=%TJylM&2r(slwRI{?IHh)n94Y7Q zHt=93Nc?^GUg2}^9aF#6;(5kk&OaP;p41_}-O)BSx{&;IB)g7h%zscC%$z(jjq&@$ zbr(#&S-UeP|MXx)=-cFTc&6CLdKQXFfEJfilHjyi_bp85QFr$%jGAQTrx$k6%cO?z zX1T14*u<6o{rdvQGN;6PdKOoFT1Pg_09V0mlToLdL~}5o*U!S^H+(E?V-TvQE!n(# zq0O8DI{Kx0PJplIQ_G&8wpu>Ma5;g_bm`It2rOHj>G|@6ry2q>i@Yhfy7K5}fHi}; zz+ExtqqRINE_QlEwGeotfpG~{bTHO|Z{&-01Xcl;cGylJI6~7NV);rFVzIjt__QuA zgu7L{YA@!~!aR;IN;oIGht>P3evOxsli5ua_=aU|?v+T2ZD^6Mnb-1{>BmFawcxgdPw)!J+C`*z5)O zooB~4eRHp0#d~pXuBF%5;8!-6y3vMlFPhJZ<;EBQ38TF=QVki~Fr#Oc%}8VpTb#3w z?nF=z?icZg-XjYk89rL+lVR7tx~KmFc8va~x*3*#Gnf7sJ+^<{k{CG&ezU;;Xny@e z0{@G+L4*vQ zSsL?>_q}1F9HflnFCpZaUAx?BH~VL(PaRVFw29fi`(Vq#a_Q8x`g8@!Xvx&9=QBO% zq*R-}@pOi>i`6LjDRu%nB(iY2W^}Vqln`XQDHpvuYI<^HZi!GM582}1VcRO3CVi%! zpr8_oYpUn2?v8cd_NmW}x)v3;uB&fuO%)qh&mUd+L^W)-4coJ={UVF6PPW-k?Hkj> zwUwr7k2XE7Z8PUaEpYTuSX-{k52SUe*ShZ#)jkl(1cK^Oy46@q6O>?up&iV-&oWv% zsy0^3AzIJA?Q5+1-+zbMvwANtOs@l|Mf)3Y^pkGbyl3ik{TGS>@F`I!!uRu`C~;a@ z97BmT$-yJ0!o8q~QvAkD7QeHIAY3?J*n;8r!^?Z#fNK~BRz)}od=lxXTr2=uz}I|> zgLkZI>NJLdAgusa)};Np(Rp3fW2CFny4h(-kM?tgh&s?s_=ZyZGIK?*rp;t^*{X{5 z$9Di#;zb*4gi3&d-~gch`Di8y4tvjM-X48P5dv7m5ezZ=v2Q@V%F&0U6D{Dsh+?wI z!;wB;di<)%H$B|nrw+RC_w7ztx_t~leYME)`mGD14s98*1(i`I=nN8(1>m7K4|VQV zN+OHK8L!+aC;~#9;t%{Gvo71?7?`0QqmgWB-LEthY}r^}A2PaJx>Gz}#jZH*m)Y9b zbF^TxJF41pk&Y|{jBvQ*Mifiqr61|>q#D}|16Xu z2?7fMt;{V{hXt;9(~J24(=QLV#703I;n;u3xWhy)vFhR`pJ#OJxs=l}*TcbHh zQtP@-)**wEo5nOadbEiQG%q~Ohvt)#i!84_6fH>;Bx0Dytl{IO{!67f8Ml?s$yJEd ze8pvb6Uo|%-;W3SHEZ)H7E*YP#1+|->Ifuq6O%U#Cn1c1!tN*wY(Hd$b)yMCFfER~ z!Yojgz+gj)dxXP9D&$c(iK7=n_?d`lbO0}$qK?wF7oOcr|6&MqDtfPXtIVp0`G%>} z|3%w7MOV6T+oG}Uq~eNg+qP}nM#ZSuPAX0+_Ka=YHY@h2|F*sVRqO6`cH8aTbDzH1 zzBZrc!yLW$(MRuq7*CX4ETzS-IrBl(bZOg;<{8uLl?9V5`8HL;V4*LGT;k$)3`AZx}1Y)_Dr(2VH=OjGn3nVuw7*3@TnbLeBjmt z<&1rH=VHTX@CMD_TC9{TYYG_W-YU{f*?uL*D-sz`#5s}2e(<449Qqc25IjPJW6T`e z(}u4Qa0u3x2+41Q#!(#;+B}8Knint@=UG6dFnn=tgMMi&Zi3>)%bDXPM*!wb8)8Pg zN(DRZS^R7MYn*0eFs7RVFwsY&xCsj;mMJyB;1~z()mw4DOup}+$y%pdCso7j4Gve@ z296OgU0bZYU;?6vQZ&Le+6U%Kz&W8a@rT+L(~(F}cNA~zY%qeT;r_-5=hsIedCY2< z7ZKZd;r!??{ksqo<-HVPDM#Nim9JLTZ(APW5*)5K73cdC6}(yC{i?t5fxJUo$QVT( z#eH|c?YS9~3Q4(p3QMt6zp`GRiMcqAHY&B{29Gh;mpz{$O3naTVO;suC%~WXj5vsn z%TL#x2dfK%!0fk^CCJ{a%7rSXv6Xcr3R<3Wn20w+*efpvqtR>hlaO~2Hm3@{;%ZUX za;K9Jq83f;8gwrfRb~hCn@q1UN)o~PRX({0|xoIA^sek>}V}z9QfqY11uY?Ll^HGd&uYe9OgnM zAmP7ieXM^oi~ZLL&GPS1fqxYJ{u-HojNHHG>>ujhpCk1TRq!t*@ZU<`|M_rbW%{2E zS0+}rze{=tT9VFtga4BB2-)j+j_*37tr4VFYWJwfYsH%55phwz)=H6(CPWT?ZeF<> zpFn&8%o~HpDUfQsK-vmLE2dAcZGYr|ePQ@65Uw;Ssyo}`ELi2x#qDUjkD%(9o z_0eP!%c8SWBQSH*W0E?F_GhPWb*VqwaCFqUY6^RwwSYUvKYvY1ONS;gM#Abe2PVJgYt|+V*Oyo`Q8h6Mo{sb$_)&ufl|OoLBAu=t%c zM=%=T;Mrb%8uk8S*Suj%)uQ2rAZ12kh`}dVL>2zo4xLl$?^n9%MO6$p!-F(ZCid<7 zPiiT0sP!Q(rx5V4#fVTE^56fzq+%XM8Oo)rfxf#gI}fInU&xDF}=CE<01WWfhnUsz;sDAISwQ8N)=UyW=l~jTHN zRyjo~TB_sm?mfW)PRhVpk)q%R_J9~0WlB5JMjN8h5V6bF(8IM}GfcAjb%z-p zbeTpwfjv&15;U{Qi>qVpDu2=Fm6+#cwkZv4r3*S6J=OB`l@eb+&mZ1JNpfe$4+jISA^H3J5 zkk|}#Gu$;|qJw(WTa?Q13)NH9+v&K#yp%_aZZApKqMyJ-d zQ}xbnVOp=oAPoCUYKnogU$X7c`b}*gmbL4?I`mdNt2B8~Z|lS(l+L*MRYyf-1k-~| z_%J)AfcvZpE*@)@w0!1`AJ#>ha;wUz6$+{B zs$^s*X1E$ZO;SRVAyLAKpu0l+`t*d8M91Gf$~nz$6qMnuQuJL1oTB?xP&~11`JPglnBxpi$S2ePir+KN)wspoi?D-V< z1n#wEg&fquHnKWFL!p!T)&;fW5gZ0k7$a{ha|-+`lJ0cs7Z;ZsX-CooN(KY0{B6#iLu+yt)oH*9*ZAi<)c)V(3gy ze-po3v0}(zh1-e3?@5iKe(gEbz^R;YVnT4)0zuLX<9oLU80$K}kR&0aJ9XNZ{B*zY zN6d>+HP@_pTFs#-@hHH9rNjFs-G%?@g>rBszoSR~RPu|s9_K928>x02P9VZL2a+*Z zYAN-dm5{6?AT1lps4OSUsEHOv)t-1|G82nfkuqy=2OC1_tntMqoRUMtKVV%uX4NOI*Xhj7 zi+5}?wvMyzt-}Ie8DsqJX_$a(voo*8Fbf)im=rsZ5(M&(QlZi>Kjm0&V+Fqca^}r+ zl$;y%iaJ;AVVt$qIvBE%VxaNs{c8Nv*6swZcOE1CS8k}1ol`dVQzh5BMPUS^XjAjvfu^A22yT&5%e4l=! z=+a&}%+|$#Q_hL~gB6%+jlP(JhJ>{%1QjbE6k&|Xp5!=A1f4|ri&2be@>MuGRN=fV zmCKYVnxIO7;?7%uW|L}Kx2GBAhJYY9jD+2`N#6^EuF$209?}Cq z3gP5vL*JzLUL}wk50yT5OFjl1cGDWjC^4Ga>NHG1F|1HG6X5h^dW4Ab2x(bO41UlB z3Uw<46evkA23upmIBM-O;kzZM99a0deBCN4GAH=+g zqc8iS%rGx(6*3Y#AV(y1y%*t=Du27=X z-gO8!=kNSz16IAFD&_cqOh$kD9bK^WbV2`g)bz5adLPC=21A3IS5eXYR0m6Z@#wS<)~rH{`xGh?%#(Dj!>4S zLIzLCndm42al7ix4`|aKWVBBKEUZuQZ4=-U^U^-v3|*`}J#V=3wN+U}v}sl&$wV=D z;m(h&5I4k5afqEC*4Yg*(bqEHdvR88oWIUPsVu@g61rI3d#R=AGX9voDqsmP+hlz| z3i*h+F+-nl3aY%hH3Y2UKHPXF^Vv6LHuSI)>>WA1n|V6dudWYPhlv4YZ)S>7$H~%? zoC+0==(9vY>Ljp}RZR>>CShp}@17R@JZ+M!FMfP=<8@!Ve{gHnwA&KjSWxM(JSy`E9D^iyO)=fDX(r(uI&S}mj91pdzcQ^IoYc) zN7^5}z2|G+TEG}A8s4>l=*Lw+o%vWj)ibClNIy1Zh`2DM<$8moj( zvvbK9Ayye`xz2E|m1NwV?(u*_B{-%RdcKCUYI^gvc}~OOyHpFiTXyq%^sD8pL?GzX z0+TTF4e^ioAd~5ohw*?@_@vN8VZi?8AY)j4U$H_@I#Y-hu{qXo&hjZDncr*k;#qqo zxo_Cq;py)?T%hw|4cat4L+dV6s^%$`a=&(}KPbq^aHZCj#GuGzvG^!Fvdt550at33 zFlVB{qg%;qw6b^Vz+NC0at6=9B>P=TI9yKiw%Qm<3D;k6aU0r-d^IkT3{gy>8$VNf zEdXBg43?%8@zDzI5>f!w>mqn+`gCE~k2kJtArHMC$?aMLm(3PSk~rkH{at>-={a6e zf{f^#bM(CeB>-HoS(YyeNP^-}6meP5nt6{DSyFa=-djWhTqg>9u@t9PJzXP z#L=&<7<@?JBv)vT!@l^q;C}7LJ*F)wD4;GMC?p~#KM4-31I>>b1GT=O3*)%iWRRRM ztpu|wGiTaFHZi6DY>%R~ij+NRGVjtRNc!ipY&9%vNd(u=E?OE?(=#t@1$HqGb?9BS zpw7ZLaWGO(i;k7AA#_x*irF4Gho(ju?64+0T+ZQ$UlE8J2~%Rc2Ja-?afOm_g>X=9 zbuD2^kk9Fv3EhqOb1{>KoY2=0M}rg*!JM6(mX#?$E&-0QC?72H8*ecP=0Es9YSwii zVZyV>O=49vTD0xl$6SSjx$ds*7$I}h_OQ;JgLgrUk`T2R4{_^=Di)?M7#S0NK)&(z zW_EU!Z|+Pcxh@#jGvDpIni5ikcdo0`R}dKUnol>;K5Nhx8pc6`b0*lJYbSl584u>P z1sb_e+6NV9HT``E{lp7gd%nM>OK{(BltW&mf?1ekM||TT$oo~WM-~dk%S%DvOOZgd z5ZZUUDRA(>+5KtDk0P;w<1l6uK%u_(1IhJ@wsE zTYf^vAqLKOCK5g}hmx{sPR;EcW@~=+?a1~{^e2E3-T?C^CI<&&+#m&k7!5QJf$C@g zQ92DHNEFZSyL5-N2;~oB=>v>w6;3@|3KVBnz?R)79#zYoAE5OUD;FcI*mTbH6^X!2 zo9dY7QaQHyrat1mmU$sKqq!xAWx*Kd)T>rfn6|pPIdj23rK6QgG%x2nD;n&pB(d*Krc?t+Nyw&)5&jeuy~!{!cEtk>;J|Icu02)axH{ll!`l4Vd6B3ovzNf` zRFSMgrghml^Uzh!HjsK+y!;ZEqBs465hiK7rR=<|FWsEc<3p8!g zROcAB!Pg<Iy#qHyj;6XubE+9%C~RnwlOXnNE)LFH40$#SfAjGb~gItB*(J4A1o z#huJt)%-@3P4kLs8i*Az;nEgy>UGQL*F?$Zt9WDlS<|jZd&&4~i)6w+>cG&GhtQX^ z`r`I??60#prsik$kP!)r$LI_xxbz&oDB2!LUf*`6)-Q~NV(?M=NwNM21$j`Tl9m}M z*jqEmg|-5r`d=4O(5eXCDLX!O2Uv+#xB-qp?BS?H{Kuhz`NTs3N^i(t_{xIS19GZ_ zY|&x5j?k^VV0aDbUAc#y(KYkZIw%>5+XuU*Fa&g#JfqN&*c}TL#dhNL;!S~OHg2Nv z!fW>@$WdTsigr*yXy=aHZhU|g>M+ar5-%4gnMnJPb4KJ$hKDja)F=H&i)famNBthw zTCLQi@v1-;PNs?1IZ#h9*7&!su4Zi;hXyW--3QLEqQW4@y~KZKsYlUqBQ-No+7^Z7 zZe1bXoS0$T2^2y^y}lmaBWMk?Rl&p~oQi(*Hy* zlH1mn0PRfxgQFQcDD7~7W~wq~*em)iXGhY{rtm~d2S2e*gz=}Wvz(xzE_8!wUGbd} zjN%NDw?23$&iRz zhId)9@WkE-8r*`!Dh4V9$sdzN2ViW@9em3Ehe56-d?hDesJ94=vj=9(C@> zW?@nS0mN#dlghw!OCLs$MWhc?vE08%fwJ?AWW+qt(o-KE= z<~n!=UcwFX+<4tK^wGRiKif2%wQ#<)YAhNob#h-P6oiDe(_|*;J3ozIaIDoWQ;!xj<#v@S3-cOpzoa$zUVx+$}o&-3si%_;reH?&#_RmInPT;vYE7-z={G zLk{y79r=UJ{BM}aAJpbglJXb#`M0S5_gLfqyubK+8_XZ<=noF_*V_O8266dY7{Gr^ zT$tJZUgA2TrER~*hT*rRpD+Fe%TZK`WPtKz+Nf!b4ugUV-i=_EZ#X8Q<%=}_NDkqr z-_(w1vqDOiOz{B84`~nX<}05tl{?A;MUYR6LaaBE88<}v&)_Y<@oUBL75{ZORc~o{ zmEDf14CM?{TU)E%j0xTxiKN!Ha$=6Zp3%1In{dA@J8l?^nt2}16N4afwMt%T)LBSCfb0LRm;Pt+Zk0ekofNX*MU= z3;(tV&Nizu^H!U8>P#V(u+W5%Rceb?ig0UfQ7|UXw@|PwshO%8jcmE z7)LE=$lM;97V5DwUvNp!Gsin!3}z8n9U(+rKgYGu-N01UJ--;+Qd=*D+vIO^d;NV3 z68&Jh27p=PB^3%BRTBD1pa)Q^t9BRh6(ZHZ6+l4J3vy~DhCwp+@9={AmOqB3B9UMg z^w0%(XcNYZ`9M{k@0@{`_7nhM@6^z29Wx+9o=_l=k&Xa)duSxkkVGtsz>(%^kguEW zW_RH$U{=vxopI-$M^2nEVpSoF;LS6!=! z9NCeBfI_%DH+P%1__IR`f?r;;3#XS2^iq$-2U>{+Uzx{i7{4LhZxbD8?yJm(npBV3 zSjDK~uz_)K<2_IER~5+DbgP)o7&i+{Kr7Gi8A*OyS?ux%_xtWwOXII3Mk*0HLIPYh zo5)xkJ(UN2Cm=qJ!aMm*5=l*4Xi4`0rUtT%hii-GOM~UBln^Y4h>&*y0E4H6>zWZc&97B8N6Z4y zrd5F$Q;bvV%DO`R98YV{hQR0pQ9SPl(}K*egXCAmLjD*?AWRu-3>1+ThNg!$iabF) zR1zr(qWGPC+l^AUv_B)z$ixIW!1PebOR*|kf@w5BnE4>y-vN2E%32G%=z>fG*Q8I_ zRb0$gsg!l*=lcpn9WV>poP{nw?6ps8U(euoIcSLD;_d zVaYL<3!JwaAOsO;@bQz4tLs_qSlUe{w=m`LmZ{Jixom7B*N z6l3B9E~UP=7Hc?%*E_U^p=btZmsG49t+l38ARPF1WTpR3yRJGu-JIO%#t364jAEYv zCKC-cNm1DpB-H`XLQjfmqvX!02-nNyi%CI?hwY$AHwfNOGbf9~#AB%+$`JJ%SyO9f zA^r4jq7G^^O{>&8yNGJ%TnJh7Sxx>?h@!yW$#&|8DN+wsE(44YJ3yqZhD<$NFdZZe zoorIyI~Sb}k4F~_xr}`>G)*q(m7<5g|1JgGkmlfl_UoGxkpUbAM7EZ$j44PbmMf;5HJbpyaw*VJ76c_t%2v=hu{H*oZl;iE6&k_gc?lQ|+< z>f;2Fb!)(-gQaFCX9j2IH-60>&DC!`B7pTxG9g`Ds~TAaVIEM>$%sg-dKUBfp3iK1PV-Pe|w&P6m=%-&o zUNSg+1HiKM@+d}Ref0B6kvA0=`|e>897DB+bF2-w{m_8IC2tvp6KGw!CQ{w`%3sO<=lo6-EBKY}Qe^Yv*GAK!K%zt^;4-Tu$l*`)1u0@!Z(r$i=0;r;F82YVEDJ%JjL?pJj)AtTH>$ zX8P?5)%x5;ZroOANrZm16Nu_gojfNy7F5ZP+gGE^W__cEO3JS1J_q63X_S1uWfq66 z?HS`4FzFmH>zp*oewnOWKxW)a>x!iZ-LLxZdrc!g3WA)V;3de5lx!L=~Jw%#^g};`&1#0e3T<%b&;RBdp_v&fuWuRS|<(!mN z7beLk*L6MDeTP@tbLVV&kxYytt^onG#{B_-q}^3Um?bR78zt2C>5;{^(Y?$O10b-L z9`f?ru#=cba-=!=R`r~rVfwuU4Ii_9m*-Xful$75w)6i0P5K$w5Q z%0I5n{sgiAHmUrd`%&2bb~gRrp-pB64)*_-O#WB4YN2EVio4OAuLQGX=J;J*X7)*+ z7lB236Kk@F`23=qpYIef6il8#d_uO_?8rWG0z_a?(3Q^-h{MBP^rX{M*d$Ak|Luws zsJnmQ=cSqd2gB=LbM#axp-$;an6^iTq7F)HPv9%VK@bP|9HCe=A z15CG8ODfQgoRy(rXM^$SXTA$e8w>4aRPN6cvAJXK<#wV8!R{(dP}f4p8aFba{E8L9 z)Ws@R=sf-Kss;TXQM>kp~Y;dqo zv84+rwG~!!e_?k5ONg|-PPyv38FB^~r&uKXDcN&W7~jXKnS%v_kw$-KF_etEX0n!{ z?w$%eKK%RbDuQVP(=duSaNO9ejh_kH=I0~BNDhZm+@`zAS?iFA5 z6rYDcygGSE0bl4BgEbHcVkPnz7;W=5|L@e%Q8-c|2J3_P@ zk}>GpAYJv>q4L#Y4<%fWU#G+D6^^IW0ZW2Ek%qM(k$)r>OpgL6f%Xl2b^Q|Wf!n$;Z1*a_Y{3KfZ_cX<9J{h zsK6bBSLPN6EYWZyl7OEsy2uzD%hQ2%e|N|dGVXR*KqlP#w^WAk$nKt>;KC1Y-q zwta<}K6~4}S|HdO;!F?Tm6p(9cSo4+=Q)GqBI7POc)0|Ubd>B!Fhp5T$vK9-2wMEa zfncFZ?02Akv4_BA0sT$-WZaEO&|xsb5R(B6Qb!7hvHx>*L{zmQTKLqA@bMc^@qw9) ztuF0_Z{t?7G-g9A+IVN1otm{onkL_;1d(>A=On=>0ES?um4>f1DpR%oZJkAR&+aic z?qu;2XEw^rwZm>}8C-Y`vU$V`cMg1HfLg@pcmHC|;YMN23PEoWZ&_T!G(4l3G(33HNtEME+e&7c@8V0v zHRCvP{1?KYFjuUfHw+Nze6g$gI;e9Rr6)MRhax#s)r>c9?fl0eO4H`<>X%v*zpGRc z7n(Hl2^=k{1nq^6^lhy@DpYTQgD?FK#tDrLXhK7y7OJ?E?G|p9=)m-Rbor_~a32r> zPHR9}?0Sl1LghW%gO;CXDjkuo3J<_v=i-MZdC6H^ohT{t3+&-!at-0j?P21nA+J4v z{d0+F11smTZ5VB8?v5HX0+UnLzlKpV(*JI%j{KdH3aDW3Sg`r{KET;OVZ6v=&ju8~ zFxwTmlnfbRz;-GU*HYuD53ul8zY1F3>PoI0kqY66Z-pdbZ<;`C z8Jkz>TB@fEvsd_{Jz%tRcPU+nW$p;k$Hzg+rLpKU)8Pl}suI~p#uwTV(yyII3a31I zN28#US5Kd!B-3+6M|ovmQm@9EfYt)@DcLX3=^irCCYecyLkug3jj%50La}%99jBu+ zf-VCOIX`pbCI3$*-e+RLa371N4PfWmBCzk^dnTATY zE@@@4zEr9QeMA13Z)~ZyjZ?%En#W6MD*3hgZYPBq+rr!3F*nqvmvVORT#huN?gd+^ky&Ae%olhlV2I~ziSaysg3O7?;Kd#rH0J*8_twAD7 zicFV6K{4RYAitzcGi{EaW z7B`tKENv)SOC+3dGB7{^4wfW+oakZS4HQ^K&jk@;ythk~G#-J_s0N2`0-m4LCrM;z z*q3W~Hb!p;&Ns7GF=y^a`y`<_L!M%PUW~Y5Z5@dQS224SnTC5|=Ox7~DGCa=v_7s6oJ+ zX5pMZX>kdA$+%<|NmdPx15w3HKgGZ`1w9Ly<7`@QpqRnS+gx{*W%IpzZ(Ki15+8hl z3RlwU2nAk}T1Uo8iOp!X?#PsKDVD-9tnCM7$FWg=%v02bL?>786hqPP6A2e?qYe@1 zZ%~0ZEBR~~Ay7=DI)g<*YGZ{xG?e4AUqu=@#~lzzXNl0NxDb9N!Cc4c>M5`FPw^Ma}i8}!lj z7aSQXjQo&1k5upsU@%}DiIyBKplE|0daY|#k@$5d)y6&N%_I|2A&?vETcoGQ@`8MY ztfxZYlJ4Votdx-rMK6Np$}>PnS}I`S!_OG;`|=(E;zf>+J4j)(C;Z&r4r9Vic+lFq zQY{E0AJMKs69QgC7td~96PMo`bRzcib)U!@?_q)Nw!s+199v8C(JzSRXhJVw)Sah; zWzLe|i5YS#@`tW8ULDUgS^KGQ1X~<?$oK0$kb|3`hj1m1=JN}t&N=5+s0 z`t*;Uq<_@&|4nY_#r}yM{dt1-2T}TGOVS@pfIsi`{wk;Vt@1My{)_J^{fpwzD>&I3 zE1SA#(<_LG5z?!edbkkMOWGQmn+pHOQ|LdQlDhx;zNwwbzfwBb{uWB|-*G7>4u-!g z_XFCRzvDWP{idp?f2hGbc+^Kmq8Rw^f}EOIAfdJ}M<{LE)2HjUh?{q$`Ejsv4S z{uQ15Yy7%*=J@sug6EaRm>K4CS;qM(zkUHD=L4ZDb7jlU%>P+*JdG^Nv_2E@+Gzx< z*2=BkkKNp+)+A}R^~tk#e|B;!CDRGM89RH6rXh{pv+=WLd!^m3$y0lA!S7~hg5N*_ z!B~p85XKlrN(3vRJ8yCIc|vywQWsP9clF@ZHLP(k!03v9k>KrqfeN25lPF$OobiZc z&(4Ft6!~_&@$r!%^vbNjP70MekNM%nx0dC0DIYmeky-<6N~q%Tw*NeV0=qM69tgX( z_^eCfjy>2-#buw%tj|?FRTc2~XxdVBMn!Y|P|=04wr12pSMlB7h8rTWgz|LKa$+;(Erg4qBP_D0wvHFPiu^?sC?f9EuW^f9`vI7H+Kz09-*5HIj^MK-VjMy(YS&;D|DQXabZI~wonwZC`i8D zrHXo|$@KRcu4uC9YO{l(KxbBv_kfrb2@Ng0vjJ<>vi!ezTP(N(xOJwR{q zQ~YO_qi9O_Cbo8$J8lUvZDdtj$Y9=c1!!wVAMHDd#Wj~IhtR^ zSB_-zN<+4UU%TYNnL|@tgrJuV>IgD?wA=OD1CVL6j}}%DbpuG&wwnyU+fGFXkLCwm z(!4Dt?P?LrzvQ0r3|pcnL?(>uRSHikJDV#`Ga)kcIpQcxSPy|?M(q3)sQgyll``_8lVXp#Zx7FLSXoO_Gy@f=PVNDAVoSm-w<{Wy1Z_(iFEk8C(a}2uBDsYRYonTZ`#12hP70$#F zSNlW85w0$+Pb2y(&BgcxRZ2=^@Z#?DdTED*D z=4(b5{O%g0;Y-xC>-=7C!#lQ8 z2eaADi`fHo3Rz=1FM_mltvM{7E@gqYBmb-KLnb{Hz9~YmuTD9e$3;4*pZuLzawz|{ zIr34EGSTQGPcC9#4b=s|1{!ZJk@)kc3g)jDDSY5azKL!mHwN@cR}?Jo;~pm$j1l1xG0q6bWVFZ;p2kYVdy4Qw_q4zt z6o*G#ON-!G5;uLl# z^h`eC#BgLpbGsjkJK(^;u8K&*gR?Y)2d@R;2{p$y93f?Q=(#`=5#U35$&0)d zI`dttG9>Yxdi-$sFm`?UVvxm&9nSS=H%Xy_87lYU@4fkn2rOSbNgeRTD9wnbXe|JC z2*ZN|_NI8X*%O>!G#2BdK7jt6Y$p9HOjjPD^2>4Ac{?;D)%K$8YhR;l7*#PO)u1;V z+)rm3uVV4KrJ(Z)q;8!^%NoMNhtoM|5*lr!uYGcg9rr8;A5PlUT`%0t5lJWs-6%-B zT%b^lKCWvvebcI)0XCn`t(pdwedZhFhlVU)epk(89oJq9Z#-kSwN$oclE0)9uHa8Zan*4G@%ry$zK>7;0lQyOUfn#Rg7%D@(M+!ug%y+Jmb{*_e7ek8Qz zdx%3VdS*Ffo2+JrlX6k)eOgS~n-hpbDMLwgGZxpHLG&{g$^v=2Buk>vOW=-po7Kk{1rokw?_?w~VL9 zRq=7V)}Ws1tRvs=3i~SV#n(Nr5oH5qVQS_|IX26@XKak?ya3r4s(R6uSObS>W@_`4 zyv||NbQ@_42xPSA_v8r$x^$Ti5E`oxgXTyzA&B!MAZ>%7`5tVJb*}jE=|smDJD9Rx z6}!vE-G<7lc!Atba;#)HpJ3@wN&7VvTTbOw$W8+Lk<269LS`eNFHjQMSR+M-?)!-g z#E!l!Af<|hyU<3j!A?Ho%@NtPH_IOX2Ax}kmpW93xZU?(it&_fh8g*5hZVjgcP@k-g9x6;(HJHh#j`_Qk8v@vOu|C$#5E->sXoag>EEA=r8F| zwJY-I-rdo&JI}J@{kp0Fb>y4YWMGbO*pUX#QGcGx9<3qLpJ&gs4~{=vn z<4E)WfinEfv;Uuz;jfDG|2cX1-F3I5_2f0%*(Sj7Bg_4#8F^Si_1UwB^$ zhF*+?`9B&let%>m{Fi^{|9Sh@IWo)t_sR^mzvYztx8#C}`R|9r7h2M>Ys3G#XSkLy z?33#v0Crji0<27sE^BVs5ST4)^W=6p05A_f4k2>RAmQLbiKS( zSgGeyt0_Lks)qIvX#I4*zC(QaG`@c{y-&?m9l&ywQXNCQuIqu+rDeB2)n9#Yd%rE% znO&$bZsD_)&&9Y(`3!b*o1cU-%42ML@ts+I(Vqz&iAPTCud%pqiow{cmM$=T(@o-1 z=r5{n*Uhqz?Ne*;v)a2xyfNFNZ7I*~tzPqOsp>t*=eCnyvm>C9*Y)sTzr?@n3U%Kk z{`g(v)MAOKeSQo3(a1I6O?JlCaK+aj@5F~g)tuBF#h`%|RyaMpaIv$DK}Ke9*q*ET zq#Mf{MJ@CD+;}L7NKO5FO>mS|E2zHXPgv^|gPsOrotQ5)KN>4&38XC+lpOz7%p)F5T8L1)9@NcPisds@3Ois#3_i8RsNX}cB z!S5CL(SguSOml51SP={LbtS(Ax;sAc+bQ{*rQxFnYeOL!WwC3ebe>EXvrBFn&LNU! z#qf;O=PMTg)8p`BoHtNLrz>~4#FW-BxPxCiXrw%`YT-D79{0KiUMJhV}WV4uCtB@e4}}E<%+5UW+u^wAAyWDYXhPM~dvv6aPq}T8r<)cLTy_SYG2Gol zSDd0GN9YlTpRuDm7yogI2R+kQi@)y~L5e!4PjZn~#J_npMSar~Ej#1K3d`)L|U9EWC$9@7@ zeFokN=UiZY)Fcm%iJ!Jmk8%MWFc#PXG@OR-x2zOm!3Kymo|b8)U*~>A&^b{pMN_Z@9o(8-t<5Q~T}mfWktcCM>^Ccyn;I(O-LL7zNa&#f zA*iEdV1<)qXCyrm9`?lS@L&$-g|J|4VhpvG5S9PD*2+xRbYYGG6kngaLT|DKvFCQL z1wQo(ijxw-l5B7<7_tz`!rs|=IezDHUi_Loq`4t5-*Uo^MXWM`%BsHoYYZq={klPl zhNo{11b3`6q!<{7hCJhD2>XzqIAp1Ax;mOmas>{Zb45FbYc0`t+L~Ja{73L1K$8HS z*^WX-6U1`QmC+0-^qTU(b^p`&+%#IW#EPGLU9?nx$#Hu!P_;{|rjWJLhz2$#7UwXm4RjA*t}0y)xbBG&Bv|>!qPR zw@=3P!CsJcT>L%VsDt36FgwI}fbK@vZ=FlH1sWZ?1-}nnIcsPR=DoQMF&Vbz5}~Xf zQ6s;5!@VQqW4F1@VWVN_VyGsWeHMjUSPP5A6jGR*2B*i?7b_*4hLA}8K6WRprGkCK zFwsUG5i#u26QCWk3e(v;^-Mj9Zm&0vr2m4wJ5g*MyJNSN-8*qKbV1pq%RlI@o!2NP zaTcYz6Os#!chscceDO|JXI%L@tdu}U^rcZafeywR)^K)=61(l2B!1IWt;&NX-~;V; z*tnc8+pB=?LQlB(!#6H@3wj0YxeG&V1xVAdH6ZhZth|mXTt+#<`s_OgsThzj7CzqC zaZ$DeY}ZdHLV0YJ0q5G%*(EQm7jv7>lrNrvLy<+e`nMSzUS$5yjq`el@1F|aVg*hC z1DHArB%KBHkr7xm6??7py^-vr0_Rz8+j>?)^4){>5Y%(jm;EjAr38 z!h$!_ipWx3kq!s({7$&Sh*!sISmws*mIn$Z zetXN{8DAFUC?U>)1aR2VqkbPNrDwzX-cV=C1v{>gU)EdNwssa)AyG3y zQ8hPp{8JGS!HFHYeATOcdPKGfwh)i6CIq?*-q_f`J&;;Bz=&k>hm1>F@?B#kD-Q!- zuMm^#mbks0ooYH@p`T8?M-2Wb0 zX80`!&VTa$sAy?^UodS#LD*`J{;!;DA;Q27_Slx&A`gK*3+qakPt!t~s4bcH#urO= z$iO5LKm??cxgR^rvE<#aFVE+?>aP^J2)40hV7B?+P1&7pQ(WEGU1_N{Ip~oBzz64V zq;2*4a!eb#T1mPoFBF?1@6NgDzME)-XeMt3abxh-o}uq_M= z+x458SomykX1-L?Og1+~5rpb}hB8VraW~7x zgo@*wP?%}!x%}->a?o8V$zVK~?ieqNF!SJoDYJb>+Z%{OB(H`Y&SFBxhvX=3BNU;0 zCNSH0AhQ~VYbSbkI!u8$0W$QXGQg_(v__C4C3mt)jF-tE=~STv!P{_(0-?E&}cgbt2&!#+--5z$~fF#QI^#6>N~U9wDGvOBih8G-b~P z=MGN5%Nj%%!6lxluZAb}!gLU`>tv6NNayk=jtbPN5s%8ytbZsK&|_?u6M`@H&Tp1_ z+j)iD2YDR%W@aoMM0dVh0QbzD#ZMVA$S5Mn89u!@b+fV?OpOC6II=viQm~%pqf^?k z>F)N{hrQspOTk;*Ny@0r9v8Fcmm|?vvizkDA`#ASB?to*BNed#@6^g4NTp z^h87UsC7kc&?cc#rBmWqfOkxuCB-=d`$R!s=WV~|Bc^Z$Td(Udc~6u#_OXxeoCEkd zc;&Z+NILVZjuYj%6)9?T}KWS6dlgK4S{B# z*618$NUihDW34WHn)AB7qSVgOu8Tny2KmEc2PJiW#d8A(;Pl%o*$8D57Q9(PIe@N< zShhXG*0Oq-ECns-Qqa$-7XspO9J8cva<`; zeyNm9Hd|#r@Cwm`P}&Whyp!k261vwBoZTy0D7a2v`}`1ADPMUBK;ROB3lbpVW=6bE z3#tYNDF{$;amww@L0sPfb~Z~X!xm((N1?LtLNW)MnezzI-m2!@^`)W1DSM~pF+!%fvhxwlx zw_nZJlVoAm8(zIku81YSP3U)4kK?Eiqon8Nc}u9h*4(B2pH9H_nf-Oh{OEqy&P%;9LiG z5wAY7LUL)}v)QG^Trd$R)(yKgHD0kdGB=o>5msGCo6jDyWj6#%EF3n?GC!Ybi_ew| zPN?om4D5|3$Rp_!U>1Pd6?!p=y{Vy9LdLz(Xe0;!G0_&AjPzT%E}-ypR6NaGRd~<7BO6 z8*BDBp+{u6{@%pG0(HXRx?Lxe8=kK-(-PJ>(hHCALlQrilPH>xH@@EOYc9mzi=S(| zq8s|c$Y^_=<2t*)|E#iurrx=Hdnf1lc8JB7ErP-e)e{VB(za5XU3z>q1P7AFrga8$ ztb(kuX8k~S97aExN*A#gKC!814tQKDVs3L4fX|;h(g$?zRK~xi!bu1W&UUmFP_rh( zCupyaqLc}n|K z==;Nwr4Ubjm{P@(lB#iick+z{B7x+fRUb!Y_Rel5U+L zfS(CG>*Clu8d2ap_xJcwW5H`j5h(pZ zq;PJ*kh+?HcreWJmX}{<)`XEnwY8;pT|v8o^)wV{2}CFwu0Xs_Qx616Y7Hq>PsvnY z8crigRpe_rCoNHN@h}Vei>MVx6^5?9g2@wvAYJOgZ12G=eT%uI=|D5c*C(pk1OLLw z$;%2p1@ihJ-zI7vCX9*js6@Z-o+;VWtX4d<9eHs z-E&QV9UG3HQq5<8Qi;%sI#1`8e8vVfz-Nr0&)3P@8l~UD2T)qW%8tc8<1iI;C7$fI z2LY!c#*W5=Vh;_QqnS0x$f+Y0p7bf9P1uiz!*48pN8E+bssK45N{pHar2jM_5{&EB zmQA`jI{SV<4;9M-uRQVzSy!<=0S)lMssF9e)b3#)-7b}uO$K4EruBn4g6fk~6dHbU zXU%@ySFVH^!#j*)PGz`TY5op9aOReYX*R0kWr!x1fk>Ou<=d|N5=pz>a>TX9t@Z&qo))MQUu% z)e&-P^KOAsX)qU%lWyLVQ3PmY@_~O|kAwX{TdjW$06#UWH-)ZUg47n!4?Tk@p``gN z@3{?|5*_!E2f{?5ilLvKtfX;n&lgf>Pf=fZ0XSFf(-i`fU{?_7RGHtj79FTE-Xv8V60)+z78Hf*|Daj$x2cea+9xf%^$1ymKgdxY^l}z37 zZjQXz%utrscd}{RD79SLGmcL-OD^?^AM;Os$E$yiQyLjvmp1D7*3>BFQ_Un7IXj)s z6w-mtL7wIHpchsAwhBRS6Q21Cnb>yK7fO}|!$d|*HBeKF=;hlW&w=qVsE%;q=uZ&c z>f7bie1bWpX=!!r!R*_h9UDjM>^OYV&t9UfK!A&IH-H{lg5Y>ucPH&#?Nas$f_pOg zx`ZzvM)wmn?)!eivY==EkSaDv$=3K~ARtYN)*>SGY1B`KiUM-g7R5e& z0`KPF-FRo&=-8rM{hq~{jC@E9Ux}%i!mgpvux?fgBBm(BA`n)KxMZQrkZKDCx|9wF z(B?i;+&=f$jiHu@TNs{;29!uD`9R+?c)XehgGF&8!E`Ullu~lvv%g~}Q6w?5vqthx zGlP*E3gRy5IR#8%njFW>J&O4xJrDv#h51=st*8i~TPk@X@fbc5F_h;>$&FW8I^O&t3{I>(~h`X$R0K>`qAp ztYK{_6@>~5-R!R~fPCR^6dQ*cVAwVttlk$u;!;UxGuGk+Q`1VwIDYj@Z=NY9)|f;F1Gj#1&SQOp6_FoXLFEn1UUr zq7mAbmrf+!Ewy6+hy(z^noT&X-&mgD%sS-Dic))#xb}tTMb|Qe_&X>2E5JLfD6_+; z7B`9)LV_eZmiGV@G|t44*Jlk?%tgqkQ4UvCOhxqOulr7K)=Vdp92?ZBZ?W$RhYnH$ zt+jeEu=lDlzhtoA*;O)|h52<+T-*aT&UW-4Cxb(5!5;xwq6w3pkaPUdDcL=3zu ztDF#Uio_qXn23r*sBr~goEKY!mnt*Oz4Erg+Tm%5d|>#p;kkiH-iCR#Stm!&ySTMb z0xT^MwY1lJkA8fwBnJT{dJdtJymjsncN2Z1f2I>psjeM~#I#b8_1eo}w4c~P1fC#D zgqnN5)l5^fy&*N)bDLA-;DqHO!DrkH5!E~#J$}B`y`Dx0pRV){enL1huB=^mx}t6G znNF*NJO@%<06*ei188t zuetzZ0zj=O6k&9t^D1yXVF%tijC#7fP{E&vNU!~nNV*2bm{^2A$}L+gZ%|7NDU@#^ zI}6mc0T>Ec^HSTPpS6l3Vvq2+6UDqWYBd^nD3c^GyH!vzyrrvmh$SeVmnLWhFtVEe z7>`g44qsT22~g?nfT$t2Frwb8Q^e_y^WF)|%Y5>YZM<_^mPIUXE}|I20nuz)l8bf$ z{WWPVSjcVE74NhouALQS8w%JLMD0yL=XKMIX_1%pHtbFKVr-xm{D+sT8*F0Ux=-o0 zGQLULL{&}lh}8#q);f{l&eLZdOleLBs>6^ONbQ;RYRntNm0PVYAXWSVQJyI*+a|rm zE1MI5)Eq$0J3oQ@Gw#hMoMa_g+b1KhV0kY23(e4Q&O~TAQl<#Q*l>LhzTGhSA!G#1 z$Wd$UBwT(pC|63Vk6acB&#Nw=$Vcm$ld(e2T%GKJ)!LA@66)fMph^gL1K~kZ`9~AT zuS_}{>`9iUEOKXHuoF{T3Qi!)oH~{$6vOtdULd@jh5I6beF1nu9)ys5Xlj!7u1BkB z5v$;&o1J5PVsRlcxE{UM6V_&(hj$Vb8)AZ?BDH{14!|4gS(#x4y0ekxJvajto^^Yo zsBm&dBbP&HIwG)uzJ==N5qWi>#n!h8C9R8?FKZ!sf$=+-F0AU$j+W^K`oqedUzl1^ zD&-{k-<&f`(##rIVsQxX<%6TSLD9^8Ex;v9#h-5{k6=QV6fm0<(TDzu`Zg#Mgm5JS zn6wxUHH`}an;<`p7Pv&j!4~~O+f|CLC{<@QyTm0$LsIY=KXQe?m39P{G(RkV@L&Sj z;AF61@L6-(Wf7Um9fW+JYQ%eu8$fB<@#AsFNQN+|h<9@xazVkHWKHP{v9xT)^hQp4 zH?Nd;2WJ;%>H+4V<@m)+>vyzqmuCAX*-T*z9V?eGhMpsAHs5~S-CrF`Aj8Rx-F7)S zc1f+gvaW%ZZAvF~aqbS7{h9)pMNvVI`57o~&HO8G^uorq<96!4!vD zX+&^^y-V~|Qrx|Ulb+%I24SxaMG=E^CEP>*oE>5dY~g+L{2 z#sGRo#`%SUL`{Hmr4n1w7sO~c_+i<~oh2yv0Nf@=NGI7a0JI#nB8_Cj%JS9uV2cc$hVWpCAHjp9&Y=bw}U5NtA2JW7$n2iFm{7WV`?Zg*yLIEuj9gjzKN`bDlXINkNJi2JM8aElmG^QXt<=` zhX<5Ia*#)VQic9-1k6#-LvP)e!@I^_kJLK0^KwlVR>}4;B6bO~lz2Y?x@@~oiHUv_Rh_l;D%)vazv&nti5=l9 zbP2m*5zK}Tn}#u;c>Jj+Q^SFBP&JYVBG*e5FjcZ`4TAOoR%tAD4NWghUEhUd0hhun zzmS}G75giWmblN-2B@rWk}`e7KWWw{mKnSd;k^f3`$RQ@VmThN2Fy$tfjOhEc`L+B z??^d72obO)A6{!@^1LSPgO*bWWaVYLO-3i^sx#vmNF~T&5I<#e1aS9jt&jL`_9siz zMU`-}LZ{95GTsl)dqYWT!C z{Pi8|U%boz`}7Eg-{#Z*M?aD3ZzGr{6ouom=wB`lm#PPdqdj-Tjkj`)upVB+5Biwh zKb9o(60uuWh?3F0XX5Lb)foUV!Q6z3tl;|TGYz(biKZnNLEsh;M*kI97+{YU3yHnu zeWgn~bmvN#yE_Urbr0~3Hb*E9K9npnh{>ch?g2UY&{f8p`pDYqA~QMo6$^o-jwqcK z*@&ryoz1h0GEmrYTJ|C?glNsCZU&u+B5>HSLVr!Pz9H7@hEdu+B;A$U=DuC!^NRez zQa?xOnh7FNsiynfZJ|KRu5R>8AMK2{1d6;E@%{W8r|mtmFX?ld%(NGhbS3HhLf*S< zb&tqlFTEPODhWM(7Y%@-sZ6u9ucKr-U~2Y`5el{mzO7`YcbAcnXS2q{HfM982WhY! zdq-%JfV(%4$fomI`$mB9x*yMO1Rk#c3w8bw081U6$+#3VL2`-MM7o63^4hF2a48AB zOg;-b-;9A^Vqf?H1pyrUkcS+yE>&eabj~hciX$?$w_0G>pv*h-_gex>Z#w#fha%Yw2bp#fsWDe7iqrj) zra*SBp<+<9!E8Xf<3lk$YiFyx% zXhVd}VjSi)w6OjMtXM-+SCSxAQkMI)icP6XgcZc;4)XC@zj{jR=m~i;BH%7{IGhf7 zl$I>FyG`cHH~#Q149qdQ)%jwi?6@K`<3kQ*&5>^OlM@=QH4yZO=_GL9@!?xIs|GTr zlT%@+N_V@cw;>*p0VJ*IMGRtv?6v#tt(Et(n|T6B-pEmL(I?=f?!m1Fq(H-G$fp{Z zm#djGjZm%?4+G?90;hiz!xiz0VS(#VDC)EZ)LO0T$LSdMrM}|NFg`YjSXQ-EpPL4I zX^Tdtrh*UZ+6jfMUuW+Cj+Ep6<+DTv6~Dy}r%$_a4_k_RALBmMExdz2q6i#QVJEO; zdVB^x3mD1~B)|#lB7s#oKv1wzCp#`e%r-UtC8w`FWf%N2_|b%BT|?1vQc3FGOSEHM z?>DTk_-MQ#2Ee|=KVOP5*`9gcCB3+|^xWru%b9^j->P`mVn8WPJA;k%^t$bUE7GO>}d-c4K`?1}uJ?(@gjT1x+R^yze)uAf{eN_^Fr~2$T#GkPw;oMm;8XD@js$JIzhxoP$v2FGxTdG?pMP zciuDu)tDD8{{Flr&P2vqU; zw+{eV$BCi~!|gjGL5i7ebVmhvR0@2W?K0bWS2p;e@&4jRz&r|;2}I1uON{_}ny3In z@YV?P{lH_--lG-v_O**bIWQtw?~yhTdXrw07HO=dRwW8&s@C7uS$8Vl>yFL zSK*do+Nn0JmbW{z%c964JDwY;cH=MgoP$IH9x05_Sp%?x0?0W2Tp2t`?o4&vL&D-p zJ6f{k{1V{{1w8!*xO_JiMa!x48_N+KspwA}yV*e;5=Xols%2tFbsyW(3>BkuAiqW# zNOngvlgCd|?(2y3qkDbKM#E@1rVUWhJ%e(-0pe{pN=)^lbv~Ycr6~^^NE}U&b9YnQ zv@I;JPve<^Zs@lKk9FL0Tf;UUTl<@$`;21Zok^$Zg>I*-LYFAu4UcreztZ?gjh zWrcA^a5+csGYtO$>NJU4ID1gU2tNv{3R(iAg<{jW8hZDTK{dO9a6)xjv>)$SjSd|~ zO&e@OquF{>eQJl`rOEzXE97!n0NOJJOjetaPYE?u!!_F{%~j8;3EHKX zn&$f1S(W3U<6O?SOx`(HRgkZ-mloYF88!Q6YPk>2W<{06jPdwn)Cini3|3_!+MC%{dn#F9+YGJZT9Vda<*uw>HnVoUMXzuF^l9% zvqM?TyT&Mzt8mR)24g5|7FZ~J2MJwTEI_T9>W35why6T(h$Ps8sRofI9=zl=1c7l@ z%~l+Ww-tDWeRsI8dH0tLZ7QoDa$4Qf7nYXD-CrhdA>qD<*R*k|#Vc4dmTd*8t8aFx zb`>RPa6hfW25nF>1iFA&Mx(4%*hwZ17B3*JgOtq_ZN_mb{jU-VaF%UuvxPq z2~jEY%A7yDu3vd$hC>?{jev;app$j(mq7Ln*5{iYL~PsBg*$jE8>T8}(lU2+ZMwGA zTZQMjTi*3uoDCkBDB0aj)v#mEUQ9zM$QsTbZX0QfSKxP!=F8|tLKe^(BJtagUZ*6N z^4pMf3k=xs%8ml$Pes!p+MX+MWOvkMwj;yb8V~s*z>!;3(!eh|2?h{-v%%e@9;Hl2(vJKLRh*fn4;AbIel;fg!2Q z9mO4^nm)L`4GUy)QUXe?r5QR7u?Rx$LjyM_++LJ78(6V6WHIm@q2DT5mMowmT>{VR zXXgfN!V0!bI>RH1a6x=Kjp!=|il9K$_SVi__;N#^bcF^}WTj~2!40&s&xe@Tq zC1j73A#5<0-%_a4B;r7S1<2zyR|m+Qw?G3ex2h_jse&9RLL8Ux&>R+NombiMS{#Qx zYcu*1K?F!1!BFhi7$wKD49x1hixr+BuR7?G7jx0OyFYa+ zx}%@M!oJ7#Y`O#5l+Q(9BGJ=sqX~5YnI<-nrbOOyV39~Dxi=!(LWO#p6F-emrw%&b z{QeM1tZzeVFKm4n&r3y}VVb`j{c6CN%qhUpkpO}P;#Dm1`JjwGeT%Pb`%o$iuTW~Y zQpgE?IUAEo7VHWChwJ<%Ps50YB!aMgp6#yzn`xi>alh>NrC(-lhR*88P2@7KV>EAy zDZt^j21`1{=B_BMfORe7+$Bz9(aISj8#^1d$RiKpFK)Dy$h8!a?#gaWG$4VnsIOvW zemK*qdEFXd=|Y)%YjtpttfV5h`|=U5ido+UfH|o^wuBH zvlr^QWTjo4iCT$R@h@r|s}1?OolP&W)B0P>iXoj@44=6iPA%+XVL6{??bEyZ(v#UL z9g2&#EH7x(o{2ZkA0{14>KN{w#kq`TpQM#eqhpi9uZOU}+P8!<5eiAK6oK+3w=?-u z?Y_c5hf)+2w9JI&L zaB>UzqGwNU;cyn_B-?})56Iy>o>svG^+0-FGRU%`ieQ;#uS)}}`Nom=vc8UKABIGD zek#6UC|dN}JZ-R0m&B?A?;UWp{mioHLZK7Gw3q2Q2@jdg{)%?{eGmG6v>0P(sXgVE2J zP&7#rvWz+gJir>uF_PTw;G*YllKBs}}@#d78m@)^0%^Y|8cBRE7+ zzj!M7%CZW4ASop_0m5t!2v$OGwVr8EEp;velHyqMc(!nkkHUz1g7FwD`(MFg(m-Y5 z+o5f@TV5m>&_qdy4ot%83#C3EcJn1<1Vvgm&&uJ%puRslnl`OhM_@G!n|$XD+zM9m9c#?viz$&kSyVT$UF6%%@w!t8yApz}#KjI>hH&Q(@9%y#a$iI1+-h~}qT@k?fD zKX7~Xf{Uk|xCkKaX4xmi!>kWLXyd1XnhMWAYe&^9?+1EkGiciOz?w{X%j}k2i-f*0 z8`rnfr4}l~1>g_iD)KrU5z3Mjxx4dhcF<*PZ#|8GT=q!4Z}9 zph=$eI&Q_4M3g zITFw75LL77%TMlg2{9Y-?fL3q23O*5_qs@GFSg_XWw&(k#^y%Q*ygrj*U>9 zZZre&DSG=nV}A(peZ^9qH5d9Ol6?2>n?*z77w90;jK&-uP_86<%v^pTmhWOmM-M*!6rqmq?m)aNRmm3Y9uP1Qzk*{*TQ#;*uNjFE4hrhy zED9%08qbBO=MzTOAjkrPC822T)hSCJ!L!QD6zxV2j-KPB{AQ^c@=pDRUe9HMY(5S z6GUE*LF+<8k+n5jIRq1ETlR#vHF2NHygv6_RbRK8RMy9rLN0FM!GzT|Z&iTMn1BWy zd>)2_^*h~V1GsZ*)*td{#r0(u;l#D{R^vocQ?lGcV>J4=~M=CgkCqa3IOc9gLrh%60~!N#j8Qh(Oi{YKBz`=xcsxG zBDUMXGYeBBbKVMIdo(L2>?>V6M%td+l7~D}Nnj3i^%x3#t-VzG-Th6-~978z|mrR!P8MwCQvzsWxRRl+W0hJeF8I z0~);p1X9${TzDXhT8TXp&SX8|JL2KFVrao&!O-#o3gNQ+zAuyX^xo>q23Q^#&-cW= zs8gW<4ogli?TS@oQz=|`q#B}pj&ub-5#lZ*ntbclM_t)UeYUBt(3Wjh`@X%du_+GX zo&A{gV8#J@>g*yPHugdgfrMa~Nod9=&_f1})I@?TGUql4&rtT;aa&tRO>wCxIbr^p($|uL+|dl zfu}!ucTak1e+s4lHi`JxK#PCrzWs`}Kba)_WH9cNxcblj-9uOJ*ZODFbT|)-r2RE_ z_~{7TU;V;gy~*D)7yVeO;Q!ED{B7d(f9fsLQ&Rty1lA|I-*OHI(f7gyGM4g%qz5O$ ze&2bv!9yC@*`drqZ4VQKv8~T|btYG*Y~azlgtja-1dPZqo2xxrESkhVusk4sW`UD* z14GMpVL8I5S1P{pTuf2=4q)BhR0Wn*^YhDfbu^)6KuNkL%$5zTe)<8vcKg5X+T;soji~)K=dXJ3;kxm$XOiG~3iHO{&Pho_1MZoKai-P;O^Z%`}d_ z83|NY=A4%Xj!UxXE+Bym))Q0NnsX6kmGF7D8-e@?b}7LkWgokZ93X&3#f~~uODNfm zHOy~^&-S*q#lx>w(@DfN~cenIgRgF4LGB*c%ymWS~)Ti2dwrtSzQSl@p`oI_4tJN z60?UQk5qnAIrNR@F;0+@2|kYR#H(LQMEg`^gG5FF4n5iY{LrDn5Z7MBlq^pL8?eht z@cmU9hTe%n>xr^?nXCn3jDH?0aoUGzUXTtR4vd|~UW1nxRAUp4YWof0%&MMO*tLNk zWmf0oe39!Usfim&B_=OQy^h|y`Mz(4izS_}_p3dcP5^@Gs0Z@ykicWgrKTP3T4q$q z92R#oKf2w4MJeNX{)Zy`+c2XaMfgXggo5v%CHQ|Y4^L|gDIF^_8%r%6E1ZWBRF9=o z#=%^NLgFDC*h8W)4NDzUYaGV!bN+cA$a*-oQlk16evx{b9PA-LM2Yh)OBgFFB*hcV z?@#^#^RIMd6u&UPeFOX*^XV70UziW|*1ysDcg%-+=5LscPceT|Wd->_hs^`0)c@dF z*g*S%-^Wx4I1lp){s#9@zx|2rhq~_HNc_7fAFA8GV?MQnCv5+#D48C){Kmp}^*mIc zf5&{v_AgADe--6FFdwD_{tff-mLDqruSNL~Gkn0oq5g*`AC2ta;pl&9=8-!{ibu^n z+APkaRv$ng%@XG?+Mik{&7ajo^C){ril4;)dp{e(f+%d{*L*Ow&U+=ddmAxPXA!>KY0F2u8$Us^GMKdg_8Cu+%L9i z|9eqBq!alYiL`$fCGB@b|0MdCdcIdxKh^V)m*nr5-}LaqoPNXdeyZsRca>{NLgJ&Eg+bj>GiV=20C|IFFS5rYE{@HuD4g3IE?E z_mlcxGX1W>pE9L;e8W?M>Av0a2h2y||FIZ-uLpl&KA!ju^P7_YfcYr={|@t?f_-XF zKRNxAp1$+^X!4KTN#W4_qg2v=vzdRA_?Q9oArsEe7yP>@AD1EcO+EBaP3f0<=)Vi> z518MD{8N;V={SGK{C3M9==}E@=^vQ?;GO9y=1;2rf1-TkP6~(q5&x;SnVwqEKjHqx za2WpDJW}=>IOBf?r>6bxCjI5X;$^0W**q;b=>(bBOb*0wb;*VZ+$ z$5AGxrlfp$ii%2^gyg}!vDDG9HZU`Nt6{A}{Fa%TlIr0fB^@;-9W5op8%jDNN=hP< zCuxPBTE(|shZW8vQ$MVXN5fjf*i7%~1C&1=QKETp%joF7Df@r_`-buTX-G<(Z%03V z-_BA$I1Jy8zilaT=qUfYAN7O6zWpd45Fb)$JUT}V58f&LLz=U1zsLQD;K?`IzwLkf zJ-+qPk)?mQ!uYWFuGZ!tRnEJ`M(#9V$jkZLJ;Rt8!LVcaJA2ja zz$MoErI>4204j#&g_R=X>OZ*O2;w>>IUKWxzTXGSc6nP+u&cMjlvcUUiD_ftd zZWDt0aNG!b7zpFZScrjohqMB-%9H8uRi&@M_&XVi*GUO_HvQ*UP|KuTe!=GZo&Hq;gN3n0vk*ZjNG;TChL9^lK05ip^-xpDyNZ2XQnD-d?SBotTE?O z>h3&22EH_?Qv?!8Of&<cs9srH%`Y!Ytb-_K0WUl_+Sq*&*!lQJD=?@O5#caQ)h7Vir>&T%GwgCx==&1^`4 z+#?Nsf@|ox**o@SNVGfwFX4C+aW$I%Cg!H{1|kVK$qa-7vcP8;D#iQxX2#~oog+dz(V5IO<@q%^<&p}8;WHJ7UOq0xDrUTkXSN){8BJQ5 zg~fY9M>fvl;0@NZE(*bDyoy^cUlnPRwLWDLo!WsUU{Nb`b%a($FKpi{lYdHB<^fgE z&-0j_zd#*HLUjNd;cBV!AINH5t_Ag>jGj`I(7@U=VS*8rcwY=v5=guK+C9HUW*pj{ z&LrFfcq)(c@XM=ufDT37hH&tdV|1sXKAw_ZLFZ(o_2~6z&zZa60un}i_M3FX=&nNH z+LwoKPJ2VhyQ4clsA7}^LqL@Vm>3im8yE!S!^Xkm?S-h>>+@6Go9)pbRiCfMtsq#D z=3Pig1XD9sy_+C-1FR*c5lV%O0~Vjj%~Jr)jp%Xx48_vcIW@-a7y>&5!w%8x93l+z zi;W_D6~Gsn*35&cd+L^@T-x*Un%ZbyxBcZXF*b=3zdpu9) z)Gtn7=#NsO-aKFEV7Q06Lv z{8J>)!K#Wwd+AR2E$ppjZPnAiV3e8QOp4zu#)h47-AVkB(AVUB^TW2GWH{fEONP0#;q|nKU)$0(XuLStiffE@O5EN+K zQZa%gJBXq=Zu9}Qx=>BzMESsC)O#1S{5x1mPJVvP&h2_gTRP=6IIW^dmf(991#rbY zVrgy*POwW!n8{FrU9Wx1@JaJD;Sz6LcjCQrz`l*w{s3w11-2Ac2~8Ch9@JPSqf9UBRJ>D*gVJDafzOFxh7GU%Iu zf8;zlA?{x)`T^251Ew+d<*hY#u?uM@3kTvVEv^vH5(Fb%{R|YWgZ_;cyJOt#+hA6o z_3*SLy}hr>k(x3++heQ#`D@$*9ano~y}o4Er#Az52I!~n&y3(PzucM1_ma(48Z^;j zA%v{ZWmNY?GOFXzejGV|L1m|-WnOqRzP++KfxL`0FZJB%p(t4vb`8r~SsEqECuykm zOcCEhvG3A13kLf*%1yi!7cnt!<8H0g;9Z^bQe|`1(<%Y*Qnf#R6Pc-?#NJgk0Q-3~ zc|AlQzJd$UvCyN9-@NqlV}7wcVXCF^a82!nn^$b#vbAK?gp|sn;yeUKhsm|-&BK6F5IG-W{hJuUe%g>Z`k9oL+I<+QdGi*c`Y=!h z#hZ@nlxOBC4pnEPKm$sZRtboUg@KngB(JV8qzkn=)WJ@=J1_;@bC&M6^hoAmvD#>w z)e$xV%&_yIyj=#I{9u}DN32eVr7p{K)lY$6)pJ;?H9FIpqYTkx^;~m&VBe}$fiw-| zF+DyNaSs*|Gt9=;Hc7O9qjp5m9T*X^tvqoSp?09cM*)!7kv<_jB16_a7Te;xsXnJ< z1V_LI_H6y|0=un{atW{nwJSYHUm5xcm82e#SHztjEB8a0bhsnO1FyRZnlC>zvEK^ zE<1B_Cs_oF&K|-@yOpWPDCdej+1`f0^8g0AkLhH?%Iau*(geMDdulQ-4T6C}*xnN5 zIBL_7%DffVhxmktMu!W^0Abt{#~o9U5AqS!1SG+oprTBScf2r&=!;tj9D<5Q|V1`etq^sZWf=3Df#-0 zG%osn{v+LO!<)KGCls+msi+fVO|&pin!PX{Gc4Dj0Hjz$-|4h#`?uP6j9rfY(h|uyV*38VLZN<$5}Wx@P5n)QFztrs z&~y9ECbiBG%OqvlI_n0t!iO#d_kiI5t|-knBvBG|GusR1{AG5&E|VQ>2d^~L06x=f zEtHPP(5g8C4t1Vknm|<(7c6QquHMhlwy^5>_!ISg1v%<0qf=<0N+HhYUZBl?(^8|x zw@~L*%s>E?c*ybH>8vi z+-6@W1ZZ+Lbz-9K3Npq#zU}Z+h7(@xXIZFlxc!KB22nMb5a5snPn)o1!1Uur5 zI|wpQXmVU2VtFNl)Wl5j5xSO0e2G4(`}pIwH0jk*C2h6NJ{{YhTSS)Fn*M7iA?R9R zVU9QWNmnwbubyd?`y?<5VGD%@MH;qBME^h1-U7OcCSUg^36K!t?(XjH?(XhN+}+)X zD{&$2?!;Y*ySuyI9o}Jvcg~#i-E+Ui>eXG+wW>G0EBjy1ubxsWKb0Vh!dpiu4!=5u z#ul93RyWz<#;-_xHl5s$KI$_GW05VBErR!pY$Rp@u9j~QRG%Z&?=o#LW#Xp5!C-r( z4;A?E8j6pMxG0(-p#HwjE8|?c)tUdxw*1Q-`%#}>S%j^`OxdHc!WU8;+4Es0X32c^ zv^6e<$dvvb(Jy81+=~69CM5^b;H<`Jq;qT;zS<3FFc8lCkcMdX7P^Nges6?p^KCTc zM`iWqTq`F5+h`RVt-5$uUd#zuY-4xYY8NWCs^G0b3Oxm>lB5mJksD_a|K_W-!^*%vM#O(>t zp?&y(DR%Zwn?(V2+Es^Tix^nttY-hw2VUZIO=N_%taUA>CLj9S#@B}g+w9=oW#hN32sNh zMuh%RQAB@KBE5*$0jz>T`}*CgBN{}^=?thnw1X)MJ}Y)=&}qc$82bd9O_ozkqBEZU z#&{G;8n9hsW!Llh2Sq&>Eq74?P%d9^!dVGQ!{Z1GNJS89;E%P-vLhFseIG}WM))Rd z5IvY{1wf_7#>FyPLN1*@pF0B$sQM~tUEOQM`BHx#7t89m`w`@UXGunRz)vp>O`YJY zoaU7|$V}E>K@w&cnomA6xbdP>ygWiIav5tv)f^=tm`1~2I7J92AT}&bp(k(*wBwyE z!y=J#@-;ZK;=LEkJM*9$T=Ycs3wq&$?Vbf+mS9~+*L%xoD$rd!t^NdAaCPginL;GC zqlIMj>fQ?8;YAF5#lp*p3&MKgFHh@Zbk19zh~k!QbO+o5YL9jxoXWXCm8?GuFfzKeeEkxydF0`AQSe5Zjd%-Ux!0 z0*S-{!VgE_i|?h@G?88KvM5W@xpc;lMJ1m6ySl050H(f3ZDN}v8D&D~xxt`L>~7_= zkO{sC!S-+;=LkHbFuK*IF=k#LM`oF!v8 zXZDlM$!53gcYot5ayi_OSNj8`W^w}?1kSjjGx6v|jS4AYtc>Cf0!2TL$sPz~FNL3o zuizXL*C-iE#t#z>VQ#fbvJ-dB2G_9o!O_%$H>h6ovUcp-IFS)JkBm7vZisB*h)<^a zdir_=9!-}-BICeRiEpfchXg1wqnN?b{Cn^PXF?Aab~bmSMCJrP5wCo^OXV5S%0K)X z>#ac7QsUXtkbax!=5GJ7oj{8eLbPZvE}}eBT{53(ANiW)3>#TC^X&GU$up-X=sao! za3A$X#~!i0n~UDpBW&_Lng}Kdu?L&y5B0K2a>hDnf&ku%wVUKmuOo8e9axi3!5?#2)W2nJx&*PwK46WKN&JEA6;wq+L8!i;h zXEcf<*q2F>VGsGNY0?YB%(A~YXNrAh8J>05em1dje!X#};pJd(z+37eP=pggH9P={ zPvg-;`cf5Q%XVbbPb_kQAjw;vz02%b&C>*`0kYYO3Z1$FuW5{xrWR#EyJ|dp01{+& zNK9!RhRASvaC$kfJWf|RR@Z^Dk!sk?#d|fjYw1aL2pn5RkV&H?m-}7f`^WsO{Gywu zI{0FPl{Hi^g7G2gN{|`ayPhC%m<${~Z5L&8eN9FEp&rqJF&@@O4fyi&PodbGIj7fp zHEZFSX;L`+&P0Xsg?U|cH~egzv&6I_?c@_&Ayk8;{&+e~Vb{V2&Zv}DVHDdZGkb(8 z-rAkjCuKbH2D@2(3pT# zkQ165H@pZO zQmOVvq`0%BJe(woY?JDpc`=!J^Ap<5prfC#L7Y{bwwcb2nvugEzPluty8VDUJqjb8 zs)%qtc|bEnQ{b1zLsSeKpjHb(>Yq7ZSA2=IrusS)=ai>f5%1I8ge5@vdDh{TE0e0Q$YB+>n* zh>XG(r?_at-(4CuGmSfJ(o#4t*1Cv%tQDH-AkBa0LD@Dp%}QYr5ZHZjHke7L&C+`m z26nN0=ylD$U%gn#YV16#bX zu^^U5)a!buttfQ@tCA$BP0}`D+$Km{AE0H3I**H3UF}xXLkLY_Z zI5>U&$2jAOxUk!Ca=HoW^iA|v@9kVnOv)BvefLckZ3%zk>Es)@(x@+Zk%1t|$?CBo zcWMAjX*-5Q2HkHr{mDX5&Q@ANmPVFFTKOK)Tx0L{CB#B;Rg2_uz{19xN~-WrU>m(z?r>XQEu zYqaz15H5WX(IBIeBA>ut)l@2AC&L6Q*yR~9liaL0t7@|Qv<1h~SF!r_5)^Lx;W*@` zZc|a9AaU$0Jsj8gq^n#{8#eVK)K=`%3j*oe=_wP01maGTh4L>r0n+z*jZBddw$45ufVTkytn-!U( z&F5B(%QmhzE{N^b3JaTDEmex6=a#LZ)~+(H^I30to`D4PP9!&q7i_y0`8u4KJsL|T zc|_h0pxB~qCc>M3z7%6IO%46ILYKz>{g5FYbxd!bUR(2{Cd5IeG*&sOIjB)C)sZG@ z!qi%c}05edNopXID}<9I-6v4@8bG@a6ZP4PJbs zE*elgZRYVPdhFUfA?IqH&p3L`8XVHU~S^o#v>)G^kHO>XA4+juV|Aa z+c<5ui4r4NTJS3AfC6Im^xXzdPEbNU@WiN%w2_c^QAF`a>`|_}op=ed?b(n)@Lefk z^QN--5D22|gYhpG*ZVJ=^fA-3qu} z^%B_(-IuMi8Mye*rQBRm`Q>te9>CR}EB7SrF*V_hGaG@w(U6l9QnIsy96@G|{Y0e64xP)M zbNAgjT;ix7)X`p?=;O-4jTyZQMFG=);zLZI)B&R}G}}0kH>*WXB4`;VU`W{7g)0;s z?a>)6B77+{p<^&o0JeMWnus#ACd>D*LeA%kBN_a8J>Gv+%LFM-%_DAoYzqZO3pt5PPfSi72D|Kx zoqSQU%1L2oj#1kf_q9xVc!*itqRtM+=4d=GCEBjOiv&FG_MqTDhbI zjHUewGdxvfk{5(C$siYy0XkOxz8e=@F`L{XWS|$|CH_5Isd(g%bpb(Y+5&Azx+vX= zL6GaJ{qh&6DN+kn7j+nJpS8;J)vLrH-gm~v>gRM#LJoXdaE?&SMiJS22cIO_n}C5g zDC zT(RiMJ5|!ssa4aS7?lvy>2BPg#aWSfeiVm&T2g#$BCqs84DxG&MZeS#aQ{c5pE4>0 zemD7L)yoi}g%7KkYbv%@?%HVv&g;-x4=*o)8_-(PIDQ9SPTp=^9QFyygD;9L*dERa zbrJPdSV~)#h+?yGqujUJQw4P#x6W$fvb-S^3?2_4`nsyR>sP2GRx@580+_F<|CR0j z6H@sFln4PxU2y8Zsnq~j#Y)lARNu}K>Xu+u^bbntnGlEm|>Dn2-HA^j`B%;bEOfF?=q32*HXJsK}#VSE5XK3sIxE)X~ zU}&drYiez81!#ljFZ2cglK)dpf6MtBtn&AJ0C4*-cQz?~PqIlE}c zE3e!}h@8mADQ#F}nZ>9fmnd17o7Y-86q1KFe?KDl`tB0}5U@YN(OMK|3Gb(vcY{R1 zz}ZNLGqUVdwQ9yq62~<^&5WDolI`}_J<@kIzSCc}oL(mHUb?)l#cZWLKE5QJTCoau zhhvQd3uGfZmd#f>BQ-Q3B z(3Jqq)#2oc+1<%g=G$tmO)+cJVlgeHN|ltA7QGVuO1unMT$G zxzRwp+BXiPtuPLa;t&~B1+@szvM0<|4u!HPdH>=)ad7sC!9FXuvuEev zl1<~R9VptXmMKntgIzd#-T!JR4DOtgc=%?XZdw z$0Y>4&$%AKut1=Gx_-KG3o7=`2O~K8c$bjmUI}9(8hTW1Bcw|@`c#*I!Q{SSV=Y51 zVK`)qyUFszW9EGxX?55#iX?$@4$%=+%=gh8>MSt7GSTj*M<-fQGe< zu&Whtc1iLh@0A#obKwz#u_9a@6yg^zEpaVRBeZDPtgoU@$ZpvxRWt^xz5qXhfb)2v zRl7;dCuQ`OVYm%RenkO4x>oriqNeQ*t%pi7z%E$W=+-zWA0 zc@okvk$_5#zpDyXpMq}}jisLU#UN`QYB@M#cytVGFbw!A8^x3Kq=H!y+w%Jt5Q6*d z?^Aj)ojxEgpcl3!_evF+d%gZ;Wkkw-J++tyarT5?q?LpMgHmsH+XL%9XcOG_z{FTC zXGj9slJbPqqDA6MyL+8U2JIm@I&~$2GFy9^S?CGOrCtJufWkoSG;6W9K1~;;pS9oR z7&$J|YU=B0AH~;zdKbJ)n0cCe;`J!6KKDB*ussta`yN8EURJ|6>-4SRbq(R>9S1Dd zUfas8=-Tnu6V=4%gx2r&`v-oJ4?l-L(4hu1SOhwX%T-W$inCk{I}&Wpww|@1$9xSl zzzmwWu5J%{+%r;nO?X$!#zR&J&4IRzPw68^Ldg^JHQSeuLy6ou`^?3uw+3OW^<#)yUYb*FA|wi7`M zuoW)c4Q6tP2hAu>*FHb2yta{rl?~o9s#De=d(otKhVwv-FE50as?4LpR-{M?DwQ7CLHa1_kW@Fgdcm}T#h_E3mIEY z^x#7=eRm`t8X6ufB4?_cX=F1LKe}_9g}e|RgkKD2p+>_~VIzFC!YQ7^HvmD0je7S1 zSZqP{rPo;N4kf)3IE+wRYXehb_H+U5<2y}GtTxe)hdJ3h-Ps5?pC#1?X%Svb37*p5kGz)mJhjZKBe#7#>X66R^n_{eZ?DNSuwF z#q=54d)c|o7x&N=?1(fKshIT1=&^h%hN3>|m>LkjBOHi&a{sb<$7ogkGSn|{ar5A! zzH& z>LgT~$jc?p0k4^PWY_$-(V_y&0vc+CijhY{@owVl%-n%9PxN`ycg@7?w%)L_B&gfjz?)0|ppuffW}X z#Q06)_Gj|EnY(x|96eJ8g00>Z_VZzCt}gmWycnrSyIFL{ud@Rx;zwG^Kr!T#hjI&( z+<`&Xc~^R>A*D6>4FC_1uGtMzJTA{ON=p+TmZZHU&5b7W(T7WK>xQHwY_^>j5sL4# zY%J%&%Jf*$Lb{P?xcFRieh&wl?oo?I3`v^~Xr-b+ohA>7=9TYU zT%2#-oWNT{dbBD zp_rg*u#F0nJbJVh-ot5Kc4p!9M>X(Wa`h%^Xt!aXEa+F^*zd4oSy-v3GkQA}OEz8C zK||cjZm*}_gkbIT(9Q6y$!A5>$$Y(@PfSRn&6$LwAbdMUm;zjcb{;lRC3XB|d=dq_Mvt6U5=rYlRwbv z>D=vE=6W8G(aEx4i!90>Zjbv~ZG0O%OceRtKmLa3WlWXC-u%(2o=q}T@+L_7wfyH28pc^$%MF%fB&E}q% zhZNBkwrn_V%mMoo&OyOYTVFT^C49k6s)KlMw-I?@adKpf%SnMk_SM~y81>p#rDJ0) z&aaiOP3MZ%?b@c0U`NTkpPVkKXeP$^0)}zk+0|Mibq_*olZgd$Z2jpu``Rr6EsRb5 z^P#SMkP(j^)iKi(PlzLARJQ$oQ2G{@ptOKrlRm4hu3Z`n<)9fO-^Zj-c(SK&k7TzK zgEdjZcy^*-pStJ=ATX#N!Kkn~R_9&sDsoOK&>U;Z{JbWmFwZzCbrGHOa@QWMSixop zEk+86_Rl1d`qoTqxC1w7@cQ6Iio!ME#EA~)%;z15zz~i+t9{I^6)+Q50&k~}PnnL3 zR6l*zm6}AK;4SL#2!!Y$fJ?Z{;u0grA`B%B*}URo%v~iJ7;_ zZQN|*->igDO(lw6_(|bJL=(y+r?N>n&`yQI7amseeU{LZMa!H(H*B;&DbHNDqhcbo z$T=TNj_m~AS~hA(XU}U!LBq>a0q_Z9Wv(5{?EB`|56VG78b>V~TVyOz)@YCNo&{Bb zz71#fY&LYT!h$33f%rF8RW;AkuYfe9Ohed8io=WN{nPZuI@$CWGo4bu!U>EE@iDCs4ky4KqynQ~>OH4#D*U>?-$ZWfj zf{nkgj%@uVZ4~5o>>sV z=vO~P(}YU2QV`$~G4q$wTOh`be3acGK0BEgwUgy%a_`TfHwJm?=jFb?Nh&3$|JtqH zw`$1grOByxKuvsa#4%=JP5a7h`8_V+*fc@cuid^`a17LRf;dnTTYD+kLMi@eEu8B+NEo zL(pjqEQg5j0(HLUev%(>Gf@e7I2d;EAFac`5NrpsnG8Pjpf)5a{p6gBq_%dJ<8_lg z%^Fj4^%52)58ru8pAln26nP-ItTLC=g+$ASx}+yQ9vk($axa#tZ?~-!C!-r&*C&|o zDu}RTQTcfzs7~{(N+(tj)@q!%uv)20gcV)Xjsn5}{oHn-wNnQ<5n^ZZ$_y^JxrKVR zu_#qjIK`|v3tD&PmTdkG;aN&5;*%0&PPv4%Hd({PqSt%aQ&T+~mitzAC`9oa2#c-u z-OQRfEd@0-S@jLzt4w->A_%4wylnVQc?H!WXc?i5oJfzXp1re!yztR{kPh{h=viA9 zri78uv0;fU7Yj;&z0g4GbL~VPc*;WTs+v%X!P!Fx(NX2GYt3y2|F?6%{LKlZ8qqR1 z5LHid!)Q%ioVp1AT5!X(A$j=+bcG$vQMS~{iDg|zaW|$*y1{cq4>d@k8ysM4mOjS(ZU+@_U!g6B{sf>P&y%Ym@ z!6ir0K(gP}mTFOPfVk1)}kW1TuJyIq?)tm#snpzZ88lhRdwUrTE)mA!=--rg{f)e-b=Z{ zOS4VmR&U&`IET365x1EAL~tK{)YjkAL!f%)tp}glWN5v=H6VQ$(2-wzF}2!f{w;ga zK29yzxM^La^Geh8yfFL%0!)}+x@eADiv`h<;+o=4CnHFDuT!w;h}I_d7{oA?4%hwkT~?rw0c*mz^*Jv}n)Gu#EU+zt5D3ClJMMxLH2f zZa!oZ9{b{m38E5rKFREg$7GFijy*fe9UqaBi`NM@tYS?#-8c(4!W+|-@&d!1%67g2E3 zfzn$Aw!8gyC0nrY8pV{51xC&k8r;Gki_9GSZYtVFmojPys5F3@agSs!7(rs(t(N1m zW_VE+T$KY_&o;QBpRUta3->1>H|k>tQ=*u#PZF*%_du0Ro4bT@`DSx~+j30p%p-a6_8C!ceM6laM!@oTh=ejv-ZW{HR z@An9rb?~WS7CvELvi9d$zyvlOqAMigH>B`4GJ0<)Q*X$wY8cW3^$m<&g@mg3I|=vF zT8Y`aX&V~L=J2hGOooD@^p$Xg3%} zY)HPVbY@NB!7)LnL6Jt|%+b_B)8RvmyOOqB#Su>CrejxvZcvcwh#1h2gcI`AT=)?c ztRprTOH1ug*)8@8nprK0e<`XIQ}(#p2Tm~LsBR;45{PEzUabgQOJ7MCl!7_mbXz|& z_g!X-N9$>Mi|WBCTzi#8uP(@it`|s7ywJ(w_pVR*Kajwt$({qEsY?U2$>N%lufRmZ zOlYx(U_(w7=#pEmOwc^B?4mMc0=B9%V5F2_x-^Rxc~|i4Nb8?sS8^nEud{r}fvZJL zJhJ7Z_(yi{E0GHko%Y48^t1;SyehN#D)dM)Txsd`u{kwca{D4ma_iEUHR3kB55d~| z(^pnaPVzYIuL`71;^Ru41%_(51<>^B@CI^!@IVa?nim&g2B8;0fuLDiW;r~nmcBA2 zqcK3{Q!$hT%b)%TTiq?FcdeEGu$o)8_$D{M8(!9PKLe(8_RH;xSE5Ok)=^Ig06OsYcT$ zz`j>k-Zx0lwM+l3(?)w2+VFh%9h1xS_(|O&J0H8^suJB(1RBcO6*$#maI}(#DHl0E z;X65GPtC@d_G!J$$3yA&FDSP7b*i8fBzR0*B26EGAK}{h)T;Uk%Sxyz$%Ei3ww1S- zR7X`)fjr!<2bt;aNV5BGw-)f#kZW@4jFb~=U{gwh;16TTVvjq2^!RM!Kbe=0>n@)W znyr#M7fQ9_PAQfxA;ht z?~};Z%Jmd6E%Y=ud_DKA2RlKNG>4PA;p;1tzPF;G?^VWV2MiJ}h(Mz$@) zUC_bp>73D~LoijD{vOXqC)Bwh3|xt$*{ehdLBY~Uz%;2JaoWi~U+IiUj)-XqGC5Os zcB(qu+rK{tauZB0u7LUSp$>S9K+v@gx16DzA*UkK%g6!+OL)|oIrJP@OKaA=x)$Mn zywFVGX3diKhM={9zMc*qLWh=IKOqT^4xX~;3f@IA#3{zoh>@RlS}D#RQFg$H(~YBk zjc55mF6UOQO2dmXhpU*XpjX&!XaW4EeQIfAlI7I?d~e#uQU3LulSxUvd^qu1F?V$F z38WrJREE}~X*FZQUHFm17d-E3{bs&P{ z)*T6uL^OcFA*Z@pQb=CUQPt8^%jRm}4hvjEQGVejbvvRlk2O+-Bl^9wd7RBbc+K%C zK_1B^sd^%K{gJ7m4yfDaK$(1ipkZCr1=|R(rm2u$(+@Bt01Vy-#$Fw;C2KH=z0E8sb1C8s)O1k|i(P&1(R!^-Q%3*KI;15I4hYmL)IS)BKs z3CNv+!NQ=S%)5XOf*%M!5Xyu{?qQM{YP8^0sC&pRKnWKe93G-$EMu;&t3HLTfJ!SV z)F6E7f~vVFmoaV)K(i9jj1pkGE0Qeg^{aIivX#$ue&y9d(4 zy11S>hnt}v=nP^zvkX#cYOsB{f5l+Vx1dOHt5HNsR7{9K59-6Jn8w$T7Iwf`u#(J}yZxBpIUqX(GE{H3-r(fpg*_G?A_ zA8Olw|B!z^%%3aK|HpN=^t7~p(|0tZCC$5NAOcTc5V;(~Vc8|8p!fjW#(*8=P*9>b zH`YylK?G&R)4C{qIF?8=++FHmrp zT+X&0(n5(*DF4wCf@N}Xt%)s_5fuTi_Nh3f(94Al^OmCke8Gf6>Z6Hk*r5e|1k{6C zJqRT@pXtT=VdSWkeVtMlDwd2}J@}UbYJ10`luQO?ea|e=V-kEr)Ior`7Y0JOkVple zwl_j}e9hdcII!BY+oq}nYyE|=ikv}meLm@s_*kPclQur}PV{cS_|+N0HOJ=%BL2vi zV_+9lhpXMg4#bB<3OfFsiE6&cmjhH6#OrUnl30(ToTo@WtkBqv4&mBA5SN&7%4Z(3 z{5b<`HVxPyZxvHIb(C1Vw8*0-|Lc2COY>$D@b)^Xzb)YhD1pCRIDV^)e?K$+vX6Po zV+KgCe=qx2is6@003#hOIKwZc5uiZ+l8k@XU}OL&lfUe^e&;Z;0Cd7%W;DNZ{+sjP zw8{Ub&VSpl|5*PYE&kQ#|5)RH*WN!C@Be#C%(V1>sGNUVMf|T+PC9z}zpI=PiY^-P zPDmN+Nl#{^N|Oz9_!3U)hdu}vny&M%xN~xua=9c}J`z8^#tsWm0r3i~5qgJ$27Q8q zR{}F;-LfvNLtJ$A`eIRfSf_M5by8HkSlccd^n4`srFohAHY0K1^l{~}?RMueRTz$! z_q}LLR7`vYKbn)oDwjG|XOlVw9S~8O4%* zR_&c|M#2`LYeI@$s(TI5NiVZB z7Bs6UGtpU-ItvKAPlG!fmZSX8m&W58Y3_H*7OPa@9LU^$r)xJGV?8iVH&U9%Z0aMd z(vL3awqae3Ri7EL>?FSkMU;^>^Fa(~K9LRkx*#L#8=Nd26g|KkiQ7twn~zIA~&wk^Y%E1wz;4>wRWTr*Wq z1DITQyBwrO? zX}^qKzj|YONI;K>`&oH)1%z~Ske^Kh99N}h9BVqKN{!PCEx{|t0f+^&J)TuTv-Ug) zXx$YZNKx;FpErk8(Ba%=kQciZVk`>Kg3+cm(GT4XkWl(h-zqC$Mn;396bIWwH6K4D z2)-kN^146{V%UAo?%9V=%iSf)|48FN596dnayFe{Weu}N48#pp`Sk77GyIio(h9pQN-I_}i z{y9z8yPXZZm7?+*g}%%f5W42R6@}S`f~oB%5a$lry?*<=#vCW=`A0ry#d#!6PqUT9 z#qf^oa3zmj@7*YEvaB52k}LWaUKLm@vZv)$ySZImPL_8=+)|u=yYBeyA?5+D0Vqo6 zOBgWNAI_8AvLU7rMYcwDqyh_O#b&o~JKFi3AAl*`gh;t>7gGEiVc*Hb5x0OpKPMl&ji5A+#D4UXMpNV<^hP zUNhxz+kcqQC5MIwhIxd zJ!G{vmTwN9w_(5ICL$GZV&3O>IBlAN^gfFlAPqH(Ci7TsXyPf~r2P7sO?e%6(=D%{ zh&Esax=P=6b^j)ZGN`4@&l;vhBP@&4VpXhJBwJ>6G6tV7FczaFXm@Sjd9;;Bw^Al| zkCI)+6~~HX=oy>?)GCf>%Us-LXh%aND9vYsyo{cmO&8lxnz?@A4Df3_AZXi?YC~Sr}Z=CpjRBVuyakmn&_ClvMk`pfkZDHGg><(2k-1%N@|-aomK>IDfN<1zEDr%qw)OpLTIk1#R;{ ziHeLlF`u(xJOf=lMGRVOfzq7=I?a2)vrqJi9o~0!r!EA*CUdLR#o5jE$GZG_7YK0PiMY&$;npPYB;((Zm{hZ zF@MzEi7@*!6r$74v=!+0ST6WBhYbacttpX3-A1cY;CeZgk3n|{$+z`gVV$vFIo9X7 zN+oIG5H|z4$C>9=L5ZF#P|74NP_Oa}P@liWUF2~}W4}7}gV21y>aLA?0!`vfhW@X= zcK`h0^?w)T{W81y1F3xb+50!760lFuzrs8^z*gS>3iDLdL}e6}$>r^JEe&*S4dh)c zB>roF2k^yyYw?em=vU7FWq=0=)&3FQ0j_=rcYw?P7}@zkGaV1WvN zM*lsqd;8Gd9vMJZ{=z8#(_{VF{og)YZ=SyYV@O8_Km!3c{u9~Ll#w*|r-5nRRUWnx zClx|=h0|3gukG<{oV1e=LjNurJn#3~Mik9?^>uw@Yh<%kbTHp6&i<>r$_TqXjTj*X z)q@%95ARq7f)O5(lN%}pE_(i$D#M+K5wL;V!(F>qTkSfF*vX(5xq>Jh>+rZCGnlGY zt0GHHjL`@*#w}JLkv68Do_Rzl;w;dX%W5a`aWTfuEb3;O{j%PtjqpJrLP6NA$-NMB zpDGuSR#cU3dHm`#~6&&^AboLE+CHe4IFMw(2ZjyAKcY3Z{QOdqKr#(-m^^a)R!w$tQ)hrCg@O#4K%JeZ7n~DL%A3 zJ=rixnq-i)6mnY44Y6an6GMKf(Y|w=uQ8>c^CXti*Y0shb{i1D!eXVqWPRXBvsLQV z(J7?{eh2X-{rNwowO`VCOOegFSC$o}h|zro;d0Qm3uDOP~(;O`-flJ+h2 z=O{)=%Rof~$oq>3X9i5C{WV9${Etrkg@gkvnPnT z{v5=9f5z&6G1UJa&;P%s0TlG#DDXEb`Y#UrKehN5S^ck)H*)*e@rM~8ApK7U{H^|9 z_IPjP^&5@-MtA=r#Q}HzKL4h(f2ZHf8{fw4KmGw`MSj%+@Z-P8?|+=%Mx)>PzelIH z^0(_hneN|pesSLb_8U^Ha)F9 zgpL^OHeZP6St_TPQmy36s!w&bPi~i$otsSpmxPz_2)_Yfvjj>#R_VcgvFB9LQrgu(rV9FfT&uTU=018&N+WSU!SsF^%FNv*CDR?3-(t%&GkF4+jv>FsYXsBp`rZwM z5G1zso`spE9m@I3VD~_IgjTcJbCS(w@7PFm@ntS*^F@!m(Qp#(N+HtgWr%aS0PaXX zQWOF62RPM84)K_8+_Eidc(A*tF~L)LbRo_sp<5AQ3DgKtS`F@{&RGQNF^PEa#N9NEKoDafjDY4&(MiO@n$caLY$-7DQ0yJXC2&qNEwoUL)4ey)%Y0f+2XG;eH&@^c*zN|Md5Cjr^ffBlV1W@wB?epXRGD$q+-do zst_0_#3N&NMIR+)$a3dV+s(15M`I0gxAF!ELSO7QzdxO1+(By<^l#HSyf(8w%e~G} zk0^^6?8AFSb-rpVU>Qay<;sfHB^ksx7qX;_RmE}GaD2-xe64>cXtM`2Z8CZXL|-@$ zlE~HOBL*v@fW-LKH4RMyGAmGSOpaQPT9#TK|9kW_i5UZ9AewkY4v`Feq3E=M8Td6g zW4vp;Yeb4rtJFv)z@@LyW!l{gsP?OCqM86@eu9j6q2aWx*@t+E(p)9k;zGu0H8afG zbbvEoE|Y9(;r@9pMu+GY#a080X4)-_HiWaKH*9Ba9j7&#m0GEYL4DAwuANPm()tj@+QfiF1WwTr@8G782OJf?a20s3Ww7}WBt zjUR%1XVHEz+SFMS2}^&jEV_{Xr|XAtHaD9PFn6qsF>Q=11iy?jS>ey%HD-oFZYQwo z%xCLfm;ysweAx6RaP`BdHK85r<3&5i9q{0*zV2+zYCkEC0weS7oN5TemyPNh(^#AB zK11*<9(lHd`5x~TKJVq}__bH%4yg|#2y^ge2QV+4*m-wZ*nW17-GXWqhho4QvT#wE z$22cJH4DLd*F^M%KBQyckrjifc<3V$8+FmVJa)tk_S{4ZUjy0g7un;uh)nHm zHG24<%yQR^C>toxB=7u<#;5QMNaeM1?~jZ*iBZ}9b<&HjWm>b!ba$vvcY%VW)Z0{y zRDMot#}}%#pUE5*2HB7%UO9jUxFt+_PcJ57gW2w1V7pD5lsrFJcDf8b3L-PkI$$nx zk=M|>87qzY%X+)WaaiQAxY;NTUJzcvaPM56USj}Y(7ltEndN!0cnz==?@Bd!)vbE( zPh0mF*UcL#<0<4AHP8WfEJ5lu46p-@{Nc2t8D1O4+uMUxhnFb}Xg4)AJ4^;4!4x9;ASO?ZSx4)%Z$UK_8P}-a9-h=`iyLY|2ArR>%H9;4NK)@KL_QiN*3~4RLLxbUi ztd~$!SmsoPv}$pYe0+I%E2;&Rm3g+yD)VvS(&yzX=u0WxHkd@y#>C@zq<)}p_+v#K z{ErFr2k}aaX7D4AFpU!qFN!RC!KzRu2lZWQX!6y_>$s$YgF?7*iP*)D6z&8v$XueA zR35(BPdpYbI^5$K4r0b(I`MjsPyq_H^K2jXa9d-ih37KZSZ2rdKeg&9{Wuj!h5y`u zR639k{28U?!;6Jsp^rpNlw1pvRga4^a5hZHkE_p5bLZrevuo@ujdcj}0RuGnlT9pGL2m`Hni(tp|`vF0~k-Eu*_s} zK0*4o*RQbNZjM}c`uQ-)`vtT zp+!r7NSIlVl)xB_a|9UNb2nj4jZbUsmPC@q*>i6{cxFVbJ&H6>)D4xL%$BJdR`%9b z_lPD=Fj$xj#VjphlJPbfWtk$47bE7m3CJkT$iL#aH{`a~m}eCK)P#EEl&qtRT|Hs+ z`^Z4ms)<@nKN~HjNs(++C+P?V@pXS?yDcy@iN`|qoHcVI&f@_QZ@k&TQZgcJUs~j* z&rzxz$1+KCsMUd|D3ve`-Q7< zUH{(0`5m_6Dyuz4sSe)m|6%Pdz^eL|{&A5;>Fx$;4(D)aP>}BKlvsZlt@V zkq!YtIs_%8q*L;L@O$+N_}=%u|L4c^?8kk^wbx#2@3m)U&3tBtVp%nG4WVS5CZ?gi z#K6==L@FIFn@N;QlWW2ZfcHisSf7w9SYQQ*K*rv9)vn|0U@kKC!>fre^vN;rEMG0b zJvg5!Ot$+V*4pfXrrgQdM1CI~j_KH^npcNVINZZxPK7t6ReKg_>bcw-upZj!gJ3;G zb12Gj7TMwTEtV&$io)=rAP|O++-8Tso-Hr50gteHL%F_FMd1f>WES2USm% z&)));)yeDEnvb>i+2I8``o3 zEY_C}ejXX?-d5L*@I%jT)zUn!-OO=yR_0y%=JSl##)d3wN*jxob-_dCo!&7cWXP6@Q` zHfB0*|NSCNqfjkITl;>=IGdUD>Y6=x|^7~xy`Gmg2I-!Gz zj8vDBFaQ z&=;rUl0g`)x-#hi-0ifpbA^fS#{%op+9{?s4+5R861_z*qIhkJS%sK`HDA6Ue9^dF zJU{gwTU=m5N!6m4;6Y37zgL;`BZbnD;X(ajCXq$0W#f^CC3C;%Pi(2d)p@s5+AEG zhjq`xa-iJ&MLvd~u`r@FLn%5p16-E;40+?z?*TP%QpL?4<*^fkrC+pLy1HBChp!c^ z(SJq-nAQ-3wLT>SoZ8fDhixm|WtD3)GlW#TigfBKZJBq=(oa$f4!<%{gQM7(@1^h8 z_DnZ~Urp`CEDGK=8bZrW2(4Y9AXpCV+O4n^4p4^X@Tvl$`C`;{01xQU*g}|3B&k+>= z+MK|uIID^3bIWTCVOw^ut2Z{e9u_6uiw7~jXQdB#GL&`S<_$a$ZwfvALEd#)_IiYe zbIvKTj_$cZ%pxdrI@8og(pz_{aH2%f6n9D-pCp9JjF-C^`n+ z+K3xezox_+;gmDX`YDlo&lvctC92)7q$^TXXtxjYW_GZEr<~19m zj3-Mcs?>=6>zTe{zwHCCP$bUl_cpA(rf(9QAlS;Uk!Pkb&kUeGdFB&H&11| zkeP|qnOyZD>gDy2^MB17@Au8@-aq7gG^7hst3j%{>YsXx7(z2$R2>8h_fGU4ur z=SZn9y9aqIPfK=aX1R9e;6Z~T(I@UL%}y&+>Q5P}eo#bU8~0RvauFXb#g0hG!_FNq zORLFf(?B6PglgDn_wzLDz6{{0wy9TWbeBd#co_SoMRntzdNK5sM)7|3*;1gtZu_ei z;>VI_sun05L$N`0*1*J1uF?G;zG5^~d+j?#t=4|mqb?sFA6Hf#bI#$g!m#!M8Fj@L zfyTy*><*}`J@)6-LrF%{oz57{1N{eU=7krTw=Ult&liOex9bi%`FyrO>?w4PlUR`a z@aCPkg^q5L6F&!+a`AoGRiS|O%;C`93l+E4YAb=a`p0t(EPf10sIN=sbz%u$O4L`B zkTV|m;CgID6t-#K2W`jMTsH$S?~4ka>02~|GLk&fcpBJZ|87zc>;&)le(wX zi?pS*WE>3;7TBEm*)*~acDjp-ZPDET+#)3ReJ7z6hNfY*_8Bw3Ai?VXj~T_6;K`6+ z*G>|fasjlxQ}U;5z^JrRc?Rd|6%y>Zz|eOM!%C+*EOB{|Y$S?&bY+S}N7xFg^;*^a zdZRDX?;%Z(T$-b9aD&c&A&;x=Mmk)DMSR7dk(EzL7(^Gv zsYUm`Pjc*6v^vD92dUJ(D16&v=BTb^47Y!(6r5)JI>QCEM!1H9v9u4Zim901GQiq2 zPr$xZ;2uEcI0Z&2C}3|uWY45Wif%L?5qZkjFTkhS-m8Cc|AbEm6y9_}iu6pys9-TB0;#W%+@afm0)Ftt|?z(vf34@*Fd zSjHzOQ4_r&ruWfFssDLMlX6xw&mKW`o1mOJcD-~04+qP8=ye;_)If7L-4{(twM5@o z68%KA$b@1>8m8sG#Ft>2ZbTEbsiYu;{fGv#vUmlIWX(VB=1bF?c zAgoumS<_Rqi2ra~@&e8T9U!TYVTDWbG9VGPWy2x zM{@u*e16tzOYZ~usz6<03I^rKD&rfU#`&GC zO4p@X`AYLJfY_SNHA{)cYWU4)gbGd*VS{pMsr_gqq61Z8(A-nSZR_m>T8)QEK-EFZ z%i!IZd$oMlrSF%;m!ywtq5K+om^o7Oq@JQ1G-C)a0H>to0%P%3Pp=y6oe^mkE@7>Z2*5KCJ*M$? z5Mk(;Ikk?-r^KgSlUdBIs(483-Nfj3O5y1!ol_j*uY0MX~VmoqPO7Tvv@4YoSnt9B0pNMdmbop(^&&X{eWlLRGfFATKN z(cf|3_p7>pZ;aG4L(dw_}4m?oO6{KQXE!q5K>Jg*6|0UKEv2TsjtVYN+#9M-SZW z=7R$Yhs574gN^B&PVbYOLI==WO%7dIxo=P;v)a@!Mwe&eTIL?SQ)=;^cxdQtrtinD}8ChiyQSp72S}DJaS*G#8x1&L?#$;@c!nCO8<1#L3JJu%)dl_$$bZLW{_W98=Gyu-WbfbF5v81h$pW zY~73guwz=%=-tfMtuGoCIbl#U(;slo=-Z385?NN=i){}-+uWG;N;G3{CndZ+i}-Pm zx;e``IPHuR7UB0*)J7hGCpNjjTuREj&x01oO{U{Y%yAd802HDg~BSoV|F~$Of^#~b< zZ+B)L7~r@p(t>W9E%LU%kjWCK3DuO7AoNky8aKi80s2(2=H7bcUNv_%nj`r$DP60F ziQ?J0IW6qSE$M=wx9(*G17zBtTAdn*zuc?jX|EYHblFG|wxfatTDTdEP`q zh+mM`kd>B$B<{bHEbQ80`xhVaKOmYv-K&4X{(lemfAA4Q>TUh@5#LN0b~}cF3Bb+_ z32XS5ix}e4{+o*!04b8k#0II^cnx*An>FlrwfSFgm;XH3KPUAIN&mkBUw{Dc4S%I} zq`XBND_ZybKHb(ZKqNX(IRk5&JA;)+9lNGGQA=B2T1bQR{K%qY!50;=rQ!T4Zi%^P z&&oOx%Exy@DHwY6)iBE0);d-jKFce8K_BZ;+t;S5Rz~U(n+%#tOoBV|L?H`j>@#r! zJ}oKXJm@}MZc#)wI8WvlJv8S|p=M@BiJziFBQ$q~Tzs)+m2`CJ!c9AKB+!1w%*ta# zZPZs-?KPQ+?_J56V{hOVy$(96QCOvSc!Fa`B2+cg`S8^XZp;t8_9bIB%W71ek75ic zpWzHNN$+u$A29xKTVlme*jN6>mEEWn-bm4e)!P#sKk1Gse(JdFD$_`-Zg+bnV!K81fJ z6n=R3Lje3NxBU}9^D|K853ly09`2v#Y(Gm_{*wXiKehYU|NTFUKDhRmU;D`aDfGws z(^LO{xc{B;|K*zhag5h_;ePt*f8G0Eyhy+PJiZ&>ccj15s-F^ zIj!`kj?(hza?gbmt8T>n6z~JY2D$fT1*ZC{Ax|S8zY$e8^Rjf6fK|T#;+{)#Qb3bT zY{*5qfC?n|r+$TJo@1q91;v1#9?ws14El_8y5(xPo;bkwH9Po?%Tdoe*1ck}66KyG z^}2eWE6V_@31#||M0coIq3pi;(V87?Gy5^OfG6XGeZ#h%Tyy2IA|jH$NX5@eL`?^# z*AF=^YFuaL0;RPba_2!@L^b@P$0LF6-@~m#$>L!{^)}1nzYmgV2KEk*={v{Q*Yijl zM^}p4I`UkZ0uG6`zB@Z6!Zy@Rm{mR)57((wUv-@(kAEb{IW1Z4+|WMWaz3p#U)F9+ zs-`kDu{Bv_)3`r~bK(48c^#yF2-im=*H__lnO?d>iovqy3rwgy{VvH6hV?a@rC zRo^+!P+1FCdPy*GFEHuN1V)yycw)~$R>-XMRvTfj#%yN$KueE}G6o;o7&dBiWT9KG zHwX4ElPgHquvG5y>C3k8CyxWG3y6|eH+)~<%FZd&r3<75VsbUF(`NDO3UwhpfZsM??Mh zsOyrV9u7(A`>dDGpb~4CYksR!qc5vCTE}LeqMH!wmE*lPP3HIbV8VLjd8aKN6*F4Q z!a3ekvY7K327>dGg_2qZj6rW_42t0nKTEAzSckMHG;w~On9Gsd`%r*XjU7+*? zJTzz%bEa08&}Pd6HfD=NpsL0PEH7V>iD!z1b>xxD>b>Q_3^{qSu^+6%Eg?@wy>Mh- zkWzK#(W;L(?lxkOC@V-6)vHGdHfLp$K3izzG_CAa5`piP>qz>Vx50w7M3{dt%%PUt z4!u4iDm$agors+~i}VM-h+=2HpGl;aa$4jnP!O1t<`nfeNA9iPau3EA;63;S9# zM_!LlP}5Ir8@gwcRbwbMd+R@JVTCEod}jWbjsjQNPKRhSSxipo92{kW2UqRO^^ud* zf6|mDc)~N=E^=I%vfzu{V6?9ZluUrbRe8M=Tv}4AiOG-$*Qd@{zY1wMg+Pm55(Bd8 ztnlyDa9X0~yCjzHt7}oVmrF0*v{E__pR<>A9cOXbs|bgVosf{~NEbwBrEWbUUV6s< zLpxE)pqiA!{-g*)_xx2FC`v-`*prAqHxoR7yE`MyeRARv8AF;iEnt1&LHT6hoz1A% z@ByDl+KV52vM7;mP9s~WEZT0{?H>hPy-XbT2UD2p?d_nvByC=4T?k03PE#FpE9ge( z_Luf6Ke){0#+L3Td$4FQimT~?xdPgHis19!wR3OEeW7(%-!(DJ97i@P=ut36Z8apt zZbps>8Rp7TT=4G76wxOpoS2eki%NBse9k*}abNR7| z+WZOKMVLGSWk&~r7!~yu5o^`_@m0CU#c(H!lXBBYwtH@jp_P=f*2P-l!c!yamUqhu zOfeG|gktQ{tas)5Up2=6q~HSn1=aoydi;fB{;l9buy}uHxSSAu@i*#GN=8mbMh${` zR8;>P>hWjv;tkODPs%S@_`hkif1n;A=*3@{N66_Nz#}Bw?@kWfn}|m?h&IawDQ*q` zKr~lKaoU?vxj#iT1o`E%ml2?46e1h% zk=M-^V*TiU*t_mx%s&|x(Ue-hy)o0|^!CGA`||9!k7Ty9k58gHdjzRULE5%<)N}nH6wt!?cJHycGIgED3r~ z25U5<0uys`>@rL96Sdvf{Y+1RK;ivBK$3S_h@Vgh0S`}s@I1$iM>+U=ba-@fS9Vt0 z%taX3j=o8t!QMXR?&<`v{YrtX3I18X{-#QGz1jF#1^pi~=QS|(SMp@GKk>5v748uL z;<$->=QL!9|ps0$3a+QgcXIusZjrA#JagwE1QAGc0KJoUv zwE|D^H6(#vgFS6N;aVx4l{Lyge%~6&7V?Ojb&xfTjGj^;e(KF(AYmV;$+x7s<5c&p zW6u?>3^FctGAtxu4UWxBrOk?jl4^$LzMFxGrbh|cr9?eh^J6?+PKIXI-c){u)Rg2( zJ>Yww81C0uf7sp@sX}8GECd)?9f>b*aWPNMW?{bVMX<3bMo?i{k0w1}H}@qPQ#K#{ zgruZMS)3oyXD;unMayRpwH3ATfgXgk#x`ZYmgwVC{b@lWq2eJV*-xI*hd2I-AEivQ z1@pa}FXa=YC_fiOsuF%Uuy<6Z@X}6o43(hvjC~uOX`hnJqLq5A74|q@>Cq(hqi=Lf zI7^6gXjC6D5MV3))D)(_yW)?yI-wt>A-Dr6zMrj^+C)!^9(N$WV1&^(Jq8lneLcQDR7@0n70o&%Ys9i zq*=ci8X>wO_i-IcNIDcjuZY)h9JPz<9<4^WC~bUst7(x}rssVFG_v#Bd9IT0{4hZ% zqu^1kXG7-F8o>3Zt@oUu90H@M#Kd4=sn&9-K++0SEq!o_>9$DZn+8!-`5l0rd<44t z_ig%LeSCezK;q|2XhjBrEeRBq6f1QHCZkjV$loUPq1p`E$K+nx9xUWhSvsr&S zamvFfOJ!bX#-XN#f%i@OobP64%f4Xax`);`ogz=_8!bAAJ8DcLkk0^!=wu_*XF0FX3=4FYag+|4HllDaIiJ z|CiSDQ!ZUA0Kc^!NY40wYdxG0Bj0bOM@&InUPX$*-oe=6uS(B97Q#PuhF?(<|A$Zy zj_d6H|7)xo696)xf9!YH8B_jdzk@`003o&$02}B!Z9T*s@n_EepThKdy1%SQ0twmm@L~=(?1o0@WT0P@J55s4LVoJ#xhhyOg z!^@YhCH$$OBh{${cKa7X%2_B@7+Qg@4NeBb?)42E_G)h~41P@y|j`Jq#hmIc^Z>PDm6Ejos zGpa<}(_dZQdt2*@_%{XUmx8YOE9&Dqb;T6*vEH}XxHKfy3tX;Y3_H7!4hW2p>#NXM%cqNhDg7eU z_G6>C6Dp-05|-obcS2&PpE@6Q1|Co|KWTbuxGb4oDo=*ar!>Cd@=msjX9WIZJL=%q zf~$4Q!e_d9;z{-33Cqdtq)`A7?i19qEHViPIY`B!GRP z$q%Z@J|JtxTKrJ22d$FeQt)+IKHHamS6K0B5%~zkk9*tE&);C1u2ox6k!jQ=G-J@a zMbvaJkf+1iOHH!gFIF#I@gZuh-)RYRYh21IriVcqUOjEiHt7no^YKw&XT%VeC9V)3 zg1!)dS-5%?&U_?xC0)xnB~m?BNU4*q<9s= zqFfPr2DUG8BH9|3=p*dOQgJ(kEVI5$5lML)Cd!D}y?~jGOEQyZ7(-TsE68w;)tHlS z=dSj&h=&>(%>r%mX3`$BUrAEf?ff7w*P;wy=x{zAL5N=nemaZzj5U?uMDaXT1q%D+ z_~#s4Gkzuy)`yF%#v!saIVboh<-3tsP2}}lZSP}y>${hVWDJsV4BHRr-# z>Oo49ddVnC{w<5aFh*LC9^<8HSZ<-?7+xsEEa8(CZHiCmo5v_b-+T2g5);Xe?m3h8 zU{=%80}ii8(?14C9uD%1=^k*qlo|BY?MD-HE18ozY&g@?C9uIpYx$GQ=5^3fCsbJZ zb2|ryi4yKr1r!`mhI8MaX)vOOTF@)LkX);$u5WzoW~}aJF?ho30<>AnpK7E_V)76= z6!hl`6ws_DU7-)ZfQ}O92&|F;OZF|9v_54>g|KOF_vv1`Bi&F?cvvYkJY_5lA3YyPj8 z3Ol5H&7bmvdhoNPq8%Rm&b&>MiAnwV17Zoz)D*G`RV(KVXH0r=1mEP8{vG4B{8z?( zHKU6jUS>Uu>fh|BNAjs_Lp$?_R@;~v>mLasUU`ds&nzTEdeQyD$I5xveV@oq zAJ#6E{N~ewhV`(9l24o5Y0~t_B>1qCXi@*(IjU)M=E2!bjvsqSS7jG-u}Ktto33XWKf6tXYVw!XYtT0Vo~3PJ)XXLVBlY@$lO29{fVV<{#4YE{5dq44U{fMIHp155n#V>os%E}YklAc3va z)zDU;UhsP=%m_yxFdHCmZrr-W|5N*JKs5u5XWEz z`Dee(;#Y%t@s1uk3C6J@i@#*tDo$MUc_FLhzCned{zZZ1S>XXYI1@6^NL|y^xmy)j z!!Z2l{o~6=Pjme6@>uitVs$8pmzg}35{Z<7@|Rdrg)%{?`4{vXtMM}>@kXn~wBy;c z*}R^!)*natGjberCaoz81FxVa3%8B$GK-&4od3JF_=`3CT>sa)(r?x9S{wW~Yk>Ut z%^H+dMdYM~7^D>irT@koAYr$+k{JA?+!@RN#2X-1uK!gv{LL2rhx~Nx>|{(Jh`oyq z2m(Ufy0=1qe}2B#ll`R_-ki~&Y~hzB=YMzOvfpy!MoC-vK1PG2qzmE8d6QYv^(g3z zD2(Q(*u=-BBHc=P8x@H{m!2ua!5Q$&Qxh)yv-m)!3PDFqpum`19BX+E<|`k&+5&<} zeC8BZ%fZBw)Y#}36Q0z_Kt83truCNz-3N!o{b?iZmoqgwGTpOBYS2vT;T(uzEGrZY zHj6NxV88f0B~KQ74|BPH zBlUPW$q$Dm;x#~ptR*FU2c5mtcQV?JdKHQONZ^8{vCEp`{-<1leVk`pD{3FwHDV$8 z8ydawF3O7&-U@u{IAJNTJbmVJNISSLJ3E$UN$R-$WWLxH<0{pp`FuIn?qMzKv1fj% z#DMRpX0|F!?i6AzODYkS$l40(#CXNXU)DVEm-$SS6XMOiKCb<_e>*rKk;s2Lt~vj& zYyXe}|BK%Ft0lzldNX+XI`sO6=NZJoMs|Jt^7j6^^8dlV|6zp*m%xHqqJHgIk z;ABB)p|y6mQP<$fWQc{6%jXp9vFY8GudnM@?k_Kc6Ow1I&gXwz9`pI_AALh0zXYIf zjN62JFc`GMYYO6s^Pn5x(KZWpDC;bkCvc8vQWs@7+U_c6JrKx2;HRBM=6^}Fa=7GV zwwXv@oYvT-!W_h;NFuZN?YW)b{__3Wx><}ZZEMPRDUwTJT2P{OZY3!j3xl?CbsMu* zTbf&d<0vU|D5@Yv%CCl$Q!+=9QVJ60;*@K&s68WZYC)b+Pg*8SrSLtZB&8<1Q>)GF zcFzvG$UDn+3M4Fu3JD^qVlKa^jYVXUW{%}5~K&7q+JIo5q^f@VbCwG&T7w(Ek_ zD6|uy!2=~lFJc~wjNBh^hx7eLx%RaF8>MGGKa*l9p?O2l5;PsYh-ad)5Zeb)jBfN7 zk@F3PJh?^#U!t7sKl2mOQ7(5#G5TRJl%wd% zG?AW2?W%ttc@)>X@`0moWcec&U5MBIZlnKI|NMo5ZOd1zB~(qsWVi&Wv5(X@*)hg-I6r~=F zMKwVZq#O~|FaH=k<$d$9IEy*vO0qO39Hq5b{~+xMz4kM$?~Ihv5#pYX=~lb@UT}mn zoEfRlBdq5v7>S}}m6Q3H#gvSdZ){6ZlkgRn7$WpznnE;URE1+%eIU6`&@fUp`Cd-G=wY0P*<2YMG2Ghd# zaIZCM!_Qgsdsl&G0Vb7E%+lSa9;CV-7^>9rf;lvpx|O8uS?_s4g8^x-04>1y9NKHL zkRm@9Q4b6_ZguY$ntG@NPrRiN&hJ-Y(d;ku+2!)-Bh}CPai62H!wN?U(;+$ucUPRg z@T6HaRNFA9k2gtIb=WEBWTtMKxzBxq26AFoFw4q&V6LD^`O(I!=uC4Q`qUe@y(>w# zH)`1h=hzz^w!h=ORbDn{g2~w;ql6-xML$B@Axlg`)f)|@$w%_2_gY_ur?(go^su6~ z$;}uRaBAt-s2AbDFB2??6oH)#Y^$~_kIFIQ#*H5HNcq3z zte#t56o{bIacRqv%(6_67hbWJb1OR0ajI8)NM8=4JhsVy$7pY#Ao@%TR$Xuj@0@Yk238Zl1ci!7+Grr=CcLzlTO8l;i@O@%?=^B z@$Vc2;+{Cxe0q|SfDhV;=yOnxlm@0SPfs&qgPmDF7BQXSgVzJ3ig0IJC6cmph9q3$ zW_7HJS3{Zb{5J-S9k`fQ9$1(b7rcyV$T<~o zNqt$5iXkJE{$MVrOseAC10J0;XKHlKBUGYUCTR982iqU{j)fk9QX=KQgZ)W~aXQdJdBFU(tA#W+qEL zx-w%*xlC9HcV?EX52)9rsd?~RPQ3Fyn!K;FEpwr?m&8nhu1!wen~$Wgemrff&a)`G z|DkNlqEVPnBBTVy!!P6c5pi;pfv{F`-Fa@$hVrZamK>T|R9r7C7kPjZlIyzBOZ6@6 z6WS)2?@erFKzYP)ozZf>p~Flee)QNbJ+u3^5~H2oLh)6E#DMhZGn48*^~Gv>H=1Lq zwUWI2m!F#ApF6Fa6Z&)Dzf8ve>rRV}o#TcIsV(=x+Lslr@r>apzM#PS zskD7r1U&{8irF-V8@zi)Y={-U!6SP`dPIG%H%>9RNL_EgOF2;Xg)@-oRRpwUVkSzo+xRK2=o=h`sFf$op{el; zoNKWeX3O4wIc6wTj1E3gSMKhw2(>@H&=6X+UWqqbN6I)8dSAln5q7d_hhIMOHn7K~ z)1s9A5;v`z5(P}S=n*g^cz>=a;-p8JVe?(v59sB6=eobFQQ$92AtYhd-;7y*Q~&=@ zwEwWhU}pv0O5_bm7X{g5{nIZ9^r!XgPgCK4wS9m9CvI*Zs3YB_6kV{ox2+0CU*&6B zGA2}9z8&Fn6k}TiaT{oj24&tC39DClfF&`1{3&kec%zC}lbNaN4gVVsm;ju>hZ65B zGX)LXsFKtT*p82J_6r-lEQ@()e^9MZ(azg6!*{DOKJ4Bdpp{ML)qSzGh-svYjq4Hn z87q6f`xDR3fs6=uTEg65-@M(!FUa-|OI7P>y%UMZJb;Jp2iCE@OzJc>#&s;vCp_tIc!V9~ zM?b)?6RFnU5YZ&J$BYmo2us(v+ft3`r{t#pli9Ha%bN*H$XYE=~bi1nCtxRh{ElySbiK^*5) zW-{PoyhT4oxiAyo^o+thaxGNcXk1|d6-IL;Y7E);5|lN=*@h4sCrHv^$?}A=Xv|1g zHE*7Jx?R1^9p!m;Jrl;ay@DDiAmU4GUH1Tq@r2I@&N3#8rlxWL!LW_J(p*eKz963DU%(VQofe7}#7;eVI=f){LvwN_Qcn~BAbMx`=gw?@>^ueKw=edU5`3$`(p)ztp{nr&K0pf?!s0Z&^4=fhfV=HPX z$^0t^E5A9^&=<-vRDcqY;T*uz0$zv`X=DdPUME=E>L!^&3WKLZ>!W>+2QlzpY5ZcG zR60tKwZ5d`CKsE{T6|udbI=5-aA3x+;su8w~t4R%r4nY*Wc6`}D|ljNc)grzuBb|O9xi;EMSi(RC5kI?9t zfN~J8gY15J$(*`@Oq^q*M_2VRhIz0Atg8rX?EvvpUC&%zF|UfyjUrpsTKY#m6wu}z zydr+{;(z8UgpIlpUP^w|TbN9-{0ETzNvE5D@{ zOHeA^2isF-Jh#2)MsE5YF!xEA@U&;D)zFfkK*PCsGS#%98Y(lTDPh&!GyQdq|8UIQ ztAoqt>o7boI4ik-a+e>Nula&H4ikGEWtFOBOLs^*{lz=}kyY_*NB*LEW#yPbroFvC}}V zNL<3WVtH$opl~={rI2I$Y+E%)Ef$LmgxUowiP&a)Ku7G3yIy-NjvTxK65EB;l6?px zo)w|JguLe>^r>$ayVO|Ka;}Dv*5rpa_sxQ#ztN_%zIa?UywEYm~k5OtUN&N zyCjJ*_D{H^p?jsFX$?)wnyW0&x}pRlwAB=#kj!FnEFV7FA7>qcfXGseh28LN?eFW6 zc--UZ=1zy>rOyl~HOGi)Mb z#^Nf4hyhCH3ux{wAW;dQRw7f|yAcM|UBLn7U6r?=q57=qM}W+ktFrdxyN+jKV6vfa z5dzgT%NjpB$o6rhi6zv4YV-mu=e&=qU(rV7nLXJMbJ7<*Q#&2imKf3fmtN9Vi>@@R zUa?7~ZmX!&k;ch&ujjs8HTC&oK{1JdaZJVU3qO7xH35A9dUEFF>O-bzdLM(4Jc6Hz zmM}>ADV@BGC3y|{gM%VGgn(M{(_R*29^}e33HANts23r#uhY6<1!%q!o~SDx!VOvo zjh@XdR;qw%OIs8#g_=Qo!~F^6U&S2*PM@zl4?be+|>fzTj=EflxnJiYFmiK)+4|AIjEsm(A~`WlsP*9lo|zYvI*2ukRB<-) zIKL06ua|K-xbWUiVDPaC7~je`fn9-b=Vw3?C8R{&&a3{$I?(yw+zlVDVKobca>u>>eR->rpl52SXNXYxBoS&t;3c zL);8R1B|-?W`idNwmBvQ#M#W_orO#?OXf@KTGlNmDn~>mY%QOwaEsV@I@z)&U&^x8Sch%2KA$srxBT3|5JBGaf{C0Vq$cof29tR+*WzFaaqB={ zxP7>UVyx`&=vrZm+*+Rj6~hlUd{uj?k9@YIfdhA`gP;qYSFX zLHyz7(tFt5CfZi%5ja)&Ew@9F=j;^a;4R+ztD|?s$f%-*Pdzz~dpT4xvJyUKW1%F_eXMlw!c23(M130gPPXiA5F>El!Nd{^M3VCWPf zQ5qM6gs=J`KlXeMx8&T&gYl9R%#Xgk9&~u*h>HKJmU7>QD?(c6t~7(#?*Gjz|4*CM z>o~MO5d%LN_KnRdBvA5(IQtVQuc{%dA})O^6!f~3)!#!wA+EXG;_Xj&+wTGYefJ8! zMg;s4Z(NY`>t;sQju1)pw@^?Bw&5Qj0e}r6?f!}-gG`rLx25QXHzA=Dgh*FqQ z54qR8cG9;Y=;yrs-=otZ(6VD7D*t94LA>k4#&{cOuK4~7f6Y>Ls^>F>u61?q2(t8_ z?9vQ05P8GX))Fnj49gdmZys(QdK6?L+hpt)jI`gw{m{gm)D3Ev+pu0T>*GXiW?co% z!0Rq=KKI96;J18$^K5sl&Xj0m_SKJ*Sn>1UOL#)Z2IzN<6!hV( z9?f%DcB_}9oW|m0qe}?MZvi`eEa9`%=!r;?0^bD*<3);m=WU^EJdQu9wZ}t^Es+e| z)ms}}6E1(!_}Vks$94f=X1_h)*(zzY(ZU^<`t(V_+mB-C2Ig%1CspJah%w1a;bM7P zevB5SVm%e)o#PB>XO{f@(jnugvjz25WMFo7i0#6d>>nBjfa@B_fBi>h{hP+g0a>m$Xkduz@HUN;703zk zm)&T`$pK=$-5(bhC#3S#jdlQ5HZTW7W%~1404tcC^%f11s~@snZ?^;eg~q`SiFLlw z-}R5{aPRBC-*aPS143{$H)+?2m2ZuYm5U8(ZAV`6UJgPjX>yFV}| z#8-d29T?&>yiMa`y*8uW=nu@r%6aSA0{{?k=$-z!*f=0M`;BV>Y@FBM_YE4D3jpyQ z-=qP6ke0V;kQ+l3;9J*Tqt0gTQ6EZohLj$P2!8Ei0G{%yIiUvvC0Kyh|V}8^@h@$;ElSH@Y!C zAY}h=`yN05$90Xk8|}bckd<|d282AU+wFjmQf;^U&xfXoqy+La4-C4WrY;1Sd8V4)KowdsjS@yTr0XvBE z8c}y+d>jxh;!Znu);nvB9n8*gXUq@|bNiXHgE{Zajhzc3>F?YZVqU*RW9I_0-5v`V z@~Pgv7I^2Gf&pB2uLS|_J}Us|8gq2x8Gu1R;O)6V-UjF0XT^SpKZ7|SNXOg#af0ux zKM2dYEk7XNH0aK^0AXPe^X;wiaY5<}-lB0pUfb>U2j=2{pi6FE3;71GO}{th3;B$$ ztt+=^?AK)&ZqYceZ38!H5LSHW9smf(y3>yR_O}W#xInn}?RIQ;WgZ6``yF1w3E@|_ z$HK{acfOnuNppL?5LMthqr{DQa6;hix7QUXC*Y25!O6*fhj(&8s=?fzFBfELx9)HqflxSa^FIJ9M5x^94|rX3_Evw8&*;ur*a3I1Wd~jtQ@S}8cJOT-1Y+XixUIiH zbS?-Zx_#~cH!}<1wIXQdVb&>z2Ijz&kFL(#0=@nPPHkY6LqIVz47UK6n4#wnppY>} z_yM;7qt|6Xbr$GlB2cR#MqC;Kvp#xQ83KbIJq!$il?qZAloTaq=A;&Jfd)^5Gpka; xjcWa%{QMFHV61`qm7aNN`3k^T1+sxXq~emqq7rcX8<

5p`*G3+iR6n=!0LODazTuNi1#w4pFTx5fJdL4f73$M>^% zm{e$LF#sCRH6f)>3kkvDRCi>FXSCMuM~;W_c%+sj4}&7TNoyop6e?`=O1?C{kq4wy zCJy!|yqSH&a0hJ4q=g{RA$D+?{>6V3P6Ey?n;Kjz5Kk!R_`K6kS#YAYJOMMfy$hq~ z84q`(WoKw^e3o8Jo23w?c+7snr7kNRPnx)BXeRKt;vzDW{6BQDntOPSXXqxLn`&O$uHXH+Dz$j(n~J@fPNyw&oU_dItUh2| zR!L)}e*K)S$ZGD!snpJYN-NOb+fUIy;Jn!2knmh{B}NWFE>vx=dnYbo%8=K=Qo4VO zhZoEICn8MRps!yw2(6fA)Q%V`q;|}GFI(uK0~NH^U2>CwtHxrGqF&6(pA6 z5yr#lEYJOGe)0@R<}HT5UkayAjRYTKJ(Pq=e{3A&u`z1w(kOQJ|B5T`!UTwiCEb#l z_Y^$~n?zuB3W(+q1LMbRQVK{WR}9{*Djj5XELLfK?48*^}kS`5Qjl zwv#v6Tf1RDHNG$1&+Dl7M+UTw4s38={;Q4#@FQyRLIBgm8Pm_W9Pi$UioIqM3IEhf zdg4TV0uiYkp48lvuz*<{eg+>Ozsh?oVyi}l_*VW}dOS+9=5~|>Twl+QKWUQceFir7 zc>hsc+|QKKWcyLLSknB5-U%MuU$_{`@iZh4(x{J8&F^48(aOZAI?wUTxU2LtzEoe? z2Y{dMuzx4tJC*DEFT>8Yk{X>OJD+BJx2zk^jOSau1A)Vox3eoL&mZ`njtm2@=!|lD z&Q+PKEbrOZo}X6DA!|_`aWt4G`cdxuO7t)Z1g5yeBxoA>qK_1Y`vS~sygBSUnJXEz zTW@6c7mytRhAYWcW#aF^2Bx3w=Zr{vp&XXpGc!bx!VCaJIQZzZCj+~z{aw*kQX6!7gs^f=D3S%TW-Z(CaaC%8?OL4^O2uUD zWrhGX@@i&DB#6I}zslSSK4ib92#<0#p-;up8vskRJz3P;V>^jw1lkCE-wa_;e|O}R zy^0FhN+2R|R8|S7)6-|4itCWqm_`9#F^fpDh0T>{hmr?Om?uT0S&xvzKiK>@W>Xer zUd>gnv?{D*W!jo8`)Ttb<=|6rqCH>=9KndDqX*nqw2|mWp#lwkigXPmd-)L*JY07( zUi0iIvst8s5v6N8i5`>gwrRoG3o$j-_p=o7-sm zGnbgtHzYAedueCzT1Y$)lY9Ynw>Ba%NWI6`5(Vc8i%iHLaB2?Of@fAn;X=Ll%Xk8( z$3E2TOc{6kdhhc@e(YeK+u~RQ!=&8y+&4F?jMWYVSI%2_M%-RFS zXOjCBr$zVzyi2;E$&j@;U`>1ElJ4vcugxnsRpMEn9WP7Y<^=L9I4C}5-b#KN3fUY@ ztP-8E&b6bl5;I^`6<0;EyA+-}8Q$I)l-nvj8QQjSus(lIQZ_$y5D(isps&xnAk^r% zHf6rl-D-i~)M^?}euXht5FNeB?9i)S(S!D_Fzcn_?Tg~(p?lXM&=i;9trM6TMWe(> zhbOBe93P8?e1a8X+8;KqwR!_O-zvf^O%IQ#&{O@s7tFAFHqdHM^B+zbdF` zERi#!bAQH^=yEQ2Eb-=x0L%8(&~`2U#9i4d7GV>6lN_-49gCIfqDg6m_QFvjY+$7@ zOiTL*_UP|K*mKj#DDOLOo3)IyA!`WniJJ`$l=NiC`ja+sx4ei|a(%|{3T-=%V0G{B zjJM_Mna@9De31&VU~aIO9o_!!7@pZM#ut0)sJ7-uvfnmmyShvKgG^eNlVYE~m*_iM zF;_#RUol>}A2ijYCynS!CR(u(fVKH0pVJ{sbjd6 z12pm1eCIc^((zaxm$3B zExs|WTDwQS?B=QSWC<}q#Xop-bj@oM69ltM3|4|Kv@V(&MvBzXNW!H|)MrA0i;<-8 zqSx~G1VlS~G8ykRmWoJDDEqP7bQR?WzMiSY4f6${pv11v59Ve3(5lCwY~rMb|1?24 zhV$|B1@J!fh3m_5a!FeX3B-&UN@Scei03m{I?jUUh3n?JKs2F3*uR=_NGA=!>$>^$ zhx>`ZGGB6yr2y0bZB3H-7QCc5ANpH9PU@uFNfHlHB>E!wn~q^u+EP z2c;jx07sKlp@@*ZsHVB=K*=@}M=Ry!{rdqzs$S1+yVE!I`q-R<+k}m|Hr{o-Y=aEP zICYX3v1B0E2*Yt?Q_xB_j~nb}eMS5dxEfv^t}f`FN6#7J)4&H4U6G>N!3deKX4@?cC>fsHb z=6bUJNEZ_Ws>?aEHKT8X;qoLp+9a376-}y9D5EbwZ^3&>RJy?3a~dP2(FoVz&9euF z=rD9-KOK%|09TYz2Tn4lKxa?fK-ixB{7tqnB~L{ka>XYqK7<=!4lcPhI}b$nOR1+#h83r%hD*N0blE|tsxNhSz26l!{q7P~OQ3HX z4SZ>6FFwarrts%8CJFht`XUpACZO?TS-tGJMZu@!2)xLasFzlW1fI!C%F7Bn7s>H= zr5O9a#W5O4Rkgd8FIc&lV|LAbB7%VEU#D;bzl#_lBYT!Z?f zdj@=)!sc5);U*f0NS`Pt663Pz1Ayqt^hvQ;a2bPBKinvQlo}pgqyMy(MYdcN^En80 zjPv({`L~gf+V3b|_z2EwcMGF`jDH0lPRhZWZ+I2RMy-i)7=DU6^6JmXt%qFOB{CS@ z`5SvC&a=lWi0KH|Uj;LM_Y>Xa8K1w8sIy8a94cm+vXib zV>k@>Mig6U@Vtyf4f?`n`y) z?J&^wUBNu9-IQg;q=Tv&=s*(^&_f65kQLsET26}v3$xuZ{-bawD7@pkGJFJT@F#@7 zH*_1iM~#Q^LEh>Lroy%banUt^9o&x|I(Kg9_+S+`gAkKagJTo(zDaKY1Innftm7U0 z@2EaI=!W*JClC|M9hE&J^r*e_0L{aQzPl+I?-NS?khYH3cdgz_q(*B-07}eG0x=)u z?Rcf_G^!|02<$L`B2Dk)mjsL5?JYPSRvZJG6Et3v0px)}cXeCnnIp%OpgFed-6N~o z__QMLKb7(uo6E~6(^^8VGBy+J3^`94a%q!DHcAM?N}@lnRR)V=P0V>YsY$ ztqLfYfA|R>H1<4eF80%z%sg`qqIGR908GS=SfB6E>5$7^|E|Jyor}XvfyG@d2!Bl* zs?}d-e*yY-GC?qvgWQY^L3_1J^ThT>pD6jK%^L_7BwDXn4JhN~Z%{h(EOC*=KVvA> z<M=1x z4qsPfq2mI9C0;BEW_I1&O6+lLX%L%%!d_a4-*l zr;vs>kv!n6fpA+3l=vq?Es~1|N{}Hdu7QAlzgfdow$5WWqy6W@&4b5Hu`NU5Nu93$ zX5NdHxoQxRcd4;W_LeqOaqzwGhKtt2cs`Y%47MCgx3B}y(q{)<@%F1a-p2z!vR6Q2 zcHrS|jvYK2rX(aGJdpM}rwF&v@#wWnyM!wAmyYpDpLrmbEX>RO)Zih`b!B_dTgrM` zS*36u%DsDs+vFtV#B^GS;`s%UDilS90a9ZseIN?8BbQ!3QK!YX7Lo%bq)?0$E*6nM zM^dCgyw+|*UhV+s_3W$PZ?)3~NxgEeoTS{b75BksF-G;CoSSFBEv!sf(mv_L6r4EW zyecMS$EwG0MWLg62$@{Zw?m7Ru93_Y+RdOnGwP1C-||_m1D&#YdS{OaJHT>{RBcjA zM1CsvB{?$%coRKyQZ?fJi);w53i z!z=;6_WEkwOn$@+TZUS$(?4#Tm$!ZK+Lzc4AN=h$HwZ2O=LdYXmnma0NB|};4KQA+ zV^&E=0c+B=PuzGBvf$lDJS*kGS3F)*3URO_u%RmtBBjwb^wxU1CiRUMAPnBHy{DDU z?BqCZm2(y5vDiH@W%}q7!29VFyK>R7@rcSb9pxqK8ei*x-+O+*K6+$tb5|GrIYDjN z7)pJ2=xEuxP?&s7N9(Np!r^0mAG~eae%9~%3H&FXV3>t@r_gf%=ME={WbCBe3wW## z+wpu+#=yt6aqh*;t=Cb$)HUrqB#_^}r`XvVpWGc{1!~1~K$fFwsj$V#EML|DOH0m$ zMLBBBI@j%sO7G22Gp(waN1!+>V4L1FdP=}*ExxE0x=1%hgj_zq4Wdq<-iji`neFF7(}j=d&7 z>AS^spU&2i<+)PK89jqYxX*vrMSM+vX|r}_m!8^gCB%UX!HY^F1r20;QN!pHS*}PiK8DpL>b42ngt$s+# z_}tnQk*(@Goo4M72O_vuif`Gw<@c2zGAd}a0m;@k-td6)i9py2Fv)RFq1|=Y9irgs z2S1=pJhk3`{K{#M^17&{gJl+DYgZsSDCr%ej$lkp4jrXc&lxg<|NPY0+E;_u%mDY} zV@WaifgGo|+@rQr@AjORyz0h`z=Bgz$Kg2Z%)9mvfP82Ckn_{$!Uo`Dgpoe6p|*qm zh(7hR*1gSJE#aI#9X#nya>F$~Fb~UlXmb4aoXxp?KEs|ZOV*@d z-W$k6C#l1)mzTEP{astVJ|twlg>zAkABywvLxNW3Y%~uFd?nnmOH+L%r$*|Oqj3bs z+_QIRXRC7eC>*?%U#oq>dPqr|zI@&1Fe^|$HIQ2`uQs6cN(PV+N@(riZ{D)x$qzm@ zf(jK#6&T5Bq;|JLKe2Wkx27|U8Z2Zv0#x1O@4Hu#>aCU3M-Hemg(xTN%I_3;SHt05 zqe0?NaPgQ@L{@=r%a}sfpj;o60G+x{cI|f@fhx5_?nm4sa=O(4h)iB3uilA(`{A~# zAvZOIcYev%6zMIAH!l}?b)l5teL(hq z4cFRMyW_L@VrXAP-`rteW0%6`bpb#;Q=wr6u=&C%e~Yh};AA)^%ny#Ft{#5{sKeHQ z)&5aDilR!qS#V>M6@F@9YB=Eu68o7__RHdn`aHu7haR)VpTv1GA%<~eh*$_``Q*A< z4V+Z=;A0SSOUv(m`<$pa@HQJ?VgUW~%rffIX7bEBc$X&vhmjLSCbHiE18O@%tMGNf zDyz~$6%Hb@fO>Xfe70)lCzdxKUazK~l&a>$UwQKKyo}5cL64lb6Unp?!-AJcne>$B zypTpx6K&==>(u>3xpQ#~9G`a(N&t>${3x0BSOaVDJ4CohS0ytFZr6VO(($8$@iBaNHK|ttyG`|ET8)_IvJ1GtiKg5)t9dJ8)g513w`=c1=<7Zv~`#_~b z$~}FCejXiI0$`krL{!SM%JwNj`b z$7;c&*|PC5tG~Yo_M^|_8tt$lg7a=^imE(Su>y)zOWFvRGVQLXwh)+Oa@NA?Y*S!% zYZFI~!pkF%;-U7Ubg*-({k?I`P{+4*kDmkfWSL}3W8Vj@FC6z5Q~`e4U*fQyLE3ub z{jtFvO~<;d-mhpNS{m->U`B0#rS>cFMXHZV{T=*)jkhCCZ1;%2{`yJxN5XnrEnFY0 z3)fFK-9(36BKZMLvF3?2R7nFtf4Xd7aI)&0bN*?q1ro@YCu!PWqN-~b$ptMZHGy<@ zSkNC{MNzQ;h#l^!gNrlrJBI>a%risjJu>d)f5e&ujYfjsk=+xj#BGS#OS6z&` zv7gikrbb6l>*?62tG>W=r!-vS1UmvZRz+7|S)F-$Yw3B)BYF&p4=*peYv+mS`cuT^r|{P-ww78ky?-wUg(>n5{b2N7zW(#) z$^h<#&pAme9dL_ea_+rJs+#6@KEQ9R!zrE<$Qc?S6KJse4zJ>m1d}Zf!RmK2;ds&X zB$dMX_jNl0-={J)Li$LCti>Cc9`ypNFUQtz7TOt;TQzdM`WW9q~Rq5aQQ;rtAz7zh0js zCTCVLMdTsl+lr&0qeN$>0estLne)SLs3lzuF(wC|D5~IqlP&w@RyLZj);mu$=-U#% zlNFnA$7tN9>KuHodOvwIoz47N1i4Lh@|scryn3lnW@hQi@r>6tc|l^NQl?X@}c=h0+8Yr zq;0uHtszwxU}|41ppAMpdZNRK+R@gdyHXSMJTK`BWhWBvW_7~ z`dkF%23zPeA~)~k609T8Xo;@bR^-X}zW1ue9dP|^4ZG0FZWecWl-%f#NOLI8@DPb> zdQ=PXa=c>}?j44W>i}y@|H8yG1y&h=fi)$w49%|%k=KDM6{c|VJOm=7Y%lmGS!)S!w_&`PG{kq4MLUZCxc?UF;Na#;TA6FvxfW$z80Q>n97xH}6Y zjAFni#E;#UlB}(~GbX;4L?4IG`b3G_D6YEuYn);WHk#us{xSN6(8g`$Y?8Yw_pAN) z?h5_o!N=Gjb?yI#RE(i10AJIewtaOni-&XfH~gD2bY{W{MBeONh#^wR80vB zEgis7lcg4aK{=g{@GpZuAVg9Y`5t-`7rri8mx>Fv)NU=bRGEhDE6$6u_8F19I<+lh z*VC?^^sX#w;<%X!tODo<8GbcAKx*Pk3ayI94%}t1mYXAo1ZSF*87Dgwb7T{lh6Z@* zo>SK*S+UWFhO`@drcND;9B&&_$pGO&UivFVz9iTDNS?<k2bgmB2$l}yBJvc!2|W`$vt8#VJp#5Yk$}jI^v1QG-Ur-f zr$5G2RyfoxV_cd~nR5r;4qpf)y6QtaK$!+_JF$04IG%sd!8$d<7ShST6?%r`6?7lq z&ILwIBzMiK&^FKykhp6K{CMkkQbQip#wV&N*do0}N1LoKqagk3JXdTFBmo`m#0Z1} zj`ytCI#zZ#}RlBB{Sa#%YJS)J+yfgpDS5H|C9 z2t`J_>VpTc585%A#30!9Hw_CG%4KFTzx4-gq-N7Hz-Vg!hPCwa)A1)}`>)i%-L_u{x~=*Et0VwI zzGItd0%We^#SiThD7{?^g@4@E@@7>31wQ^&%y(UAnANuz2pAX+1hijC1zXe?6P}*1 z`Fo}+DM6l%LB$OCS9xt)y12b$P9tjNaCDi(U{|i0O#~w$i#jcureu?=HhP}LY`yZm z`bET^Xw@wcfyWal-sv z;6(FskK54v+-x!U;wMkiC;Gz1FN+=DQ-X}AiraUxi9y?jquc;PZcn=8?`w~Gb)d43s+k56p*r!><# zq!`_4!x@lKbiryGn1<#!2g}5nJWF}E!qh+dfRC7vs+I{oRj?TIuYCcCp!`$*EeD;w z%uxcvOs0A-FKEJGIrC({%;=Kztr-VMeI6qIMABs1+B5}R6@OSeYLxz8bdDtGIt+Q2 z?@?O_^YnUM(E4MCYy8hZfCHuc9Rx{6de^(fQ`l8gQ+lie??g1A>Y14fDc_^rq%*|k zY1F4bJtF_QzF_5V!W0#sD);1HUjheKxb@R17o5rxD!`%dJvQWb8VFVye=tV$9m8IF z&sI9Db*k~5^HxIVLYl99ZFkknen_4JL!VZuke^Od<@8AhfU5=KxJf2R1Mb^cvxECd z&e(^BFEID;P~J+Qtm}okcN!ve)HfW-1PfH%rn~iKRmWahXZL7e&a#UfV7ZV$ z#(U=pBS+@Mv>)e!zO<2DK4T++o!Tb!C_ERwq-rw{*iz`um73XidVF<;xZErrA5oBM zt2Z_k!~FHr7L9!@X(DrWh*BvlEvsgzg*jibW0$=)H9yVIgFpN-XF6_O{sUG^Pj{9_M2 zSgNpy4cMRj6zPtH`G?K3PiSH@P$9;crs9?*i& z1Kw@8qSlpHKhDkC$c*lmwF`R6_vS;vnmi7fU}PxB+$?Mon-I(wT*?JY-F0unxl~33 zH6FMI&s8X>Cc=IU7rw}UY8~K@cWJ}jOJ_cMd`>U>DMqETgRC6ySigmOB~&O{xgq@d zfJKA@VZ;?$)hd6ZZ$ljR4iqo3Tr3s1l}thl`ee`c&f`v|G@DZd@!uhtfy%od!zFdd z!CRW;4`HZwA@j_iFaG(yr?t#)r2y{VWs}Kp4%}h~S)A%TyY&lusLj;p?)q9=+U^-} zK!+~=`s82@-L{Cf`wNrx&L{TzE{1=6Ev@<&=h8z4bQdDH@{7>Vw#`4Y z>i-}+3gChz-`95u2V6OJe7|8KO|EQ)n*TckLWq-N*vy`Plscq^MN7g8{<|gJV#LVV z|ngkM*A3KBE6^^N>WxW&ayYM1iKTzx_E0q1*FtCy<7m&Ii`Gwg)bk5${8H zrv>zF;;3=t_|HBMZSzbd2ESrn=EnlU)k+ix6*9lh@;R@Cn883Ro{bz5L1@2{9m#z= zJ|cKW(e~m`a!3ew582CV;!7rD+jYrO4W3Ug#y1GxyJ|*pTg|h^#GrL{+5Pgb?Cd;< z&kkC$v$0EiJZ%52?plJRNG$F@RzU_P?Z@hu;pl7c3jK-qXS{uGp;a;rMcLf6bB&6m z|1L5WprU;a^-AMyUAF_6hD(h&4Tga0yf1BZF;&ixO5w{{)jxh4MwRnkG?{!nL7 zVV}ftVlca7_46;q%1DSoXr3|MjmDmPPt2`UJ&9WtscatY_P3L;eg3oTc}JQaI0qc| zEFQD!_h&wxVF;lIdG#jUt?hc4dra*`Wv6xR{=6#tr;P$6&iNS(D;`Z*jU9H_ z!H95Ab6X45|N4nu1fGw%idAzC96GOyT7?Av3$X@Wn;3h9%5XlotcK!dTvv%_S_=6v zalsXCPkvd31ct!^-*1(?sis-LkAZ-eI#$!Lj3d{5a>2848S)?RLD57Yr{tkDVj!_q zL>62D5b1g-#} zK}!*HVh~vVY1aF2a7727&YMX^kkp*{Et&OJr3H*FCTj00BN1y(DM-cvDp;u_akuqA zSv^d8BL5E$?j>U=BsXlq{kQ_y5WBo-zgY-6GEV`VPBDb=0^Q>n5cufMMjcp23?K+G zKDkYqEdnr?Cqa^*o5?GIpHIA(vI1R<&x?YhSdC_lXer)e46^5++#Lvky>qD#D|9vR zIcK1X8H%_LGqEeB(7j>20K?H3=kKB(=Yh}vl@ibuVd;VbUr5KKV&LQdSXy&g%ph7R zLtoJwmxS39g|+P`3x?PlV@cUY8Gwe6OvOYwh{1Cpqx5RW@6|Q8$O$ri5L3_!2zY-j zI8ZELAd#>Yk90D~ng0N{S&N|${hblKdZ7FbZCjgC=3+d~WjF|1H|c0Ww2Nv1H`MI)X0VdyMCwYc?0nk4ol5vYgxOxIb$| zKm902fQcmB8Go2i(*CD_DVJ0<@f1^oNPu@cyHZCzU)#8@`qMsNt=3}Aw16q=j?Z>G zybddp1w-(#R9T75V?QE%;B*s|*uYz3BL1la;?R0K1|a!E9$2rcp2@{y9S>-Ek`R!c zg~t7uG`=NmckD=BkRNsMDvvh= zcJGB?fR||1V%KxaxB!YDBNj&kd5HmMDks}dF2M#m(uLwoL13)bG6V2SP1Q&pr~TGdn=Mi4k5mMy3Kp_6_(7zR{SF@o%cEj zzJAPv;mm%eZshu0r6R1_!yi9 z_I2L-N(>5k*AM}Vj$>CiOvX8(^Nr`cAXbx3r6^liuGbfPZ_sd3oPh4{qob{|d0fvs zxsO6Ggc6%?+yalEbtpXIx!PKeHUWi{3|3NHy4{7Kx~HaL=F6=V4&lN2j9E_>eE%vd zk|zGhosO>U$MsePU&4lCojxF_fWgm~+CH}XHg+pYhZ6LRp52H*%&==+*wAo&yTw-~ z04Gr1?a}H~VvKhD`hSB$2;Y7gyG!(sp*l>$sA;9zvHmJQ&BaY>CH;lcP(8e!ddy}TzGRAU72 z!+I=()?h?09UQ7Sfb-Ik&(1D4nVtT4QkBX{*f9|Jigp&>x5-fg1K(c&A(c%jk9eg+ z)ac!#uZVQ9)oV&2T^mY;S74p~hY#Pp+RqJn442!v&jBWq;4Rfoj0#lc(LK%uhG4#-j(1h z>+n)028~l0B%!@@MtQYm3T%~2V9@;R%|<(vbP(yqdL5LI(gX@y%u-GL_}XNZhF-33 z^x@U6NLDT?Q%)IqHnEe1Ci|>^KJdk%ILfXx=A}g6Iz3Y6G2=AVh!#NA7S&!bcoETA ztBx`9xvz_@1k)fQ>RO1ico;J1ojbbLGNLRI+$bZPoE^!(a4i{DcSld+8h%H`)bWF^ zQ{4i1W|*+_qB#dpx%D$Sd@155cyw>fd~I78$#5m}(O@;|2zw0NnjYTSODn3S^ORuE zisT2$=aYceh+ZLs*ymL~)ktUE_vBN!7g`Ad`60Wt>yF>HYJ^mb{uvwG#pv5Dsw;xpxH;t@&h&>2P`^qErHZ) zG?=viN|_mfe%&H9d;QvfXgsShEKa%p9}GP>T7#$rH*R~1jnQ#eKyCG~P-D=Jt$%+~ zbK%FjnEER3(w2LLTo6~`pyFQ99*4N79l`m*EA{y49z7#+RxMKvoqP^w)j6+JFeuKX zz5YHeFPFbzFI2HnikI6f#6tXB-#sy58e-*NG6osS$D<`r(zo$sX5y;a^ZmZdeL@btLkn^Kbs!!;MTrw*|#7tCER zz2JY@2V`yOn3H?db1116sG1Jnp+x#C7jeDvMCThleGTyJlZNrNc%58~GW_*>x#YZ~ zO_*r|V!9Vi;{EDK2fQX_2AXNxhyCX(s|i1ro;B7GiqP$aR&gh{D0XRrCnO68r&(%$ zNdrZ7-zwZ3_o7$2p6on!_H-O^Qj^JwIZdewGLixgD#L>VF3+Kdd`6tW@5%hyT=htS znWPq6>$>y>{YJ6OsrThNK^8T?32P;hho{%D&R&61UH?V8few??}|@V5p{-aQ>qs+2_$!C zKs}lXu^CFCEP)Mhtvph9x1Lo6NxoG@mg39bh`{tIMPVw7DBQ8W zk8X5Vvrn#`v5%22Z)pD-7x#s8$YH2XY?97JreMD3 zNsqtRsrG4T8ik%Oet)ILbO052^(+I~unMb8n540WRDDQM(>=r-A#C_B-9s5s4a@Rw z8?egj+K{`zmKh?@esnYaeFX;+yVqaiBe{!=MN_s_?CgBUSc=)kVa_7ce*%mqsdUDb zUbM=6|3S4r)#w4&d#7{X?Ed_L^h=^VKv#$QEPWHcN)sq<6L}@cCVUkD5J`)=GZqFze`xA?fT^UqdmYv$7~BuFvac)d4`Zqaa{6{% z>aP#~M3cR!?@y-`pSG>)itDxMBP(ZwxP`zL+LWa}0yT3X1PF#>9)L(nm(f-~Kkvq_ zd_k({^hM)Lo+5fHN+Ut;LhbQ@->>LqI60)|7QUbr^`8Q3-&kgEm{4DuqJ1lu1O8(0 zmc#@VW4Qx(NDT{_j7018bdAESL*Yk|h*$cinPBA)Pi)-q66#X|%}>2UVaH`(K`fM) znqtACDE>4V_Eu{cPggRzosgntFnp_t9uqs3aQVx(*tyHMQXsnrhoDoPN-g_9DmYLz zRmE$xnNswOr>w%HH%w0WPHP=emEdf$iCHEN`XcJqur3hmM;G81Bq&SiMgN?{bIiPD z0Y)W*=+Gs*=11iO5gf*T4F4M58{5>AZrACUZ}mpP1RTB|4>ML;2nSd$1p|i-R1-@j2dcd1G!%qblbC) zMuU%5vY>H){~llG$LNX1+*0{!X?rP!B88sq?cA%W@mjadkrQ(QCu2j1D<5#mVH*py zwTD+Y{hoOX4ALMH1(i!i-wi{@)JTgPPtclei;3yOeWl@C@cTrrJ46Kj&-$C@dfeFY!{;>*N+5x&|) z$u}eS%I%%q&AXjg96aozC8ceV-rw^3@8OX&h4j3lirbaQ+RCk>(id}(6;w6<=F7&l zDVq}D|3zPcl@-*RCg#run~LuLuMsA=eF=JYeXsY3<63qHYQh1W9jTpmeLHPSx}nSA z4}yrz)PM4Po%h#LIT~*DElTrfMU3{MG(GL@rOwp1N52zJ{3S!Sv749&6{^^L^)-&M z-khRtvw##&+IdfnlOf&it`W~vcxIx%$_ZM*z|{km!G*}ld?)^$4JBL%9ci#+TO0Q5 z0vZ9I`FH#zT)sDCjL~k4#Zc~9>L^vW)BlB(906xfuF{_N7>C6icdQH*{Gf~dZaVF? zyuMMb=quzbC4M#R%9S*@8WWYkKR2EThH&`zMnc_dtaH$~o;e66sxb*f$?^4?0U{_UtK zt+V}%(^)ny;h<|gF$x4cjlDWhM&y=8MU|+;cxK`@FGvF$L7;N3HwD^9_lG``MSuR}aEjJWLm-MYX|f>@(CXru zpbQdwyysU{QUJT}04itbFsF?6PbK^^5%Ot>6jp7wl4{I^xQc-?zTLWvDybm02$8LN z+C|pMKIlqUjm3N#e}|B*LYnJ+*4q$3#5BDc1n~tGFft;{YwS0fDg zu5?Z)K?2%=MRDr0vljh>A5*%;>S}lmj^uNq$bJ7)omUP z<2v~%TAF{?8e$)@i`vM1{P)5e3Yx)cf%e6W z-8b*EfwvT-@3nq_2$x1gH3!-4;$!pA1=nQ%=rOIA@= z@`0!%--%jd#b)TJ8cNO)nwvAZBDoWq;ZDpcrjBBw zCCW$(niuKjO_JH6AF5j~o#iL#v2hjUaSF-Jn}WQN(a0)v5JEFFfEH=NL%NfFtzxn*h#xmqW=U<7z|r#{Rp)AtBl`mVrnunmbzy* zY8lc(6om8+4sqKDPCOe|7$7PR%{_Vx8qKGHxHk$8%l7?O=q+BHmcGKf(q=W$jRi7H ziaj3oowEE_-b^Cc+JIAJ1g2#muk234{+?8hq^_Rci_F}tw9vo?zw08K4V82D{RZn( z8L9Wq(^4|y9JAE2G;bEH!WQh?M8W#d+_sdbVyD>On>Ih?Z(se?`VLqOW&|o#<(15b z;{-LYjnwtGEH7bp)Mdo1pz#4}?81Z0>zRnZMJ?S2WQOK6eJU~E?ztG$PK{b&A z%w6kvrDHfR`IF(qQ+CY`Q;!cOPktK?_TXT^E?`jC68Ivrr$23(CpyBCK^|3jM6b4s zWzCYJvbQ0f-n#7glmCQ%(KRuH7^Ve8e^Md(CRITNTi>l;zu~H3DCo#f9nZN9oL`ZY z3MiM6p-lDON3iOR5i-~wPZ*{IXtFzSwRB&KgN!;J%Ljo`N^qL-9GbNtH1TBjPw*Ht z0jIL2V-q(!lQ8;G0upD+hbShFsjW3s_5gKn-34xsG0V*t*@_J8v^$v|83L~JMLR1g zbS?j3S<1}_-UaZEmiNxqZ&*9h!&!}eGbAkvu(~hn}c?Q9nGIPX!O@qBJ1g& ziJNxdUM0&%{=OoqOMkvVC^og+!JXUl&O)#>6i_>BUD$Q<%j;(;uH29PZ3iy-=O0{! zL1}2z-__dTQvlGS>WM3{S=;K!=l!5bbt>v@7b-Rfyrclgy;|-^9qD~*Pyu2k&J|XK zp_{J8MAyEQdny3h_(bgd+k@#J79a00lBF&IbarI%g@x8sdRL7vP)jqz-krQdOY}gN zEgU_(iOrs|ew^?*=9QrSHksd_HNbW2*F#1(qpwM$w`p%-Rf4w4*Rna%F)VLTubB^Y zHtI*vBasa=3`-xOao3HO9e#O+0nLw8C%>xcElYxurWIe?R%X*bJl@#U=P?#@<@8Ve zp8r`Oe~_yLoAu;C-Epeu^$CO%X6!^+Sm9K~;jnl2>)DlOv6Re(-k+|M+CUk^a&{AW zAS+_$r2{2PoQ-&RmxEWqs|Jl1@{fI|G&f$4${^k9XEK|l!WDk zN|)wif%vtS?t-OaaG?KLKC1=%Hw{S0=jg}5KkN)j!bWh#600UCSJD(+lTb}%T9ha= zcf=n4L9pOw04sdiZ=-0WU>0AY)IKOk|G96Mw%Qf71Ol`7AGzd;Uj zU^=s{KDQt|N=cyCbXx}Bb#bUX>vTxs1dsx3nJ@c!=L~YaPaE3OYlqt1ci8CD*&X{a z7>-zi6geDOJ~$nl(a0XZ#_fyGLpoSW%;Ts#bO#@|rVNdu7vcAeyN`%=fSe|j1~0Ur z%Y@^%nb0GPUg}iHe{g}urW8)B0513ft91f1f{E_W?_mRdE&%$F^^a|XIPjyn~AQSyQu zn=SeJiryC67WV`eMm}r2YPhH|-Q9Z>DSN4BFCtsdtZWc{Af=Jh*!Lpfj@>qLz$MiG zL6H2K?G$WgzWL)R5CK!Fn6=gmZS^)RM|ZuR7lNmG&p7$1X~V$o##CqB$Y_ z(HNhR%E`K9QU0H$?ly_gC_1h5!gKvOuVdgiZc_KSN-lO{T!od;QW_K$ZLfXu=Ricx zz+3^mS+xy0bcrgiA{-y|<|{nTV!cDlEnhy;;!3+&`QO8)3RCQ`ddMpGQ`5u++qVr3 zaZvA^qjJ3ThEC(}Z^bl?nbPC@Sj?-6-`c!?<;zlJ8fQ@VGNUrBP5DAA`~Io1nt0YP zqI%z1Q-^0pz{h3`rW>{UvbW1W&B~*@#mhcGwDux1jj6(JPP09*_1hAgC2wQE{>{cx zz$CqVA;hImuZi8`mico7)m#a#l#ppYEiv9gO9439P*-<|`E~)DcBGG_9ZYj!q2{4l)529XAzC7TRZIf3 z(0@fjwA%W>N+uHni$MEL0ald=2{n*J|0A7b=V1EsZ+hMa&U$HV<$Q5!=+z(tU~Y0RmR26 z?>G6^8;ACa!{5ohlq__cV7$rD3CFdj>e&2jN7MP3b8~|H{48Lar-v52ppbmD@|VH< zxrS7SZy(7x#ULbGiXbK%x9GLgkV*NSR|Wy>W^a}AMCs9@!3{x_H?fZi6k^IAe&DAl zOJ@nWos#U%upy0~fSKEYuP;E=`*iV*$EpR9+HV~d5-|H06z6Jpr-v~$4Tr$Oc8y_6 zw|Cb(1^??|2+Nq^*{IRbatcQ99)Ebq34$G^T-&V#T>+vQRV5-R2sA9+hmrZ6WObw% z**kk)OD48&4ao+(K57g`PT%Bo;!+bj<#%GQyC&%j9jMSrsppYXVyzN@uf|_0ue-*C z#N9vKuNABt;saH-G`s^beXLAT(WM8ix@nvBFo;pm8zTe;h5fTWTBD_?`e6?GGuf zmp3f#ic}FHwj)qM9&4PagPO6TPJ(H4@Lg;hKtoAlwxGFdMyA~?GwezuB70ko?)?Tt zkJ0JWuRjb;9EhgI=4yGgB&(*W9`!&~0WMQzQd6%=SrF`%I6>H`xmWOQ{VoZ}AcA@# zL;=)LwQD*j&{h)*bYev0_T#7-%QB++Xo7(Q)9M9%UT&9x&O5_Scg9%#)X!{Xo4U*b z;5qVh5T%?~K5tg=WY%k$w5D%*am?5cY}OY}JunuNAI~WJP`&c4IHEv`@+isAgsCJ9 zrJCu9uYwS}iJQAkwQ&o*W+jP+=agRSHYjN=IJoh+9Sg*LTa|_r$B8}QL=ZStln`Q+ z*3Q0iS+3t{hec1Y5}lW9p!LxPca22?y$_Za96y0Y7$(4#uFCBbt)0ts62v+W0;D*^)@kiydZF1Qv*zXJL#g6nywKIe@!pp`R_Yr%}?kUUh{y}=E&j`Ow)q6 zfFt3Il;vbeQP3K@Lg8*9`+H?*+L5BvrC6#d(+3`B$CE8HckY!R=U{4S1i?ZmY$aGT z!=}Q!^7Ar}v-yCTW8$`;?&v#jS*z$K(s{2o4OwjtUJg0s(?1$2ZAlXne~0dQ(r5Ce zbe^Tv&OQ`oo+)PEO@A6p2?}v~di(W~u*6D(tt9&*+~-Q)Zg*`4!rB7MPa)%bUgN2} zY=x(`Y@cN=z-knriZEE){c<+@dr474w#;XUi|;!(FYrD#tiw)E>MfUlX;|HVc*AoU z6>V#nv#jMN}(fH=qJ*nM4Ds0em@0-!KL5is)vNC+0Y53uOkP|-P@E`YrmLd zSuC1&gnN)dTX|ylm&DQ^?QXA2*Pk&9AO=b83Jz#BS1=I7vur_L>((aQH%u&4GS}wV z$j?hc+KJXtiK~#i2L;g`Y%*pmyuQu~1K+h%1b0BS@PwRYMFEmDc{T5Y~stAogc{(}Tp0 z4QgloBi*Z%rf9>J(Y6z3+bu`U+orBuLa(Ae(P>+AINUQAlYU2~R?7OcjHaZ0>qpe~ zlo4sjZ~^aI?Dpsy9FwVi$7eQ6PE& zTcwCcAK=<`Df3p|A*DeNUEfhipy>!5z4-zkN)CmG%nJdWroHc@+=6QPj5Jhr#@`{a z+_`;wt0;#@b@YQ(wtB*84{OBqhi5HQ6fVp zoWx@XBXp8z&(meembH_NZbW3@^?!bU&a|_BT5wE-fa+Or-wlrtNp2pCUU7N*Z>#r4 z__uxep8VzFkP|e?ytM9U`5-&gwNW8XDaf}hSr?vTW7!yHpvAtt7x9NvD^*M7L{-YtMf)41h+jk*`|4zueNm z@am+dA(|vNL!^5lS!N)OVK@cINXCYHdP7Mus}rxO7@^3}3fui4wvEZ}z<<>qwxx(G zst7NFFpftb;7N$J*`EPZitg+n)EDs<$w?1#E}vKVGGDu1t}$Q+%3<}MQgbuQPpM?$ z+ONt3|9LG31Y0iNMDYPx+_^&Li|%NJs_}KwT-ztKW=!^}Qyn7!5tbo?@dMY|zYyZ0 z!V_0?Q%7EIZmOK8GEQp%>lfrHkJtV0@5BIp(;T^n3>Exo?OpKKpss$p%-p=HGWR*V z-MGSgeD_ut24!bIRajTA;uTyDxNnkXn&k1~Hc$?TlSC2d>TV{N^yYdmXz?1^a;LUw z01E{+Nn7&U5XYzOT~|WlzfYG>a?=I4{wzlpAk>1RI?Ds!)FkszfXMq?TaYFvUt}q_ z5EL6b|AFQpxjmzv+xuSMiULUxu9kaoQK9}p+1{bgBLRML=DVTI@6|~E!~FOA<7z1w zqc|O7ilvhz7rk=u>sgW;KpB|d-*FMT1J^R{V1YS~@7D#YvsmJ71`9GC(mnb;XVM>8Uz_x&B3PoD?Dv2C<} z-B{0vB<~T#@vip)(Brj9_!?38LnqwCq_3zalXT?X?^o~iHJZnGUEZ7UyyQ4MHq80y z6C-P(@WJQ5NjLaM;HzeuYnmgNozp?Da_cKT&TO%c1DsM^MK7db?z=G8(bRib7lJwk ztdVy69C}biaw0wlivtX1yMTUH4IvfY59n}qA@aF#)67Fwm(!7Fom?vAV)>`p#%9qq z7Ulgwej5e_(2J5hD9OV!=PlkGFZVWu@(^|cnFVwqZGZo!bY2^iuT@k&3dL6P9=}yl z>=!J6PT^EJe{O}NUEI{9;v0;#-*4X!q+gHxWKK2P?H{? zd7{@xd#&KEI)3gRGvcnw1=8fBkV7x=ejEeFcy>wnp=^*L&_?0aur2B_VT-NhdTnCQ zVdtKT8gL$CcIrHBTSbrUQe>i9!nX|!avR;63uIS zcrI&)S2pH1^N?Gt_#8x#2Fs(U*J|mvLeU4b`tyF1sngXW9?Y88UEbWI9lb0-c=#QR z?9!M=y^j0@5u$Gs^>KJ<-{o+6YcJL4$zRXheT&_OKQXTPBW^G%-ibT3!F&4@LTQ!f z`U}aGF}veb`>`1Xd#Q3oBUkp7@O@z4n>7Jogxy`>shDZK!*VFvzVL(S@7Mv!9?#CC zW53DGoNTQ}WP2S^0>FI1s`ex|DBVqg^O97dY$miV>=^=Q7^41)j-g@gTg1QxT5v28 zsj^e~RBh>)UHELGivPn>(=Ts@&3lNBcX)SNf!smlB77GS)$7IKKsRx`7vXaoupP7h z<=yvcgi9E>f#NHyQlW!;TU3)VG+oIyK_09)qm&p~M){<}2w!IQF%XeM8JfahJ)=^L z4NR2Ut*4U5#%ry0Bg0s`^6!;LeSnNf#7ic~z(zNofi!K(8G$ z-rdi_ym?5wU_b>&Mj) zGA(<4zhT|;OVk+vDB{MHkJWy^^rGkb!EH%%P;qsM#)y}js>#2wp#qDo2m&^L&yXH1 zw>r{ickP@C_7JOu62HGA?{27<%ke=x+_M`;u{D>EdHx{y{4*mNHcd$lRg}@+7}l6F zFVK^pCG;Q=9wG>|3c1RDA8HF)rAwXN>MWsbf@W_S>6-m3Fev{;7Yb0g~1w_ z#50*F-7P#G-`wc8{dQE9HAJ28cd?k7hcE)0yUmvXSY|^Gd;O1aU5@uyC>{D;w zYrs5r1_TuRw}I?k*dQNSmEcp9Y-b0ikw;b;xF>>o$=FtexX;wQ)5xA6Vw1|Td3_gF z9pzvcm+wt^!Av%@lkY)>IyWA7j+Ojk{}CCq_GBmufKcE-y!QTH=WyoW?NGZc%cfB& z?T7eSPSG?@0Y^2r0Gr(G^{fNnW0e=^tk?SW?-9&SRP)DJ<8~#VmGa9=EZ%+LKi^kL zr=yOqx%0s1Xt6Kznzh6&z9hbA8B3pD_D8RIfo4Od!rjpy_G5aNgIP7MFzb z)sbT#Y?_`^R!UQ0Am3({dEX=U5i5;`(5mU-HXPZ+9j1@vubTsHKm?A$+I5&<(>_T; z7dB1)OH5{X1ey#xEIPW{O$0lXM`+aqJ7b4cu(UAw8)q#BYgk5>Mo9Rs|BNBOEGj6U zzTjrvRo`70AgIvJb&=aaCR6Y0B|rWUFt}aRID6qtqK%CmErT2$td(Ev#jJnUP58|IALf5=hlZvTU|w z;y64WLy12xvr4F`Y%?MpM9(ugtU~1wS5Mk;N@a!ZI3oX63d?FHR;NRVSpD06hC571 z%UGtTl&JPP0kTKRcxYyB2;$TBso->rOZiz9?1!l`;xkH@#e#Uu7v#bgKeYa&@6{I) z;QN|Hf+o|1V~_FcbmTyGx8&tuJo={5V$4idoHrvn0HsZVo~)|_IwtB|u=ORgI8@h5y+FieYD5wvWQYV1+5QWdpk7zo(oBibB^SjuaA zxr`Ej1^pQR9C+)`%x>LgzW{p2^QsftT5lxWPL_o?QxS0!|1D1fJ6zr4_qHLXifa@6 zjK_vL2M40%pDJI`=Jk7czEZ*{TYvxJUXt>bM(+&Oq$NJyf_@l|s;7 z*Zn<{wYoS9SsJ>Zdf%XBzE$qO-h#4iT|BPZ0IqRodMgUNA)z-Nt$_dUslV1Osy4`| z){z|^eD%j^O!Dv5yuVA$bz{0Vo0&vY$dYgGwOz?k`8-6=2;7w*`yz7=({?2&f^QbY zW9ce10&b=s-rl^WQK}sFt5=OJ_jfC{%ycwJuHs41EmGmEkOUbyE(q@vUq1N0*b#lR z-K}suUD|`YwNE0SjhMfU4)Dp^Q!mORZ<|`mi#`hANhiptH=gzm#VWuL>U6Sa1tK%! zIl2`F=5<5Q*M@G* zy}g+--ZZ;CHsK|KAE^uab)lSEZe7%)&i*0-PEOBS@fuWFuGZu9{bO|J}@(cgCP zFl9JjW9N^zG#iQD9c-5Kz|SAo8PDVk!<-$1z@V{wE++WF)oZDyk9MOkt;wmUmEU?E zk9P;?%Hm6`4i^LF-q*t!CvJQg$A1KM>$U8vEEZI!zjqga=7@|&Oo&M(68Kf)c-37e@m+{ZC~_~V8Sq{dp5M_!?dkhGAT%b zu9aWse8E0u^x<#EnJw8Et;37a=n7|#)K(2aV$*_K9+j!qa${@XW{1__4l}OXCuO5y znFX&U>-J%u08Xe_Dfk&qZ_Jwy)PQU0t9IY{mxyhFruy#-mbP{-o>{XG^Bvue{yLAg z-ksdPV859yXah60sLMCq9OHbh9=}KofbX?G1L`iHvqRzv3QAz7K1@j;f2Y42d$)Nk zvr6PHb`l5%Nm?*!UJS)Pyfw7I4@ zWl@jXRh*|BB5#I;e`U&8A%r8pv>7zu6L{J86`6vbZ+fN z08fdBc?v@xGHxCA%ikIualW2dK4GsF2PgO|K#kskqGjgNeYaW*mS|g5zyF| z2!ZhIe=Hq_#BH`1xlPGAr0+bpRkt0;VY>mP^DZYv6(pGsRWnt@IufkD%20w_?fqKZ z#3^d5@9_>YiJDzkP^}U-BX&~fpAqhXdJk}a<^JZTG^|n`@q`DwwTU>l9@|t6wtUUZ zk34f+;C-NatlzTV`>iSnX^YM*!Cf{9|#Ij^caSZkMA0?knTbx4|;_S-l?Ug^I_BMTcM_C!#wb&N$)26lI!= z5nn#uO-8GY9k@PL+`{6%#425tl9D;N?!?&u>1eDyGz@y2FVAoV{P4(k))j-)G!TTm z-Fkfxqz5W{nqc;A_;{0i{qN?*H$iOWVkHah(@ko=?jSCXyrhl>v`By0&SPw;i#EeK z_&Z=v;3oj+rTpGog$FB=WNW-av8fF53aFB3ug)L2C92{M(F4^*@wMT6Cyup7m4rMx zu`G*&?h=oFaedyuy>sgl53~KD61=baNRqV%p&n+tV@zhhu^?HNO)5*qMeb$5wI8t9 zhJ`U9a5XbMIHsHB>)yof==I`3oQ0Am>rONpIcCoR>`TQ<+LjGyl1Bo5^L-h=)wd10 zX3StQb-gWGa`2ZQpg8R2+EPnuw+aM+Sa}3l)mxw3N(w*&!4t03kPxfE9Da~{{w%@V zlKnF1$8QL28`0V^eV|Ht)-qB0OECg?e`?=Dwp12Ao2H}z)BI%Gemea=w2erFwJpCx z7$V5(+Qmi6eV4oI`OnY@H0uLSn*lQJ{CN*$|8=w~D5TCRDgWTS9kVdx$q-)Men$q? zAZGf~ug^&@kA1E4;s6La>ewjGdtlRHjBBKC9i+&h{Lq_x2zK-U7IKGPsm7#oaa;|5vMh-) zac939e$UG}{Q{sqkqD6fyZDH8m1%sbPlTn1ECHh4xqN+n(h0qKyZ?u7%1-w?KrNbq zst4D${cuvnLyR2z?|Moaggk#^WYD8z-$G#L;)C@kUMeE*~y;rXj8m zis=}8H2iyT`CgOSWZH-EXG=o30`MErw>`KY=)VMj-p-R6wtrzI^75KS`k2w282uUL z`Lf|KyCZ*!V5G113MYDYI9j@Tydt^(uW#t%n%zY&=245?LO@x~yVsAZ8f+*LHasSt zW)i@OgFol%a_5#>+wj2JaW{!=fx}p^#B=6qR>x=O6g>nHJBjl)|8vNrUTveusMf0t zCh@DEkIpHBPy~%VyN8$GT7?tngZFm;-{i6FC7jq&obZfZv{-g<6@GCtiK-fb#rizo zmUYB5Gvf~d1LPtLufLQwS^Ljip#C3cZ~Ye46Zef1QX-8Ytbl-Y*8vd_DMeU9Lb_S% z5K1?QAhm=D0!vFbOLuqoE{$}9Ad(-yd*9#Z`3Iig=Gt@S>|E!X-I;m6N;#lgk}%+P zhSSxdw>PjhC5ZJ)FTq&fCM508=MU|J`L+P<2u$mm(5Bkv znVk9gm-$CmB!6L-!ROe?ov$(c!pa&G4BzNv(>^Rpqc?hJ!vJ1!utoH! z`&SY~sURZ4G99b-$w7hf0mj0 zojRIvf$kXQ*1)?BaLwWL#mQJ+TgiSt&p51;bemmsIV#Jf8fh3cHd+<*H# zOw5(oWZ3f({wx@%cI|zW#M5iy2HZW4j$VC}cnv1fnnPxnyB;35Nvz^vRuLd~jgE@uBfZIr@i{)^Y<;^eC%ra0e>41AkUQW+i0)?0-6{Svw%i2Yk=H zLj_Sma)h||`Mvm+n_NwvwevmazBkRetJ=^<;iGRl)*}u=3*$&S1tim6A@I8(D*^xg zaHOnZ^#mT0-s1s$& zcFeM?VqaxI#T?DK+Wu=*_95R&tI~$?df9c{pbc{i z`J;(D6sQMgspC>g5Xb^se?q|1o&b0(uIOT5E2x0NdRp94ZiwN_bl~@ zx5_(DKt<C9^J&-qdE+?9h@;_>UxCEB^rOGqL7#V+(x_lwZ#EOd*aKOCoW z5bg2uT`*?jadw8^W)cf>9?TEXV#IZxc}b{MZ?Y55PdWzX(|#P1qCf+O>)Uk>?#{+_ zT%16%=U1A+!{?C{`Ci2TbJIO@;;?uI@m;?8w4DQ{?pcM+zyqu)`#A*-M~~HhA(Fui z+KNv>c-0nou2Est1WrxL1yHtG`lf7+=Dq9xpeKIm%5i0tCD>)-)t*oaf4dDC4FmVB z<#r^Etjy=Tli<=TRWR*IUptX`$E!A1oh*K+p@NcF# zL@NJ4tMN!3qp=`|fXS~~)Y0@a>q)GDgdm(W65fxgaU13a@Ym3mA3y)T6quD|Llsze zYy-@#Rgbl3FhZi^5ecz_u;o4C1^AikW%ro6bO#=HR{+9)JOq(l>hl@SR3G+-fa&itI0vBDKC4BL;J7mdL6--URL0fv(#0d)-lt`FwVn)`ko$LxV(Yh`{bZ~x z3W+0OirAORAicXGQS*&qdhZPclulqUNAvVy)okK+&?U0(bLr}LG((_N{pQBl=(CQP zF`Q2If?yI$U!VqLL0(r$!9*JNz2e8k%MAY3xFZjQKYp+srEsl1@dCWo*_GCZX06Ha;&ikYB_MTPmF8)LBPj3gX3>7#r-ikg9&=P}J z1ryTDjj;1AuKns3Kr~st0SpZQLdHBjpyp2LkCW`ahHI=py(7s#&xzazEP8~Iqw+=C zSWN$+Hfv@Jm=Vy~yQYE?7Qeu{`##TQsy|#+-Y=PL0WM^Un5F;**ldU_lHMemDWqL= z2i3)$3usTo{eeS_FW$s|e;##0qD>UdD?4NIsJ`FjYrX&T<&RwrFJ3@5YRwPhrN7%d z{I#XxbNdU7!Pf`jfv_Nc&%$xm|MZ1h^pU^Mnxw0hRiIdJ)Yg)#ur-FmWYJeg)2ED` z|JvB@(7IRQUYlBs?mNng6~qqb7twj@&t->%oIS}VB+}5vffd{|1O$}nyttMw4RjQE`cqo?)ECnnl;3}!=``#eY% zxKpuEsZv(a@mYOTZb|#<^yNyW=N%Gw)w$|$*%x{ffN(aUc1CK zTAy_2{dWoN%(yF4#&cbZAD!P@t^9k9tlRkPI^I^#gpM|T#EAAwn0Xc2FFtu`x_*SP ze<7Kl{q<^Bd=&?=Fwwy5fAy{7nx!J)tB)bGHqe|DqekYsAlL2T5OW1X_&6-sZB2Kv zA})LtH1Q7yg~!5@G%JSH|1kw4tC}y#RH47wHVv37^fn>N{SX&Vq)8TdcjZJIw(i> zU%D;j7rp3RZl~&}Ra_$(rFm$SLqu@yOjc=kPCWD^k1xi9%AH&Zh$qo|Hj%+R#sAkva#f0tW!l(%jYrBrUo>3hw(dlY{y)cz0rscBeWMO0zzorbcmrTpXZstNr};j0e*1)v z(LR3K+~^f-KK9gQ3@znVSoGFkJ4fs5BS;P_s`8P|MjlKcaW`2$3?5@NEsQ}x@lsL^ zCZX5=`AtFjRJlKLF1~fM(oz5-Kg8LzdoLIMEq`Hj#i`xCz5%D*ATMOga%L2Bi~%h& z=Zr``y~(&&QsWwLO!_xz^)X~T2Cfvs0#Wx*#Yaf2cv-L>GqPLC!$fXzS_YGpIVkti z=0tP_oE{UCroi301&){~M`2BMpNtO1!S5GA@qrQ!f2v__Q-Hp~D9*l>BnLx-G zPE=cXwbiuq=E!wkthk+K937Q1$6}jhB4=zK|3)xVu*ef|t$p`TCkaRs%6 za=-*Fh4}GVBEZ9{qC5jh*>)nK!mCku0IpL#k$<-7lH=f?>KC1P6%5Bw&*32TD94Go z{--j|=EQr&kI%@;&a+5kU)xP{vW~M0SthJLI1n$f!RTLBMBnPfnot)&D?#ddFYU$h zbkhar809nFpGnb`ausXhts&M_`$n=p!!!ZYCSOO-@^O6rYA}Re+NF<17}(|TBBYdw z_m7A4CnwaNHMe-{pJLpOnYIL3^#YjJq<~E_Zlz73=I37`L}7^%6LXch&($ ztEl84QM>Jiv0+bvQRSj9VESKk@UlJ(M~G64`iJg{!*w=ea?zqnu+N!_;L4e#>(tCL zbreWnGQcp1wEL^Yd9B%#pC%Yv=^Zyc5LoWxeb~M~NS}v}D^G6Dp$#5Y}YduM6V~#E|y4Or*a-EHrQd zzm`EcY7`R}G(Dh1sU(09g-mgAnpL+JZQD&0IC71XUVoxQyMY}3EW_*^4DmR?AXHOL zNyO*f&{6?3KK`W#I(~C|@1P>dX`=M0Zs(U2s^i2d*j(aegM77V$Gqg(o zyhX&))l6K;)lB{cqWNpFi*06J^VfXc?5^#Zr2{LlLnLD#U#wm-7=Hwxlvf1#A`z53 zo=$CRbei~0Fa;8}yrENy7k&nLddgH1{!8|tJB@Mr*UR1ctbu$9;h4$5O>V$Ytj}>|UzXWGQBYFYEZZ09|E$5aEc0nE zjrfAYLB9(m4MO58zVEZIgG$3xlK8>on<_N5*Bkm-K_cvSYrDSJNXSO7@*B`|ciBs8pu=9@of;r%t?s zQ0b}Qak;yRX7e?pm_8tjgMKb!nb7h8SgXoDliIBb>U)#K8CFEMmW4avp|y!UGSe{v zCi^V>o2x-A^n8Z8wD+EF@>$B)ns}K6$-g>T`}WM>86>)1&Pxcsbu4v6%H}@dX60)7 zRAW&w?E%VZZH_J#W_eaGYtn(1+?MEGbhLsFYnY#>Su^ve?oz5$suPA2A=JSI%Pedc355E42yLq9k zD}?P~B|qX<%!<;{$`3 z9{iJ=0%#clBD28!8VhCh0A-a%QuxxSPeF?@Zm^|i2Yk3te`eN~-~5o>he*S-v&KHw z*6~&bQ<3IGe4kj%tRH|`4?L#TL|&yY`8LnvFjI)u9&>wb9_1eu5rL=947gOI`E2C^t1`zhuSH40tPge1_yZO{k%w>6@~>8wLaYm>-ErWlFEn(%`P08PpSsO zPqb*H`yeTu4KyFnZVi_`V<0XZKSeeRuUuda5Kl1 zrWs59I4tS=Tloi`u6T8OneXl;pTyjWJJXLtW4xC+rt*b`Ps>?0tL4V4I!IH=Am`&Z%!GyFWO1YAZTa#ybxz_k zZm`NmI?}hntJ=6xf+o*Eu{Tm8^HgbeVv6;r`_oQS{!!86(Nn1;oqfM7?aZ-WolNFK zs%r9Ym2XMGV`R~c;?Oc!)Otbh6)=$sj|B-Is(i3)dxLPI=Xcbm_UuQ5@k$j%AB~oF`-t^?R>+ZjHnUX^j zT-Wp?USLZK^eRRB-`mgg&(;~&tW@0~iyXu)uqD~vJ@xC@;GM2kPdHe$dF-Sv<b}1N4xP!AO1PA1P29f6^3L zODZ2?uOQ3Us|iUJ@lkp$*az1~`ChMbm*ls%_Pu^qWeisOLS71#g z8!=7y0d2bh*T6?A4~{79Zdkl&UGC7~Fi}`93!do@imFA}%?cSequq;>JHw7vWP!uE z(UJTF{;x4c{rE#>+BL89k8WSmZ>f}f@N3*&nORB`JSsE~F+v^nrI6U)c;Xf}Yw3z0 za*~}|_P*p}t~iDnyW2zX_2l=H>M0i2WgHy|_hY(;!j_+eYb;=+{9Fp=@}JLlhGk8J zn}^VNOtb%Ve!TmFR^!%V$3tFcVXMF4(n>s=EH0y5HZbdm{esZz!m8W!n1oJZWLvTi zk}LaRk{Y6it+>kXPv5tLze3sz?*={Ol=@?~z2r3{(+D&GRKZrp-xrtt45-sLC4wa^ z_qP{VuSlyu)-KOn*bRh5sGxaYxmhLf;gQK$Xzq+C+2!SpT7^*CHphdf(pM?%Nur7d8OftZ3!67So2^ zQJC2C6urPD4WCa@WB4*HI85~6R(03a7(?{DD zU|I%o*6~DPqioNP?rvjG)~9BoiRu+l^yEo$C9o|B$ss!YR-3>4EG&FT#dGob#Y(D~ zJcmhNqIw=6iFkmje3Q<^h&bU9V?zCmfCg=8kXLnv{o3yfV|y{0zjM@l{#fqD`mD_q zd09k{n)tiGint>R;5GPT=lA)MCz<^yso(HXST&K_tTjyQy&W!O2p8S)6J%tk@LwPT zo{*s4K2nZ5Euc^vpMIqI&LU?2`Ooc@SFZBRpZMcm{rvqNi26t4N(&xOyuPhbAA$YH z-|78RES(w^1R2?rfh#rljJuCa7k&?74pei*V(I3P?OghlM+CG@x(Dz3N6YTGP1HOg zJ(UFp9ANT^6G#1^_-E)PEEN3=G47XYo=Bqgg5*nP9DAOr5gt$j>B*W=|NMA4cRFYJ zP_P&8QKM{%V`QmKLR)q!0r1OTSo=>L^U30x>l87oZ*12{8_sxxhIvY+AAzYT&MFP4 zK&RA4B{A^8`hu(Lj+bzD3}4-|*qapRyfrj%$uQ`RpfyIUbk2<__$fA$3$PA0i`_FG zjNt#7``;Oh2Pl*0KrKUNTz<1J!ml;E+@QEq^W<#i>Yeg9ePK1$)jyT<|1nR~qKg$m zNDu|gkh|mb2f=jMh$Yr3op@Euvv}V8ihRcQ zLKQ$sRxWq^t|9~W6$HlcmypZPAbpe}XwkB_ZMddmjsz>Gk1G%J)GJ(IKvt|%e%L63 zQ!|us(-N6IZ8wPTnNjpH)c983G`vkv9M>sX;&KlC0XyBP{)zLmPQ^!!Z;J|u9W4@a zI@l4^0`BxEh0^Cu-_OUxH)*^}o^DU85T>IAAG=?b*|@$zeA!1vewHQp(?yH;S?MUt zT)cc51%23SI9$2go&)NVd%|$vVYbhxj@k|5V91yXxSQOyNMaN6t{@C~O?M;u)N&5h zt?5KjQ>{4GRPW8-p*{Owea2`Qa#9>5mswE({uTxf;`{QYW#LKmVSq)pQ`cA!DektL zf)0|COrZy|^!t<$?3PrKxC7ToTNxBHuK<4gWHxqvtop6EQ8LAM5Bp#Vtx5+{>bPuf zB4S|H8w-Df6q4-`^rnLqD-8eXdxgrp(A9FY)PC5kkj4sZyn`0y7i7vo0yxk@Ss~M`P72a8 zcX|h|rBZ$`=MUN~Wi~D~SHce@z?j;sb9MINe~^&47&*fKGtv3vFCnUzUG#@Uc*Gef zip&<(o69CRVY}0_NZ_5Dh|Buh+$IyELEhTw75 z>U$6;oYo&2#MILgHLdv0hCs0)2rG45Y9)xhDTN(S83^k#LtA5O2^CabaYU1tXM;+# z0V?RYU;N(99cK?!zg(LwrtIJpesStE>lP(r&{lJ{bkf!xV8`dMspblT79M9$qU(N8 z+Oh~*zkF`$d%=jC`x+3<^lrh1Vu(dxq(2rK)X{Yl3OgMX2C};uRNHqi9D+>$eKz9^F(xUj$rov~5^P|&l=LJ4q#!CKt|2d!0>uefk6oIX zbCO~hpn&$fNv9$3lQS2}szjdp6>EIqBjni%7J@wNY4~MSlkc-_GSceF8v;#cj+nkw zl9%1rMx_G*rpn1VVxLWT%>q_few$G2_9QD4fn)x7{vV#mo=@G15ZYXi9!wa0I3mM` zsD);}L04!4-$|AxslhJA!&X*GoYIdh=)j(s zt6?P?XEvo|+Z0|Thu2xxBarxt@`txe(^F+D-e`*UcYv>M2=RR?NSOG!n!@qHJ?h)V zKUQ>ZiQ6E*hFxUWZJ#ecs?u6*JGLF{@9$iGA*zW?0-02f?b6-BI@Je9G}tx?(+r|d zQmGn9Mw$M}iu+~aiNBns2kMj2Gu-{#c9rWQqC5~Gtsqr-7S}K+&fN>h9vk0>5v93x z7McVS1m1)gO@rCw0}Dq^!)}q!_Hn`PSmvkZ`|4eqlE}s@ojSyOD7yze=!Iyo6n-kI ziE>49DdRLDN92Sbzi!XaY#T|s^-4nvI=Wqnp-XMwjfF84(pn~5MVMwV*Yh0+t|mB@ za8rz%b&m(Em;o%LPfv=ZFQ>&_=Ha&3Wo06WxnfER5}-wWLq({RqADDd1Dd-c{6#E< z5eA#agd0HQrr(^LnmuBU9>vjxy`702UB=y=_AAa940r_K@ksp#1pU5d2xKR+#-&X> zT@U}VLS?<1oc&fxF&+Tz1H-$oV#AG6H=0fCl`D==~}U=LD8wc z|3(fLNEU&({gk$OhSoz`jC6qtCxL4H$HQ`Kt;aCKKl{5P)q91NQ?3r9MPJQa7t`*o zzoO%7bJY4xe88L2$UqLBQYts8C=%?`I6ROORx?kaZr=QKK>JaIEkTJXi!w;fG z=WZR&asX!I)yhJuy+|JXgx~WiAG&lb$tz?&!^yrAT4XSu{nf1cCF0~Q-3WMk`56(` zz?F18_8mqy-VUHgz|>horm0UYDd?FJXYJJ_a4geo^eA7Xe-O1a@|Uow%dS!OBXZfQ zGvb>Kz(K7|!dSdKFfXeeWhUdAIhUKF^e+Wo@}Z}!LK>r(FJVq65X)$qUsiD44Lmx? zt3xK}R^`Xe6fDnFz2Lgm23h{)a&8gk9G*(Mky<8}qd zvzv>Z+yIM>nUQ>+)II`R6*@ZC;P=VPFRH5!`Y9L6moJ*n`3!H(Ndd z_r0c{%2a0x(id)x`U?ZM_CGOOXeANyp>%Q{ z++36b3YGg{RFRQPeNyM+TJhv(Ek*Q15KcE!>Bn>|D#`nr*i_7tNwoVVx3WZY$eIl z!&UbsP&O~Q?w^65c2zsR>>1Xs6_c(t#c7TY!#(NL@ebkh=2-f*QbTbV7Sh11q!{S| z8mzV}OIPREZJ)D<$M8o7dF2lnnGld-=BhztY6}tpCxE#I{qTjblQc}PpKZ^@p%~r_ zpDDeprL>6uFRuMjv>6<}e)7$7=bK#O4Oh zFsvh#?O*AWhu5gEcnWuIbY<)p`7F%Ybv9CBefk?od{ONv4u?E~T2FtX@a zncv%(sqv*-2MC;g_p(?hs4QoTOqh(2JH8noc*)gnn8XNjvwrPk=S(r_rMSdz8v z_Jf4^2VYy&g$FpJOy-I`ysuKn??fNTJxW1uVcc_j$BU&8}w@H3zPR;%Cr-ca6_ zF@AxX-%I8Rz%%^bMw1sIN97Eg{v&m`;1Dv>SlA~UOe$gI&Z!Rq9Gf*M<(eTG8C#3Op0&p#2;4%?(dGU z>(AKqr|Mo)#NIT-T${u|?X9PsS|)F5-1d@T5;>HtvcAh|Z@pIP-yCOjOn294?0C7;qz)1mn*<=|$!C zNXB70Fhwza_%Xk(M;TWoER!fuNyPhcp{kMRTMAq;N;-rx@Ck5`v1R&N_!Af1hOCX2 zH_4l3kMp+5wzKv3?vTQz;VR7v)54N>h5(q-$p7`=@1k+>!>`OJFe>aN?vLWxtSyu1 zQ5ZR(-<=-(+TE>aWFYUMNs?!0>gSq+X{QYWDJYM$G`Mf0J#SA49K=O)Z(572rfc1` z1zOy;{ma>^kC5>l=pOC8B<}dn+A%>j@nZ=l`GWDciyLNH?jgz_$%LY5oLBE#>-6MRN zf!XOppL~RQuwdH(6&U9%-0c5aVr?ZZ#lsI zzG%Q=(}Okg<4r?*oZA4*fy)=BWpsFhUo`^qa&SC2I_&%z)>gkMQ;!%%R*hn`XFu-y zA{|2(M)EoRRN93-CPwhcpiU5J{@&DiKH4cIN-?k#4@_(DX2Z)qW+kI&s%cYq{0f!vffO*{{mVCYh&~)=|4Nw}{P!bA zVLv6*LKKodgC>gvX({j--Lu#F{q@X<510~YWJVHHsM?Mgw(oVS+kCh+WWaqijpOkB zMP&hgKuw;*a9>jY(>X)jIcpe-Fx{JP0eUjE^94>HG+HAL4<^T2L*~b3oVwAb6&P3A zBBt;khKPR*t1DgW#MCG1p8RNO^F9To5Zl4f_3J-E0kDM^%m!ZZKJgl|Sa;sp%! zTi7JusL;4-sFOVJgeQ^& z`<2nkDxUd|=j>QJps)0VOn1b3y!IV)kWs*5yZkJh(RcWX`T z+U87cO=A+`{q#ls`gD8J(S%Uj{@17$)`*HNeI!iA@8@X`fdmX-%gauvNSXOk^Y>jl zTcz>ONh@q#xlAvoBYDgH7i+vE&t1;;#CPHXNTMbt%FrVlPU3G6_G82<7B3-Ww9|*Q znX!n`@Kz;C+B%Pf313W!{+wQRd}i<00|b_E7zCs_Z&-vY3hm&tsT>e!e+vx3Qytp& za!O=W^+{%0ESE+TJUl6zbuU`J(p9eDJvFcD{P0`mX+n9~QCRI0-)6dx`M+H*mI~Op zULfEq{sv5sMGG2FJ$cM<93jpq-e*oUOmZ;H^t>Q@AjpS$P=~|F4>2s`AXFjdLA>Pt zeBb+21aT&TKBjO1=DPl89=nl_)KZH;pmd~q?u<>Xyz~y@hYxF>vM;$dQ=~rGE{uH! zj8>P~0X}5j89;P-^L9=<Dh(## z0$-vc?N$}DdjbmUE^7O>f954c!yW7UNBVNwWL^)Jkb;MvnBRmymflp)sy&EmQuRLs zj<#=aa;u$Rktm>4j=UG9!9(Z0RP;s2MBF|;nw;^fjhWKNvN@OmuZ?X8x9!BP#C=>4 zvzX`i9yr*scWiHP0ZeK%;%~_52WY$I+(vXA(H%`4%Z~Bi^3x^)kEg)}p>AXXI3*VI zOdN(ZptZCNwA>lV*LAPWsO-J|qD&O?Y&}Bn$s*Ij^&8@qOlEV!e#M)r_^gi|K}2$-fIK~`L-))ZVzzImvPt5eQ+sLb|CM*`nWVN z-9qHAT~puTB~=A(P!ECR=e37veZ8m%nB2yGzWqlIq7ghey##CczZ;Z?Ug^zv!tZ$$7 zEvQnI~HdJtYd&rc|s=IT7zw6=XleY+C@pG&DLnt>Gu~=Fx;A{?8 z>1a_*%z$HiuKeF9EqTuC;QhDE&6lg1{<+vdY-K=pBTBB^ff6i~O(CVbb z_R#POZUdxl8yE(|X>&`im|%e%o1l{cTfQOIf+F9yTCw5A<(U!=9AIT${dC@UFb73I z5Km%FMf~I5w*BY@rY3+PDiuv+;+YzPo!hu0lQ;vDmu_$5gT+={n~O9bdUf7c1&*DC zzkdDnfJ(zuXso7z8o9~x`F|kCZHlow(TkSxpz+kun&c<6kO1px3-b=%@;R~UA|2vC zBN?p$#q=sX!0DW*C|7W1H3k~e4@Dn%3Q!}caK%SqbOO6o(53B9iUT7`wmCkkrg`Jp z^27RXA^sItwHgROm#^Z`)gAQMqL1E*F=ela7?IJ@-TQ#tJct{`2{S*>{@!{%w(LgP z7f2qcV)gN&OR>qG@7kx+#DgHz=#%NcNFl0OCtr6)A!nEhsf5UaNN|H%=9_%Jd5GwO+@cjfy%r{fk4FSz-; zy#S~9U6pEgcew?LeH+-ywdqxFDlTNL<;BvL7oQ$LpS_mS+>3!EKAW5KU#=$`lf29+j>LHM%Y^=BaPHX>Fj&))mM0yDCFus3Z!hh0SgX^3R?mCnEGK>?%y#pU(nc@YtkjPeV>Bd&i8eTjV>@H} z->N?wP!kxPgx>d@-BPV55EwQyLR0m4jqL*7jGEN7)!T2D4{h`RF*6Se_ft^80&>Hk zvK#5J5VRf}#a8E}N3q>xes%F)T=Vq<>} z7ck*IOP_pP0~3KY7nKsuy)*n>;~_1~U+U*(ZMjU)%;#jivV@GJ6_UB`hs!7jyRM4T z+2B%HIniU7`~3(ZbkB+dv;FN)9&jzV9iwBTVs7kH0+=auYivS@9gm77_HU=xX0{6w zO67@FUUs_LiY?#Nl+`Ym@*J^qtbeN3RC&u4-(`pzkno&>8C1?YeCQQIo7H!h52)^` zH5{vdIX9aS9r2P(HiTeezZ%ttBkGOH zV0vjQUS({;S5u@ipR=pW19@+r(0bNVa8L)*ls<1`pnnPgQb>NIvU~Zm6Y`9SqwqbI zABPLo-m7eew<1D~rq<`_e@COl+MR;G)g)Rw?yj?h*DDs+uZmR#@7H<>kPdsacxZL( zOE6~;L>4^Ek))DY*D*M_4Z|2{E3|d>O-@Xpf*QLqyfJnK+Pkm_&BD<|-%9&F;7_ z1WqKRBFxYB+0|x_H27XL7p2%WDYu%2UZllUsRH(^*vPZm@4!JVveB+sTL5@9QyDQg zEPrRTuW8S4Bf7`+<*n=nvD<(iK0@!0rKt}w>)TBY&oqmcU^;tWRtFn(N&xS#g{!GZ z*cX8$#A&U-(B$U+2>a*Thf#O710jP?}QEAokgc!NKMg$LLx-Ph8J-;)Hi?i}pl&gEV7(!)O=ndZv8ChX&ZV|#>gwkLZl)NPm*y{h zB5!f8n^Lzn`EAuY&_?;Oc9SxQkjDZPmyxiJ>)hr*!66d^qrOtMmDeIHkRmp&O8pv_ z6qRQ?br5}SSjD`WRyn6WV=(j?!^k&&%9CC>UJLqIufm(V4ytrB+^U=)rK6eFgQ@e+ zVUln8I0DBF=yv^GzJxtlOH!;gz6R3S+jn60KA9f{Nw6< z!(mJ9#$`G6|uiP~F=5dXOMcxKw7wEFaaCOxi_j-tVBi=!OKK zR>e$=8$Vu~3E}=B@8&m9@;=R3wTr7JP9JTJUvcRm^e-q2ovb`$(^m>!z|E^Z)88jY zlh=Gr{GakYO)2-UAMLSkB+fY$^v+Q6(3_>VBn5(-6vUq<3I;t~zroR!?@vaBxh+y| zi2z1wVx>9+&)#$ozcafuC?Yh@rO!aK5)b{|XX}2*8eEl(TVsVQJzCeYEPS@Y=NuVM zSmc26%52@r)FNuF(3jFr2@}b-KGK6xMT;Z=Uj|@`jm@nIm`J&=ZXKrwz788WZU8{s=HaTkZT}shq_T};iDHS7^`~~T%#C+qt zoiNRnd|en7o>6oDej|rK!lfeYOE-&t*~3`dWJUVUZBp1uDeIjD8#m9Uu*mtDyr!+e zTuh&sZd&rVS-aelFoan~;H^oyQ2kqXxknj9eoDzY21@PNivnF_)Q|{rEyJ!KjO%qA zn>I?}NoNUSmBIOM;1ZwZD}y_uZT@W;JaWkSqy%%hiJrW^DVhaJc0>o&g!+;kNBnaX*xq?U}7CoY2*^aWY?XBS(GXDV}O| z)%6gC?t`kc4iS;R2z;W}ey$TN;>mrJ_GU&FTX*}^@(GU?bw5|yV^b1T<_`Zib;z@)D_bXK#SOp9zJZvvj;c-(P{lrieW0! zfPJ}`mE`?JJMPCgJ+#g9Z9|m=1$w)QRDX6kp+Fsa&!v+Z4GYc-eM?+~robs0Cp+EA zcNFZId04J4xi0PKA+!Gmyk@0Nb{T?Vm1KYO=~GW4D*TR{HM6pFN>HFP4N*ZdB5D*j9rDDcfuy;d?C<6s6 zd)Uut6$_IZk3ijC`iG&#+UTc$B%?d<_m`GkfUQL_K~G`TcP{+TOz~#mqtL1!l3$J2 zTtchA2xPtk2x@1F1e%^~h2Xw=W(1?^??j%?Y`enYEmdj59=O9)YsAJ~kvsP$N#;^2 zLO2k84O(KG1V5@LMVyHA-|vVRqHk*<6UmrB>tIR>@qI~e;8C}%u^r7s$M#Z{O+UH6)BHypP6EoMk5b;Tq(()4 z7<5x1;FLHJqbi$ne>g3$o)`M=;+eR}ieba={)mpms^I3YVVyT?WhR;qrT?`q^i3g` zLE8*=$VCq571irk^*yd{d1`eblW(>z-#`3u8I=|54QH7*_eGlIcPug;Tu5>kl}U%A zLk-!^hI43emCkZg>C6~1%*``tzjiXgdZtbDW5RypvA4vZ&{6j(6>UwE=pzRaFDfy zSmTdcHA#?2Gjo43xJKkCl@6(Dyo6e^L6BWV|4X5_2`wRnjCUbbwGe~dZ%S0JQkW=F zHmt7w(-9EI7NTTYnT^*kMd_YTM<^T)pq5fIpygyx?44T?fGb}5(Jg5%_k`0~y3ST&S$=Ba4g*$m0h-sRQ4Z(I?ViV_2 zUcj}IWTVNY26SOd>8&%UglP3vHf528wB_UIY(lL!NMNdotD01D*5!dbaPq}!KBVcO zEUWHTY<%4t*t~uF8dXhAifph^fRS2ePW|^OhN;J(Xi$_reZDL0nJPOP?)Z;fwNKd2G}j*W@RdzWCNXCtilip3(G0I^>eVKN=ewAHtJY7)zRM{Ki{nE18#8P7Rw+G+o5HHn7)3p)pbd2Upm@ z__(1`;ZN>u;TLYI1aJ^+-Xk06*S4&w#}L%QG_!%{#eI((mnpxO*7(e+o5Xtbk zieGyqRWDG}*l1Qg1!MseX=X&_%y4ML1blAFz76gV4gLdoGc6O14a*d6q@hKM4{w5r zp}L!xpm!%WKt94mnu%efta1XI_>Y-Ws7(b58yh8J^ITs??>s*xlC$b{D@|481Jeng z+hyfs7_%T7wSHO(EIUVMBj-u7E?Fm44=z%N{31R)TUnJf^t#-qrl903GYw-L*M zW%mSZm>N~VsmUgTn+UYsED6SGs+CGlZ3pItS#Bwy?93PJBtWe+7#4IxXOE(b%<;Vs z0qo@vX;LC=#b5f;s#$*0?AmpM?hB^@ND=v_U!!Y8HbTo4HiRlxw3`$b+!FACVF!&! z)hICwpjp5g_Q?(+K=ZI!>)8BkOVAv)D+LKHZ%Y0dp|k{>#7`I-R$-B@Oa-(r2 zg7RR!k%bLi&`g01C|syGgYVt_DqX8*ha?-I0H(wSc0tK&8!VaDP>G;yk$O;Ac{bSU z*fd1#>V3x(Y|MnqG8?#FfXh$urlgi^IQZD;<;{YG>m-{S=*tSAfD20E>)x3cdVdg; z7=x%0a|xsXW+D995xTTDPzPybGU>xDk$_(gsBuru21eJ_7SAgI0hb9V8z!Cbu8~#u z;%pK*R_lSLowb;z)yJaPEpH(~vMu1b=$u4M#n~eA{vh&clcL!PHZgz+vND^<3ye$3 zMmDhAYf5KvjmU002hg(W@Hq9LfkouereE#OuTkkt<5P{PPO+=f_&)g;aaQQ&<(k9$2 zhWZ7HZOsI1wuUUp-zhe*nN=<2Y&aXfI?__<_Go*fNb0b#AsdLX1TkY^!>7NwpM3k) zgNHX{PF$yPjdEcSVV9L6a${kzVk6?5K90ynG>j4(A8z#G$q9edtl&Zo&NJ~^8@tkF zh3wJxGM=yjX!i6%Y@qlUx|(%Jiq!ZzWa@9@Z&ka&#?@fh zjD)CAvF4$C`q;*2qt9PJLO4g`RSbIuM6Fji_~2cqOR<5zEP(DTg0{O}XgW-TRjBq3 zmhL=g@r3n-FKlgZLdp2`mJ!+T6AkCbnz=(Z;kHN#_grBIhimX`qSmsrY8j1}0SDW{ zKJF$7kd1MgQo|v>>?!ezdaMYXg-Wz>LU-2?$Rb8~0f5Vagf7gcas% z)Z|Y*YD)>5c(zk|^CCRUmH%oN6Sj7fFZlWbJ3V;fyhmj7 zo=O5Qr!so+ILN&iuJ&XX!55g|iafvsgR-F#upb*6Sbb*g!)P1HJ5OgL8oHKeqjl97 z(j|bgId)0XHZD7Pyk%l648psw7D;eW3^=(g$Z5tGVH0|!TB{f~+Q``?cDmIl4LGI`60!(&RHd8!YJ;{9$bB?|!A&cxsJfY?O>z6H=b_ zwk}h;`W&e5IBc*xXx`5NVX5b1lp5m}8%@B{x}X+Pu^LnHN@#133$an}zA8)VEE_d@ zDT@s5AB}#yWgTkrF}%iMLyKU2no*i^ER@x>-J8xPSLaoce&dZ^{8D$6>`9<68*GlH z;C{|av1yccEH>uL+#8E;2*3e!(-4NGn>`FOA)!>!?J>u5QUY}@81;+@xSFc;Npi9FRYE<7S!_Z_Z;M4H;;%%)Z?b)Kc0 zghrG&S8P5Gv@9^pJMXjKHw5L5e(k1ZpLT(EqxP*=Ya6q76wrW=`jo92wY|?E?WTV3 z*Q&h~TFkNfw3hj5l9a9WD;z9VoINKZ{zu!uBqFsr4#K9s5kE9G>N%;ZVh`zSB7E;| zgze1ZAZ+T_k2-fdv??vn@6MUG%-5z)FK7%s&^NWQ;QLKuv~B?-vRQYNgvYMaVfdd_ zvbqEtHBGLFbEC0=&3D6?LDt4p(4>QbF# zQ!8!t{6;htHYYRJB|&@VPOzK-Tzpo&gwN)nb{3q!s>*XcirmjRN_{T$Tu!R*cY17L zmw5?~$Qd@4<Y=cmqr)?!R={LB$O}uAIB`3;i*gi$R;g*hZ*=$!i zkwrPhM%FtHq=5Ps73F!_R$>Da0RoBsUMZob2{Yu5MmPPaOUhUicD|QjQ#*wA&HmUo zp`LCf9Qp!5qxwYT`eTKSF@}jWjhWNO`$R1L*sq7xbFkU}lz+LvJvOr5`s#S2`fPQq z++A$gkkgoXM5Hit6T-IP7)AEWN~Jm~Yk!-px0*=8ctd(+D90|A8lKvf zS5Gp(JkXwXk-pRtlK0Xhl{T`ytH!7{{*j%VivuX~pD*7phZWK$j&f*LlF z-^fOME3fCLpb@G64(J4WzS zr~ZZ}gAF-d^cgXpxyA-B*jFLZ*&I~;8c%H%rOwuZO$N^_`E_Y=zo_=G&vb0?;XG0= z(HXwS{%PqNBwl`KV#O-E!PscLS?(H}|5ueqZ5LysE1@J)Z|AXhN?c6&68@nhAuUdLOlYTDSO}W2=^JO80!FD637D`4LKAZ(!ZlzCA2g>-^JD(W4_7I0&t%K1n zJ~iJiWmMTzdb#9JZgH5emwQ51Kh55i48QH08UC6Zge&p5Y2k3 zYI=BuMD>miY)0Zk$q%8P6znlPT`IlcL}Bmz0H5*M5Lxa}mZP50PIsKJC(vSehoMo> zRG|5u$jS(=ve_8n;DFa?a5k~(z*wZH#D>2OZFDy9N*+=c^KAD~&tb1SPS~;U7=ulP zM0Jn2#%5WPGF)q)7=m^)Ash4J_ESl)KF(vGM35%Mfu_nvTN>%vZd$N`&99=}tV-g; zRjJXZ$vtISgDxc*!U=D;Q1{kohL>dHd3(8`LZ_h49^JP?{oAmC*EX>n%iAX4J#`uz zkU-w}={aj`DLAlkXD+~AmdHWq6nImDI_bVGtBBF6Y*dy!n+S#+W-YV9kDREj1<2-) zd79DL=u3&b%ySRNei^XmH3>_sQ&5W3eIZ^Ru*j!=yRji=b`>`9J&#b5#!Pm$3l|la zXXjGR;8^x(=VtvlVUhKE-^uj4FL?H6vyxeIi`H&@Gc1Kh69&Q$B#1h)QA_F~lU7HV zq&d`X2*@nPS3WS)S|~QUZ>tKjNGb!7s3V&w5D9_J;YaQ$ohc$p`6xA9DYP8Za6^wN zlwtUv=Qy5`T!^Dn5a%h(2?AWtsF9q2`gZ6VKM? z+OnJ(aYEOJGs+U@B5xr#m=#wV*tB-D$B>q$!lpU|K)d0m0N4yuW<$FuI;T6uMl1w| zKFtu;vjZdNOE`{a6k1{vVpeLysm7*D8J*Z1N;yX!v>RV|=IkbZ9Dv6uX#|^y4K%<; zW+Sp|IOYxh=X)Q|$fCrCwi|Vm;FLBR3O>Q+6C?v=^LA5?Y_fq5KM;(LC7qIneOwCS z0bMZ3!uE70jUs;XK-h*p9?!_I#D9ISU->yn+l}C5=|%3XMWXTzQ)L4hXL-K zo2Xij=A)~cde^Wa{QV`A4OKnMAosu_*nsS7I@Hh{g{)dhhBfl}LNey*t)q4ImYxxR z3dhk}NOv~5FEVV@MwyLyf@-Q}IaS$!7Vl^nWus+B*@($6vVqKgW(}ZG8ZK_^i&v;0 zV9deyiB|*>6`SmM>{gPYC{bU2r0qsrkHSa%xIkw3+cdeAmkjX0stv0GWjT?)a5*SpN7Dd&>* z`K(pMW?C06II3O}J+YC&6{Tczr=Q=+Vq>y_*h#R)bf?(dkpq<R!Mq|U$)6fvU52AOGe+nl`OE#-NU(>TH zBJf4aASS10-AtZ=fA@NRN8QoF9%?;Mi4E(ApoVZ22X?_mADn3cB{m`TEVKDaE(BNE zz$SnVO$6;m`{)ErpO>(wLS_$cWW(kX@rk;v{~3YEuq||j--5ju8={MO)EzDCsYhfi zaplh`Fg9B{R%3t73qVb8oLGFGYGuzm*Ez#La& zlfCd|3bZIT%zFu5q|64CB-sQk9{a@x6MYjvDPSlYRxEY@7TClbDSF^#Xxx%bit{-v zb_r({u123~X|%*qe~w*q4`F)AO%ogZq`5EKP5MSApy}jxKAsDx0Xo4r;7+D$d`3aE z8xcYyKsmXLDeIo-Z1JD24eWn?)koKqJ($LpHcpDNGcAx>?_Pf=xya zIG=+h&TrR6l7Hr{3&3+>bL?FHuR(5Rgx2`Taz}mNLk$nO@l}jBvPJMz@F6L~)U$z} zk;fCIutXSpnG)V^RuD;Jfo$NsmnH&R(uz&$Q#LU0rKCvSt-^&UUS>AE<=DB%zwtzC z7h0>Zp?$nyg9_43>9v>GmB7S17EyS+5l&EUpzIJ6KSrN%HgK24U{fqt;?u`8O?x(p zzu~J*Fg&H+8U`M52I{3xYd>}_4j%3xERkTt^~$=9_t1^R-}tJBFDv_AJFy`j&PEa} zN7vb;#b3jH{A{hWq3M}CFcPiwuXEE~94Qlv{fc;%Bdogdb-M`J5V$8zDv_r4ICd^D zlwu1u{QXF*`p5>iBC+i)ko!%kgu8k+kb;_u618@dyn-o$4`0ob?Iu|oD}3QrpX0+C zG|c7xm}Yxmxi|eLFo`A@h*x8<_yN!K2I#z~*>xx#R^4G3@Sc5B8VL+GcR+<+n~OJE zZAv9i6*_+&#ptsxR~}|d)_N?>0R4yfDOAg7fLpp39KZW9+b_t9UJ=e?>Y%ma!bWd zR`Dh!)XILMC(y1mH(2?Yj$&C%0*%qfa5@_9fe&?|&*jXqL($OC;mlpZ^q(aXY&Zqh zP*4eQ@u?bsiJ~Z0<{-=2!0F12Kq}n&c$0YW6z)3lQ(RvGldQr+O3=nl{CTA>qOyqP z1`)4vyiasCmEg;G96J;XY{2+%*&NVRB{pngMo-WkgbO8?*yL1q)fmrro&NXR?`z6^1q-Q33kZ#U+d!!x8WSHex!B-dP=+jk-z^$uKT8+FYQBaH0#Rh{oov&!W*^V6)JiXl=R1c?KE!3Hi80~Hn5_$zE!)DvuCc+lC`GIGMY>n_ETjS-bTEu~pWC1~v? zBC3?+yAm5zrp6{#QJJmE23Fcw9vNID;@Kh%uwl(a`oP?S+ND@ph-Qu9flXg?J7L{* zmI9xjPj(=mB0nJzOK39hJP}PXil**+?abb^|jY z8i0Y=#fYAexj}irAWn&J(mst|x8Ao;uq$@P=ubm!mnea(-!$O9C^EW-w>>M zf70wuSdVrocIDs*FCbDvy~SEBqW~8h=)0jo@FUpV(6t@0>;=!c_#y^7;?-jU==gOE zLlJoaz0m+sYT1+<%L#5<`OGGM zBixhow!{VlY43JEn}8Pd0NK!biJxo%*LFBd<&8k}EUbk@jEz)+Xg3F{n;Ki2Q z#@w*iC~jcGZ_b(R#+<#2JS<1vnM$!NQHKZ$hRB5HaqN&6yGMXsP(V`&Eps*j)tgj; zU=vd|B5vgcefbh!@d)jv(oFcLi?~0NlV7cr+n%Ko)3OoWyhWh)LC5w{>CASG8}cHS zNL;Bf3ODSEw8AC{FkD>Yn6owvz$cQ^w`r9Pm+Z`T!_Olr7SDC8Loi^*$1ZuX!NwQc z>P$AvCN@50$2y~8SMJkt{5nbcHS7;(k{Bq^%kU7h_kcxi@jEe_7813Na%>$FBBq}O zaH9KS4a;By>sIxB8f?qMGB_JZPtYk1ygUQilBd`NGKg7>K8+N8Vj09ATr>`bJ?(Lrs~s5!k^_l_DC(} z!(t3!Y)C=tFWZM;ldb6`kMtL*c)@V}foyo|s$s(iHy)j3)1lq4yGl&99(BEBl3kC& zVbV*D&@!a}=YKt$oUx&e3X_RcEDu~XfCp$7Dd7tWm3CvYVc8gC5YMRLz-N1prQL)9 z(}U15W8*ilDOOZ3QaPpZ23R1QY}LfZ?9*7u9oTSWvUu*khQqOkkPDus%;r7#E6r14 z7;{VYvf_z~ln5I=QZ~gRhetJq+X$CyKf3SCM%RXBR}aweF+{W*Jo77TZVL8rxMUL( zEiXDn2G$$-Y(}L|I~dWKqdObfrPk!;s@Ji*VB+N>a$d~X1at`+um5jop47L1H_w*X zM7~iZbXm)y_#mHYstogs;-irO9b&I_C7{vck+2a{ftGB@;TFbw(f_fBFf|nd8``8` z7ZNpPHkrp4>a;XH*zhK`72V3_{k4*m}Y8?mT>QP2oB zVlxwFpqmibR20kd)}x)WSF$*jz=7~%XBqgWB233COnZO9CZKF!MCWYYZIWBKSe0`G z*dCC40g;3`@SQM%8Dk?}xs5lBW;Q}sCy%gfEKCg>oMu70fia1(iHkef_fOOcXR?Zn zjj?chhhTnUKw@k@p%)s6{5jw(8JrPzGfL=g=`I=j*tu{u6)@Tj+_^v+IJ<=xaYTf( zIe^y+T=I?!Y$20d0kG^t5fVI#hQ-)?k6vhiO`z83n4h*OL3o@zULTte#qngV$`RN| zPkr@v1G<%LNZ}DsIvQlN1?@AHg9p8Jx}ah7=TLY)TExva8Igtp8$u`9%q4ywL%X@{ z&PLl}C%Pdz-f%X!!t!*TeFxnE_f35$hQR z6VZP3NFQ|v+9B7D<{HPFUB^0Vultw7H)FGYoKFbbJm9c>(8Xu7HiL#}zf!IXf26crzJ~mtpoDp8sh@J`b!`RT*l9s;* zQKvo0hSY_ceilvNh!aMnVA)wxh=}eTcV~!{^R!$YA%V^-koj>o(tW}rQi=(NEqYo1 zTHIx6CqJJXjLAk{fzl*7-?}?L3$Z>B`!MLM>@LD4UzOPKxxr&+lLg|Uh63u!hEqMS z-2el^GhzomHyD$RQQnY_;{cgy6=xG?nrBBgqQ$jh6EsN;a}i>MMWK&wO++KuX~%I0 z>C~m*MrGHPO~8`2VWZ7BRC&~vzFHH*>wrD&V`c*vHr%X)Mb6Wdhuzkt-88dFzF85Y zoDF*?-;5Jb-_fC^T*>55{h$PZpgq)JGL9a_dGVRqbe|J1Z;fpxJouVqb5Baa`(D;`v&GS z1)HBgl_b8?SB)@ioxSqm&}N2#(Va58A*7M7>0y&1mgS~f&RyCKyZr$9^L-$yq^;Tr zM?K+H_OA)p+O$TMizBw(5OT;nXOXY6>&Qm*i*2+h*!)Q7?t3Nn z-5_!b4pE@86Mo94m95RlAlQWTqZE3!+fob3efq7glCPe^Vf$`S+4N_Y>}-B&Dz^-k1Lkl0M0`&n=cQOwq4q;c1=8%;Djn~zQ9n!2rz#o6TEt5a-n#Tu`SXEuf= z)nb9+eag{>%^k}md-_Vdmxq2ZSefawfU#*aim^-``rY-Hg*6y{ObU3XduCJ7VlOtJb#*hSlBMw2FiR}nxhDK^QNWxX zAUqVrBqrm#ZP|?`-iT~?*6eMQdIbQ1*b~CMkqyG0+30GbU5Vk*#__3DyWwo^`JQW) zF-)M%b?BLmQjTU@Y4$GG7JV9LbErHy0?*frHB(k3u%XlEx!o8D`m$+}PO{;X0#)u( zyi1gO&1{rzG+PTDYq6D;D_(h2ZITV26sQ>Ghe?o)55aT0Q91%!Up6h$aW;4GYOj(B zOCMQ*I}e%f&umI+YN6v&3g&E)PO_=QrJqaCvIRD2;LmI{m7ul7m@ZNn>yu02+k6yk zv{&o!$l}Rfkrw(iI;o!fG@%iC?7~Jr|115Jkt=lwHsWQ-Dn?qmX@G1nG$rtJZDu!` zz#Z5aI&RPAV5F<92=r<6CTU7)gWdMrjV4|fHbj%63mZM1mW8qc8+s#7dwG=#bltWa zO~CQl+^6J}^f1^^)~8$8shlnlz8kAdV|+hRNJ_K_cbdJy3d0lb=qV5UHL+pC939JM zHo9`?Qi<+ivFlq7E9)>d>9$3R*D;k{Hr1#pVN_-|x^B9#iG3|4->9MaRIJ+~#7~P= zcBfS$7U_!ZIi1<)x*3%Xeq$1D)c~IpCR>CAqjc$EPh>e=@NTT4y0Fo=9JcAxHu!=( z_-YRHYbOju3}}=NGm{fpP8YlztEet)!a$SaUb8n?H=aj7*}88CSKiRTm}6$6lv3L7 zq6O4gyRwP!RR*UU4VDzqXHA=6ov-%Hb8a=%^|I z%^vQsAsXF~F`L%_mXR--#S>Y!1 zVS&b2U=W4HFn<%vYQpa-j=Qm>RBS?GFC+1d!Juus5p(T~wuuEaezI5R*LG?MEQLw-)tTK`5-T?A5}TBmWk%+! zZ@RK!LkW9(3V#Enk$+Avd&0o*yb8x|EGacMTceDF_&S8}z3Is&pc$mBA7ksyb?>20 z=^zw}(yr*Z8%tI(9KeknlTG*%7Fcw%=*h;Xnee8P66%Vo^Ra{$Cwf2{>q>rhW63Gm zB<3^>FXD|dVNx2=?4>Y+zTbl z1}qT~E`HR$-B${6-nk!3Ld9lns6O?7P}2k~9C{;Esx+;)D`D4Y+!(+Xf)|>)NpWkz zm74una!WRc^+7Kq4HC72i~&HZADfWC_d)dg0yq~d?I(oMjbI^HY4&4DE!l*nW#-^# z^U5E3xUDWk>vj_@ikC*Kpw}?QfCEcyhFdSkefxea5fvMAnK`Dtm{ux8?8gQbZ)l!6 zVxscKIiWTlsetRS?Z*-m7%=n19B(RYz@uNEhMHfAQs9_VHrkaf-qQI!EyA@~_hSis zFEV~=vH^c{F3`K(!2KFe6oSY6nUBBH&vLg7qq}eRV~Hr(OPM zPoEPkQOu%$-FB>TcFACm)fvM`HqTdv>S1h=(*#kj5upPck)9pX*90x>o$L305?ioI-@GAu8C(A3vhFtw zo8%ok2_lcc27$J%Mwi1e`+h8WBpV+V%rpaRpy`;#Xjr}bw3t6QNUwX$D<8ACYjN$z z5>&8B0&|I`hK)(XbafCf5-CFuOoxQ7M%|Akm||lt(EyuOsZ60$?rpT9QdFDsM&yGH zr*9^<0;Uezk5!;#Q<^fv*BnM-vlMJ#v{{Z-tts;zjg6R$C8a4duqmI@=77}Y1yZ`E z;6pDm|w}Y@V39&goL5QEF^n zDw^?)m^KGA8qts1qFqtgek@sqp0e^KdfAPu`g)gEx%_D<;moF`qO=;XFF0@MDKcDwssM5!nmWc>D6w|sd!Y}^u07Xr`QqGJ{&ginu3IksHy3* zemHCrvg&pzHJY+N4wUo5VUw<&_MYPnq)eX8%%-eQxbo~j$t!1emb+$Es#kvdUa49n zG9MObk>K1Y@Jz?Unx+-|b5+ume)4%*8Kp+MQF66sy0-`S54`{z(qGz>DfcI13?E^%GR=pf zhZnq>V@j%igZTu5<^-LYp|RPIrL1(?{tT<}uy%43vzkw+EXnsL#p?-@Ox33?szMW*9w=kxLIY!-{bnHoN_>*C`yr|W?@8ds7nX-`yfm9Zba*dw@ulqnSRMqM2ik5n z58(XLs^Dw(tGCW<+(r1n*zDcaba%-f*p1Hz#pci*r^_j3Hty1y+01Mv(ZB=i)BH)4 zHc=t!l6s;7$1TPmH~X%+cYbYx@#d(`Y>r*!n>4;ZX=x`5>&)gCJBz24d8 zRuyz2bIoAHqp!mPqID!xMprTT%fro`+)NJ1LieUR{8QyX65vYXr+|nSp0Fa zJuBC2rLl2Qz_V)CKCz2c&(`X$$AkMwbbB;T&Y?5%N!DQc&+E#fFK+QKECU#l3&PKO0sdkqYZo<<2 z3Cn6*l+L62`k>pk*<5`*-@zK_JgSe^cDSkQVBNZi%%-)X z$6VH|6~b{gIjNQUad^&b+~w>fn?UO8QSZKWkxin6n%T(Hw2kGQr?T7RUliIsX=L*+ z+oc*W*5ng3UX`G8l_p?Aq)@QUCh@wsWiGtAct+B5+@YFjy z0tc(6J(Qn%V4PeV*q^VsD`%4+o8|dx7(Ryq*qjn7I2GX%;i{qh5PHi;d;RGo8`V(m zBN%PSCC(2A%5;*=4Jan2lHKFug?n&5MiaPL>98nrkDz29T@-IBnS!Yb>QYXGS2c7Z z{g`h_7p}62XEtuKfw3ljLfg&zF3s(s#dWgX#C{RyKB{_)Kaa!sm1+hR9|t@V0&J)p zw+=`%kqCaJoT^VH%Jd#7DSlw3(vEF<0o*9jcS8(Q3Rvvq-y(k0Yywj&Zn)H9=gh_p zB1#I$=Fu*tQC$Q|BM#ZbV&|h}lOq@Wch79NNNghQo_y0t6iic0$5LiCsIZ`;)~1Pm zpv8PD9`!bxnawmOTdz`rUa7`TB%bo1?ZzLwG*|NvoD@tvNq}z}dbD#jNBcBj6MTZR zW@h7F(}|1pJG{n0Hrg&v_XHhPBB;EBCMlAymmn9ub?9-i`B9?*m3Pnp8@ekE-!z16 z=kXZl+3b^m?H8bI9uF9(sq1X=brPf=0ZEaK>u>1-5l1q?NcoR`AHyZ$>Q6p7qc6;4wpkF*EO(cT99PV%@W6X6GiG+l`^Y zFc55TeL&pHF`_&QN8n&BJ$hY(f&m-tK`94Ct%!72@#*go^iMig%6uW`X3&1F?9%h0 zvsoK#96Wn0XXSfKSl1v2Yn~CE&4s7XUG@2W*94aM4zht>jPD%8aVNA0|G{ zr(lz3;zoP3Vp?%M7PjCCFbV`bbw--Eoh z)<2I2kuq?v7I*v|Q0_@Ku|!U?xw3mUVgsa0ed}{ zF6HC2JJ@cLN4-#^orVsw$);VX`JidTEvtiU@`XR8j&7$ctW#M*r`Xd+&PKnv_Q>1K zzBkjK;I-yqVK8m#a+{OdC1#BKGnwgEmqPg8nq31qjtTx*| z$sS0Wz^!`xVv4g~xyL3oMI6x;jF@+itjlcH?)7Q#I#Jz>_brJ*uDf+nhqbSX^K6E# zu#sC}xSVqAiu|dAY^KwZ+iYI=?zJ1&+59w(fcf*8O=nF{#3q~BbVf5(g6!4YZl=<8 z*K+b#!MxVlRcRB&&tJ}LCQ^0hVzQUT+-^E+ZJGr6ucln_HaiU`Kc{M@{!W%K@A zafePH44vVS`N3E5=044?(9!~=J+cTT!g9tjTNd-WfL(tx8@qnS3Ju1}c!+$V-8|wx z&Fy;x@UgW=%%*U=-K^&EW{Cc0j6Cw0%@}GOBu`+o9VDac%p`DGZ1_ge#%1|Nmd$N8 zq_`Qm{w`s=_(T z%*Ht+QlQ7h=6hN1Yp^^nHrGI8mho&2IIx!VaOT*zKNZ+X{PMe^@b`bc&weU=aAu?^ ze)>ND?kBR_C&BK|gHL~+|K4xD`9p6Jde6T3=I^e&C4PkGYtQ=+J?~flTj>3d-hb+O zpQE2J3-2$#y!-r#x8NTCJ{&)PCPMokmzP?-0u7=03CjQ7_r)I-yQ26Hw(tMtfAZPk zPyf;L5C2@%=yUHkf9uPyzEU2J*j~LMX;l31k4xfwA>APIzxQwd^`CkFIr-q=01~Gxm<*)yz zCx7C3;b$I*7x8i`2XU5F0+`3w#z90{{KeWN%_> z3NthyFd%PYY6>+tG%+v=Wo~3|VrmLAHy|(|Z(?c+JUk#TOl59obZ8(mI3O?}QXnr* zATb~>L2Ptoa&BRCWgss^Wp-&}Wk+&hc_1%FX>4?5av(28Y+-a|L}g=dWMv>eJ_>Vm za%Ev{3U~pfRtZ#7*A~6+E4j}U&h)PTX1VRX5P!K1iSb>V7 zB7zf0QN)7P3P>FgQ5-0W3OE;}s3^5q#R-RhU$8>^|62dA^i7y?_X7l9+_1vAzMB6x zKun1U^Ms-807y}nXNof6vm35eI3h8Q2O&1#@-jF8P%wydxEY*Oh}Qyu<#V#c+0X_r z+y#h08ps0`paFD%0Wbwtz!o?FXW$OJfjOmto3R=KPa28wuSHLyU2kwGFFan-|aqt>UA_zi8WD#XV1JOl{5DUZ>VIZ!E zHxh`1Au&iil86YAEF=$Ej}#+iNF`E@)FVG4Cy=wqC8QU*jSL~9$e+l2lz>uE6;vBF zM(3aml!*qQ5$Iwx5lu&P(E@Z6T7lM}htX#AEP4g)LkH1k=mY@}WC&^mJ%Sa1LGUC5 z6JiMo1TkSXp@>jUs39~G+6Y~Q8-zi^7~vg8!jv%@W`#Lpepn>N!P2qSSP52%9mJZk zPV5FYgpFgLh_Xa2q6N{3$RaKzCK8tu3yI~#I^uESd14=Ng!r07BB_x~NDd@FQVc1X zw31Xp+D&RAwUc^D!=wo^nXEy!AiI!*$!u~axsbe*e3*QOe4RW(ek&y-r7LACAl_UizN&OBop%eHllYP#M0=TA2!&BQh6dhGgDRm8j-aPih=Bi@J$=fZ9&IO?@dV zD{Cz4E*mSGDZ5FwUiO^q1KGE7%5v6nEIF>+8o4UDX1VKf&*drdM)FMgCGxrQw9#Xud_(X}UWUS<^#8oO#+OKp@ zX;_({Y@qC^%u!yiT&sLuc|?VzVxq!QNmeOV`9Y;eWn5KBb)IUJ>I&5=)l;g2Y6LZ7 zHI|w{tyJx(TEE)+S=zIhvv{*M&T5=>ebyWG+3N1XTKl!SwI;N6w0*Tj+B>z+ zX^-is>A348>ul3Gtuv~ttm~@F*WIRjM)xUAmByqAXce?h+PI#Uo}XTpUbSA2-lV>X zex!cBev|%v18D<>L4v_HgARjnLtVoKhIxh!hIfo8Mhv4Qqa8+FMsJKwjH8V=7`GTd zF;O>RndF)@nA|g!HFYyhH?1+fX+|<*n5CHQHoInyn%kKtnOB)#wLmTGE%+9@EqX19 zmX4M}%Nol8E2340EZ2WEV zZQ5-9v^BTo*jCxzoGUxmXYQK0t#e<@vzW)5w`blhJ7v2Cb{p(E>^|B%*o*BO?MEF9 z9pW8!ISepV7$J-j#zjY>qle=f$CHlloa~)4osK&F;cVrc;(W;Y$$XRfy!o~Bhh6kt z*e=yBgRV5!c-MWdgKm0mY_}S>hwcXMT=zQn$4oP3GV?I=xd+`t>~Y-Vji;06D$jN= zf|svXkynqml6RzcrS}6LeV;_12A^?XJKvSQ?S4eR0KYAM11xP8hgHuS_jmAL<=+`V z4G0gY40sr59w-iMTYxU`U$Aw-y&$6?VNgpj2xbLu4Za^@5|SSBb0{e^B(y5@QJ76w zURYPSa`@8lL*cI@JR(XX?natMW<_>H$w$RS)knRF_KGfx9$YwQ;i`pKVl-p;F|D!W z*r?dL*oj5ni?%NsiL;97=bl>lImu3PpqIPU+jz$Hf8Sx(p;^aYk#V z3jA~L&N9vVCTl3$HM=VN?eeJQ$5tq=5U%LXG0)kU^ElTh_xqLDO3uoTJiWYic|)t1 ztEyKctCy|rSYxoJV9m%{-?azVNv}&;_e(xKzbyaN`snp-1=b({idN%u25V! zu)%r5-fyvQ`QP?zoV#)7#!p4uqRYkf;_~7TC7hDW-`RXu@!jW537dLK?MwG;CT$jO z?%(3JGn(I^UC+`klvBCW3VEyqIIX?&dobNR3=sS zRe4l3?b6z{ao3yO+}+prxbJD)tG%~)@B4lHeYdK8tD9?#Ys&YN_Gj;ZR2x;>^*!VJ z`Z~?J;<}Fqga-x>h8^szcc`yFq;;sY0d2@?7(E{-Xg$JB~4qHU4Du)2`#n$BUYg=A7p7mZX-!)|l4b6aFVU+ML^t|7`v9fs=YC ztCYQSbZy<1?j2`GJ5F|N+qP|6JGO1xwryKGwr$%^Zr)SxsXF!5z3tTZ&uVLp(WhD) z>zRH2o-s$4F3lq6qVjCpzCU7UH6~sax-c+CocifZdC}r-wbPoOnVZRV1U#wJv2DMj ziCTX)E|eTjLc^xTZkuY`dJy)Jcxcsrx!1k?Vb?L#Rs2%czp!W?wY2JX^pw?g>GW|9 zQ;mUYRcEDr0(E+J5q;jx1jj<_67GIBV%d9v>RfjvxvAwI?NWW*)%S4=t`2MF#q`!_ zI_-5mAG0L;)PEi99L)Azw_)u0qF=O^U`6C0+7V}or`FTXZr=EQbxue|Br7yaDhm0t z>iMnesA$Ujwf`gf@+NSPfM$S(`%CRse(%6n%n(bP;9>WHU?LUZD>Fr<1|u{aT&?c0=k`m zzWmw%Omm4es?13MU9+a1e4i>BnPJ2`Hbxyfj^M*FX(^*Qi%LsVyxj(nu5BJk?l`Tl zA(b**s7aGs=xud#HAl#sZyhF{bO%D1980 ztz_KC(12y+U88qNWsreu;*bD8Tn{JvU{1}Qx*Xk*%$!bzgcEqMTAqPFXe&Fc#Q{92 z7dSw*bPe9(Vo*H>_d6a&Dd|Y?FttAixLd`t_;hGhGLVCg0y9J_MR8LRH}qhleQ34; z@j3>5V2!EKHNych_C?_^q;*Seg!~cHm^w^xLEPqefg+H5xbWgU6)4a}6KEs7^u+yV zG);Oh<~Y68t}W1})A4qi0@fvmLl_GBFsgrS1&a_#=>N7`2IAa=4Cz|z0|t@=ukTg; zg#`u17!kUncd2u&`F;I7_tmKtv@FMtgB`SB8SOwssm1npL}uHLQe?59cgB8{&yy}n zb8Mh-Atx;9WoAWbXt)Ps8WA27Tndq?nhcJE2Euw(WJGg%mt@GrjOimj*-%wN5&Miq z%@Xlc&i6PgoP-9I$lV6Oll&TcrJ=x$k#2bqfC4WDt35)9I_;xhb|>dWJ5{WFM>_V1v7 zN&Ok={t@$U)B8k?H7kN4c+VphNk5PrU2~^4_bR~K8uNj6h;wjYAPeJ8SOPObDM>q| zxZBG^hInUh327yrBmSmE=It5Hvhp*#QwPVptr6If?s(|0Bz|Hgf_Q=C_muN^7M9Qw zd9tvK?A0?!8Y9QF10lP53GIzxMhQVX`|J*#$^#`ksya%EMe9|A?p~d`9-OU*%uWyY z7IDGMir^y>_p@}p?vpI(q4IqJySwOpYnETGM1reGf%634>Z-YjpEw&qxjsDdI#gcp zN0c*)GXBAl z{Z^IoefOogTOO@uHxE`&`%z@P6QW4-6*UJ;AD-K3~ds`5ivC*taH?wWJ3Q#yYd!u03EN2xzYL$q`>7iUg&BlRb!{>XtQS!ErJzWP;UvI(N!B^~)0)y5QgO|c59D_^&o-#$Ohga8>VR>TTK za}>6I4jF| z&rcU%glA9My)fj&_l4A%q^{ZOw*H`+76OMPv|&j{8`etpgn9I)+0BYLB=n@Jvl2BP zbi|#AzW?@s4k;SRC4blZ+Ku zk+yf?kCWR}$QmIQ$-;{6FIoygNc99|9OR)VOXHkipo75t^hwabE| zQRkMZ*yfjN5tYMn7%osw4L~&Lp4;^14FY}v{&(xP6kEl+d=wfx)7|a}_?Y8A`UR>G zh6OH@57=K#YTgrn$1 zg!jyybVY$_gN6CGV0c>fqu4sHS$Q=gpMe;NWJvu=WiqhE?%33>q~=d1Ra6(F`&`GT zGy()?O)QdX-@p%&A~Q-BVvJXmm^UoqK2tfnoSUmDhBj@sAyn~TrDr!#Qz|W?HCiaZ zFW&(`N|ZGggp4hc8GkB}T=WhdRZIm*V@)Nd){Y{E94IL{4`6*C)U?+zhU$nNmZ`lwqdw z%L=@JL%)(MNA&U&HIhM14@)7O5PYjlh;1nhR3HAjuSAHEaY1#J)5=Aw5spQ?L~$|j zLo;|H8HCCu9%n;vgV0#HqeZZEPWiDMg#0q!y4 zDbsPc>kJ3mI=Fw2meq-CJ@`{i^LnIC3`({&R(vy$%TQ}TL2ZnYreU&nhH>z z`gl8C;cj>IpE(@kj&_Qk&wmyl0@l;uIi#MFwIhmR0kW3sCA zPKIpB;~c-`poKK0krkT+uS&pR%`Mi@kPP5Y`!kkfD5x?v@($H;q-~z3Sa=8?E&j|w zqvT?F7z%;>#vhD1T0bx(It3@f%LIKR5~Qlc1dowY#Usi&!g>K{EHhc%%QBSZp&D0l zZ9|vmZ;>Ccwav*Vxn^!Cb8Z?OsUc~#8U%(6B$syrg9=D{2?!%{9HBj|UK!9+#e|~A z?@^m;)pX{%0!xv&S}vHW*!v%42%%}Suz!iA=rwoOU%*VVd0C8sLpAGcJ-$8iij5Mq z{={6$2}*bSMe1540ZG{w+Nirk zt+G8>O2*WkThA(B$!N8K+_f|q02JebC;01Y7|l zV{J}yf-(t}WEWYcU_=wO6a_@cAxfaqlNef@{2Q%kxHST{}rG*KN|jqUm>8gzS`>h@@zU&c&`9 zaAVc@Dd6B>)803f{<#_bxwO15w_<8AX2z5Gadv!f+8AAFO2TJA&0@XmwF6xx=V%J< zULUf-cI-_2JCD<^YbG`(*5_^`0|-l&2$(Kq4z-r^5|{CqH>Xj?7$8D{QWtJwu0b%* zunO&qcP~1ctJ$>{(QufSi)lnOIS6OQJ~_gKi-BQZrS%QLD}aT{?p7Ah?iNO>MofQ< zitP0lhMR^2R@5f>qC!V>CJpoedSJ~u5_2Yw9en1TKB~6f zM>iyI(;&3%lEMY3qxUSeD>}Ot%!T$eJ=iPLO$Z4fAHqTej}1^9m^RYF!E~aOy5LYV zZl*%Wpj_%Tp}_^{sZ6rWRZy2V;FOpe3t)qPO;P$hIwA|+CxaOR>MWWO_n5;$iDvfV zmd|U-A_TZ+^xpVX+#w~HQtuo9hE^#0HF;P3yz_A=I3&ROLzfWX$c!lN6XD_WChIfHt8zN zcZMX1MnBhTziIsH1adDohcxZ)~48Bj1iMNbUfbQ+DjLCea z0@JgL;ExATVUZtbjE9UA;o1DSETp%=ITNg=OSPLga-2PF!a%_p0Kwovc7tY=xn+tq zAq%`vHYmMG?*b7HdZvCC8KpnESs_`FlIXHZgaN0b60d)^WGK~<*=^+pZrYsn&54gj@SP?g-x z(!hRU&KC;lrb0f?^2&Drv!?q$?a0K^%9og^0h=@`*r2D(qRa;klFEZlG8`WBM1s1& zXoFedPDe22rTVSCUb&w`H8?lT+5RL1yk<2QF2Wt~!yGqsfM!lw0GcdeCF}GV;ZwCw z3Q9%GQ;7d{KgcrGBsH8_dX&$WCP2e(Cun@sssx<`qFRLLzOsZy)#i~(Yni3gu~vAl$U^6cI|1`pRW~ahw2sqybuC+ny+uO9ItniPR<>PDC!QJSe}LYRw1qe+>>HHOIz-T)A;T&; z+6hD4QPeOX8j@X`1nV0+;H>1Pluas7>wTU;iOyN5k&#Zl459t$yEAG;;p?N6;N{}` zBR#<$Jz=i_U&hOVv&}N{LQ9WtPg)C60yO_3zbtQ*m~>ANfp*$K+tT~fCd8N+H>2;M z($I%EigY64_>KX6opok)o&m-KSI|FQTt7v7&L_gsgp3ly2EoisP;w_wiA%(f;`ao> z@y}wLl@QlIJh^Jqy18W{w}?;Akp@v1ldq?cVdcg3yO<|@cw$i6qR zc>>jbo&0P-8>~*#*^gnhTCFb;XzqoY?`r1Y$T^EeDa?~{q3-zY)w4vS?n#Pi`Ug)S zWgV*LwBOCTF{;)w5GQHJV_UHYQ+;xW0qc!_B?Gbso$!p-3q?Rxcd%EYH#WKxjP5p8 z;+o{JkN^W$l(9i}x!1m=7;46@R%O4ldAP*UK|eVgjXN_kg=u*_DO)XM1!uPEoMzUf zuvmuc29j3u-t+D!`<+(3N4+-~$!xZb@_|A$gXN`-rgvScqZfl}uD>6!H*4f1%w*|m zd82;>&L`}LU#j!}o1G< zZ#(%PTmE(Yzvz*yowb32kpu2GZju!g#-&j-a&f@b`gVuEcZ>U1fFd0=E$)BtCmKci z@9%$G%!(}3bhz|?LnlQBYFfy@uHgIlicH@@bpPyN`zwm+?;gg#dj395MLOE=Ukv}z z#m)V%=l4&$`(NqS-@EvC=5=DmNEE?{tIw4O`OaOTkT$`+10aXgyR+%H^;k&x#nuIIVe>a*-cqA&HrrH!1Wqm9?@ zrQnC|&1xkrMaS}q;?LGS2_u~Z$NDaB^{-29)C2X(E1v4FuGQnbHjQotBeg0P@7EUx z&hwwiACIxlZ95A%(L;B|AA0U9Tw9ghI$K{yuQE@Ezm%Y*_M&X3Fy|hnW{&wP$Jxj; z>NnrtHq@EUCT=n|e#;7RLC05;cP|{;G;1wCnRO9WU~N&DeZv5F+LGkQPob@! z!-XNoXD=HiC_oE<-R3jl>l_}V`g45zp8`HER~7a25AD*5F6Z`?Vq#lQ$$WI%ss$A zdK<=63knpsh+Nw@RF~0fSsi%uzk)8RG?JGwL&hlR1Wev=)6v!={9+PLrj_G>`T1<1 z*QF=dgeCbIs`?yj}?Dapctm=SQ4-$q#y3kCn<)#ROw!9hUgS?a-F*@+n?%TJp zpns|8v11)4)tBlDjj^<2KhRWz%+>sE1!Iz_K%1R{?+h?!&AKy|Dx#t;mAD;7;!X%SNrkW<-Jv*xdn zR8e{oV!F5WKN}wSvD`m7m^=We5h`opupJoItSb4nIB0h8eGm0+UKE_?{)CPl9{QRX z&A8OFf-sQ^KI_Al9)@sZJeJdZOA~@tf=>6knl!xS5C%dY45SdMQ4uLYs&Ewe&*Z}CJ z3RR+FR%Wrtgr@o;3|nL8XO^855%^SUn7AE;yf58EKB_1|Bw7#h74584uzAn}Vw`)0 zN?gF?J|41@6|P_go2LBCgfql7L$JXCI<$vB#$uujZ9dy|@z$sm#s*4ZkJZ5j5KiQN zaOA5^G5~Ebz=@@R;><&5bBwmCR6u=yU*)Ef(ZM_4pK}VBYgvN^gMp)Vp&J!sd5tnh zg?z9!`|E)PHZxHN!-T0!Ze&7(N`L4ncmXEMnfV8%cWRSyP^7ZT8>VaffUf~|8batY z^RT82wk;yel{+#;lUkiSB%l0EW{GuN$&VYKB?SLBDN4)1l_qpu?uO7#S5tjp8VDUH z@bo(_RLU}rh?h<>@DwGP_6t34+^(jz&|+zj;Vz`L>~eTfNG&BP-rr?uq1sbzZNe~t z%d;3A!v{Q4Lifr-+LDE2N0Mn}#Qq{|B1age%KWVT?Ny7`WPgOS z7~5nolsqA_;Fcwfo{lc&PHah#E6ajZU$^$f?i{$)TjK&^YX*FlzX5$nMXFao{ zWkd!PD_II+^qNO6{}fj*M_LbF)oZlPT;Ad;nvj?1((?h&n7VhJ<7i_yE83XfA2;LE z@RJr0E(E656!k_gvEHuE49Rnq^c~thp`B>l7smck0tfHph;|S81z9*w-MmZDr^l(@ zSS6AULSQ234G$fNDjNxj(Xo(0Rw@Aa4h_Hz|M08AS}-K+RU?=*k|l+-M_zK;2O#y@ z#WM#W@3fx87AV1-$Mx)Z^wnlF>A}^-iyfOr2OfD3LlP`07GxEBU*3^*bC%{1iH${E zl(!e{qx*MGZZ_5aW>s!n6#TCAlE^KZa|16oP+wkN3^%toLL3z`!p;}d=goV@N1sIu zO}-ex`@{>_7v%@Kx@LgG-b4Id^0f%8d0)!StD;AiPKkbyNv}(yDc;wIm><-VIDf>Z zH|!d{pTJFdRXSjAvEI-ZgO^O`Oc^+H!%jY%)0dc=;~!;heo{EhIF9?I)*eM&>fO}2 z6!`Kk6Dr2dBD|+gn7gGCB?NX2p;h?3u+}fh6($Fs$HA%)s_1mMc*mz{GE7rGuW&y( zKg+k8O>&d*P96(-R+TVqD7Atiw&`&quJ7l_1e`WsiNb4RR&7fBk?lMw69x7S1x!pvb>>xqjS{?Rk(-(KXO2v| zJZ-;)UmasUd9Wegva~#KL*paYyK_N~g=6T?XtO(AWmX+t2aBWKZvd?j`vPjR zs9U@(n_oSd!OKY{OCV3~O(;c=ED(fSQ_xwV(X3-=2`RFWdf)H>^-g>7Qj(+8lw~Um z;sZRQ_;|T9eew&!G3I|ELzE4jk)XHXN-{wT^ElUielJuyLmLQt2Ovr2^P(*b0Gj`R zw5UOh4$8z$DgjV7Nk#l8o2NWG3gD^$th{7noW;pj2oingEj-V+9lSE6$MN4qm4Z{y;e=D?`wB6jxVgNz&8=|q?uA;dLAdsZ~Qiutg zl!V57CypW?z#bb`84?W7fDsOUW|509bAvk$76j>72d;sL^0O1(nl*s=#1o@?cUINO z&lFjhs=US*#T=4TAmbGf=iHuE<3*#~xK{RCS?z02iisLy`_ ziY-B2{bP{iC|H$#uClOAIs+h|5MRkH%ri;`rk78o(!;Jz5UrYCA69GtN#8QN=sa)*LYY9GcRZS=~bB(z&i)4-=V;cRFOa6~x_wov~^x#3gwn*7TFsB&> zqT2h2@#m&wLF*YBA9&kVpWVkFK^v}rGFD_=gb~h1UPD*ZV@QR7yAhYTxwb&Pf=Hl7 zQuQ+x``_Ip{8QFHhy?)JpzmD>U^0dI1Vwxf0I~21&c;oEO8GK2$77ZdUiX74LBI&^ z3818M9b*0GtA0uIk*)t!D0Isv06>(Vm3};<0;A)YK!EF3QaHz|j;_lXn@oJpG!yq7 z?(rV!p+Ur@S^)L_MEbh=%vkdwE98rq4FNT2MD($EEP&5Vq8@bd7xmQ?(NVz%h6f(= zHBp`g+q4L%JfSgx)HDFdgF_|*JsjQKj4=VjUL9TH7s&hxF8UmnUSo7M5Z?WD@1KCz z3H~B+eiRJ(WybI_yX8bu7TYk)+-`j9apXr&&ArS{)krHIil_k|^7UYc9~k%kN6}ac zOLMfLNH#4RFD>oTQRZj%B~EHeqyPO!!Jnfg4vt+<#Osy5PTqTuRjzYyIph14xF52c%AKVh(Pwncqm4=epg)rB zKx1vi$|vY6%Zu`JVOi_viCe|$HqNe0CF7IBR_apsHLw|$JrDEO}5$h3Uw=%QoU`OLzRCFe(wX zlbg+h%D)-(Jt`9X9%E6DvtOTOs$v!m*a&27k`078%p>WCD6y6yS(8TDmvUEt67pzD zjrARswEwlNfEHpgDx`vJ&z3TYHtk=qTIvpXntWGpTL^TjXH4M|Y8Y(-}d8%NjYv9%P?b_g3KI>8c0VD56a9SYr zy!OfXFIRmt8B(5A-0$KT537R~yikr5V67&;a3r;Jgm_}Nr3;cdJtN$H{}< z6-o5`geERg<=&Kb?S3mOG|PP#5Aj8j!yJ6ygr(t~jtLP6ToLI8D&&Ld;aq z4)Pv^TIM`ZitS_&*bm~WPk~0-EF-Bl>3}485$}-Pl#>($qQviWYE@Y%j(D{HdcFbc zHKAqhJU<~P-Y6_*)y^&}l@k?6;!1Y1t1n^_mh@Y{@#3R5goaf@q0$a2FAAEyUogz} zK|S1q8c3|VOoo?S+8r>`6Hlk&u=RDg?q8WX{UYC)c{mNKC6gbiS+!%GHjcMfgJH>c z$Rk6vT_3iL5P~-yI1*E4Ei%agd9Lr}w`|Bg#Pb}uc@60;sbKmZ^wQA*+H~sNc)rht z)r;FBq8SSgroFc2rw*=oKau)LaMU(67(M~+(iZ-V7Y;j1o%DN*rQo1k-#TvKQdh~D z=(Zzuh-P2WgDiq*%o04DkzfLG8SELE+~i~Bd(xc*>Vi}}?#A)q;hG^5x;DR^1e$`t z6pe4Dt)IZ3T|wBfuJ&?;Uob(i_G&>ScWS#6b>JN*x(gu&*z{MS#iUHH%!Jn6c%9>%}KyJOj) zG_F<0*R-CM2fn`~Qz7+vy3%9Q(x+SOz!*U5FkYLR$HZ}s0h50Kao_sL#h@_QgLG%| z!Gu#_;zq?MKY&%jT7Yn`E~1qBmaF~xC$4?8jjXDRzKR7tJH!d!vmPbCjLb6rII2b) z1&5TjI}yoi#8X5=NVINO;l>|4Yz3g%t1Jj@j{s23a(?(%cJ0l!ypewEVMEO+o&7zY zNDnxBK^;dlN2~k<4NOFm$j-VsU9@j={$H)m(MErErYK=}dX*X{4L(>i#A`LTCA~rKVr}66qQ$4i&7QsUHKG zngrGAA}Q!@2({AdP{^D){TjN=viM=fEq(|c_@D7b*Jy5DtG^Z3^DEG7}Uy}8-k+U!V1?i{ena_Ke_+&jf%^`b=5 zs?4v|S3y5h$*Hw&y*OOIKXtelT)pQ15t%kat)@PFE*-t=ibP3W<_kZuhVrnU3;zI_Kb?fPfKgx{e=di{`1r30y)7iq<>hc;tQxH&%DKpn_L=kyzX;>brOy z(DV?c_Zj@;N-;c&l;DQ4L=H*YVW0LVV<{y(V;rPIqnz>MCGf{JJ!S)3+zcN^j>C_O zj&4nhE1@m}ds+$3eVI3U2Wx%H9^$q>g1^9*SxXYWdvn0~%~O^@RF{9iElU&!_^%*@2d#`d4=`7e(BPxk!3!rXt&hy13>|Ao2#qQn0y z%>B=ql>h%RH{D;%oAG}@Z%CT|0ljhm3BCUt=l*X5{Qm{LA^$t{{#XA0_uE`df1~n$ z2fYK8IilBC;VvI2QYe60e?((;g;OBl{;+Ey_VGaygB&c6#9ChsT^hNh>3-$r5}k>o z?1!N;4Pw|b7|uQiej5StQbw@%T`twbS@G>GO-bPVC9tv9^5~0!7+@&vLfxRZ0Q^=T zr->A&^mL9$v4z8Yj*QkjdRG-XHiR?br1ORGWpy@mf9ish%{_lK_vxx|Kl61yN3tb7 zq{D-~XRNmRdiiGS%{s)g#(weP_=9@1c<$4~YBn6*wX5dT`mw2Pkzl1~#O!zGkvbUT z;$w+^^ubv>OnDb91Sc%YR@0B461M}9O+T8y*XN$85Gbiw-PSjH!fiS0yW8-+hWpZK zay2a6;HrW^5<63P5UTJB@t)j84TJTC!bo`tlCTcmjI9l)9z|7iSijMK+NO58YF{dS z?GAe04eLti(Y6D8!|X)9Ot@diAR)P+=_hG{3sYJP(Ao@*i;4$+lLKSG(<Io(M4-W{GO+)H3KEbGy@C)j)a&9VK<5m2 ze_g|B3A0J+eoLWlt7?@&L zpbvWqsstR$CGDskG=ETHs}(Wb33&c~x%yj@B+U~YF{ot?c6aaqkAns8IXn0kPhy~CzHU7IR`@fYjwyEXlFGzC>Rr? zf*_KClc09c*G`&(!mmR!RazM5OQEB`sgA6bcmF zYk??Q;afllQ4px()k-;$E6?l5T2f%``_Y&tP?3j5FA25jvIh25MQO_}PzVV@Dw6fs zhe4Uqeor-H{8a0Jc}VO2XZ69(!}aGRSB8c=Sa0( z#XV5AT*i3=!Bh^QkW>XeZGY4Tvkc9IIo(h*8`9F2>AOGsV zB#@2%KixmZe@+GehvW9YaQ~S8_SgPP7XKEaf9wAJW6OUk@V|He{+q6SyL|sCc>g79 z|6f`BSHtlCY4S1s>y6-_diS@q|2w_Q%ovLzXiW@yatr%qfFiz({4>s$X*&>R4HyFq z>{7ZX{8GDwVL{2vxTsD+jd~6CZ0OppOMu=lBHS;Rk4l^@bbqJy{RsV)>`mfPLHW8` zncbW{vlFYn`!~&s^%cXyzPeK3M}zmqbz$B_c-`n_cD>H#S;w%V)0e>Ggq8JW9c&qC zm_@bskc8IFY5CpT&WD3n>$=gF(UbS6m$$XEva5>H>czQEz5Pa+=9!tXvvU9B%4fB+ z+SupDk}hgiWr9&OmTH2v#k5bmKkctdOs}eoD5kK(nhj$`idzH1XeV?U7c6M%GSTtH#TbfdiB1ld&7Z8 z9IO7G=1-L&yC)@1)3x!r*12J5*gMe`i+N+HwPCcjcc54ZyXTV;%~1Tp005DG-bBEL^ zZrUZloCys0nPb95mnO~0BpNZ08i&Vr)?#PgJ^j;4i^k4SD9~OtT|H9+n$N5*IY{h4rmC zRVcg`m12<_KK3|MRF0{hWmgGc_yEOksp*xkP|&Y#7c?Pc)|^*cP;!O%F#%L?H+Iv% zck=RVhqrjk4Nk^`qb<#ok&PW{jekRg%ZKXI73AcdCX%fixkk%ZPJeZ3whWf%+}#oF zk`kAzoMNQ63-g0@=Dt#%FyXs8{0eR!E|HKWG&L|&+o&@RM$hTo!Mlf-`$qtt80jC5 zD_-M)2cfSjR^E9-j~?CDw`znQ67as$>k|_@%WmmZeoSlNLmg^yPQRA->W-QE){yCXtj_O<{kNZJagWs zhQLDYp*&rQEMo7Hc;?C%Qw1>=MiN3tIeErcMOSP<*2T8mcF^>}kMcszS23730XD9H z2eo}3dr%Iblxsn`R94z_I3PS;wnnNe5r?pQ)ygQFZ@n#xgRFPZI0%T0e?Ua52B-$? z5LGww%*0UoS$4XY`bFq4jzlXK8uv%j=QEJD7FVq^OC1fmtML^33W@OU%)04UPL~3bF_Hff0|9wvLcIZ6Ey~h z{Cnwa9E6;lLcE%y@YTNo%+0UkUua5L8$~INI`etMfUphkts4+n}he- zTPUW{a5!kW8_;tn%kbUHGe$d>RmY<)X?v^M`3d&XY)VH=xHi3`j!($m_$lLj==PTiYeY!YJ6XDv?G6Y5I7WDY3P(l}5 zGx>XoIPDQ#?M;~iYV6T#(2ud;?`jd?Hd}X|Pp3QY@2@W(&&wif@{TvzoS8HoS6{C? z?~m)<+y&*+=rxvu_u^q`j(lyT)9|w@lQ{H4pmSv9n%}GLs!0r-BQ|bcJH0JmCo2PU zAkal9%Ya-VSvS|9qe@LPsBL6tUKr$qXQ7wW8+kv)?a~Q(;v%jOD;-Hl>p9LIn;$2% zjNDm5x{BowxuYTzRmUx7y|q8^oyZGUmpY)&)pdd0K8zpZOb&a+tkYY_f>V#z_{YEF zKP3~`>gJc4+f7hD8=4=xUZX`n1Jo1!4#H_?nX{Go6Q@wy{#6B_f@j@GKDE9k@rNtd zta2*+NaHFzM-2t8<=ktZJ^QVKV0mH5jmZ=M2weabo$QV$dMU>1Llj^Vu{qd%kMe{p zyd4u!5T`oMWHYT3lOEnDxNyL0(*%WC8{Tc*i38-HAFsDbr#jxR8Tp%N5F(ijX6&bA zh-{<9TbDE0`)#L z6`RV}ASJY5EGDhj(2{^YLw3Rw(;$tSo$#c{Hk!Lhewu-z7vf9GR<=+>YD=cCza?lX zD!zuPSFQQsCN7;{0F{>*F$V(d(SIO9Bh4 zY<5~4<@B}6CItZ#CRg6t-Z=dv?c1p$SJOdbG+tD2##hzzjSFkS=eI%4F}9c?TE|63 zqc9XD;f~>E4G8 z%?NIGPs5hBhRx3A#Pc|L@NkRmGQ3s~PeNi0Rc&YJB!^wrE9VCaqs}-IpE@F)hE+&=cxd;F&&yiVsln-I~wVNx%6c^A?!}-gSR#hSm94Ws6 z9#!h!s~ANS z?J91;L#eL7>{!s|9Io)tzy(H%pJ8qsh2-FI>Mt$4d^a^(I7g%3W4g$~p<2=tWm9z- z%EfLf38jpUU0Ebusx!ec?Vh8|(Deq12(|1*uP}$4v0j*E4C&7XZc+R?HPYR^d6tyc zyqR-+8O7Vm9zB$H@r=frZ zfEb$W+;&Vup}CF+A*xzapbA^!n*6DV#N4wWOL)3jDlH7v?WbT47(Glh z?#GJFunY#{^jd#Nu%tRDgePUpftC5IBkBnm0A@$cy<`<~DUl84jvBTpClrsRDlSpv zhmD$O^~p)))|BK@86GmDhxV0POd<$LsnZ3~s&TU*_NE0MFv{5G%^i&8&Udhukwz(l z3W-U{F3WB^0zr($=OQIn6(r6uShsX89Vb8~!Z!*x*7;%yKqF+DF@}QPe)h>W+wCnx z*se7uxyYxS@2q%TX8>wR%{jt&a~tU}{O|%T4u&C5g-d|}lbuwbcthGu|0Ny&;8;o0 z0bbaUjAzrB?;9}!7frM7&gwC9XRd@8=&Z@D&h0F>R5fW6JkB30g?HYEx@@HyRgQvr zI|j~hZ(vf3Rc+9|=%}r2urmczRgHvOqPA^1&m^sS_h6-G#d{wGVW3AaP2W(^w3~X5 zLS84@?J|KynIT!GnKP3g@7}(3p+MHmNHCZhxsT(aw!f9U5G?O2NSgK)s)G->imue) zF@qd7nGDw3dN7w>El?D*sd~`s^(t;x?cVNr4uZN2c8mC6Z`aUbtbtNb1+Qc>swAmL zeTIz@>2PIMAR;=6a5ulj& z_7iyh_T@z7ikd(>0wOZ$N#D?l);9|wPdtE~KPRV0Y%%s@A?Fg)^I}8ckl=>O9svv3#raHY`B4}`ZbkH{UR1sxOHOiZ|1y2zCic`6vYZoH`!M7_?c8oqYC#1 zZq>x466DN*q7l9#BuNLiL2@FMs|MA=z0N&epFu@-fTNk?nop-_LCFfDq;Mk~)*3xU zpIw=;j5C*D3|8KY;&`-bcyJ)l20DIen?@;VRX$jTr`8Q*p_e%T%7p5 z3c}7DYsvbPXQnRLPtS8lw2#Pb9Pm+D*hb9fnaE6{rfY3VwRcivrf-7A0VC_d{%1NP zs71G0kcbldL-+kQ$RzUsVbhrA5Bz)zyMaM7?Pv^|9ll`njgRkYSs__0#{rUWipPOB zv(x+y1eLeiLmlDooIr;dBxD{G*^r)8?@hgtR2J_Qw zkW8sTw`$MMW$4keY$vi0#-bqt0lFh#Shj4cK#Z9F@F--!dQK}ySw<9i!DhK zF%)#&gOZ$ldXh=7Cmm@-+B|eKG0;y|B*Ed%V@5XZpGU}F9mpe^<==IU4yA4WKfJwT zm!Q$v{aLncblJ9T+vu`w+g6ut+qThV+qS2Zl{`uQlV_5(X4ZUwbMBY-wXgl#`%on+ z4=a@F{wl5)CrQET*+vT_C&H<%7pF-bXD{liBMzW^bWQDa(m~?hk4sf9P$LoWfA}&G zsWZ+TfWR3s!7Y`bN`XllE$tnxC5vdvUjb7eNPM2aWvU`)>(i8oSk?}0a$=?^PzSAc zclyR2EomjFJ*XTvSKQIXLOU=(q)?EVnm2u=P)^pP&{y{E%hL_(;EexI+#0oh<9&d!-DMb@}>eCN{Abqk#j?_XEAk5I(X+9>X9mLd)l!jNciKE> z0M|2(*PS{W-c77|- zL2-u@<=fx^%NF6rV?s(WhtbTgTv17ikVPGgns^}FT)h>pCA#t{$Ou_$hj+D)6e?EQKxNKws7b!@=aWng48}6VdO7)8A=QDU9!R6 z?b-OI`vzZUIuZIei`Bp923Qyv+5T=gvHT?_@%MG-e`7eY{4HtlKbzIRZYuv9!|AUl z|Ng1}yjlI1HR=CqII;gFKk>Kl$N%m={bL#Xm%zq91uN*3S^r$X@Yf6e)o^0@H}!!m zf6I3Krv+@X=0uEk3*zQ>jlR`j8!#F3b}E}6I%Hh$G-)ljA9@0MR(1;Wt@LwgNpkr8 zuQB+;o2hpT$(!QCs~?dnC9=3^$H1@tUIZ}Tn6#txP!7CtIiv9(uPJsSMU4Hv8NBc> zhz&^;GB)^QY%Kwd{bQF}ckSmSDr^VvnGB+De=2XEOZM+!Uw>_UMSmPF)r_2$I&0JU z40{Y)ln;feYy@Q1(^8ASUB{}+nNhpC`-chi&^LgM)sz_H9dXqUWwb%2XXY{gSy>Yisr^a=@fV>%KxJGT%z{dS*Vrt)4-P_%eFl(^0;J^*L0^l%g_J> zH*Sk^2KO%0^+FFdHoT~SVO)sT2L-r9(kw0ZcRCF6!CFqM(4h8KGZ86RAgHPxn!nWB zHn^4Z=apNkzAE9>=Ig^P#pibxxXat}mlH33c8=@_*C3(bBMPtc=d07I&QQmT}UxaQA&X_2r zx;-&<5@pG`9wGbX_-*Y^m@n}iK#i%#?E9Mq8B>J|Ol>-T{4ejfm$(H7VJE;4JiTB$ zzKw4rpX4gqKlKCDKA(3!p}pV}Iwq;_`(Ive+&FX{p%2ERn-pJ#=Q%FNoBO*C?0+&Z zaape;HB-ctWxeR7&2A@g!b0xU%XH<$mHzw`LSn)CMW7D98KtU)Pp=+EicR}rlw%Vx zOiEFX8s=EU%d_JCzmo~k8I@jr1lPGGI7yb<4d17jxQ3;PK^MTT~HzkfxDetPwCwL5FWUu~*Y^x~9(xm3-JU;|?eB*WMK zONt(WV#90f;2w{du2-YXzIg&+TB5A3bxt`?ZW_8ya0|*UNc1b&shgqP%}^yrXy$IY zE>tP6rPsouJ4yzer&TzIJ}v-=$HGDv!3ozFh}ZIH2F{u_%o6q*_s0C{g z34cA{jlih|QCVI5aHKO;Ktdo7tfbo+A6gjV!-abhdm)BEPc=K~*D_!$tr>1OM)Q$? zRXl3IGEr&n6Gx6`oO$6fEP^eyhFO< z_s=5n&hM+4l4GkkC*Do(4ZW|__PI|6orv=D{)K_7v{YFrq^a5PuVcAcW5J!Z%blnK z2Pz>-NqWsP6hWl|Tr%)?C|O?ADhmK?L4{V2%FBr_-eklGDPE-6j)G^rbfA2b;vhxR zmSI4_U60FCl=hG^aZ}cb!)<0s%xB#3Rw1MoxLE_=8u5?a?@x*+A78PFrnU_GhuL>s zP#Zu6KVYG&fOmuUJs+vdNC5?gHJo?%D=j1HN&&)F#!5%EnC({c*tm!B%NR)bBVJzD z;89;KTpyBKBAc=T%b{e31Vo9849Xj+pJO^2dEWDR^ENUyu>+fI=s4QB!u8i8AZ(88q&@74qqUL0VXO-^}k0Z8uq80*+Cnt`G zyuM!e-IgPv4;UBRUI+#Z&r>)1lw)8s?A>NUZxbv(R5ndMas^TEXERVQ$rd{s<##;Z zUwHo{wrW7D!F2@}cV{-ii3C=0#zA5IAS?TuR?_Kp|EQNhie+)v4EJBsy7M_J~BGf!s1zQsK}{kkuF|(|Su0nS#fF4gsnH zP;iJ;X&OE=hoN!oOtGom`yjGI8Mwmxh$P$Wn@HZpzK4haCDhI7N8AYb49(yv2JM^& zDh<5Njsr?7i6sR$(#a_&5WC;{^{lXz5GQqJ5m7P$2SejRkwzlaRD;`kC#6>H4Ry-f zuS6`#5uj#(mI`r#FjT?C2`KZBcLb!D(BlK!e=qTH6^=Tq5v8WA!f3NxY@h+9mBwIA z3xSrE5=Fqh=s5TY&9<-NmIA-`vO&S9?v$(Lm^W+ zaa5+v+7Oe<4kLG7>x3G=^iMYwHDP< z-sVxKwg_c*x3;5Wcw=+Br3p^pF7U?2md7&)*MKT~!n$!^Od%c|S@-U$a!3oD7o=u$ z(+h5>%eknax)9r9dPr|;2qE>mcurr~=h}!bc-sbGCnq*}`}HFso0q;q!j`w`zc|R<*=#41{P`z%% z%X+UrO>!7Ddy^ts*>_BVL@+HhhMG)eBy=`ZfvO(lAcX%}bOkxuezR3=+Q)d~^YPxu zqc`jxv)WPa>@MN%kw+W35p5Yo0N45(sM^ob10@@z<1f44KkpV} z|IK9ncf5g-g@f^bCi8#hv;M2e{BMZEKPL0P5nBJ5dH83z>i^%#{9jP8e}O6fF|+>x zDE_yZ{ZB0VpOVq6|14(y22HU3O&t8EnY}7=HRf>CKID2vX|~?D)`~53?7)H_oyd(~ zBF?(B1VGQsNkPZkn}Sd~qep-1oAMQ5eOV9M$qx-UEO z^@_c$^7D4`4By?6;{B565`0zasSs_~KI_l)I*{ecOU+mXGu z?FidyjhEat$rkUQ=q`K>c6>04xg(GLBCDzvx^K&DbS3Nbn*!5$KC`Oj_`fmd_GQ3&k&k5eyiv-WULJ@!FWmF72 z#%9Lt9?hOgwAY=Txo}8u$=&I=tI&_JEo+r1cU3EQIRCD15z)K&O%)?|4QJ4DDA|bHa7C0p2GpuT?_LJqYi$wMLCsVUZ1()bOdLj`?*6ex z3xkRdR~5<4*W$&GJ#G_h4ce*P_Nxjsvbl9Ir`=6>y+bO>Iu-nhV zGJ1=FIU#{K-R*E4FHd}Qhy{#K^CF1^useqb>|FU%4UIaBZd|GoziRSg}t)*a8#lSHO+n zJVbT43_?xvvUgo>lTQnaJ}Cuuvru0EK?&?;?pkVMXVgT%ch#Vgwm`kt%}PftH=yXk zvQN%|uFP2cX`}G)_hHj)*Ne}%;MbB-tS*{>vzu|_cUyHg%n2f2n$N@OI=`L)Y(KQ8 z2V!}|ZpC#akb}E%uH~+Iv*nR@b=^Bb*M4CJYusuSTuqyL8sgnW-rerYp-&c~RLj-1 zxV7`s?9H0?WH6$D@=yX+;9frrg2b$EiS5tOh@7VILvh5?GhqtNE4%!z)Qrl6@NIju zGROCcQDyVvvvQLH9a{#TdS7h~zsj^y{%iMy^mqxgLWr$4T~rc%wo>Xpz|b70f~U&qy!62@)Gh zZY6bEO-P6}I5gb8kKQ#CHhE%aBidd~wfP*i#ZZtXtg$R?{^xr?VQ^6L>7YnjMD zROfTUbth!IDIxPa#R~@bEb{I&MEl~YgiB(8L?{FHGDI(48x{{)i7RQOWB>D(@S0$) zj>v*!FUlC<<$^O&uLW6Ea-#KLg6 z$U*e)-{N>O?mv?&v`s(6hzxuJnX*IIsfXfv^ByE_Ql621T!1)u>%j`=9wm)2zr<~H z5~u_e!od+i>q3=PI%edErw8|6+^DE453d55HxvuU$z~Lx=r;?zaOiu8h5)`En>)(5 zbfqq=OU5HdY^oxR(@{5=WCF`}ods`Qu4Y;VEJS4r)x(ub;FHC4;^5;-8l3}l>M0=z zF+wo(bEqXyP#$XQJ6k%5pgG^*qGFtb+}=`z#td<3+7vRUVp#uG znb0bI>h5fb#qet#L8m`?@XV-Qkw&U!+E{41_N+J|%E$eww_8JVhclmn!T+qH`gTn) zm-ZksFp`)d*BB!+Hy~n(`3AKz|pTT}=brR#yLqQZOyZgX|nL88J%Sp?~LAHceEo<6a`C>A$0D}=` zejAq)(q%`PEtHQ5ByxhoQB{7iE}ET1BCD*^EK;j(t3K?NWoR~R|z0^^p1WhUg3oP7xMb}g(E(ROIo(QH9cQqf!ZeklyX`s?w< z&XXDP2ipP&X9A|8FO}_;ZtM(vlApDuAKf29@k{y#Mc?#{Vq^R^o0{_xnFO;eJm1Uq z$BUWi3%A^5f^0drfthmWb`6AGJl(H@JN`cRbr^blMu%TwJU$#!1TC$5iBXs=YOfpW z)qnZ~{2f#I{Fr(GD^|>a+qh6{m8n$cf4?3QYje_ypYMr%>H2< zLa_*tn4_N<>!`A`e_I1D`b_HIHdZ}v7au((fjl+a=0pNyDSN5itJDvLd}02XnTSns zrUaOXjWdpW8s=G|J8u`w%dg<`E-`tb%!EC!6D@YXUp2juCUKGdW1JvN=E?`Nt_S%H z8P(=D66XhF6JQUbCqfPQ*>AO&7RFcK1-8MlxY&i`${3F3_}T4Y(Qshc-?hfb=GF&- z*Z?5*1_03XRn%^B*gs|LnBZfdZ2ALN{E$75B@6OGXP&v;qw=P6-aCx@HGFm|vnh+VNw0Eh($Xy!4jEjs3^VQ0a@_V# z$#`4}HIovcKIy8v1CBaMTY*(3t#}rwO35RVOZTR)@^Cy37UgYs@p#@GYK+abttf?P zTy33P0*PC=dH%3}s#xy|UF_nq&d%y6`QukOILkqa{EAF%Y7~(td)!}6-)1A1>7O=M z@wk_AkZMyZKT*~QPxuoR$jG4+YnF{gb=f5M0`Rh=fTo#XSlMm5RJLkEZ}ax@;qB(; z;q^*-NosHXD6*tX#<#ulVfS&%McMrX!|~8}7%5i7oOBgsK^f~v z4_cfV5NJJ*5RP}QH|mt6l$wK?CpLC5^gGFGOr{ZsC1Vh34BbekL!_uq5e;3$>!g>_0DpKB(gdTH{W0qZ*&c5+o>N3s($USB0LVvn2_mp)1|e7!7i zLYByYB6Yv_5a=lVQCG~{%dr8angG$iswImcX~Cr2bOcFl3;<6y)|yNwq8TA-VbijV zd{eP?@XXWnBQo8B;zlC8`jN3d#Nq?>BptZ+0FIPfRmQG9sjm~zi9#c&>xoH2*vZwv zx3kCHgHggmG!NE!Pj-zoxct=7rB^1B3(;<_Z1fXH+hsE~d-I7hmdC(@y6kZEHa$DPGt z##s1-pE;61K=+s+0ZcU03rTob7beUFB=@xDx~RpS!VfjfB>`?TuIU^?IK`=d$P#Wi z9l|}okkW(zBSPMa{w5SAq>)sT=v*@fUNtSyPkXgFS~D6R=;ddlk04;efWt0Tj6D#{ z(}RH%>u``mk>$^}cLYK@>M%c>m565MSmXm$A9G2(u+aME<+nCrXd#dxt|yecZIsVx zSy@Ma-o>)qdp+dym=~KkQme+xTL4><=ki2`joG@YR z%!3>qmL@#7YQl8A2DNF9rx4EH5RcTX7AU6r=*t`n2V%`UtUE3Y0;3YAy<1f+EZSof zx5*Qb(@GsvX((!@8?ozt!MZE_8}Yy9RR$*T`iBSaL;;F*TTNe_`VCkj7r-m-ReO@N z#PK)yuWE7dFHB@@n`LXt-j@j$<@DvQZ)sJ))_>{y-Ahouf{Ey#wcyDTbB~z9OmfdL z9P0XKMt4os_VD(^?Q2|gNowSn*h)S<(Mez4_`}tCg>kizNDOGLzl#%YQPa7mtpt(S zhqk>}I41^w4s~ERA8V%N-+uA%lW-+xK%^e6<}%9OZ(Pt$ou38zCYl_#)GV7>pf@mS zb+}KDv`N-K0si=5p;QHb3{36YFi`>`2r^Qd%tpeJdP7QZ69`|#P>w44Wfr3hKzCTVvB<4-`GO{ zj&R%S|{KR|spe&g;=Qm}oH@c~F0n=@ z@3`!Vo3LLqxL;@lEVymXQWn>#zEt@|+2g=t8h$SCA#k*UP8dCC`r5dwQpqRa83zg> z#|N0!Hb6TamcMDXi7-OVfT#lEtln}Zj9Q^TQjUC^_VFZ*pOIcc+(D;-+a8i(FEOsn z%yW9Z^wgKMin`T>4WkNRdz2mSj;}ml*`TuYLGjN6wi=Fn?_a?NVzLqbt$E-v@@%Nsk*&r zE@|-;$1Km8s<-g5aKV=obT}Nsy3Kp~8YC@xR$N8YKI~37=G@%XkKd-Sw~vsFM7)LT z&&xGvUd@B=OWu%@bcHCnT@aOg&{$DawvdpDHI_wpr=c|@80fZ21MYc5ErC96jqPqhCK|_1>d1DV=yVet6Q$pNrv07)>cXyFVx+A>lz1e(W zbXo!lNMQI=8n%Qh1j$ggfD$kk9R(|Wmb@&vkJs?za-$zfw)EA5#8V*Z$^~>vw4nc8!#sn9}-NF zbZyQPk0aIY+K4_(fnDu`f6mw(*yQ4)dn22YB@Ex}z*e`@6DSoxNampP%{~g^9x>%i zDLz4~1V5OpIa8qBPhLN5eGGW}i(!MkrU~e5pl;ul(G+Iq<7`Tub7LRhNxEK1bgF5d zWNzcgjw&o9?2ymc@C4m_BkXT_%Su^gPw?OWqJiRizzx4{A{t=pI#|%$*v+W%z}*X2 zUdH$J;vS=t#V-En0MS+Gjprn)kjE&_nZ~tsDgTX9ptv^WVA9q(BTe0s5wRc@4SiHw z3c2*eLNdC#F|$}r>VC7%pxK?U*X_J3=6Gagccu&rs@5j264Z!G#|&$6R4}x~h)ccZ z;@#uQ#ZAr|!IIb-Pdlaxf{o83Z@i>7o|<~13Agz2@mH{t^9Ahjx48d>1U zqV`c?1sWs0lJpp^uWKg@Q|MNal8V&?$-cRSJoPdM2{Y*td>XIcB`9*36S0LPq4(lraUr;PRW^o+&+)3$m}1%Fun*M6&D}$d z^NmW0k?mDtmKmj2ESlKc+vCP=32n?a#e_{r!T@qay$}c~FF*JT5BLp-P!U#SGh7;z zf1j-G+UMK%Wr;?hb8%;b_o^NN00w4rwG6T=6(>P@yJ1>!j*ufITfE&Rir08elP04xLL-Cs zLdDi~;BHAmH2l$o*?9cv$L*D?VPyYQ`{B6{rTs%{0#k5{+(=63m)ExxB>ZhtdDCG> zc>}l1##Q7(P$W^ygOLcudE_}3g@M}w*)nErxBVq5U6c2C7A{*{On1~HwzVQFU$bR4gYax zqQUGA-H;~-NG6y4E2VM`c^OS;==_RW{Jj(`ctum@R+Wt${s&#S2gHS<)nL^({d`Qj z^IKX>F0f&iH>bQ8l=jISbU+n5hpr3kQ0g8zr(J%K1X9{TTUR1o#{9jGo2)wWf~&FR zIV+cmdABnp6(MeSGgj8n;shDp()Kq#i)i@L|J@z=>jwWX+z>1MKN6v=f60FT9VYrW z?g;DO0-*mWgk}9(dh&nlk-xeH{|&hG*OPz$*8dxO_E z7aQcCGo}AhDfjcF)wLK`_t&3heaCG_fc#FrrD-654 zw&VBk_(;=nZ&<_c#~&Ym?!P)CH@0)&$+f%>Jau}0oS#1lb-bFse;y^2DLzTx^=Z|z*k)vQm^Eq5z%%nW?rx8S3PCN#42K&H1#g0 zoaV)r2o>yHU6oY3bUH{2c&<0-iqE-SUcP)*?A z_p!FjlZaG2QX{mLaq?E|>G)|$qCP`mw|jvp?ZoK2S*V}vuQbkhc$7Vn0*p9ZE~F!| zGdqRxs2Jxo`rZ8un)}YnX)st315Fpc@SF$1k=)TiESEK-CxV;$0o7oQj9SqO>OZ5j)fC zTfuzpNfrp~2VV!+h`R*{20c9ou(g%>JOVu17En(tFHYPM1vCQDW!oWh0xsLMximo( z22Sk^@)WE;&EA8-o(IN?04EnShWS`?eH>nU#BRWhEKe)}83Rr*)T?rfF=rxcVwoB| z7Zu)B4)9|eel*i;xRl=lqQ=pKjW5k#PaE0^|a}gqMR%J?DI2X$*vslflZq2xN{8XGAuV z{N8X65nE9SO!nXqp8<{qopptVVm1+Qnx~@);z+?<2NV6u zjYbZtgmzOuB?mfEwDIaiXBxl~L&YK@jbx}yNbq4Jf$9yKDisJOv;+3VgdPI4lqKZ| zFTunF;D_*8MmNhuQ&ntdiMk;1c+hxPlr7ZyT)TcClVTa+quexTc0jpvy{u(HjIO5S z+nH+%DFR9|3}Rg(z#(R_TL29Dc&=>W^6|JE#r!<8pAW9Shd|($b=-LHtK5|eAM8!4 zxhW-^uX1k~L)A4!La~;S&mk#P*nlT%S|X*!K%8|U&6V$S45wmN)Td@b`#Bc@<%2!z zvW)ApeSW-P{u0s6fap+eH z;jiIJss9@wT(464E(DZzYip4wsy!)UrpWZMe3Tvo#>siC>DgPZk0%$Ut#Djl$ib98@zP_-V9BfqxWb1(B(!98l5vWGqo3&^V_p zn*!;VVcW9+Jt4%Xu~zPfMX~tg(Qq6X)I$jTT)6w2lx4US1{KRn_z$uGYpjfM8q1q* zMH;)#W0e9w_coPRL`@P^5RJe#cwUsl=1fT95c-O;4TWa!*yN0ov{kmdpq_2Ap~R}H+6o?nC$#E=6Rap3jPl`D zgxW!0Ni@_qX1I!k09+MT>Nob3FU6Ai$-VT0HHGGq36Vk40a1R&)08w~ZRAORO8K}% zigaC!tK^eJLmzX|7mOwwAkdlw6+{_05Z0tYj9NWZ4qhoMnvhO|5zQzG-gks#f17BK zkEde5Fd1zU#PqoJ#$tCk746jFri|(YroCkF-{FG81rq9}RHg zCg|a$uS^d;<3t5vb|+;zcaa#@WHmP~z%1-@keasgJyz+LSHn(}+# z1h+H}^2!2A;gJ&-Cyg@R7RiFbsJ03;!5Hv9S=3rR%rV)Lr79CV`<2Oyg zSUD4DdVny)RAHf^RXaWu;Di}ezI0|jq&5~mh!FMsu{!P1jM`@y*aV1BC+^9n5vP77Ax_L$D?xC+3l5 zr80%~QWDTGar9if}nRXmip96TyL2;80A(%D`Cqhmc;Aq{+_>U3QKnWtz-}<|P zSP>mHRIp+|_RQ5EDOiJ>Is&w64cdEq@M|-mM(9gnu|emk`Fs}i*K5IG=e)U6w&^A% zvO!>T;Z5Y?vxZhs$3PB6dU|i30diUd<3KRd4AG8gKFR)uB;hA(m?AlR@J}TZGtCaK z6f|x>Z+zX`uQj^EEO^B7!)k$gth#3Us6>cybv#f2Vcg;_YaXF1H{%7nqXdz_;XAp5 zPmb1S-mxqdj0B?q#Al$H{I0s|#tHHL1c6kK)W2i%qf*#&YYBERmTo!hNu7>YhvaC$ z!thyPemm^H-ebABvIL`0^3SKqVVX&=DZfCx;IwA@J56yz;P>9$8-vZ?G#Ga6N|$`h zl$b6lH*MuAyoiX7q0q!vFA7tnB}jY+(Hl{M5fu2>&NQ#rod@RILAB0aX8` zLiiUU@Xre2AEMxo4)}*C_^$~nw!g@xze}CJ5man{p{oAqr2j-vWo3>z5Rb%%TtA|4 zqz{!_2Pv8eS2HdI7sL-T{E7|_TBRn27jdfV2!YMj04SE|KGuH3;G8+GGc{2b@jocS z;m#tbVg-xZF}^lhIjTRQ=A5E#F^2kDYlx-rpZs$T-V5d)hAd?P6hS;o5u} zpT6K_a^!>Q5Qxnfnp|vNXEC^%dHT}@GvqX7bH>S*^-jIuyeUgzU1HfUT5);#9=N(K zZ~g5BgTI}Hr^h?ptZ{wjQE78sPTIh~aHdo9{z|!4Q~!Cly{+8xJphS$1(%gkh#fDy zPgcih?fN)8>h%7&B<*0}RpYY2j*lnXzR2j|X#Nnk6Y^@O+Jd#|^I6>ZHhcZ%bGN@7 zz?)BI=a>2XHLx(zB0Kwp9=rXz%`H~d$;FK$`wnl*`ee(CgAezf_}$Tz?Qk|1xD~C$ zwymW+ga56~o`F}ARX(s9U{Y=Zyf%?OhkV}Bqt4=y?ot4CBAJ5zld7V)DpaQ=&|*Gm?e)j$I{?yIYZ4H%;dU$)O!vJFm{QE-nLb4-ULpq?k5Wj zy^|EC8)B~J0D$PqQfG8+m&bKB{!sZ;O%CtXweZ3bzMtbyzU00#(x!8;xNIl_(Bs4V zb1be!Xh;w!=bc8bkFTj>K*|e6z-c))Ilj$pe2@g6b-Y|Al*7@oAy+4%iR_H5bTD!e zFLQP0_m%_^dsT+3htaNvk*Q|0*vrQAlsM=}M$Dh2Dl+vxV-zk> zsoHD?0sO8@`KGK4#~C<^U_jJDf?a2>noL!pl4)13pQm=M?w*}|+}w!fyR14F&ON^D zKF=?^mo=tX)V1jr7K5QYt&cd&M0wg`mXa)7W(LitYJ)5h{=@r|r23ZG+ER_hjfOzd zMyvw5(HWULsIrz940Ed>fMUAQq@z5%JX?I(yxpOY#D@Mv*}GqZ77oz86g$LFYZR=N zwVyu#IqfxPOo(M&@mYA=kaH@}b@)KE3y~6D?zwL*X|Aa7?D_<7?7nZ7giaHk`!g>t zcWdBx@p+B*kDuQ$xNODoRv>(Kr7tSMV#)|3+P7rfJYvm{UA~^ycR1*TYb-zvi4pH5 z6kkOED-TPGvCcsAom;TE4k=zdUi;QTX42d}!1i5XRzHOVcR>>uVDYS+5gL%07M;;b zP+vzuY>VF|0RFJSfJtbP5+gIzv=K~^rZPXsUgL0m=9L&S=ruI>K{WvpvF(ita~VM0w0AIgtw30lP=o-BkOLp< z`6Al9W7Ni~1Pl8t$)tWAvc@2yEG!XA45YJsRXm1@3dF^4o3nHNoV}AvCjkxPexAY1 ze>eh4Y8ztCR%+0#sH??c%!W*X{;PQ1OfZC&2g%gX_342pe69`Q_r>QKf-+S?ecfXP z?bIUBe!{a~L+;FK@zgI^-fIo)fjp*kT;eQ;Sa#mhErp+b=uQYGJ z^Ej%MM| z(v_-?2j~*8guP&AnLgFAm4#J-gq&ckz;61k?zM~{Vgcf;Y_~4;#5|48OSpN4L_d(l zA6AOVJTu_ner#La1qqIhgIxK;K&6(~NUdMz-oyQFzjg5@;&uG!p^Cl+gk{NleF?ss zQ8chKXFmfIvo=Df(&S4;Ba^d%82i{u%^b(#z=|!TIB;$oVq4FVj3i>f$pe&y2AJGJ z2X86etXw9I8OiwJBEK#N$6UkiCMOski85RNRFTXJM+##X>OG*wFKod{aN>S37~l6wwjR zTv;}EV=$$vWd@MhnLeZC^M19dOiQzhyLJb8GbB7<*W?mwULc2SIB8=N0vIGO?9}NP z6z%*5U&I=1aI68)fTQvXI`^v_XqV;UxZvw%8WafwL_{fpnwl8@XO-ife%VCvYex+&z8rev1YMhjo7RS!3kV#62E{? z9GU{yxz_8{qFV8LGik6T$#fj~SOHo8OyqUuZ3~VTt?ki%!`BaF{AT5yGYN9F{LD3f zKEsj&3N18DRc5hOUidJICx9n&>>_E&6sSueLM!epMstY z<17Q?D!s|nAS41r_q=#_$d9G}LGFGU0+E-vGg@Oy7WRW)_9_4bE8-j%G^Bh;M>?^j?4-n2 z5(xr%hgPfEa2JJa=LbnxE$gzhDO5hJz!7s8{ejJ}vg1NN`eHAt9y%>;Ph^MT>* zcpHm?z^oEID-+AQ^wC5c^A9_yB2hgTtidTfJw%xVU_Z<`wKRgZ$2F_dTeqr4{gv!O z);hf04n%v2fl&^7Wi@zM+y`9T90jL!pRGF13C1wpa@QN+s^U%?94x54-_(XqJAApL8zRw z3s7JQF_B+GdS)_O$0YWneBMW+tU7dg4L@WwKhM6{M$ zK@Fb|rTdmR+=ztdjm(KdB{%D%1-!D9&Jy+|T@cCCDHrqd(_|l!cChrd_!^oc-G*|; zK*8*h9sHVd7+e&fz*%(6CBt2O@^k<|v7+5ZkQ`P0)Wi<$|JhL8{ju z5zvy*+rohaOjILduHE)v)M$8fzvsj}SP(94ZAGbnda7hl)b`qQH82@pFCs#7CFftO_G7{=~ zbkyF$wye#16Mh8pzI))o{@L@)EIGbthvaa;V^Jxm`%+6G<_FL)` zWEW!EMiQ}n@2n(46?qW%L+wnC(Lz~U1SxrlCM_=x9HKIKKFQget#g@)+$6~zZ)|p_Mw0C zb)xt<_pITSvy7i^6XM=+Xg1G@W`57O7*F>GnYvC<5=^rmQm2MEQm+e%%6bHD5d0li zT}5p1L%A19hKcLKghL=nz=0)kk>-%Lnp2GnqJ2}+)hO3|S*eyIQNEE`OxmG>oln*w zr{|1v)HXu7MFCw_McP^GjTo#xrWUzk&4{c>TaB~dgh_poK%->cuz(R0RYoRg3EDi! z<%du(8z`)pB(Awu{M|}~B5X$c+TgGg;A-T0p~BJC!wX6|I=)=2t=?6>e^$k@{ggx( z|HS~!r{=r-Lz?_!IPyvt@;V1*G3X<8#)9tr?||vm-I^BoqB(yEYhD4oEe&eQ)7BhL zb(3aLm-CMPZgChRT*z`+1sJrL9i(I`$kgf{pl}2pCInqN7lgPp(hm-b{%;*N2f*TY zpAk4lgtrC%>)1_>UNpsrJx9C~r2sP~ZHklSbCP^Gi zqMcUnd+o~+{U=GoCbKqDjQq=nI7u9{u6GvlO6qB#94>tWYU45Q^i6K`Iz z7EA2H#f3Bo$?fDF+@nOgg|`mbiXseh6z`tizh_&#qo-5kHJ3P&m&b#^Y?3~fzm#}!ecW~xhi-e$ zSh>|XxPy8ca1HNVucYtnzxQuXO}=lYd2{1)GU4zgpfF5f`>E?!InjT9_4X_=rGwC< zWfR>E9nis#)V9mfOghFWLZKWKh$kK=?7^%$1QA?5{GiU;osli7||eEMM=;jg#j65v`)8kDwQ5KWHa9HJ(1TW9g7l2MM1KUn507OU1gR@ae zO1mG|x4E3)PmeraI)Rn&F?gG?P4XH<4Fen-v5lT}>gk)k;_K$dC)Zlp7H2&C`WV<( z`rufyyY{`mBMy#F7_!uSGkXvLx&lxIx;3us4Dj~k?Dpi~{>;h2A|oE2G^E47F#uKU zsH>>L>Up)c_i(44djeiis^9&LutaHR^@&%Q^4kk5 zgCvojXs&6_03i0BZj8|@?6SnjHNljXz5qZVJRu5m#85?n7u|K~`E2v7YL@s&u`WMA zOTeAYJ|e5diaP%8^fM4))+1`67g+I+MD`jOSWU}}G`Cqa2I5S`n%;}H6~r2Lq3WZpiqMi_+$1hTevn;YPs`K7Ki!JB3d%g-ZKj z(SWR7;ipo>WWQ;M)QfaO3gaBx49!A|UB;dkyG%`Z{_^12G;D07=S}T%CD$BtH~|2# z7aMy>H%XI3PVz&uM%AO#Sp$0dom(GI@{sIYzf53Q^iat)))gM4G`G@Gi=<52#axXE z=>NsrI|kYIFG!nZ+qP}nwsFcfPT4+X+qP}nIAz@1cpXUIR5E!AE87P;<(JuYa;!`lM~iE9@2|U6 zuli2(wGWe1t?j5(B+Y1NsF$OQo&13InK%hzb~@+g^`y)00@7j>xp6S^EK09=6eEwy z0l-$5TkxI3NL5cq+(b^XkqHO9lA;lY>fV?7b@M{^Q>R^Ks1szsVdE9-NzO@PzKB=j zhezA6X#Q|7JZ|Wv0bVvCf(wm9Gj!2%5M&?R5`FQ||btA`#qQi6m6P!pL|e zOpvvEDoDD>R92!KqCw>J=@=($g9cFAc{(8TE_n~tNRL~k7Dy?@3L5yV9IodLS(&0_9 zG?qvyciuw$`Z=7$p0eE}30Y63-b`M5Phz}FN1Bm$`J)Mxd()o8lT%CfnbsqMPZEl<56J695WF{bue@1;THF1u-EE^ zfj1t@MsyH!_rgXbX~ZgNaejk7N#ew-CV`y-r|EI64HT{=tB~HV za{w~A8?~w}Q3)j7uweMA{bVV7oHFc(=&YZUn3GF)uU_`%7*Kldq&`f7pizJ_j1uk< zd$k&#Z*{6t#KUw0cBgl~Hqv0ci{MiU2f2HoRy6`4F!&Xeh(3T+{VA)#v_DPpIv8Q< za1b!>{5kql&+eUb*YAGv*@=~8?L`wCsPGY%NVYTi^QvYW|M~hrnhh@d|2LUCRRB$r|f~cN9Pg=$$i@%&fi4;XmXyv6KI`?Kb z&qh~?m{%-4WSjNN9a`k|SlZM+X!Gs_71Tf(%_#Qi>J5MZ$Wgcp?z2y`IeEBuMqm8m zHT1YD%NZqF0gWKv{0=@0%nDg(5 zO5Z$2-MIE~;NuX_0B8R-{dtXFm~ zjLf4PlrLzV5z<8n;dUvn2m_(fDsdGAkR?zpq=c|F1(k?Ej#5|2?$xcY*p}3GMv- z&cBrG|7B?BPfCaVA88?#f7-hEn~MG)37$U!`+u9@`4{y0|Fh5z`#+l+f9do8a4G&L zeZELX+KFVu;ZJDC{C*L_B11REhf@f=S|+p%0$+rRN>R?QOCQpI>@}ZI^je6 z`QFcWFgUiI^F*UPu5<4gN-{}JnUkzIFr23^6&pI=WkV=*7M zH^$|FdrQyrjz4MCWc>u~z|b7bWECG<@fU6#z0^Uu&G3(#tNtuL24AZ&*Vy$H8SffR z>nHKNH?arguy-*RWvceQtt|5(1zS6(yTdJ#r^zkdZF9*;v!|`4dgm)amh$V3t&pFY z!(fDf8!zVv-Yxl@>f`m*b7*MCz`bhGdij^# zeZ|1#tDDEqo*v$8xzOd5{rlt4WA6KujyEsoo})u(DLmtaJ>T*(a?tZ%C{0GWAOm-L zwFD2EOC|g6zCIiQr1!_4r!QjT6c>bVa2U)lv`Rf;olMk9jLwDAprK&UeFnnhX!^WZ}AB`1umhMi$J@hzY<#lta+bvN#1pC`# zbXC&EHp06EH?!Rt=>{tRC6yS3cnD)SO^ADkfTAu&1!VSkmzSCD>M8kY7nJF;s{G}q zsTX~mI1VhI2slg;71^CB2pKHo@CUQorZh<_sxA3v;4jIwtz2#@^t)6p)(F!yO{+XO zpLva(cYbOD_NMnLR&z((`ia%mb`5LFKobP`skF!fRW@l+$)moVKfuuk$tC0c(8Mz- z1yvhHJ){aiGQFG^hl4Un%G*gGx%x#E5bdUSqa0Y{MScKD0c-j*FuzHFkN_U@%EoZC z6G?G$Qkv^Gsr*6#fFO|#>er3>uIJZot1j{g3)g@M7|VEm4wjiqIG*Y#MLpo@^7D_k zdQvV=USUu1S9=Vbmr#xyU=_9!9C{tDj!udv6l-UZ0!_wT_A|%#!0n- zhrgYjttXt=T29hGvHogl)<3KcwGqMK)WiNg4SMd#AQ;X{uz!x=wO-a#{+#(6M}bY5 zWzN|Upv$^FugMKTryfPqq$HLOeo&xO07*4d-V}=F*DRcZ|TQ|>UTs|+zp9dVQmN-#Yaap&!DeL#UoXeUKR`qj2 zlPQpBI76&vVo^d6Ykn@~AQiAi#3owJ+UD0It_0jXl_Qi@!D&Wd(A2^mMSAHNW_+ZS z)cT&w?(hw0*{-oLe9yBEGyS;f)xj&H{5X%*-E^($;4fCY>c9EXRaazrH*|&!*!TC) z_TQmK{1S?&7_$;DKVUHvEk(~$B#3n&Nd=&wMN-r2dMSpAe^?hoU@Qn2p1hl4?At<7 z#|>mM&qP85;Q%faii8QstnF1U2&?*rKh!Sf3+ypBrjPpnS)Yi>w?;b*%1-~0P*S{} zfmPMW>mrKtuwKG2f_nM;6ueNIrfc;HkV;BX3?^||<1y|f@@soR{WKkrAOQjZM+0zB zQx48@C}=NKG?v{j9>Q2!!wOU54M2aa5UTW4)~+aVL*jrupEM#ei^@u&qexIPD*LGS zX@$^_cHA#sP|`1+0c?!U<^fUQJpgXPuQS|3mGT>1vk)gPD+)sQ00HwW;!I%UcfPdC z^M^35UUUih^z5wMs?&V&Zqd8?I$rPgo?ff3{u%>P+{Po<&3nqoXM^P3P3S!@7q08G zOzxcFZgTpy`J=+#2P82bPPG$m0!lQ$Y)AD#>O81pOw{+42Rw4Tgpv6Giq{@Jo{ zF46KhwluNlx#Q{UnUpxDDBLt$ti}SFeTlpV@?EDe!NjJrLXA~a?lUEz!Q#0qYvY82 zF*3y&G$|!$0t`U{X17j0OR=aj6x&=3RiZ2U z7BA5;=@cA3koNe)0yXmkiM*=}8vfXZvn^dhs>bZ~Xd3qBk6yl(Nj8-lg+qz>KjQA zbewQA$DyCA;PBcVg`cScHy-vAZEjJmD&3O|&|)O-+i|RkNL-DCij%}{)6wZsU8?|j zc?7Z;j0HVBqQ9MK1x;Fu*a?X)^u}XZH&B)ZvbXd}w98??yo|1{l%HH@;E!8o5L^h! z^Prqxd~ZNE3X{LF^d9+Ba`jwJQjxpFrcbb-`uu(ARCs7!of2P`{BK z>&C3HZ?jW`z$sg4z`=k7!AxF2*9X>}iihn_CC04wgi!%i#qatK}76mJL*(ofOpM1z5$74Kj zqSnsSuX`gv3|AJhrq!DGgGxTfRgrHk*%85%+Y)|?fJ#6IhH>IYfRK~v1;mR3c(F$k zkV@GQh9S?|tV9yheh^QMO;hB_dn*s*XaBQ?U#Gv%#9}){#yY(X<2{|!2bI5MoonJN5{3n?d zhu)7L``7fNo|B_s+k``7!zIS6GOJ#$94RKj)8WO*WdY|cSJ8=40gS}SsC0rPkIDD2 zKIvNk_N3IJQ_C6Y!~%WNARc^G0ZG#sjsz0G3`GJ&40uHpqG?sJei(~AF1o~JUlxet zW)Fmk8FDWnpA!Cio&;dCvv@%^{6QL8<42@xv*9>DhXrQGN+{y#a8>gm4)BWmgW?sQ z`iCJIB0;M0@L^#@ekhA zBQeOnScBN@u-0CI$cxWFY#|?m_yV4{23w^)b`Fh*kBnwv#U3%h86N`NN>YJV;zZ&Q z)BXS>DHm-mvZe@gLYIF^ZXm=P!c^inCTOE65UE;@kst&DZ%u**r~FYy*-FIKQ>YAv zRIoVVFEWRNsTCgWzlhyJ3zbIG{ypgfCNa+3EJf^qrHlhdcIq;dQFw*`ej??xo_#-% z=D)JybQVquQmi7ai0x9`=DLVIEyb*eZ4b*$1S8hrBvL@1Gqp1h zwfU_{0pJltve$9#Rz#7e2?Y!mB#{|t90CtMW@Wi(UMj~G1uj`(M!dZo7J_VtKayY{ z)JibT5OeCqVv>njh^L|yB>SuyYz44KB>8+E6S~febR>bx`4h??T6c108V%C+p^m|h zT%lbSV>u)4-7hjeu;$fmFrDuE1w36>tUo$}#ff&v_qCBf2hXPj1)JEbwWBCA$2YDg zZA}5{Q4)q}(D7IF10&Ly5;eoB4s(n;U3uAM9wA5;d~&X?-LI_P5Hvk$ry@0%dz7*;>uju+ z9H<{@EUo#m@#1We29J?4&|^+omyQcd4Mrdc-c5GA+_p~)3Ux%U(1x7jgOClJa(7Ov z!F|a|8e70gr!a0%2BOj8TY(qH}7E9&D+kM%8?6gV%4T$+m*V*LaU3&RP5Cijb-eZuU zEtD3m_(58-C3LpwzhWj9OA_j z3iK3F-erV-;>IdLBm1KC(dkLs=4n;VFiZG8-`Z!qDcssCgDm|E%NAGP@e&#CPqmxF zRAR(S@D1ZB_hX%4cUOu!4;LLsIX83RhlNHj5M`Wn@i(}!nGI(B!m;n=oY|fD7R=k| z@j2`Vg{!3l4L?OtJiX!XGZ_!$-2^LAxvI#j>ZCEC z8I>Ny_k3&=YxN_jG4;mgsVRAn|55&}M(6k{~=Ic#L#dzCsi>0q1Ov8RF8K z9lZ+IyvDz~-?{=vS;ihsdx>;Kt(1|))-y{cvP{R;3hGz%6#|>76epJ|rd=61EctZ2~9g*`534_fTywxsdxY{7s*#!LJLhmE-p-*t9^!upXVvF!{)N`v)nyCz$MZfrM$VxSdBV<%>yMftH>cpXMm^W{oMnM`Vdq}8UvNk} zLsSIRiPneYnDNd+*Rh4=zL4(PYNdjlJ7fLOv;^JxI5R)m0g*g3<$Uf7|HK~pKcNu?N65FdEKgYOtw$6CSGraj7B!)q^x z^wpp|UJ?{VKu$PehJt|#XWvyn3}~WLbb@MA$h@EWevoHZh0zOUzk?`u@wu{@fasx-x-#Sc{L62dCJv6p+t2Nko7&0*4C}>>9N<%P zD+&ZLZUepI#EJ}^M9ZAW(%E=}2>~!XGFL1kxO%w-D&FQ))}s-qUVH$egey!S12|_C zq*kb1U=ZlsVFD!%?qN|MBu4^I#OrY$q{yI@v$k4>)&a+fv66=VOx93oze{luLf z;2Hd@I@W{+Si_v|&PWGvr;q15p!*=dwZlg2Y>5+0sgQz*4a>w0=IoRh-)ss65PO;V z;bY{|?j+E3Wn_6KMxEy)-pJ=`B1>oQ%QM#ksm0gBXZclA7}BF2ZUF{56&T=_9z@dP z*Pn5M)_sDcUV24~#6S!zzFmWZS0KpAbUFbx^Zi%)HOR2Hdr&0Y6}J9)Fx04A#fZ(* zoi2fj*@I)s+Sf04MAN4c4Ehjub6*+c9oUj(zt4Uxod@)OvTi2uH%@#(I5NvCDMjQ3 z5+J?x^qP2Cz`L_va&;CyERK?ya^?t16||>TE|-TgQS^K=rdmkRBIRPlVke4511O1e zCpUjHF$wSlKk=jpUwz>kHQ_@f(lLWsRLDPnu`WRIQ6o%$T;8jdyKeB;#yH^VVs!H2 z$zzxgo#Q}{qUCwNUGOy=T0(SNq|J0+S^AhGqe^Q2+J^<9gC=NLjYE#I0YR75tIxl! zdj;xV+YfEdxRo^uz>z>vW00D`(*1%+T|Y6;wVwu>);Fjubd@zSGNKB!2T4rNfX4zT zco{cf1&dYRB}At}1(d~%bfDQ-8L7A&xe_VUr#^GR=Z-4~yK1XS&K+7L9dP~a=r zi}f&Vq*LrHJaC^)WkB)-WM}nC5Q>PLm;(8!ld)yRTfh<^F;a$ie_AsNL zox_WxEZqC9+95}I}`rh>f=V<+|HiGgRae3}N~7oC#s(M9WSpbRJ_A8{Nq^q3l`GeqJ^AAotKObnF*LQ?bf1bi@Wu4EeNGrgcNe2Sv;Ua%&!Mj~Ako1vhr@pWbc!+5kph<>XXv zav0ub!0ZcJuQh7m$}YL`BYNpfOTU3(U1r9N7H<8yq@!yx=PKaDZQ*iSGAFMNBu0yI zej0yNzOBGIF#-b*K2QYx_|Qj~%#W=QrH8r;TQi0OXB}*wfsNqls{JbzdgWzzw7Yd;12&40}b_WBM<*~2Aboa4XJs-B-w~%SJ_Jd57AQbH+uM0&I<{);e?~zNBz2m9+lEvKD8^4D{ ztGI~9ac($$cQS+BF2sYVW(?Wj#jKT}8Tp`=@Om`*qn$)Yu`Cjz=g2G~CAC1tqTY*u zpBB_4DB)22uG@lD75Xlod066o;;nJ>IvV=UpXQsOhc=L3j=L(M=K;od*rHq%oPLY2 zr1BS>k$=bsR>n=yyzTNg$8^J_R z9L+_|$V5}&@0%@Y7_GzH^$a$*G{>FNi}pBRV_XC4!+b#$uIIv3*@fcVcTLx|k6 zJ$*&yVllWkfUO+=&zS&w*|n*+Mt+)fjfnky%T0BCZoNOl4owtxipO9-ujH+_VGxnU zxs6nEbv#g#l}TA9xzA+ekr%m)Hvky*TF%2Dt#)$z8$@*GzcAXC8Y?z!iZ%OMXoQF5G@`9WeA$E$n z$AkBc`uU~~H#MnP{G^|FRUvh}NiHk;@yxZHox7Y!&P(-$3FZ{9GK;-|?T@(0XQLSh ziTl7+ny#O_;jYo5gd3g@-k_d#uRl}XyJ@&{p_v+ADEqy8K5@3ss^q)@`SdzJA8kQ* z3J%NFQ!Z`2S9q*lN|wC87=PR5{IFOXSu%L6<+OoY|7P=M@crc079mA_0NPBBj}~P~ zEOGhlrVxq(k-}V~^h?5hD1D^T6g+kLzPC2+*C^+fgke^Jy0>=Glx&KjPLCO5tqAPr ziiP6RSc|c@FjQuy`p8gUq0B4_&+C#FFTw-MW@m1vGq6#K8Ri_4dI*k`(muVVI8hdG{la#{$p zB1g-j&?zil<)crOsk5Sm3HZm)dC^21Rx7cp1AueImm?$*kRX`a$`=B15wiaL>Sc7^ zP`LbP#>u^hb`Ggti|oqLJSlb|t*R}6&W}1a(&E&ihv1)l@Yj1xy+6EPDWMiR35fM3 z%tyt20G4z?6VNvnLa8Y$C7&xofC_w^jfw<6N_1*Aj6|I?1RNJ1DTm)=r!4@wBV?%` z-V|u>TrtM9S-ZQSGQ**Y>LfO&ycXn!LajpYMpmIN#Is7i2+g083N;2w6rWQD*uOZ| z65DeOGeMnao+h9i(OHn#c9Mf#Q*Dgu(H8PuC^9$4rtF-535Y>C_E=X*YI#OpH?2$$ z-YaZ&KebE4p;$(h>5m!ELakFUqOn_Rg_*1(7MOR(gbX7?1kOOtb&8DFcukv3Y@h8F zI3~$WnIf1QR0?+7%a8F#5aC!zo1E9w3XwbjmxSRHQaEHrv9WAQFqhsRXR&v{X}>c? zOydkSDXG)(qa;m+IL00;ODzVquD{x@(d)_TVagv3-0L_%`XF`c{J`XLe6n4o=$hcB@KtSW~u&2<29M zP}6NgVOZXFg)~lb(4b&Q7tH+|BoR4%Hx#iOADz;e7M6OvFO*;i~mxO3dcWiz<)m{{QV{RubdP9e&^pF;Q!@0;s4u6#{U5&$??~c*5AI!U&n^O z*Sh@Alw_5TbOK3>L-%tH1v5%CmZUZf&)Fda{s{x^7~wh+DbvXh4iEeK?-36dqi1HeEAcrAg|w*P z?bh;ZejIaXt@mf~@BR1t)6nA%U5ysYjAq=5_fV=9|JnAqEGbvTPU+7Q`fHcx?Lg94 zY`XghXQPECE?tp#(XHREsA#WuKH_^*nMx1kh#r@vO^yd*+?sb~{#aSLE@BFESFWUY z2Ig9<4BjLsxE8JDF|!Ft_u0N~ue;jR=5OHh6f9Q0he(ZgUpLMi*Z7w`7iS~;3kJSy zzCgjmF%O9eky!1fmL-YorDkT8HD6QL&}PcWm@_h6an_avTR*4D%dCdCCfMR(HGQj~ z*U!~h3hpkpE3r1^re+^cZ=>KjmO$D9lm0+pmKlT$Ml(z-{bP3x^O}w3A(SH#fIvvY z)9Jmpr`7WU{`l8afU@}0Df=xkTY|f9$NK|>x1W{jvDeSu%#mu=b?56w$nzXd1^7L{ zl_e z)1)^`L$!#6cxu=stRE^i+vd4W@aG6N{K~4E;jfmQeH2CM7CLyBQWGS?arKIU3t=sZ zZwsLVm?5s;pSGJrpa*$knFK$GGzQfLsWqul^Vx5Q;z9PD`iIm z{d;J|@_+QE0x-I~r!hK^D0!4yhKq!EetEU0>I8ht+yHF|F1}%ZFMXZr#v>faC`8*Z z!$P3kjs?C{DOVm-I^y)XSMoy8*@3QZlJ9t(k8Sn^?idm4^v4TX7PDBunp5tqv8e{M zsRrzcF#0Qu-gE7?xISd|xV5=nPLF4y*ynj&F(UHre-0dipgQ|~fl(0zmi7op)V{6p z|A0FtpWVEqKsCmCGt+uPb_TDy^4;4eFQo@*20W$s0&cJiHC3X8la>6#K)~IcdUfLD zY#Avg}Uc>0t7OHcB4e0X9B2Gh9}01j@@`H!2HyexrL&N zAZV%f3Nc3q@UeE{!~4;DW)qSDL5m?D#N+-H7tzR7+r!~2X$3VTjbFCu*|Urlt)F$U zaC_(fCneB(yO7Cek5A1v!0R{) zm^!dALqNa#1)GQd;aCJB_PYKsivCI<4ejVI4B6}P3t{c`XYLG1FlDKcdEEEQy&JW& zEeUimR{5+L(Zekv&8HH!Ra(riZ)2F>Xvf7W3Scr4`6m725^38@Op-uFB7z;o5e}9l zR4_*a)q{L>z(L(z!dW+9udtLuFY1D{Qn_seOfJcNEk#+Bt87{_)Z!JDSvG}1QZBNl zb|p(T2?XZ&T1X*}vu#l$hEqfhSbo;HjQGSbk^Q)v`uAdb;udaVq4Au$1TQD*ajK@q z%Y-Et3f#AVN*(t7>udO=S}}Nj+uv*rB*r-&#;R$bvOhFX2&AUEbs=J>>dJjpp=^Oc zwjX!@#QX*Q)_saX%1%QlarA8gNh8&2GppH;u(bi;c4%@n;&XKwcKHF&9!{Ji*39Fy zzu+|YuVClpu7uO^pJT4!x3d+CMP4HS_tdI5djv!<-T_B`dbaJSi)=k){E%VPwiVB} zC?2~4ni1H`ZFa<6X@Rxo)AVOLJC}y?pO!TZ4g*g}u_g$`aAqbdij-%ZIFmJ+m&k~h zC;_gfutxn`(Q>D6E?DBL?g9@J|EUN!Cq!JY(PjcT2^D0LZkbi_+V3{|*#$V@A$wid}0`cTsr0!qgP*$8WJ+vL1lPUbHpQ$DPhS^deA&V|d3pKYCV# z;_T<+&k*}l0{30B$;f#4^$ZQ41oAE=>7B#-we11 zAy`tANc@D6LYcyLDFwvzW=W}r#UOzqM8L8EPna^k|Fk-feBL{$==fIk)UkE$ZYb>y z8yAj-d;k$n-)5zJFx5-Jdd(jIsQ@)ra@Y9q$Wm#1usoMBM>)RXYd(#URTpIx#ztLga$bAh|JNbrJRm-w&_aLR9tk*?=Kr ztVhe3`2d-9h{A~(E78815e@i7^@Pmc4 zQThs~_wc~B4*^88>L)awPg-9v7(VqyHUNU;Mm$O37p@Up4jm;uNPG<3=jZm^^yM!U zpGS@YF?K~w=Qj}zn5O4mhidLsEd`DqA6Nu!-;kTtiiq)AE zF-;`0Z5hY%1K>5kJbK26LdD{T$maaDTujWy9LpTS_nY0x%vbQ2K+g@hCvpq__o45V z%VKKL6?SDyIew`(vfgjrw&>_r^|QLxcmC-1BNird~%TgN*V63NGF&Sfk?e(a1D@ z4YrHzP*azI(3i{I(_I0twCyl$y%hK-vCOwY#cU&wT|PB2oE1-dmZ35^2yO9_La?c` z;H;}Sh={uRF$;r3xDp%BHWd`}MI~CLW@l8f@GJ{*H}$E!CcLD!0ts{o{i@808cynb zTGf4O7zHEZ{%{&#^9E`TP-X^tu;-_8JL02$&RuokU~ZkpEqep~3o?m2c0_RLMx?|B z0xb&?e5t*8#=3S#Y7qb{QU2{LR)wXaL}370(5xIO>Ooo0F93QwqARDn`-fg@oe!=r z*iY3Kk!-v+WUBkrEtHaB05->N0lOmvw1*oWJHJ*ZHOrQHk^+Y`I0`Y)0F7c;d*A+Z zb}0Wg7ygSA@O^v4kPKP12!}0^g5QWVw5c8U?dL)Py&n*=Fek>S(e|gKy=2_=qAgee zX>=%^@{MGx?XS+Y7OOKhX$Xn7SICH1n%#0iVdeYva#N?29g@?jMM6hGeR#((bnmd! zH}1wV84tfPbVV zdt1^g#{|;Wv#KaClLw}wM>xd1DV=d{KJN`tZ z-O+?oX6d6;_x6UC{+vglq-3)sm*&pi=tax}DU%p&?-)SYmFln=LN2qnKP|pT=HDKFf;lu` z+_5*=B4C!v-rP9RX--Rzh>@3TfG67`h6IXWgR7z@6_L8Jk>SX_6sreH>yHDJiy7?f z8gj^*v$jmS|$B8}qvJ*VTxZUT3vA=mBG(0=^8zJl)xG=mUvp^@Gf!5D1jp%FgEv zNsNKl$}XDm;?N2K^#pyb1In1^GyG|9-eTdn)w!Od&$Q7wQoXf7Zw&xc%jf(G$7q&S zVmHM_!eFT9U=7WO-9J|E?HiVoK|kglRi%UsXEPc_=Gqz-*A`!~S}0t=&YHFuUUCpj z$<4#c3i=I6iDHsJu7*?ZCwyGBC=~0CDm0T$hB$!zYB-KkqU{l?QZAfPU1vv84<6-W z5ZYW=96(9;(5F1r5bW;p5`5Hn~ynI)ukKM*yRbw2fxY@y`j zv_PMeD;o^*lr=XG)Xi!_(9bZSa4~20{m`AH&AzuEA1}%*RLHtWd)v3D%ONSq@e)q{=6HMaJ?)Sb$P~>XvK0HG^YQj*)vx=UzcMXJH?56i{7;D~ zhzZ0q?n?G|Z#O3bx>CT~6AME5+*XV*bG-02g!fbZu_q^cn*camxo= z(aR#PT=MVZhnRhsg7-*H5}OUOgwxr-ODl61q>k*5%VFD?AU|k(#+Nki@g$ZdARq2%@;&KwY(v8_jY<&XtCs*wW;p?3%l zUYG9VGB60Cy1UHsj>g>#J90~)#iY;}Ab}hvsPYypp%bKxx|nUMyiz4~z-5ohDu5R- z3b|pk4&VCIDWYFrvhz7W8UAkMSPj})oDci1C-wEqPk>%bGyLhp)OSCphh}acQ6%BSe`sccV#H> zC3yWdb!=?Cz=zS&@N7DUccT-r_pvIRJZ+dn{{yI{kZWg2`-1MSWq1?VhnEUjt9mLuPSzl_X&% zYE+=-Pj|cuYXwjr0V^K?0!N)R<}VCSFHbW(ts!C``)`Lw!noqxkWd6lD@BzC@d%;) zc{$dQc5)b;Lq;Gyy>Kc!kL4hO#(X<3bU<$yD5hWifu|pCX)|_Q;D9}P863@aidPS!hL!^s&EvV`^r zk`FeOxW1L)QqA;R-o9LXeR|eVkNBn6QkaR`Fz7_Jn#1p{Hg0x39U|Bl3$PS3)F$S& z0*qx)e@JgKcSNzCUW^+t9Mo2&<(Ic`hHFsH2u3KjCr^CEV;;%9%Z_1SlTO22$dNR$ ziL|ysa-C6xRPS?sK*;bzS|-nOrc|HkiXtk}{$z8GnA2kg1s?w4y4bMpuaB1y0A68< z=bqgUdl?Uek%y;`K0%|e6bZt-pBs#Uo?d|?$FqdhgL53huvAg(0F+HF7cYdKPwlbY zg!<0lEU}{i#1}A_rGdMZm+qT{mXOujg0O2GZdfcgQi9>^ zKAK}Z6D8t^rnVRsflE@clSs!h8@gr)O`RfVz^unHZ>y@P$X(`xsO}u(B-zfQ9N(H9 zg83Kn%4ZV+Qk$%@B92r82pnM8vnz7w5SSpxg4CF)z4t3{yUAej;ChX9eQJ_KiJSNX zpn)X5nsd%LZ-_XP9SIjvEZ%Kqx$=6IXDe*D1rl9VMjqJV-v)g-B}Op(18EzO7Ha3k zcAOL{V!GnR5iton?uAZLE}$XLN;r|!O9 zIZSK5kdkgkQD%}5_C{`qrzXqep>F01ce>oO_|b`;T$_Dw4lraZ_$W zY%gwuD=RFHZCUZ2eG3Lka>#6ILcrEirNFt%q2o}BJ_=rkY_bU5$Ra`?ppFJ2X!}BB_BLjm-Nmd<=rYLmh$*Iy&v0Fi4xVn(yMS>%UIzOGuRQ*Jv>8&UuXC807Ee`)srnm_Q5*ua1I1OGrN|Hm0xj(>(5|Nlld|Ao@^ zKgj0)B5*+PUj`2TIV$m&bMTMa$^S8Mpe>!SK8)DCuijgh7+AG3+Q|T*loY62M?FS} zI;MRXSO`2-)R>rZ5H4+T__6Wv zXhT1KU;WX>lf1p1oVo110CBJV-8Ph>q0YRN*b;h2-_mJHN^iHFToZmaa(`;C>_d&E zrk3*lnehG5d7smqQScp>b6Z@=$Di#gKfq4^d{rU(xVibh@a1-^$8U}IIr3RMV&cjN zV3KFiF?dc+-Kiq$tm4nL&oxKVbFrUAS0c2YkV)|_tX1^6 zn`iKIZ`D^#YQr>F1?D1~RMAWAwnciIa3wv}8+V3%l|rmdXVO*c?dnzBx*qFlIZP!D z?UxSEXjCU!I;mIL9Nvnq=}WEc%URrb3NXDOLdGA`(zo1!It=hC}Le9UV zs`V;Ys`q~`2zps{*ncGrCqyo14ZcphsR0Ul(-S|wa*sTxlZn%!pT8O88k%_J7s7b$H`tUcn^-y&hPft=)yk)E*R_b1FKPt#? zx}A<0+CNQb0J`;M!DkzwB2$%4-Bi@N(1TLb7<*r?>l0tjA_~(%6ScJBC-F)vp25ya zYAtM-0I5sE7gB(2$|j<5d~0|+MiF8M^(FQ)tF&BXrPn3+FdWQcAaqu8czZ5&3IP4O zepq|wNaIX)I5rFt+G8+Kt!lk&3M^XqIv02DII$R}oqTB|&MK_}X zWzf`bc>(M(fBODg>$j|N&G1wc^&w6*Hi?J@Zpli6hNw!ZF{M$69JgUYXZlVHLyYlr zItLLhzMMI_)^S}+V$@p!ydZpyS08W>r^=vJ7=J<{vJ}y5J+j&?J^^r2tX<}Xm1;hE zifL^TYEF>-hyl6EDlFwY_)YBJ*q&1ff5P&L&S=XBSl4XZ2bS?;Ih}9?)9O`1`)CX~ zv}YqT$Yi*kOuXL3vL<OW{f=F1o|plE>9>Ty+SYsO*BVe1H}PS98I%!V=VHW3tME$@X_T?`)|bS#De<=h6{{5t$Upm_R>f z7Qb6TOR-?Wa|o%GRIcK2mVYLssopMqkQ72i9c}=gp4JcXvKb5Hb$?KLePJmPmBB&M zCZ>XAqVYmZkKn}7jNGHN1uxbjE6Q3)AZ*O_0NFL&fLOG;iM-I??0>xejkj0|NBuYe zD|(6$?Apn*ZW;}MX1Hvty1i)jY+qD0l=HaXr*B|Z%(r%9%W7W1^MzzjyjujLInuaL z`j-m#u-F=QY1sOZm-b32pxDtQel$nQkG=H1-IUx46M4qIV&?$9{N7#|mJh_1ZvHMn zJ|$V)x9&byYuu$`(yRwAO3NC zELoQ2bE>|oDnfzfhkhV5JihVd!2|WT8Q+Ds_Bx0GpTTGH5BuSJ0bDZs77I-~uOrZS zlCGifgkcrCL{kx@=T(PrQ(9hJJmy+*LdDJ&9}=oc(B>~ndqGa=o#%~pjsEixO%84~ zsh?YLyl|E{s2Vd+h{kx~_NIFe3$?DL7_Fd~IGt!sqj7DOtt#EHGO3jYfjtgr$JR*B z)6*S9N0P0^fiHC8Hc6);$Bli(!FtJ9A|ECR6UhjU_XEc#JO1yicC_0hLnv3(;88UNrk|C#-J zV$*l;U4;cQc9SR^wwJjV(iuC&P~9*X46s1=W~N z3Hxx-JPG4Np;yJ%ekKySg?O=eET;-dku&}YhAotjT?_0WV*f-y6aVER`wFO(AU8j_ zwDBmOMhMTo^&^X0`a{H0vf+s~W0hL4`>;H$3&>+zJCekZ5PD!iJ83|wY1su;3%TOh zwD7EXlOBptJc+|H$4`gYdz>XbHZx9@&* z9OTk6%mFp}$~_Qna9HB0CVOhyR$BMJjnq~9H~Y?Ngu`8Vc6j?=vfBHm%lT_YFYD&a zO^~2?fdZjOY03U}--wjxk08rqAoy7+V$49eiLayNo!nIVv&hdZaM9Im#!D%heElF; zGnbD|<4Tskf<4ZHa72yugz-eQ9wNAi69_8p z0wxPAnyDMLqcY{K8P1dE!*+T{-F6n+hk|1Q;u>=Y?; z8qx3@sfwa18>yVS5jV@tt|(nUqX}x5!7u%C(=Ngzmmw;3?~vC7K}1gFZNvJ`L=%eX zfIK}f*zbj}gw*^~{rP;J{UuG4PP_z)y57i=V+gsopKS-xNQ04PQU_ws@IQ>)`>5;0 z^TACrU+idnLXC(^#2*b9O+d%{-S=TtJ`hH#=xN|}QH9V0XK#@o$aRbg4blqK+evtQ z&m%qSgqz;3=Z#|QQ3rE}DNcE>3})d)LG@$MX-?#4r`ZWizV_|zZQV_dq#wAqkMnKX z(lY+$pW4n&KM()K#oey;dGz4Pmc4etXnJdJ#W*u~+v?bas;a)XF(vY%-bG|CCcOSWdAnKNP08d5wx~P*083^KB-to`Ec%uGKpaHD z@Y~Bahj8;q)kE9AWdGL-QW#uK{`I_U)y@&UNlbK!4G>0HtV&vn@=?l@QPS&+=a#NG zK}$f|S~@dZA>F;ALiFp+>Cl?1UhYweDuY~5?MfpgY}^Wq18jHGlt9v81#stLpSxih z-hhyWcOokp3mQh4*el)cT4?!7UKqVE{d$_BX1~D7;jUp5F~57+U!=errxL3LqJcf zHEY9flRQgl%YB4Z(;e`uXJ|xp1^TOThh|j>da&v!DrJ!9Wx{@NdV9LlOp{*C+T2q0 zJ)B3J5tq}vuX@C}`9i|y&OBiDh(P$@YrGVcxev`CUGt*g%x;ejmBxB|Md&ep?yic4 zfCuQ}{{bJsv$S;2jm2u!2As2OlS`1xGg}Nwbj0)wzeFif!9%&{1&J=ZerAHx%py=x zzOBCgIwvy=1tJ!Wn83GLQcsz-(6u_=Vztu*=b7jS9T2`@i?o^c=b!U;`{V9hbtz~>W*_uT9#?J0~MY(4Di zC8ukhD|-#%fdJm)P34n3xZ7t}6GtU_!hWnf+$TSi-=-#Ej``RoNlOH|uvt2QM z`GHQ&AK@8R+aRGT0NfrSad1F0GI|ILlJ{ns0zfuZQf9C}b^X$d7D|Hwc`)LCQR_zl zL!$?zrSBw1cMF+F2%D^@z|v-m1xYXl2CON8pwCp-XqVYHd~*wPtpuwIlq1KG*P8$= z5(69smn#_Jmx)aoU92xjpn*X6jN+7g@vzlyA*y2QCHrig0Lc+24%UA8`u1w3w~9SH z%)FYi&x#bB8M~6j4u@mMZ2JRitKZ6OO?-fgS8f7<{dYo9vf@5SEG|7h#psNynnb!Q zL%7S&*++m$vMl09}_+k5n66l?O{+LDu&|(zIxtm_$(4!F+ z4C;gYEEVk8*d(A}T=wg~w{qu+#HI<2b@-XDtA&Uls?w?xCdjWJNy$1PP&Y+Y7FT{heneau++%R7*DsORNvNU^_YrTqdaQ zSrnkV@Q4bMlc7RrPMXIQKYdVsNkwGxNt1ezK%r z2{sp;(fs6;fO=@*)!^X=I7oaJ_>vdmPb6gB`rZxn03hl^-@<$} ziu9ao6pVe0OU67zd-N} zV&w=En&@@e&BtOGj(;qHdOz^CI)M%uQt%U86a z|5fu2&iTwrurM-Gmbiow2y`#hntIA2l_m2j_g4HYGr!%|88J^abmCR|tDIGyv#n}i zT6n_ZbIuF@BG1iMbyfaea%S>eZ$>S@=~Lakxj3NxD9~u7xpv(k7qme_}@a2b~$Y7ZjxX zO=tGpA!(>Q)DQ}qe+gRzL zrsWfC+}ugtrcLz@oZuDTd)@MK^?El=weE2RFPV^~6A=8ag&A=B3u%0}GrWIV%h$2J zx*IoP-&m$^Dq3~yabI8V^I8G0GFO-h3~ZXnz-4Kp!D5A*WN_OefmWy1@NTKbXjh&D z5=uS2hs&Sc2{Z39P05Gy99DtuT##T9;#!@7EO>s5fv#N8VAIa|4OVxz9-gWX>h*I| z87uVWxC2^6?H^?3u$WDyuiyRcE>ITLg^O?XKA&3Mb%wqclFw^%|?taF^Pa7n9z&XLo%yM_*SEe6CfBB4klt$Ke^PL`3ZZ zzqhWmKc!4kX2ZEUK8grEvABUVlOZ0l{xA4XjeZHr?94w zb7#uAeZ!^fTl3zDy$jVjWRZASw0#EldD+@c2tkX=l55-Zpq-tByaYL#*`3e!Zlr6) zDf?r09U2@t{ZoAViiw%&z@V*%if8&Rm6mR2N&TWBaAz=slE$CDi$&H$TM}Oydmz_E zmc@i&M9xi}+0VwWiLS%%sCzuu4&%fI?b*+6XSmm@!q;v&ns^Jtogp?s2FC*=oKiFV zNC3z=6q!loR;z3089zbO!W~B?>I8Lvioe_ng_c14ed)!w;Gh$90LTv#GV+oU?@j?f z6ydLGhAoafyUO-5D{X+}=@G_frGl>#Nnitl4JDyO4%Y{fq?(h0x9G5Uq zLe0B(Z%=5_KLiq`-DX8M$QYOek#*GtI6LOOh^`DJ1i5)McKpw9zATtIF$MLMK_{`Y zu%XDw3Wbry!PnbQS(`HygGAPzWBn^64jMG>o287A>^O#q^=POf9F9?z=2nGH{4dAE6IhE9b>g$;%KcF$Gk@i<2`W!m|%TXF>`}1Pw#9kZbV{ z((32^`qN$FfrbPCD9L+`brj@O#DLi4kk5i&T(w%CH;=E2!o(k&>mZis>qFO4G?8(VAx4`>E4i_7;f$f;C#G>Ou=Q>=9JFas$&I+q{Q{e=58oLCd^yU;>w>X z#b0nI`#YNBNXFkoKBQ(?!5Xue+1JK4`RbYyeSOZblps4Jlc|WY81Pk;7ysUR?uIf# z_Cp@V*wpN7L%0&1D2ro^TnqlZY&~jcsclaftH}y2`P!ua35GqYxhyyio;88QNEH8z zjqw_2Lj#mmT1~F8{fBWrTJJQr-U5a3(~dv^_+YIh_pYFfGI5jGgp6m%AK|qe5XN(8 zqeTHBQ_Xu{Ac?>3u3X+Pjz977=vb-*!A=f8K29%p`)~NuW~q&|KPJC_hlK#4#ut@a zQD~Bfd7$_SGNhAUGPy1RyR+akIOq9Bz#2=&9XO{XD_d9g2WU3q65kLZx@C;5Czxs> zIPW-b8kDA8_7m570)K)GLiz;BAJ@tBfvf)h**WbI0X9KmuPaeYbnx$cQb%;dP)_MM z5DcPGZPN1&je%{H4_bv3QHPQEq&rk6{Ce$QC&Yy*5DMQ#Y&my>~X5y3}A6>jg`9H==kpVyGCuolCU| z*pD?}mH9|M?RAnFz}qyEN33fDNXwIV7`ODc_74&Rdw)4d{T?bg5q}K4ES&%-s5*6- zI@Ta{fJCstAR_J^Jdv*sD=tLzFOw+wvoOb`JgKWCgR4MB(KOGHWwb@-WOuui~#z<(Ix4 zDhL%eV~Cz2sF4sYwhMaG1D5_>9jO5;fozx-OmD2~N6*K!gEX0v5FIa0S<3&rjCmvI zNu%)7$&VWaxS2=NB&!2^P96#IQFtF$(fBbh-qzGDF?8cbiLD3-E9sY^BT5gQV}w(K z63h?vy4-^$2KphgF@PmwY(y8#tsGbYzhjDNkSg z^ph-pX)Y%W__U;#jrERzHLMkD_#hct5CFL-&p1VQo%F|_lfEa;3z$z_CGBt(Y5#?w zq{6>n9XiouAq1!>l%&d%0cCCoqK+aE%VQOY2&c@VfqRVO_5w~~_6r&R4GC$oL*HXcB#i?+- z5XMRp2RI$VKa=YqB0(uV3FsNsNxVEEO%RlmluknQ9E4-wO@{dHOkCMXB&m|si6$){ z=gk;rcOi>EN)$XS(KiFqmn;bCXR_LGLlq)L5z*Z4W0WY#jD`IeT$B<3+1Awhu~!PA zZ5mR-K@apPFHwY>LCzBO)SV@N0NAxBH_RI%8HDtwLLx~MXovuW2^RvoQi^C17o6ta z?sWi3As8Hvsv4h2krj5X#AKrZNTdWQu9DK^Z&ZyUp9&0dvArw;I4!?}y*K2>psqY^ zzM}0_Jvh4o-SRUCZA)(B?X5?L~Du|-P0E&?^Cp40^zR5(6S4d zN(*irP(9lpowhXUy?D~!b4f3MCXYZ~I{w`6#4yv~oCsdmSM2LmH*)nui41dC;59OA zfli*7%-sCJo!x~t1%HXH`5J$Hh0>=y{hVYfUs2&<8zpvPKhPiCoP0 zy1jv94K_x>tX|#e&d*q``a=ch@<2q5>lhw>jkMuyjgwGTSAoD|+Ai1goiRTA(k z=zmbLg2I!^OBk3m07bs3nNV=8MZ<_a(+4w&p0AB3EX|g9$BdieXb0{s{k0zooZPzM zTP1ltEo!9?fuCd7-_A^Ru{NbsRvUzZ2S?`lg_UHF^S2@BSJX+xFlCbFix<@VKTSCU>N;E%nyoc$y2|$-N*|V@ zNQ-kTBwK!F^3=Y1I``fRD!*DPa=4*|+mkVBu)Fd1rkIRoZ!eM|!Itm}qNxVIO5HEi zVkSgmFfhiw$L@r&U63Y{znPjJCsHuOUDGwg^XLE=hvtz|L40YOv%^;@T(gfu5QgLX z_5FQaNXrxQ?N@xh%a{_FuVe2sE#}X&b3~qM6E5*)QaZd2A9v^Rc)lSiMB&3ZDhu%) zg#2-DHOEMSv-joYMKf4>glUZK5B%wO)jdFa&qf}Q7b-5attMG5v!(H~ z-vxH0c3HE+rk+wL`|)}|0nC%qaDx>;cC!GvLV|e7D77A1oBSvLE@AC3#S9!RY>e*UD7UShxH`x#OBucdAsv>I$pE`e$|HRNah}l{rF&u(>6}dF$q}d)talk?*v2e< zPP$wfG=*qlWLtc2K~Quao1$eVp!x7E)%is(1yjgmQWLeowat}9z@Dg-6Xy*!{aW9)f!j-0NH&||LJ3t^= zS=l!a)BIGiN~Z94Y<1XeH8Ef~!c){$FlPTwcT`I{xYU9*T16E+@j7x@o-sWbxO5Dy zrj56IHYByC`A}%9+>Akn%o5(Xd9YO9YL7Ig8O$CjQP69CRr{5)`2zcl)}ASZbig!HJDMB{|FUz2wDc#%Lhxi7 zVyXQ$_zU4>2y9bYbIx&VPb%!0k((0Dm^h9;SJS|r*3r(8^PO@1E>wFTkO8l))$FzC z=~m%4tud9t**`;}tH?=&+Wgp0y3#VRY&cokgBYrReWVa2D0|7kNq*G^;4_wxx*`gJ zV?{ii#k_iMowyC7mj2+`&ST7(Xrd2iPmwRPYr>Q6qi`gybj%`F#FWR8X-40h{508^ zY5*=t&Mz*a+l|anNwGbph-axV?I*1|{mnXae8Vl*Om%@$}ECP(hV$lM)7-VYuD{~S!3bayd>N|M0zYbe*viTLS=c6@@J zATx`NN2fW4IoJ&vLVVof`9)}QGcy37VoTwFw6F(rop3qa+i$BHX$r=Ih~ml#UI-} zAG4HgT2p^oiv~O{T0wHgGuRYfD|1uaA{Ly@v`T{PMm!p59H$t0{TBcM+{-cL72g)Y zmm*B$_N|`XMfq@O3 z17xrOC1~}v*u#pDjyvb>sV!$_%wOaw7Tz~DeOKs&zL)LY%3=bLxd60^-BHYjazw#S ztNO4gW7W*a{8=Wco!hyiW72C%R&7@@kM#LVr@Akz!8WN(DE4x5J zv*(*H{$x8#D($cUz*;=>bqn`sP8UJ(StYx-*mDSKs4zJRGx(VVphLiQC4Wx!T0vqj zciJBj+GXKF9eP@U{}i22FqX8@%#A~wfIvkyV%2JZ5g=NIZ2_8>^-a%+mJOf*7P;CF zEGpuagNm3fIG65D_ZlI2=`J4>f#jJ`FgW6;%-O4jc5-Ry)aS4NFlQ56rk{}x-rN_8 z8NV!hN|Zo`US_iu;2`D8_4)-|T0Wl-$I#$Y?1TSjRPwUGpZz-|_IcsSljMugd8OAj-QVHw>YnCrb1#`UE45hzZ4>2s zW|;x%7Pk6ExV7_Rj`pN(lgQhj_F`Ndp7DF^Gyf4Cl;Kmx-GUIEv>JqT&jEmRxz6Ad zw9KH<-piXqz=%KY2Mhc#0(td=5%|PV!*ELE9L(}@LFlJ0KByYICJTPAO$|EoAZQ>= zIwoKSe0?6yE*=OmcFkvW66-w-!?ggs7FZpejA{Z4A!MSp&F`~nVcf2K8%`LqNx2}D zksP!ndK^oXEDHKyqPQ(RD;kGUo~wDpKU_Y7h)F}i^vPt7O6kU=XiqPd;L${N$ck47 z_2EE^&q16`=g+N4&q zGOoIMvkcjZHR0w`S`EJ7tlPOcos6G#zqCNl21;2rx;Q^;X^Gf06G?4$%7s)e&cZyc zev5ZM$Y2A!?sEx!;#|=%!SMibb|%ZT?AL0y$gzR0JNh7goLsUhLXn_D4oRooyZGyk z7s(h7@vJ+@_{{(@Q{-@g*fAS3ayvUS5uYPA12c#A-g#0+3*JoA_Dloh{jCmq??{Xu zDiw;2oaNqObcRLFW=`^KaTcA?Be}$Wc67<->0OM7PB@fKj2e`tYHNH_J(B%xCO={y zONr40h+4o%9a3ou(J|RM|0y}cfk#2QJaAcwoZG>$=%v_(P#;L49<(;SylN#HvipFgBk4{=c zr#K%NKo097d1@v^|Cs}Y8`8D*iQN|XD9N@rO#eJ>Pq_-YxxPH|c2thb5Ro@seu#8i zDj3=e3ct38b~(|@VUj_Ky7e|Fef>zDt)WD9++l03p9p}&AtdJ+3=0vvXDk&Q4ab?E zP|07draG9dz8)jZsD$%n&PCYd55!Zg`Sl)vH&X9grO6@xkU0wGt(MU0cwj)szH3AFkmD zQs7*8b-!^jy)BJqeCbrHzIk*-FBQvB{|Tq$qq@C!9%oJhN4Q4CIHjlw7r_#k1qU(=&MdE} zFPk&VfTs)iaeUf00o<;a^S66zt+PbuDu?w$L)PZmX4~gS9Kgd}tjDQ&6{WAu(}H+u z!JvU1SAz$M&J^-Ek9oS|wlO|q-CQem9dp8|8l7Ic&u5z4F55*lg@<0@cV^erFhql0 zc8aIT)IHJ4Fe7^`?yr@*tjqlDd=&0orbt*`yyf1%F5t>yxHJ$dOw5^cMnE$j=S6c61)H|i)}4xP3soplXzwLLzo}Sv zR`o4dD$gw)`%^r;?|oK`(Ukw+Ud}(=hJQE^Y>b@$QOm{oU-z~DM>s9#zv$Wj@N)j? zZ2XVBod4QV@qdh$^PimU{}`v`<^68$`Ztiw`Cr|ze;YghvbX+s#!k~WLA&3K*nO@# z6Ly)8L@x~liXVd0nUr{$NR3Laco=XQU@Y1}yc|hlVR+5;m)vLe*fWY$$$D7@UuAA1I&irGUNyia{US@r-!$7yQn-Ze}oU-k0iPz;tepA(nI3lBD?;cxa z5scb;3uU`ztY-Rr4>iR}p7(N#x0TPjg^Sz^zw!``=_odZCU}P0N!M4@yV@OAB#l9+05u;D z&aaJYne~o)ljNKhf@)5WXIqY+^t)&^8Rb_U`Boj}Htt$3kFQaDmnnTl@8+iKqJDpV z+7DGkKZ>mH{?&7XO;xB?ZKyo@UVgC*=<;L75!Uo$b?Bp(zt6{2TXf-> zkH4ZeUixcy`u1b^#N0RYrh185-Up|$ra~ul?`X;j54SK5HKeN-Yu^-EGXbfo4i4KCE}JZ zp+#|VQ-J4!5vx1r0`BFwIcR2=lnCx6yaF-s{%k+@uz9Uk6zCxP!;HT;TuOz!q5}qo znm|N=#o`FEYaUi#*uo2hWWRpkt!xgE>P#|dvy7YWDY5gG(^`-JPZd;xz^!dkHXK9RshZ z55yAD)KFp^*9~^{#bnBW6l}Xyvz9$DU_Vki4`I-Oh_0vJT_;;nNl_52ry*fk&K6p8 zm0xp}zCeREt36{7YY66i2x#*+b=L3s+YaXmH=|ruQ`DmfmFmhfI(!R7Zbm5iz#pTH zQd2dZ-avm17fzPRr)_q9Zr=)dAlGm{n!eP&s70KUt;}Zv3um$z#?=3~$#|sawH5LJ z=#rcUL#P`~QuCH!lXmXcgt|4BMko??ACUIYnl#R27NviFw;cec?Mk!jg&@!M6YB`b zD7EqK-G<5|fP0F7mXK`YSr8ph3X0pw>TxP*K%TSlASB{uLgiw&7U{f>K*gf} znfC4i+%?TMILs>a=i9c5Wz>;Z_Y8_i8s135_^EM$X@T7NR%kUQ!YQoD%-i1ZGi2M< zE(r~%{L)BjR6H0G8V22fB7(P)Buudkyq~ET>J^9^HbT#8l+OlQk(V^~temc^O3F8w zV9KFbSIOh4a;+Hz%SoO4d8I`d8<1<4-fPSfGjQ92B#+CO0m(6faUwz}oUb+nflyjU zN48T4_I_|%AIm2`j8WErq|E;-0U9ttBAKZfGa|M5Mmpl!f`^Eqp3wG|<}{Ax@Y_T0 z^X<=D7O@_~F~3D%{Yt|y70OvIx>X@P=lt~FDmI#cee^Q zVzpkJ(lv$k;3?ZfbIH+j&UC~xkW#m%U-;#yp(&&L!k|Azk8sfxz)W$2vXPP^mddMi zv*)=aoGgNIXtwb2u>uLGZ1ZHJ2wv?k_S6vbcyg60?i8!RkAC}xMu!6@UaRAQe7}b* ziewaWP6RO4U0$X|>dPT#G8euz!F0`{hO8d!YvK~ocNI%Y{4T>{!}ymUY~cl4q<}R4 zIc)4!!PKN2A%(=3s^-bp*^Q&C#~Kd4^ZK!+MepUTW0c^{0+d%sJ7CrttC8Ayhf9p< z!`h>USE#+YkM3=Kz|LbW(0W}wI@?Y3QV!uLg=lGu*^8%8; z`3hrc{0}M5=W;)pa_6j`bFgRzl9eeFQBIFa1~6%f1~;;EUK|Uszgy)zGum3?swiR; z2x}~d`+#olJvX*4*aKUAJ{Lkka(F;z%7J*~T}0gOfdtmJ*Fg4$ zJy<$WlrCJ3=bb^^&c_8kV@yXZ@s$IL%Ty0(*_LzjH(70M$>tFYi1pF6Lj{OKRt%u7 zACSFoc~rAK?9Z1wRe z@J$PgNiDq7J}xyy1G*cM_>?o=fg4wXtHedLZJ`xGxG7o)kk7FSZAE46@>Y8XA<3c_ zqJY1=n;5ch;YsaMJPLJ%%bLyf{yJ1)#^ZTSu40106Lu$RM|CAmq z1Q`m^@5;4JLje{;m%s8Qg}Pa?8K3tV15hPR(P_L(KgD`Yfo1X2G5l*fx0TU;K6Eq+ zziJx|nI)a^gBny&<2?9}+V2LRMKHhT+rhun5k+~$rL!(!ZZWV4#a53+zn z9?@X5XGI+VgN4Zd25Ey(uBYfV2c{MJu#VY@EFHDh8#qFy8Io&1*0YxC+kcb&f~;_> z@ujj}Csd21RS-AEs{5d8s2e;FZ^vPhn`nxZV!5% z4w#NjhIuO)DIP+}JW7Hz(9%fc0zjuJ{0OxV6uuC<2(>`yJ$E_J4~eox{^^2^8Z{%1 zkSOE@38~-v}$y z#jaOwF(KGp^%(`#%VasYF{V4%aA-guW+K9IY-q5N5H0U`bQ$c27HXRfvxE_V8foz8 z_VVcoMQox*Ji^g|nbZx`@MZ(}noQ7D)G#&$IOMPKfsOyXE;&f_yUWPA5Of`^eK?66 zysTWSAUNROraT{S!vMwT^;gB@C(oq%YFM+&3}B=;s@n|Ti8u2uJ3)x4Yfe`xaG^T$ z)N1tu2TEG8EI8R$dazKXv-cc~5IU@{x$=7^tPGAAvk!iWZKW7uG)LFV= z2{oh5Te=ZR8Hy#ZNXS4!Hmil1_B)k{RSNJo+mdin+JkdW4_WK^ZxD+X4e9p0VuiWx z+rqCuqQV=Bv zr%2P8%wrl1q=YlngtN~iu+0zq-@$@6|H@K!fK_U*fyT_A?}M}K%(oq4=~@X29DykT5T4J(W` zW)xVBBRHYls(Z5F8itMb#uXgVP~x_geqX4Phd;{Qb5*$eaT%-8jAyG6 z%=C9MSV78iuSg{B>%4l%ly&&EH|!&O6!@3juF9oAKk-DJtWeADdT(U1$tGqI^%P2E zwHM#LO9<9-zY#xobcQ^a3ZRCyg{>bBgKuj{Q8j`2JBaY(W9RFHYC6ia777|m0ZAAa zT>5|wnVLs4f-gU3X~aZ^%_VV&@JD%P-%3qF^6xzXDOR3pVGATyAn&Xyl`nKaWbE6` znsRG}95kXPdh$PO*feFX<0Ldy1|7D54sCpKIH*I1a@pfz)Cx#p1sRUHec~~28=bTQ zO_{AR@Cw{PSClp0l!JeO5phj%XOU5x!9{#q09}#-ih|!?TL0lxg2sb?zZ;8ExxkJ< zR&NMA=kY0&ZxGyKKaF4Dy;MEIwc zWWVpK&yOHQL}<{%C?vwC6i`to&!QTtavLTLl$GY<;Mh%F3Q#ex{$4a9Uj zWO1fiaV;R8JwI@`Fh57XxPB8D;?$f$F4vXOuc4!$X5KnJ9obkorRght2D#H*^P8!S zoC4S3QL(&g7*RDSnl8SOivCQfWag92Mm&up&`=kU8N1wfv3H^GRiD3^0zhzOdc8hU z1f9K>pwWa&-Gr!Y=orihb$y*RA`va;AmHYpkq8{@3V?IveXtxv2wOiRNT3^Yrf!_P zO9nT-l9}Jj%#aAR{j`Tob)eO)K*~oqchSVQMR2|RnvzyygJ6kpwKbtyIAwNJC;}A1 zzAeBGRF1&FZS@!e7;G5VK>ftT=$%(@w!4P@b?tu00i^e62+*BW4o-0CL%_!ySMHxD zcfR;h!lZQY_*3A*TBDn06odiZ!|&+YIvn>wpQQRD+umsxWpIiKPfUwYl!9sDHGPZs`wT%R!bnZND08@35xYclfBZ#kp@j;HSdR@Yv?S zkSbz^+b}LgckMWXuIUon1ay5xWTgWW9-_O-EofiW)6F>AU(0P-Pb*Ch$UlgO3a@X$ zXSeD{nax8sDl?_XLV`ZXPs$7rKdua79$QuL?_se+Yo)zdLT`2;Vg z5h&;S>nbV}k>v`a+|};1Ss?4(0Jjwwzjw@EMH>5kDo(S?`NqJ5tX`*#>GX3EvfmwJ zWTe#qjAc-93x+9@D0#(Ewu$&^ST3E6IXiL6hrkA;)Wv{@DW)3pJ6YVy@?f}wQYaCr zGy#OzJdQEL!`o73e&ELJdilK_ZQasmxs~ANi*mkiz;_gTt>5|z6YOv(%xo+7#jMyL z9Hhxi!v{D=Dp2-TCr4A?;hpPGnt9=fR7mX_0KLJ=a=DxteBCkb_w*+^1py1l(dOP~ z3ONOfvsd3#clY&oO7tZDIXpuYGczbs{=s^9vTatWJC_rw{AY1@8Cp zmHVZ>{0l!$NWtKQeF$w?1Dl0)9JFd?dnc?-_droB2sr0iUK|Jz{pKhOL(O#6R~lJuWh z?0*dN{-Zpek>Ow9v(kSO!{1%-|0y~BKZ@c1Z^9BI!+(PeGcx=Snc*hwacj~R#LexR zlb<+RglWzR7bZaTI0Os`hH)H#P7IH{SyM|eEVIfu=F#nAl!zMRhKz$OQ1yc$w1_|D ziY4J9_4f|<&qv3_13sdJ8D?>l_uAi&m5{ z7Qzmn)oxx~K3d7M5kw$Cq5U)w&N<~o$Ktj9e(x~vA)Q?jzxH!%mkJ_kN+KCio1 zuZMge*Rscl<*#{dUy}F77F8jpDf+RMA+K;eL+Xu4$mTqO^97tfE{hYX2U8LqU2cuY zKCa&WOmcU+AG$|2>G$KZSH~SCArK#^w1@Mb`!UWZpX(jN-%ZG_d#s%v{p~N`X!7{v z_-8`K;pgP|{paQ8@CB6;U-LM}T2bbMLZbHA>w3k}TMmS%oY3~zua#XtQkk2PSNODD z1Dthht#m{KQG@z?rR(dj`Olg z#NBv0bl&0nZqh6#7})s!bT;}A88kuPkdnxjmC23<(a(6=reCi{<#uFgI76T5ofTz? zVtRaV$#JtbC2DgMJgLy#SA0>iYw4@-yo=za@I)>E+YsuF@kGzqc+^H>>YUp_C44VW z(#dVre6H-Q>(Soh5v;;83F>&{P@R~R?EOOK@qpc3h^gsoZ12M~9 zu22`e;(&6RK0BiI?VuPak+16;SLk11RQ7F@Ty8)s@ew$#n9puZsvjLCm*cjpdsMn_ zO3+!=ppwUkIOI%Gv9srHJ*RSC*85^7Fi!aeCsmXw!)Q(tcX3QToUCkfYNUK_JRv;< z+Me^Lhk_w$Ns!mHW36sliR#Qky(^Ey6HyRKncQZz9A zy>696p1w_0L*j3JH@4ia^NY%_>u#}H6*{8@h`W-%?Od5&lTqu+J%~##r5^niFE4!J zViNtGS8|y`qBLGxT4(>wOjH1~hS&bfdZT~?NZaGGA}eMSx#(AcSJySVr6xo=pJA2# z_VcFi$USuJ*P;G4%-ZwNKJoeGkXH=Lw%L@?QlwXoq*@o~@^FIci;l*W*pT4#P_1*} zXZ3a3z1e(>S0BkOG0`WEW7>n+zSU8UbI(F$jWVRF+?7wUSNXjP86>bR*F}cfmM&Zj zP3yUjncFr7!;_D{;6U2Qw0U%Z6Bmv<}zTeOA zfGiMR5YSA}(y$gL15T(`np!OU^ci;D7P14H+yUQx3UC2=EJ*1Q-clf7azH7A945C0 z6}+k~C?EwY*v-1mV%yMv16qr$_Fgrh_xt`VFBwXUObvzt!fy%`nqLP7(&|Jm_9VuR z4k-NDQY{nq;sYBy`2sLR+5||DiRPxG!@sEFFWAw8KfLqP_8X`(J1}waqr+E&vIJQG z2@(VDLl($9sMMrqCTFXJW0=7`lO9o2qC+&-xnAb}d*oA5+ zuZP_4?p>?S2yH1?i)1dpgXE7Y7Xgrg9HFoPE~2o-+?@$7E*Ezqei-s)^3UqQ0_*Cp z&RnrvxTNS{=jR*C-HDKr?1NchD|F<(bW!C+P_Wo>#&Q-L@V(KrRJi4UfH2_VA(Ri6 zT`(YG20;f>IAT)HuEZfndz4!7%3j)WzKCzQ=uws@L zr9OGF!JH;*z;@biztgzqepFw3A$3hWJIfl;s9t-d2nbzLd&c};b9=$rrmw$DN#zLl z>e-nUM;e0%`>lw6-y9hC0@o|;Pi=lhrLgudF!L$XFwzXEhbe(m{r}39viko9V6Wh1sc%rUsiJgxgRTaHhJXn{- z_K7cD5;_SzO1v&UaBQWWu8nJ+y7fKCeNic%yYt>nJ%gU%w#5KM@0VomLN6>_r=Rxy z@O`>hUIQ<~YuE1Ea^3UYYwyu_>hJE?%*SG9s;)V|_^@>My^KG_`Rkr>FH5>|BJdP< z#2QjOwr{*yc;~#A-?LxT-!-m1_IhUCi|fE1oixLapH-<~-VHFOq>J=A%_5AbJiV;2 zRq1MZY>sEOj30NP+6_)6lQvKXT!TEk#|g@I}YJg}rn*p~?;oueQtU+I8sR2(A zA_hOdqPK|Jk|zZh{Aupy%#%FQf~0aZvD2KKo~8&#v#pg?`s7FV_znCA21B@F2GbcP z^gKihJdWaZ!BVa>lH+O4MQn^SaU8!lr@t2l5`E{qcZs@jmp zw*~#a5bWlo4vZ_N&k$!$esRVI4G1BF0h&J(4d^RlQItOv*v3yOKzkQXL=64-N%~}M zAPhv3b>|FuQ)``B|EhN`Y39@4xBw+MEM7me5r}8-goLFQP%aQi7Ly2B(Bx~6Ag~Mu zeu2KB)AZ@3D{K+~wCq#NIg`VP;y%MkUl7C|? z6=MQ1B#;;dto5XGvUaUQH%6*>2zqglzYQiYz6%&@@0MPh!(s2kD7`AIS0#v5i=yq> zQ#HkfTJe#hu=CK7Q>y%YIC@StBM~F! z#IqI6K;flyWKVpDsr@VbSWFE=$lFJ!{&@}|wKbGsyjZL_P5!nf&xy|CcrG;9EW?{eB1kb~PJlhEHq=$9C@l6w|3 zXf0f>x4a|F9mpn?Y=zCJ8N8^VzD4WISpuG^&N&2P4ar&0{p7x8=eIl6U5_e`4w#N3 za*Jc;s7G2A^*tA9Igiw8N8^AyX`-JrCo<7vWe+S-bu^u#cV(^#KD{My-O?V0?F1oullS5;psMU_KVAm862O)z!1m4M?_Oo)wh+1G;&*<>D#{pNzhk z+2h^d^1p7>$J6ui@UTC>KMBGU&L(r?gV`CjM676& zpWxJOg4k))FES7+0y%)y{_(KZwa%M$d-OH{a$1>_x?l9Xu4}D(@z?X~aQ6rOoWqM8 z(lild?L%^fYOokCZ>neXce~!7k8IcPk)fMsC`u3PaQnDSC?skqogntMC^V`;F!pmI z;8CquM<6H8<1qW#Xz&(b3ho7i#*EHQ#2_=X;aarA`L$=&&c{ho(@vNRR`|=8L+M-v zrXGcR5$0KQX;yD_TdSUudMnbt_d~XQ^dOI7?G`)BHeD2ZEkLCuX_Q%}?tDlb87!v0$o-`DzN$LJU4C2CJ3Ip< zKVsuR$a(X9ms9+HuZHKbGu=F8hKWJpIvZ8r?fnEyeGGrTzlUUe7ag$Tt;}_ZAC1aB z=ich#$ojK=4s+@}Urm3xKY#JijQ*YxeEYvxdkd&MmS#~K4Z+<#cyPDi?ivX0?(Q1g zT|#hocXvYYV8PurI0X1#NV1c?&p!7%=f8KcCU2&ur+cQSr>EY-G;!{t)!e_%ST z#kuAE9K=wmViqi%(~5p~$`|OE^eAsDOq}kcZlx4@&F$fm8U%LV`Y{g7y~IGiU;`BL zrSP==e4C_L65=ItkRvtW7@yW#o|C34%!}iIrD_y6T&fFI-R#dVMDB0Kks^w}eK;GL zaq(Q>Fh49(*eU9nF)xVGL{nW-Z7eO8?r#OliH)wqFk|;grZPG72=M06--+u(0vX$2 zkv=cuj{rljPT2F~FP+XMYA7jPt*gv<>`sMcAvqLWpax#VLq}TVo)x@i`M2~{Bmmr{&?7Vj5+1;%ObMWjby$$`_}f&_cP%ESroE>DhSiS;o>eK}A_ z&n}RH22Dz)bUaZ9zCn7waz}A4a}-`m(N`_8LeLB9Qs_mTChq~#`j?8cq)BaJMZ!}R z#i`5>YqmJDrbn5oTWH>wX-hbBH)e9-ojb9w%1R+!fHw;+L3EL)vp$TR*~3POI8dLr z>`)b%f%b(yXl1Hi48YR)*@;mXwR+Ez_!r~}5H5@~qD-BCMCI!DP~4t~&tip+JE0L` z_88O7DBI0_&P*vA%fdJ9buFkO^wyrKBIme@q881qm;WAKDsUs1phBoAErFvLVbSTP zxHAZNDp)MElj`A>XEGERxTHubWU!r=Pjxi;ZrUA;GV}o#S<(IB_gZ!8s6#|l1n=TD z5L7{GWjA17?nz|z+XA85j%m9|VA9iJ%r_^&VTg(ZwPR;ltE33t=);}?#=yymiUiU% z9m$6WBSk#31|gt(E%SpAJeAS1Wq!Ma$mC#U%Z_tcyV&Aq#!FrR?JUE7Em$% z@_H&Ix0NNn%j|RVErlQ|_X~HPO=TZtdoCHbvAEYE+?zu8MYY5bF1Qk7z2!TKhOe;s zSbID+e~A=m>6$F9*QkRvprs3lV3(uMHX7k-Flr-G)R&F}d>! zH56snMCKD5(M@ehEZYy#1ZaEK@uILnM2iF-;96p@5p8h6#hr4$yNYq2CqQS@1mdt` zJi_gZMt?CvI7mEb=FSOIv@&4SNt>`C>$reSfdb1)*#4j;xNf(Jd-Pyg%S}EW!!5)W z%xS+wQYmD&3&hI+5+?Cc26~@-&kX9;vOtI#n!Gd{g#{d$MmJx!l$K}|@HF+176ebv zs=;3=;@gl}B4^_sOJS%H1e!KQ3;`NHmM-~`%xh~D7?8IxMJn+xr^me0rQ4K=NW25{SF)7juQye==7KKizHbG7xOyK$UZKRP?Tx1)c^ zp3lFsI@;AAetaZcXi%tGA=n-s?!SvH<&>KLtW^Z+CgGloM$6+jTe3r?o^yZSE+^td z{9i%l51RG_5}DZ8n17K>db+>dkrAJEMI{c@FmqmuM= z0Ak7bbJZwC7QjN7e@z$(_1oQzp6<^{F@O5I(bN4TxBtoEEj(e~_9GiYz_AOI2LDt< z7%`l{k-3rSx}v&`VZmHct({M$d8~mp2pdJaK^nnmm6t>iCjNAZhfYSWQt@MX^L?s^ z&az6-vY=>!VT{9v`(7-^7{+K@inW1vi*_MGt1*FcL*J-52T95Q#}qSHQJCmqxDa4V5hHAsX)v`B1eg_HxU391ZyNA?`tRS_I| zl$~VOG{gyg_swAAqZ_F_v(VsonRrLIN5P(kux0LpTb>=gk8dggYFGnO*4T{33Sznpre|*C79|ktneg`mhB=P7PdG?ba0hz^dD`noyEigjX>LjEp)6K@=iTEUd(VgYTs8Y_-jyh2vSIwSO?* z7Sh0^9>Od3|7s818-+Uv+R|~=1cgCx=GEcN(?lkLL&Nnb&}?zsr0axFhk=JaBUCP? zP;Idj@(rK3t97|wRw=_H$hUWy}5k9B%MI{Xl{{w+tLVi@V4dg2wo1&F1ZgvnXjK6 z>{FE3wmVJWC05IW7r5V=+=omDIrJ2Fq%}y(G%q)z637$h8cNc1?ycz+SHcH`9A_ez zyFmh%yI^Fm@ut@9sr-@mY_Nd)uj6UPc9E!UchpDK$cM0&r;|bul_DpKFV-NK&6>JK zHPn3A;h{ejrL-LuFc}s}^O^e7th}m>NeMYIw$22RMf9F&7#@GQg6nVT>H+H5FReQi za9;E=-6DE`ZEoLw?=y`t#~jj#f&C_#awlh|?u|qNaTS{Oy=LOs)qFk&WFyd*(TG=h zi2=K;!d+=5sAo()E9B|-KB%P8?c69~*mPf#rGjz4|>$(OB)8R1e`V`Et5mllf7 z$9aX0@U_X?)dh`>-1q@w=P-Jd(W#m%R@ac)+kT#JSQ{Y=SO8cyOhfl{8{?* z2lIbXI^$or&i>r`K5It2e zJ^Nq9{HVpBYf%6AyhHtY1N8Jy8T`Er0UdiCb1S2#$7ckvX8wA5zdx1F-_pOIBWwjI zmsY_+*WSh20ATzB{7X+j%dcZ+@Z-o^5pfYwSxTX|!cu?|X`h6G26lS3Cf4>=wgmL_ z&r3l=(F$4WS?QZt0?L-s(UZ5b(6Rh25jL^4vllSdu_a&zR*m>gleY{{Qs*fA#mA)8BJoel~tS$(R5GDnQBqE&sjF|LZX99~JUkLDD)FfU5jw&6(>M*#QduQHT8eR?Y-!)XZ!I)C_=^1JGfx z60ou|YCzG70iL0W9-pO=xdGrJX!-2)p58=OCcsm9s`#fJY6b=-K$Fq27Bw(2GPVc2 zjkF5(1{O*LtSkhy?|urY85x-A8K9nzh!QXX>RL+2`MJ6QPYrNm&sPc<9T@<2f4ro> z+sO~fuZHq#NcD5@^>aB-z+mj>`~OqG01*5ftNl2G5g_} zgQu?GXZPz2e5hpdCeCA?R3+;`qHy(9yvGm*rwRl`l?asHRu`RN5@z?i{)AxJ%P0~x z#e|p9@?w@wbp1`_*>`K)*oqpt zv3`UFUOkYs5+DUX6A)2OJ-Z|%AZ0%rJWfMVFgblHU@N~@?>_)Z3V_1BLm&rIhx9Hq zd0lMU70(t4Eb4_L3bufWDas2Z3I+@#+U2^!2eTp!F3Fb#4;2Y9lI^~Tim5N)OB)|_ zaY76_5x~%lIR)f_9~C5&ed5g?asYWt2R2TQqbL|HSkHT{8q^y_yt5mYwVdp&5_xLt(@Mt3Uv6W`4<$iW6GU-EnFw@K1GdmOv zP=P}G>s;0Z8RylwRG%=gU+Pj->erC1M07lEY`W*7PwE~E=Q z>V%L$g_6z7dpt@v1Kfr&(~g_!LNT*n>4E~2kqD8HUkJTx`~R3slFy%+ugN9ZLP z65pGfeqF|ZOLWJ624NUqAA%2dE7ZWHsE6@#PK8u3D%V9H-zI$R$bKjil9I4uRGw@$ z8)}G&_~KcWeTBnfWdvzGS}_s?VUADQ%LP-p$D|o@(){6O>kg*Zfs}HmQzvkW%5JZw zd_#Ehjf{fEay~ffRy9|4dtxpJ8drPe0*jV5g@r!nXKt#_^PXV&J7P}Nx5J%m&_?Lk zcE=4>e#};RT9~+qoJbuhA6lGpIA0G@CS>zj8vCD&rF&IJ5%Fx^`NL)sbK4KEe1*xA zgSbQuv(}8w5GV$$E1HJ$)}%d+`d}8Yz@0!{?F&|V)ZM~4x|kid#5DAUsSd@$yhVwQ zOZ7@OzQU8v0||QzMA5eQl8ITW(6XL09~?xPL?%Cb8hKN6?o~ufnT40JItg39^be#l z7e+{0YgVGkKq6wQFzU9%hH?-#O(>B4;Mwp6cTEcfMLPwCa^nWn+m?m+HQ zSIRd$lkUxw`5UupR%z=g1+rP8_EOw2f4h$_3!J@}<3H!CRA0D*cQPrZq7K@cJ=fS}Jm`?Ws3ykWU6i+oRs+~R;y&JNUJR*LSRDX{iey&Gm z5!Cpqv;(#tLUx_6@u$9stbB)BCKaN6bORa@gVY*J$)Uc9L3JEQhBSH8N)eRZO%G1V z{Cg5_Qomv3n>rDqmpbU1Gw*4)JNgmpb>WtzsJwC)562O`_6yr- z;j|aolXnS6YnDFB*wJgu#@cV-no6)}ymUB36VWYW$#f2D#%8B>!GV*)cawcZ66{Qr z#gith5QA~$8tF4+-vh4p)|rJg3|gT_K}5}lnKj&c35g6a1HGr6ka7+hU?T7OP*j5? zx9(J)j8#rcl$`CE9A~oeQNnS95`|e^tQJ|ebS}K)*V&|KqoM8X^&LlH9l_Fsm-miJ z6>XLhy?cr&xf#SluSw8&nvs$GviI47RWaQ|i$jgaf8ewYXDR zAHteG9yKIlrchMGDa^PBR04#{Cga_;UgG6ZxRJ4 zhg7zh!+Q9~>j>$g-H%h2oz{c;WSca}6tZdxzLTh7tA zjBO8k_w6Owq&C(zidH`Ng?Z-KrW06_y6P=wV5tylOHJE-S2J?io)ZmPjDZZC*Zx3y z_i@V1P?8=e%lqqr%{=*LLz?wjinIq4A)E2za0C`5@o?T?V#L52;=l%~3P)frZKR!yL((ph0<4{$%kgSJ_yRJm0#wH;oRPTn?RqezV+|Yzm&vT4e1a+Q>fM} z?$&|{hA#MsdBeigUy|zE-(dt`Na>7V;PbvJ`mRFYaRz5f$($*XTw9i(W+3 ztgA?zzimaSf6N?iT0_{W%gr&fWxd@fvIGs9LiwoeSFP1AJ*Q@p8L?}%5Ei{HX;u4J zLUnz#B`i#@DWIc|&5M)!i{?DVEj>vY-9)XAl!TzE3^rj(wAQy-M(;PTohZhy(p_=_x@}@^6o6@#-+L0EkuwYcyDA_t5C4_mLtIJlg){?uSz26L@vrdlFsWhFskP0!q)yEcF*y@l@(Fs8i@3T$;-l zkQ=m-u1t9EDBT6o%msSGW=Nypz-n(v@AJK7OYCy z3S1T|!f2}(QH|eo>0CaBkkqbYl#!UB_Ke4Bo3BPgLhhT?erx1~ohR6shp2`^l6kkqq(sX%pzd}fOq1|<^+;{H@ zbyTwbShIVCwpc8;1rxHNMLmb6XkiH>JPh~{{TcX2v%e^dHFTzIYuG`Ym<^13ax)5Q zdpMQa*Iurjy@afy?CB7NbNA}lr*5Peh(~HX+RuIqHW2J=%03z?jfK}BcaD0@Zl}7v zF)xC^-ouJqO~v`3sBwO=#GCjroD~%{_<=Jjl7sm!g=AsQsLi)bqD@>h{%ugUaTG$8KbpJ zCkRC#nv6|6rYqJMTGY9}iT1+T_FbijMQ*LXoIv2>m5fq)!{VVryJEA0+9~eX_~OcU z9EumrlS;yq2Cbg9NASBTp;QRfCEXwfV%Fmhs~U*`{n5;XbHnG}v}hV* z+Tmz&nDBjha?kK^_ioqpd51c-2hFYH4*R)je)%3Z{w~g0Xbc>1)t!hzH}vu+b8hPh z_BX2CSwp$sQY{*Lsam>UMdlVxmWwJx~e&MG)aI^Wu^Lehzl zs7eR^v^?avcQ6e)()BJG?F9!9TUhki1NeS6N+y+4f(x^=$53rx+|-oAzQH{cBp=1& z#om6aVO&Fi(gZhGwsrZClgiz?-ksR6(iaB3&9+agw9t)9Z+kbqC=8LJ4iy?kFBy<9 zZDn0XL2R8zCYLqWZ+Hg<4`Ey<+s~R_f{n9ksaiSttPR_K%f8{bWH3EyShw>CpZxME zJ_{+M@``!D{4EOu$Vy#E%mz7wmO1PZtyW zF^eJ5*f6=@b89R!^YgSE?E$XV>-)sOv-Y0&hxC&#nU6%=88!qVqNLXuK}#PWLH5cY zdj7?B@vI;|X^o7`bnJgYwP!8yNy^Uj+o18RDLx4q*ckqh{v!FzOn>1whW|?6{u8s1 z7vz^vRHRg}*Rj;svDH^_v5@>Hxqzal{|U5{LdzMdnd{w|2)GFCNl-G3mNDTBI5R zs4@KzjkZ<3_&Sg-zbj1^66q6rb70n&d!+zGfeG|T@ae-BxIiOpVR!P{dcdOQJl(7N zOp}8Zz1QK;w=ljG;Amu3ZsVtKXQ|6U-3IF)oXitY{Fnpflki zisdJFX(SI=dN6ZP?qpjeofrNDLf9lt|FupK8Z1>1e^(r#OK}d7Wb8zN`LUMbIL>3? zEQOjRL^Dyz>+J+buj!!+&d{zsMW|6YK95`V0I1ZUX;3*7^6w^$d3a zQ0D2pC$U-B`K$RbJmb4x`v9Z^xYFlo(0?QV zTsFf`@BY7#4gftpr}&RZ=dFn%vI?3b4no+Ap7_OlZ!nb@psFD1!Pi+nhUi$Cq9Hj< zg;4P!q;urH-VGU4uV4Be;Hg*0A%cql_reMxsw4Q<<;uzSU|ykpOq|_eV%)CT4r||% zyf092a#>znx*yaJC~x27$3ygYMPM`dRHr)({($0ph7hw&i%tzpg*I8aH6|&kE{2jx z2jV0^ZcpUD$XJy9ye)&>;k z`6CCd7YcYB5cqf!0(cpB+vgUxH1E|7%G5>2LrnivydSDd}c$A z+zS>FGKsn7=F^C5F*wsGjheW9{Tjm^z4km2Z|Huc!T3mZT*otc1VOJrQr6yKPu z`Ns^tp!aM?Frf%rgaV`zqVsDcb&txBU~_W3x^K&OoAr zzWdGhklnDJ(M<&LLRzl;nQ$`hFTKsW$q@%OM=n?K$=Z z>FD*3@~KTQhd>+Z8h=q1O9b6ETQd8IAQjy6;FrVJf|3dFm*~>|L{(R1Ep+M?)g{u= zu&(Z#KWn$o?g&IECMf;>G=mAE#6TcxEt3I!5fbPN6dCzDFa(Lhci?gpDA<1P7OWGx#xB8SNHp|iS3W*gO9{`6WB8d8~2cBYC2yCIE5 zr>}`&t)a9*fnDav5J=K~`eo}iTI{6z5p?Ecs)wMDm4rN88WxUs)t$beWSBG@jaG$x zw}xq7OIr~G)FO~c0@jU@W4U5Kd^``QWiD#RY5y>Ya0k4RM?LyQ`{V-YUY&rJ}C^2dTqT3W+Sz_;jy(u7eV(`2s6~1cz%3@)%XSjB8 zLXmwo<&6JP;HWsR?5G);QSUYJS$`8%1d3pTOev>AdY`E1%PS~c``BG4j~&}K8)xg) z2o|N*eZ8~y$EMPfP}GwabetCQG%OkF6~&8xwlFM>%)DA` zs}rd+A@3)(g0d}{W7oN>Q}1Er4cu)Vw@SX9S0G_z#=-?`zR!EAKU(7X2lzKL&1-G?W-n|f6Qru-b zJvF{=gpCIN1id89sy=pf%gfs52s>Sp`Yn-dxOXa>xfVTY%S>{frKw*EN&wFxn7U=s zRxK|fO~yha!GpfX`>>8z(ciYjK&{=;`q2Z9O-l z%22%<)?+khspyq12d;T$Ro|^Tw-s{DTH7)GSz>sv$kEKgyu#|T zice3XF|TYKJAGu(TrGJ+K;~N3LN~cL`1O0##PXq$i18Z=lbxfcjga9~VGF*)uZ1cW zK{7>gjV(HfC%fY_^no+;VCG|HpT^e$CAKi%72v-v+$Fb%7kmA>VKE15lA+XjnJPYH z0?%p~WU7Jyeo065V#z1R2OE=PS%_p|;BHpStU#gB>-d!D%t6{ujrQ&^qth|HXkx)3 z-X#BS&3Z#VfpfF_{HlR{y7<_9z)8ZCzP4#-)}=Mzt$Sr`d$)lSecEj)9XrmB`#mj=Fv*B77mD$xYRoeZ_vPgfmWKCi)2^rv0Fk$Gfb93p2EC? zP+_iLexp&Wfy2|3o$M57s7m7U~a2N)qHH0S(w9c4!v@c0y)JS+1up#ikhry6;IK6DPCezsL8z;K!aS_z&*5an zaHW`!YqvFd{;hZvABS4^+A~DsbY2{KMJcc>wk#rDtLPE0XocDC}9v^k>?qq1co3Pj%_P+VuaE zx+Dj1fs_}a6p#{n_irZNX9Z0D4-@b2QS$#uQPQ>5(K9o!H#ab}*EKN$7>0ieY@bY) zPZFqKlBXp0)_)~)$qJfY$J|u>v&Ar;Q1q@IGy908fcOHYg^5 z4f<*OCHtGf`}sniTG-!|hM$`Af7Cf+=1u+R0Iqc&A?lX2Xvm91L9%sJ&f}o99zas0 zuO>0F+*aqW(ho9aR|9Xp8IdN3?H0Ngs`G@N6NNS9smv}V^L}xL{2(Zyaf}oX`DOn` z*hUIITt=RF<}=e5S$58lEKxsEo@j<)9mHZI#=7$!v*S+L9St(2<$R8^N%UhcV**y_ z$U#SK)>GgB{1)2H_>`xLToPKG=i;8s#}601v6$hPj3=~x`FU8!$*b!nFMlo19)P~|bbi277xt&<%J3XNXBye|dyU<7M(QK#lYrF3|jl7ezp43I1 z|JINE(q0*v82(ae{~K!ZhwH{4o(li$0RE}WJ~=9|0K5*^0TV0IGXd5hXQN~K?>!Y* z0j={7Rh9*yv;KBfU;&){QLs401*FHYXLpmpPmYUcK%Pb_TQ+; zPmiSEo(haV)ZyQr3XFeKd;y*c0QLEQrq(I~JQWV-Bb;?>q7LRQEMhF^>Z0_u0;0HJ z7%}=_81=}$2IxZ@;5O$_39ZTni(ZoJV@pg|Sy8Cba*ck;e!zdwT9P?FZat>Ga=_ho z!RvQX-*$lhhJ_WX$*+AFjr9(O59QShIUt(-;uHa5pr9l_Fj3hP1~^Evj0y~9HsC@a z-i=KXU|bm{0t#?ZeiUL7)SOLT-wuP4W?Hz-4N0Jm#8F(ZPaug4QEYLbIG{V-kRzh? z_gHY&Oxj@%yo8W#x*a4;Saci%9iYOZZ;-bA1%rGD5P*Da34ks|$xvPpdlHCYuLpta zKh6m|H$8&75ZYXO$N^pRZnA4@5rKsA-GRK!Ari$2SR@lTlDJuxy>PREm0`kq;lxS) z*q#5_v1&q?e!Ln~pI2$5W-ep$`}1Sj0K!Ow=D2spSM zOJJ2*mRr=1Fl1!~hOKMdc_Y$;_{C`oD8$Hp6hT>LW|3ir)59_2y-p+{jz3}2b<-o2 z8^XO_tJR~A7sUR(LU*P+5M{837vbIayJH@$8BZdGel~4H@-Soq$avrtHk<|Y8Xm4Y zO7azWU|9^X2?*ZX14=aXZf(drn2t6IA8#Tw2o5$mG2R6{2q$YHq%lzuU#`Jjpa<6*utf7_nL zL|(xF!wI}@w4v*POKb4hhve}jySrLXuO%{lWFd^^7KIq&#h+f~Pm-`DsoZID)tmt} z)q#4OU*!BwXz>o+KJ&hwV(d!Qfy+;1aJU{Xk3Q{VUfR~_(rSkY7ktA+W+lo2V){fg z>!AT_>edxm;Em~rw&OU?Wy76?LZf)D{WDpp_fA9>LSkq)nl0h3*xZyx~%Edtgw`xMHT^#V&IIo>Sj7q zzS_1#Lg`-4;`4}(ft21F!JCG9W8) zt7{q%iC)foU@R|05K#vw?h)_+)AcVb-zh&&TwC_@()8+m3{#dFy?~d4ql;Y4r7;ps zU;%X~P=1sT7s|23Bc3bjWin@W9`emDYksrLpG0pQ4&v!o+Vn0PCHvxI0w;qKbr<{O zi9#@;j-13k)waHkfaLiZTP_qGQDgm@yvhe6@T68@X|fxokObdu>1>yop0nM>vDg_C zeAwLUMh-=jfkXXMG(k=?!>Yiu?SerQD1C}%S!z?_jT#}%7+ZZE|Fs{QT7dK{e#P5 z9^MUj=J15jP~7EvrsMvs+Y5$azoh+8IhUq7GU*|jF5zl>;Rs>2FHq-KN))u+;=Yry zpht--ZUcKn<`FJaz8^(`hg@aPu=NS&wql){@sZe(sa{r6XuWCB207qQZhd2>Z364p zRUe-uO=cKCcxpE2KVy`$Jau{M)h!b^-Wz8fN)E*ybJ4t?GAc$fby}wJ4PiIDdAPX; zusR*Q7Fcln5tvSBG{E9(ezC_wG%hm)IQ#rFZWegQ|>2&a>ag`f@PZskj*6 zz2-Z9(Pr%%zK6Tl!JWyOc;UloV1&9>BZZ**wn+>7{P;A?K@Dj}cPAO;_L@tOw1g5F zM#rXFG*A6i)>LA4aM3+XMV!egSAs%Cao^qLrDgaCHpLv-gXnuo9FSKbm8b+B@X-52 z^aR(lRh+52_dQv!t!K+(-AaM{nvK}(h4eS1c?K@{p=T^O(xQ5h4~ZlcaMu|x-2}iZ zT1vkt;_KVN+7m(CN*hj)8MF`>fo-c)hF_wpCmFOnHn}(Je}i-wB=w{wPs{Ie&h4)K zkW87pGyLU2R&-+tLNzuUm=AknJPGJ_P<~r-hrlBbYPTxKwzGD``b}YUD*Ng?>!h41 zwA|`;)HJ$>jm+UfOO5x%CH#hweZ~^zVj1vM=3KZFEV}QnX^Mke!x^%msH${sJrmk# zWb`YGRQJWU*77KN2>_jiH6TikN62h&{!&#?1Nr@@+;Afi3|sQt7LUjU*ZPyG!8Jf* zfK^hGcYSxwkeW*K#vR0(9Z467-wEwQZu20sN|Ud)iCU6PB}EouR6Qe95UTjJE*Cc9 zyHY+l$m_l6&ZMmrCETGni|nL#^e8QsOgcz|q0n&TIV_NgTWkX zW2IdYT=g*@7{*VHxVA%5R#<7_gW1y&XX7LByj47h#dpVOQCr)z&FB+-EUo2EYu3%r zrz`d=P4UG9#pe!g#uPO&pnPj2QJLqKD*f6Su^S}K{*|c#wj8<(&5oJK2d^^u1BLr-Pab zYydJ;izVQgSzN?~2Q$Q;E)@IFuz#359wapvM*Tr->%46WrcvWYo;<}MEzWKv`4x-+ znHQ<4kgHk{dyZm!7d=ENsgK=QNNR+gMB67U=38BG0!tF>H)(SVnie8CTY3<-v7)Y9 ztQnwYp4!U5!Jgdfcr!kS-%=g+*BPj>8@N<2*k2@WufWkh6rNyf3$0Fe)WOAk!k#(* zm>hKz%BZ#|=SS-$Sr|v}Spwt{bD?b#epHcDQkfgJF4$8Ix0t(!o@FSPRl19%EhmOb zJlw>aT35P%LusvC!(%Z`0iz;63++gg#{gXc(K?oziSLxk93RTXx7$CM>v}xSp6i5* zOJOrjL6Y(6u2ikOQi4`ZfMZUyX9c-j^~4SRgDq><602Ro>p_aIQa#pG^a4CbV|4xu zXX2@x_}L6R+HCzeu`(mLFOkr(2+eLroQYkf^zW0ua#`vmMH+|Z2^BjRokIC>(6X@S zw{$GDc51qGVj1?RPrA#OpKyO4DF|Yt@TKMcrVwcS$)ay9N#*{;8688WHv`M7wB-0h z){JKD9g2g60VdPQdv|j- zfsQr;J4wqe*K)gA-}21Adi$W0?Opq)$wFGz`&Y0O`Z;$SCR@QdF1r&fbe-^LonS3Q zZ`-Zitt%y5F&0)Z2(%6OuNb)qozZAzCCnMiYbkv>z#$1DQ%_D&zHGO7r398pkozk37@Z-7daaGf8UI<1)0Pxu_fcqETRUukB8ks8SO(l{lUC zo)kOI_%X?Jdz3WUNia`%wBtCe(STqQM$_vWwPm{|Vy{}#c)AGO_1x|nRtb``7A2v*5;HEb)`R2wIR z)HC#-Fdvao7n~2gnE5Icryo1&Wt2~|>cNh4z)51-*XuIJMy{}FI>S$M4`-)fF@v3H zaF5~-{OK~Mul`{NXC`Af)NIr-J5IrX8*l$$vtdDXmaEKBZetHWb(*kx!2mA9j%mO8 zG(|4cyche+O^aADw!9}e38(U2=ZtF-THgjGsaQW*U%_5`j%6)78+iV_CAUscMy%ORM`Ze+tbqyqoReeG^i1NBw4|TS5XZV4FCUcNsagIwhsf!dYNU3%W5`Wu4oI zYADXk@S{mlI(&U-yF?_~8&=80Ic87#o{b%k4UtAue1GDbC*6t>no z5zP_Ue0SWJDwV~7Jy5b-tUvWgxAlq0b3o5(cV6bjaD*VqzU7Sey48wh)RvY)Kr0w7 zGphzR`T{pz!X*J$6}t=eSKVkQ2wfVAVoOSerj1f%O+v2gkAi$+8iXH*fz7+nN@rUq zn=vNAOiGQIxofse4l**#J+68Mrvl67PCFDM;A`4+vk)>5Rt2;^X&bYjEp&2xm~R9Q zTl}7o`z-{Kau(0~tn@!aQwG-GJ|@qa|C5xFf$=wBeOCXUq<^B+ ze~9>AZZ@mK8ceK9nLAcKYn>>KjR3Z4Np;g$g4>^l-C?@GLtdxmLMS3$`EL$Y1oFijRC_Z(%V4I|k zj7J^pZnTW$){Nv(ZhpXQCV)zsH;`sx@l4Wx3rP_Q|85Hfz0tKwLB>hlEi@tPjI8mN zqo#2pP2f5&+C4^mvbKh4r6G}~#gXXKE47($q2*iy*qP;sQIe=0LF=8*qJ~vWfg`d9 z--88n6*X`pYYD6#YipX=ZdaRXCmnj_uTACRNuqL1J~wp6PG>j5{)%O|@{NNAt3PZM}QL>AlYwb_!A`pqMHDa@HaDL0K|U(5#0n} z-%n%@5N-r$>`%8x|19}+qrY5X7=KdjANx`{&I!+5#adCSq8ui0mVM${L}gB z{}A1z;Pyt*1z%cqnqUec8b^@at`ozsJ3{TK*PJzrYnYu;dTVP4hOunQF{V&Gz@S?HdoT(c>G>$mj=-0CwCp ztM?i=Z=%_gdGmm!m%@hik$6d?tc8W8$zehexJNNjI+?u9%_Lsz=(6zU0TI6*_7%*Q zwGsA4)*=u>bgXzuXTy++CI`%cE{sSz0NTPQM>o`KO2-G+vBHS>j+g|<9uDFpWr+~% zyEb81KqmsQ2q`E+7YgvaHcMAGVm@x;**kadTg-qSUs^?sFerKjZ%D%llnyF>cRUd& zUOH%z^Hn{g&ZOAKfWq?7<`8xq{3uQhPtx4S6+W7-=!e`DJ8)gZFpwqpm%=Vu60BY6 z$Y%kBfU>t01sQKXj#zSKa3geese9Mbj%xAi-Lfji46w@r$$ z>U(KZioZBNY_+N7kqT*o8+0PbBMMH(d#moK%2nOxN|(BJj%9`$BI*r<kN@EQ z8|w9x4$T`d;Xk-EwRNB%@%pjTp>G8n=3?{+IqR-cY5M@{ zM!ZDSeox;#4n^=y`*KJSnmvQgIia#o8mXfI=rf{D2s;7C=XYPVVM4UI9_4$xT(MU5 zY%`rx5FQdC7)XV5&>#}NW1n8_ejJ$^kERV~s;>YavM8;L8_+lN7S9!Y)L=^?7XbT4 zfZ%WFv-?2TOCGZ5x#iSJ<)u=MV6LwH4usJL*TQ|vskxpk@qi0`J?3KNJF8$WyaT$H zBl*&-B9qQEb$}mkcewL!_wfQ1}O8%F5N37~o^oAH}`7v;<*5{)|?lV()EdxWx zLCHQWwL~(N3YL|5HD@>Fu2vFyvB$IYTCCicwp#fV_TgINLsiO4EH5IiRzXyBhKDIV zAa+>Qw9fs^`0&w7xMWcYFekzpXN}I?sEI^gg+`7CyW1;g6nsUxdQGT+R;vW5oV)K_ ze8x9?#L3mugKPHMp*3OpLiL4==}hT4d)Wx7gUU!NgKX2r(q-F)Klp}6x+b}4dbmqE zXu!uNN68r%@>fjtT}O+q!+yrTMq-0otY1-?2Q5&s^jieX0u|N*zld|gLY<;5t*xD| z=XOG9Au`_umSWA}m3%r{>`cwBBBmZ>J;9>Uq2A%hjk2z8-``dPDR!cHAjxD&CXqQF ztlZ+EdF!X{xuky^!q&4h630FO_39lyuy6AF^3Dl#eBcuHhst@x-W+UZG|W6?&tkK#_W0cc z{Eq_(S_Ojm^3kksWGyRlGE>y!kLA|6cZ!$|+AjK$#KkYxCK6UV_F5@59WmH1a-j^q z5-&0y#0_1?j~}JY@D~^aAMOh_Yg7p83L**G9v-lPtLA zV)6zv?Z;Oba__h=3~w+GAIcV^KLML?h2nq&Q18M}6J5!Q*Q`qq=&wgz5+^UoXQtK{ zuT0#s+s&o9(=v%Qq8DkRd~ld{M|s?E__`|FI!NEkU)&cE!itZ4sz?k$zv~v8w{%$U zHkf&uVm}t;d>WT2y@|SZ8*;K@s>WJ-SA3W5k&^uOE3)DO8u>skc1wa?`g}QO+;~Nu zq_dj@a-81!(%d?G`MY+{=CBL1!yA2QR8zTJ<)afI5+=m=j}rXHl;`j&9>AUcxfoLa1X zQrg3~h4#qNMjnNzSA?kOVQS-rXJzk=d-aXm*Iu)h{nNcp!=AzWEIrguCjakloIaRW8E;RTpZCuqJUWB|dO)+&I)2rY9 zrstK_Z;)O);m$tou3x4FzCW3K`m-=(c=w%qf<#GOpK; z=0dmeT#dFOCT*H2{eAU4!Vg)SxRW@7K}>KIJJ2?5?iBmC^U8rp`a;`G>f+o8X)}le z9yd~U;Oof87m$>FhlRto$>D=cGcDcvrl$B_`5TMy&KGgjqh5mvtak$0`5A>#PWj{? zElV{ySIcMg8kY~Gk=OHV)zm0WEP!e%py>x#}*|bcns&HY| zXKx5^KdP$3=I+`#qQGCFpr#bh^4k{5vyxn(=FI>97<&ikOt!6SIJUcE+qTuQ?T&5R z>DX4swrxA<*tTu_$+`F3b3csl{YSu3hy!PsW;iuQ}K9BLdy=#G_%RO6cm7 z%)$+~)-_pY!cwEwNe9iX<|C9(68}RaazR6Z6>aVrNAjZC@7CD?Z>o+9)5W6n_pJ`| zvEh4gxchNAC`<9De0tD5C0^4`m|o-Xjpc7><*vx*mGE--kLFe>&g{fF0#>~eS&cM7 z<@*N!>#!7&Ch(ji^>J+8-`yHIt6f*9IEXlil_3WDiNRv#;8xXk`St zmuo&%Yn$39X97y5BKXn}rK;>-1MKSb@Vx|`ZY#pgBdAp{xIGajs!y)j_k07l9`+BX z6n=>?;Md=nsjyOIrfJ-Ek2ai-VJ}OS*8xoPay5BxihZDZNFRC=fs=rP$suM!=ioQ- z0_rDY{P@3x%YQGiGcd9JhnVoM0P!n~WM^afC${_>iqe0=o&Q+>iWI+G{|jFJ?f6eR z&Ht3B!>^>QE-OYUZEC6KX#Xj)AZ^VqNiA<^?D&;c{;!btp9Ov>`cKJ#zrxdhvUL7m z+6-SY^nX|hUwPpFNil(9{6q#{?JL}6_|$Ot+W*=zd;+>J+dsMrUq@eme|!IZ%<`!d z@!6pMf`OlXe;t2Hm3;1fwJ&cbrZ0fW{F!IK_Sc=h>|a-Zd4Bc(b>?5a{bl*oQ2fX8 zFZ*9!pPpYmeeHj3zef1C{cHcL{cZoc!@ti#{q4i}sr~TP{=V+Z_iM~w+pqR@?tg); zf4$?sp~U}$nf|BG@81d$pFrZ@EP~I(3x-dn3TnnrL5wc~0UkRu%l}3qp#GFt_!~vB zf5}4plX}5Q2ld~X7c8IRBL9|&_{39x(+HTDKWPMCW>LJ)RR8}*QD2G^Ujz9Uq2Tl8 zUsD(Vg`)nl{Qc;Eqo{wYzx z*BWR-TU%$ET3bP#oeO=1F`S*D5mveR{RM5DNf9*tI6HZMKRE8C^Z?VW#@cs^8W zG?uoQPp}WT3?vI?;99p!31$}z6X@<40LI$_wbt5H)j$I&@a4f0Xg_8`@r)_0FaXU2=eg(gn;4g?Vj#H)l@rz zPnnw^etul^A1AxC$UeU&d5JF)t?)4EeC|EBARTP%oIw26Ht^q90#o_$y4Fx2s=(L* z0Od=}p06ot0Nm7&Eq$mEU>rO<15$&20S_T%fz*6n-~$6-PO8%N(yfi@lmBfI>ULpn zRdvHZ+6Fiocs1QOG0T}TtC4u>i58Ku3;pmI!p`1Z8<@`u08_=j>ct&y^)~=sRla}F zoHk%vrbegn4R+ts+>uuAmDW96!T#?4xzQ1nofCMQyV48ZO%&Uj<@nmi^%?Yi;7q0`5DgfZ8+=wx_eWvrqh0a7pR%h>}4Y04} zJ2D_+7qW@|x!E3ogS~r@>)<;j=SRzdcELwmdvk5A|K!HJw72=2F$|tFYnDGVB@*~S ztBk~h^Ty}50BJ@0jR3yE3CO1EV`p`w_bHP>ChKGaGUubz7;W93uF(#N^AVuTXI|8T zLi+py5`608p=1o|5ts7%gD>Pm1nQMne*MF_|LppCM{5_3mJz{Z# z^P@8IT_z=wdT1KwmB#`g!#mhVr_}r8y>npy0<)^Pq*UVQg#HcH;)S(p`DLor{D}=1 z@MB9%W$Ea*?z{dCYJ6T^9BWt9FMkz)uAbq+cb@Qz9kQ-r?8}eMduzN%?||2&@|xyW z${|dhp^1@+2|$;Rw}S_5&K+<67%&YEwKpN8)bo9vQfH&5N&n96`db@EPvi1Vwe7e4 zkJXRy0lqBODI`AOxYPs_V+nX4L8Che8)V>t8 zy!D7>QZs&)mORj;6SVG7;V-%EE^rRqM_pkAu>cf-9eQK1%WymeZ?Y_L46|hlYf)aE zUSw|p^qYnYOB)%A3v}dfz#<%L-Fu;zCmHz3BeiU3LC+KD)Kd((_=t_)azBeFSM2V_ zv+NzdM_Sof7`PN2Ks8uLC6n_a#t0961503`StQO>9ph^qp#{`XD{eM(<8esTdnhYs96xE2!&iq4tNpvMDE9kKQWxKd)rK+Jj1@qI9F*6vm}mtrw=iIcAQh}&*VV4e&OylW8yl+i%1eQv|7Cx z@v1a`;1rWt03$Xb!Sd4%_YMZ`as}24qVV6o`us9R`v_(h0wEU{i5xrA|F);2kxK;l zL3#g@U>^$#Ru^0EBk&Wf`s@Z*GIA}8=VB(jBd}+~YK~H(ox7NV4~%s$s771eE|Azm z7}(?~onGFmM~h3+GteeCa1!cBEmn*$+=O{+GWxJ@wpO*E+%wXMBM%Nmdyw>4QYw(cDVIW7N^91btXb^DV(nTUa7;~BqU9+>bZP1V+)7~Cs?kVN*%-h z-C(F7o@($HYCURz#F4cJn1MkO^FiN^eh0;%#4NKo<_l{Qv3384rw}JtN&!*G%rOL0_{%$)!40t(pi|RA)K++ zwM7d)s(UZylN|of@%I`qp_ti(o{|%qC0ZQN_k{tC}TorM#t_y^mMFGKLEk z%7VG)HRsQztbaZBU%R`L7W$h>lGIzX&H>#?mqv!(I>_(7L#;IUC+9Zkf- zqU)`d?m6O<5b(KbtsgLNb8opJzG^%G#Z?=Kv38GK+M1evL7=aPJFn}`vu6E(kxw2D z&rndNB6sLA8`W1tm(xO#>U%Rndo|6b<5u)mHp-zBgq%o)JyZ46`dH&|hzQwuL1J#v z)LPnBTdYbizzY2FtnG@mNv5eF7Xld*?0A*He!!f-3y1Gkwra<__WRE+?MG zCsfbbm6p`4PteDX$0dhn^J8Oq1hFXRzUaCIt)Ip|AIW!Q{i(-*R6G3#=ei?CHjVG> z%tA*^JUq8ok%i!Is!~h?`^NrVb^)_6Re8?=ctE7)*Kd!@{I3DVK?q5rpk1N1Jvq5E z2*m1mD?hE6j(ANDeFj|la}Qi6TokY&|KTf#|}zsFd1DEDWVX_aodS&jn75O62n@ z{3-g0lkQBwQ*oD61sy<^W1{|3dEpPT;CU)b1g!no511?o2IRxOy~#giRQmve1WGQV zBluowX0jsYJ9nt03El%n3I)Da*x^d<(`cxXizN8iD<^|nbz6eD!ZU=ei#DPG`VnLc z2n@U3={m2Q>f;0SDHbwC3tIi=(@!~m#R<)|6LxDq5Ei1#b02bP>*=7&wP;t?-230n zx+aMX7}(d%HAk_}`U0HbMWy3p<5C|`Tz*3c13h%A~7=3P+Wv^MMUSLIxi1 z4=AST??r?{y|FMh^R!n)i@~@c%O1K{*~$Xt9A$UHziM^1ljWemjSD0x4xBR`24mP7 z5Qq~IFX#=9;pd9}0J>aqnV*-<(xxiZDkFQ=4G-}Mqpf2c;7;W#Av?xIe>qfJJ#!;{ zlzLfZ@SZc_o}_WTh}0v@K#VoKiwp<_{drY@shj4j9%B=2``ypD8jezsqZj>g4YEeA zL|oh{5JREqN!%?_5uAv!#7kKJ9)oG_-g3*|cycmuxZROajCj)e01yThohW8j3k*Ya zGSL=TiLVc;a&(M63=0lGj#fa*b|mVuWYTn{Qw&2-&PHvcV$!fPDC?t76h!i~!UTtb zBR-eH{VPp}^(h>lR@o)`S@H7XRR{`AppcQM?nvVr6)K9d@jp00B_zQ$5fnDaN| zj44m9rqX^dCuUkj8EMS3SaWn~PsC17AuIU&-JXH1uDbjK9fW~?_+Afr9IH#>Y507+ zlG7reD@Y|aabgLS1vE9~-2D=ai0nCh!}0pw#E_@s?GZJfRd{O+6H|&`#_6n=rnOf= zJ5E-5!*#koySo9j5=mQ7{?F+N`Te~fS|K6Sp{O`{vz67j9-~-xY;2RJ9P!VMWRmPh z6`fRyhQmEqPs@l8olTq4Ai6KEs%C?vq96##(pgXQ5r7R9#r0d28%**wS=_SZOJB1NwNPi@^&m`v-|?dfQ&80@_OniY z{z4dac^82x*f%aomW%H~T+AKp?2EXZsc;+SxclI8xec@FK#akX4*kisy#7$yj?1%sTVi(y7ggm$=k;noS0xy(fr zPkA*4pF2ttf^v2ssXS2P`UvoVrm5@fHrMF1_%+l|l@7Q#fBSW-Hm} zPi*~MN&>Rkr~^xxDWs_qN+iR2xuV3cSx5!-OFf#YkdP@n<*G(>#E3CN0UmSlu?Yi~ zkMc>XC)^8fndIz!LU>q(hdtia<%}ru#wXmi2yfK$s}R3AV;ECY#QqY} zWdJUF-`ZlJdNPz14U)~sK@569-s=`=FZm`_bT?nW?hXC@4_XT{glhxUIPPmnYE`fj z~#G|KAouxusoAQRWsSr-Ary3b$LcSjYM0DnNXnDeLy)we9Guk(WMTKI$W zhMgKzDA62s&%P3$=D=ncT>i-4Zdff<1w;qd*G`&I1Ya7i$b5byQ)(o*Vy>E(=b?6d z-7ve_gfeZ3=w}U>NKCC~WnAAr3_(oZ<+%pHi)G6|3^k*^v3 z1w3PBQ2#s!74f7~gv?XVd9*Q^5ZqJG1nn6+qbRY;IarN7e)F8}c%ed6)1T}HF{>xU zI)8&fs0*qB43Z3+B#orh;-d5lO>N+!Ut81>bie0#v&|_TqZ%Vk*oZi@Jd~@PjXGds zY7D4ohB)pCx22u4u_XO3tXo{Kfy$euAm`Q%bnJvra>+IB5kUG1+E6?+K>|o|y%JBp zuY3>N*rY=7j;Ul9MjO_#c!VjMz2Yk7WjLZD@V;2x#;}58;FD0XI-A zC$qs#s>2~-bXY7%1X3E$$_)i-Hjsi4pA~H~v(@nsljZcAXq?Yl{!}qG$w}oyR%JB@ zE5$ky%vJ!=z7ut9ER*(evD}5l9_;5%jOio<+JmPbPqD<-L1{*yU=yM%XM6s|lUj*y zYd|f{0gZPqwV!0m3<~FzDVm)IiAHsN1FBF9&V5{namx}bFPTlM*TXGrIE?8G(Q{8h zGtwJ6o*xjVi{bfJtw&v~{x)u!Ts|Ivrv6?u89@;e>#juQE^YZ8{tkqQ&HR|j>J6i; z_$~T#arE72)zekhCSW&U3t0>nN4!sr`chv4S9NA533<6;t@r)Sy--S7kx)!hb`P$t zrkDmZ#%2$9gI`2+xRK8>d6lpl-Kcr1v`OOk0pjWSfF&Dx3&9^SU*}})g&s-Do0!OZ zA(Df{E>T{;y+GEPW#yP|>!lcoUo@ie3pWQDwWH;~K`FQ4R zT?vy?jv=ipLj=1o24kED%meiuzx3hve(euy671RmjmP_NEM%iieN<~YaRSY#c+i%_ z-K3zN-F22JTTBt^ix-%8~yu@yHt za_`EZ=7;0UKinkYQ{RdrBl_SwHMKMIF3uDuTp9*0%kL z8|1w&lN#yO$tDdOjPQ{EDK(o<|?AqT8)z}z!< zhFiClt_*YyVqH810brzGPsAZ0+Pn;i!~ z7_%u5a5DyS$nq_c`G6PjG4gkB2v5i_!GGwdIkyo?>3{iKbuOSM6??5~M$C%fm_mUtrLg3z&U4CC)JeA1F(q1$wVF3Esb(Rm zKruGJ`ddAWI)9I2L|=!??H!F>m+}l+(7*h>g&RuvqpfG&;2R8>*lKAg9|tm-sQisM*|cZoJ>jO} zmk;&bXi5;;yrxZ=O3rz4SrK9Ywo*PtS>H@XmksVdzi zNIwK$*l%T+&VF3kLt$7yH8;6dh>R~Jp&A;d{=90SZ$A(0a4~3uwn}Efm@HS& z`2Y)E8_bAa59tWHlNsc~y10j>k22-(Iuj^M1U2kY4$LjKDMG1*Y&4^bqT&gVVkA#p zg|MS!=CaUc5oYurEQ}L^F{*=Y-+p86Dpj7;c^w4J@>y^;hN@50MmHTa?g}E%caci< z==4dsp|x^i-Edxw<01O4CH_5JhXoWI4sau6L{n;_Q#7TQz%(2{CL4JcleI3V=*bQQ zg2{7^O7PMT?N&-h*;FEj^xlF!pJ;O!q}=lDF3Yo= zF3+t*stOw>RT_jiu3dfvV-j#+ppDA$8TMt%`p)+EQ{%H#r8*gNzmNk5i}SiDeXne3 z{@K&YAImCowJ)R70vK@eYg%W@TDOc4bB0T{t-it%<5nFI zx~|H;}+>0NyGPh0B3hDTEEhXP%)PGTI?4Hn5C!Y$?$&gXf^A6TML#+TJ z*_~kg@dVevqknjj9Iz~$XE|wBU}@e6Hvi2zM{IhOLT=uJ<7AxwCQ)pQtVQUho}-97nWFV8&Fw z*g|9b@uhI^0bE5Jy`G(EpX=@QJdp+V-K}*e+LoMP_6K5Fp;j}j1pJj+edQW z7Y!<6`keZf5VyJ*t!LnjoVb0ym|2IMIU}JY${+JAb%V$oCY7mhN+gS2&mbUXqJ>0M zd>HN_#S|0kp_k$>CTNm={R)-Rc_!gg5`b7Cq{MSEZVa=2Cnklps4deFTiAk1KRwSm zYBQ51M>Lni$#yhm*`?Q{VU}s1q$$(PzXxMuJnx2~y!ehWroB^VO%~*^$G|u6Sxe95H+e(pG%iv+pUsSIyW zUfqQzlzh#fe+@@^HBzGGEhPOMm`2x+I-UHdUu5Uq+B^v+%ea?U8`(htnShwbXSK^9 z`9RvEHN2c=%3g6Wb>P;x{&>Lpn~S=&H*Ja@YCy*O>QPf@i63};TWdE7q)^@R376Fu z6KAO@T=C1LZ@ymFHG^X$j%SCiHfF3hJ&9-az1WrZ@=2r9kYI-_JdAv^wcp%V1|8g_ zy51kJvki##m(qu~q(MVN!&$LPNe$GI_rq&VAdG1Oi@t5f>>()I&?Z8o?yzzK6fC$dg#J0}C#$y@ zP5NM-n!7;1#gBdiMY)$g435nkQ&P~E?{AaWc~e1H4N@ao2)*Fvzl2M87I92-a=A!9 z?w3>6CoOeYW`9rm83YB>Z23EW;p&*7?UvhZvQ{!DZ|Ffgd_xER z<{ZluiWx6xctEc$dEc5>h10!bs*AS|03ijsDXVcOe&@)|&6>=spUFCJO4eh~@$3oA zu$JUDkT)YMz!#sJ#BHxOv?z8C%Su#v@YG3BEsoGB%5U9@FM+z(m$tub`?^hS*T?!Q z))CF=9>F}!gZC*t0Q$K(Ff+RRWUD#`a^o$e)k8P*B;QO>o?>`NlWZefHohDxF)hb@ zG=Dn5J|xPD;+vg=&Rkub4Pqu7v2Rx1h&lxeXFPw?Q@#}SA+F;GpfBGt)OSC)g1OWGrvO`&1 zc2d+`VEJjxqcr@w=|G-4bTgEOunWXjBX(svYFm!PH8OHbOT+@!q$NDnyXwr6&S3JT z&NCy(NmQZSrBN~aX_Il2-HH|GttjW=jrapcb<|uL8-WASAkQe_p`!S%K;cN-g)&|S z#UFX+beYnyj`N##<3QafOX|#;F z3{<`JSST+s0){2k*>d*>mlO8B$1>?JW zW4%WGW6T$rnr^zB6)|VSdVD$C=IF==xS zpM2s(RM%~H>R1b#dG93Yij9g3o4hne@kR{Nz@0rV8ua9WU8)=W7-i1wwI0~Z8Ij0_ z#MSH<6rpKd8}u!p1n?;k7o#FbdM~I5A#i}!SBWP;s1sac3oQ{Ngx0zI+APTd3Y;Ak z(c7PwTzn@doP;w|yv053qBYmkF3LMjbc^WjDy;>fdFzk*ChTZ(awQ~+wl-W^$z%*+ zaC;58{alcnWDmJxX<)QC50xN@6@lX===d?M@=K9AMMpK^UI zeVQy3uktahsp-W$!A=4!hqAG=+u;*pHxvz9-MHj#BT4Q6dQ0!617e8}#eb_76$V_g<@>o4{72X7B^cu>~V4pUV zyac)s>KF7!SO5%S7eAQlx-GsIG(_7e;;~T^WaMiq4@a#|X|as93uGfK3>q;b+}t;N zy>5N}10dkX6(2NUU00+4hzR%V^k8qm zJl02r%p@z6a_X!H+-zPAw3KvXZg*J~A? zBFQvt;kLh>qKn64B_Ty6LNy*`BrU*!g0R5N0%derB&M zpy);HNz@K3tMf6S4;iLqGEbunS1HzD#V#F}rUOSB^wP+zA*|AwEJKB#*!<{_1d(dc zhY08^#uG&5>V7s(Wi#-|gVpwP!5`V+T>Al}$7uQ4{==w8T1FwIb*Zma4)(>=Q%ix; z0W;0HYrFI&;&-;&xWnUAVotl*O5}1oiO~a}nD{r8hlQ%lNQ%@bu~gODCT3RapL7Lr zj+5)v5YG;pHdZvK*kzzOPzfE##%0V%(}>E8<@ce|iM4*X63Jj^OVFSnW#fMe`+kr( zO#yoQU?cPu8N+=>I;Si^x{#`+dZtV$r{Z95g*>r-)Hm%&5!c^DMka)6IJix@4sr=) zw0lNn6%ue0&c&>o>{H&bBgQi)a{I~HhV6&<4*MRd}|axjlZA+ zvBC<`=o#NM_fj}7GRn3^KPjEpEHQpX=@-^sf_PlVJ%vLAxH~G8))dWY5oa%CuEnAH zQCT7PvnIqoA=G9alR|+~TyVOVrcuhpC5CXkUm?SC6tt!+fk1}siFU7xxT%%HOoB`l zP1ZnN?X&_~>s&P2W^CaHm$pH4o zb9Q&K__(Gs5_(+ORm%!Dc7#Idm4i=Tj`l-dN!4cfDTLqm(qstm^@(A~UB~^J5MGW% zw%f2`)bP1c^Q!7#5626**#`ZT=Mpt2AkW_5S}U*8Lf}sO+a&#=?3!yELqu&ErnP6N zou|j;LL(L*aCF8cJY!fi3hQ`bgx+?k`^6@AbD`(@O0@+O7M-MoO}=xM3K<>D5EKDF zYB_siA^Tnzbi~qs)NiXFe4Gi+I4Kt_v0ys+{N{o)NAz=Al_1@iE#==35i%tpmkC0{ z-eGtbY)(w#I+kou_#T%1l>S_th1yBak9Da0)~<4Wii9bCcS(q(6W zIaMwmOE?n?7vCT+7#%%tRhh|qJ>KSvw**y7&{)W$t1(ZMj2;#Qvx)M@qL6`hMcOzS zM@}q=dE>;6*@RMBif1i+<+LA=TSewexScvm@Sy{jtS;>cDOOqsZ=17pMCiA(eEP$e z<5Yu7<RZ17$s6JD>H&6~LjgC>x2gvvpPtPA6J6|14GB9+> z8C_E%#p-ueU8egSK8iVv_*n}V>U)xIh{RFCnmJm0|71;CvYOf#1yhuU`L#hRNXuBK z_v?6>2QXB%j--@#k2ng~ZT8)SZ6hDVFzi`49W1yXG3PEkHHQu5_n%b$>2?AG!ls|D zC)4NHAy5@Q{|U)O{pcX}eYafLJoP>TFJ&z8N6x0*UWvj_c*xnF%gecv$ye(sm(C4R z;gfy$Uf9f1pFEkuaUR9{k%x=6*Y`>be>@ziyIb49!e!b;6K+v!HV_Vm$P4B_+&0pjv@5uUKuJjj3rXwTjK?D{}57uwrdpE7QjA6qhEg zZ`Z##0N5LByFn?(2yA1585fDW3-5MN;j9YUDcgBlO?8_cBp(9pl5)hxhH66}Yiq}q zoaU)Yj_MNeAm51Cm|j7apdv<|Jes7TpLD2363f7POnf+sHF0QRZF|!CU?$-YR<5QE zJOh3^x+JJDaAGw90AJ=scqt$sC#Z%gh~tU4ziOE_AqY$INY0I-gqU$H<=Ir25qJR^ z2I&mZx#Y|DQBtzl3>jT$nWc26x6RzyxYf+)Q(urepFRqeDfs0C8oyABTaU6%G(y5$ zNaS2dRLDfA^lQ|)$J>w&zn*(ZCnwYcF1Q5lX^h}CH*Fe(aduh?X_^9GKh+JJuAL)B zjfNA3FqogG(i}{-2{H!RydRz&OF26{hGz^F+OMaAj#gJ=+l9&(TwNB~YacUr{NYsX zs8Nt)0~1e{IU`gO^^HR{z4~DMHUz%*{w;xMQMbfin#AeZeJK|zW}Q!F;1Dg}sA0QQ56NTg{ha*gwWj28Rk-F7SNUo-SoB=K^?je?u`B zgUV+ow>dx~mrO@DF%Hmn%DnuxkF@y|EwYlTGaSzv>ya^Tg5@r$OX#NasmP4VQXxhi zdsLC0@$tGvZfcxzXhFLHCL5-@Kp1Hu6X7SJA<2aG14+y6^#&GdpZk$iBwVlE0ItrNC*K5GvNEx>?L*Vwn#WsSp{S_-2y0U9!f{H? zV~iuIghzsa{w!plf6aZQb`_rMJ(ycrn4THhL_hl78SdCt?M&K&XJindj%I>d#;~f{ zGt7E2)#j=+dg0~-A0xiBf*rz}`db(WnaYFhiWrM0&Yn@biLF3wLu0&7CK>n!99FiM zgRO@N)KL|am@Tz)sBB~kF2;6Ji)uFAh#@?_4H9>@X8zojAommjRfB)zr;O|>nEu4# z=llDmA5%k+&*NyJiOot}DQ%{UHvb)ST4_J>{Tj(cY|pEUtJDRWXA1)qmpnU1k1!6i zvi*+es;nG-572t1NK*l`wS_Y}EB4GQzDt=vHadE)P3{C*SA;2ly_NFY&R{h`{>I@q zkJ%=~#gDqJdRgI2p{Bl#$a?*xENMak(JH|nsn=e&qOpT@3^J2s(q-fvvXdJTt<${Y zEKe?y8msdF{!tZagCyz2c&F?5MxBOO_J?!Ei>Y>}=-#XIq$|SX>g|{cB(11iNg2_m z2(8nx)$a(yH6!-coA+>C^b$T}RSh?2;FEBp6j{9$c&iC1ey{=ptw+=9OT%?1WAl$T z+9$KUf)8oQd@>r+ZL)Ku3a=(-Kv|%PptUjK`xOM{94yhMr28^{~?zpA>IS+CW&?dDsNa7H4If}INfh7j{{Iq(# zj_BpE7!AL*q$o@G(lr{68M^CHz^~I9Zlq6tey4aEHcWix=T9X;JF>bViO;a5D_Bw$ zdjk!X<(Wmy0V_n}S(RMPq=eRSFX~!{aMW0_WR{=sHk613_WQ!S>Y=Qq6oC#`nLex2 zTy`T3GiL1DPCd@7=(Qyk?VOz{#$g}9NvMnnwU~{2Y2j7*LHSh=cY)`ghlaeD1x0{8 zH*`yOP(Zu2Nu?8~RxqCvWjFVFj+QO=77nDQ&ndlUYh!J5`(X9=W=W`sj{A}k_MqLST*rXX?YeL*Rs;M1t~5fh|^wcxDDF6k?2@QQ{ZssSBSNns9^f3 zg8(@S$cD7%H<7`^EIK+VnCwi&fh3B+h_XjK=L}lv1G+RdZOC*Z}n#H3QX7W zu=_ZMIacvtrD311yMoRS;Fnoh&1{R>nTre~lS=H_74m{dJ83pKjtchE3Heu$D)fJ4X58$Vy`CF#$Ry_(@MqT=LgxGpJ8)E_@5(SoC4F=ca& zW+Uf&9esK@b}_8Y%I!Ls#k-UmHnNpBO@rDnzMuPcVM6-|8dsJHHU8q*kZ)7?PNkxc z=l7WTx^>ELgH##MuF8j}gyZ2Y8qC{Y@YHgk6ox*i(S0}d;MBC~X-Q@;Mo|j1aeZ^7 zizU$H$~7x97cn6UY*DJN`!Yq_&U#2p);Ee|`yTuoez&DLnoZN=FidI*ia@?adr_=n z9Jg1mvO>!l0o0E~BsCyR*0V)T7%sWj=rlu5QG^oQvu^TXi8mnn=_eb8cYe^M3@tW6 zHPO^QkyS)l%&ED`W45i0SR0zOky!m>uQ#(84=Am)9**DO#yT36zW8Xm4)r#5wYp`K z%d{zHE>e8}-W4V;%K8akbAzyPPwtA(V!cOc*aT}-rKea;r06odR6QQWXeL)J(B5vPG+q! z5MRY|LA;vgAmEN}VHL~f**2{d*b+$vOilcBW!rQ*ok{!Ny@SH|IdgTqE96))&@QSH zdagqe&0DXyRLRJ79}Z%UZ|&$4Xk@empuusscRV0Zp@2c(;4DXj7pBVo5!^a>nikxh z$C|h_Krjz09FYOkkOB$zLku(BxIX~R8bMPl>)gb03Ah|0fpC?76RluTMt}qT+fesZ zSv`0L06Z>w;Vti~J-)Z7*<$jao}WSx1FPbayK%l5$_|&?bLv<7rAO&77+ZJN(Yb6@ zs6d&J*GrzJOSq)xHASsiXy28Dy^Ixpty@S7sxu(Pq&%Y&-rVOUZ8*Ufavz(d$w^>t zAbYLbVro-fNFAd7DPvYL2-|eTWB;D{`si4{XMEku5@3T^c(cxYB_QM)O%fRRAXcUQ z)O#bcJNHCMhIe01Hu`g2>vzf?&gHiAVkPi#!`UGdd?xs9b8KYDrc_Hq0plS3dN%>5 zzSnb$#$MzuYG%AZ88(K8fdWo#x)FcCPsrmP%@yo3&t}6-(`v7Y=4`$Oj zOu5Sm$A_4fU7;fKMiD~f1l)C_gNlHNIBX-9)_uoB`lv=LeI8+5Q|da$^s>XA~FWwgyq*&*^2B- z{IUG;gyH+*YfkN(6Qk>a1uEnv`_p4vuDh@Zm`dlb+H784h-lVo)*56oE(I#L(R(^0 zfeww$k9+)tVV>R-jdCU>JtYVZ?9BJZS*UyS&l#KdmGZ3PtwlDMGsT=X^`c6i&Jhh^ z=p_oJl1_KZWU!aOGWJoXpmTvep%T%|nElNGPJ=>iKd5ss4G94AB8RK8`?pC14-=R27 zww#M08M=g4!S8Gic^nQtRi{6Tw$UMI-}MKxaJ>mw7IHjHu=Co>*IzwL( zU)z6EMZcuE|3wx3l46%6P!vF;=s-viN>sBZFD_~JjaW#dFvpJ6?1Fju zj;qi<;|)ChpzN+!{oIxxPl%^w1qc){SZcpwH<{(#h}4L++zT@hl?fb0%k zzK}BlUKPiE!pTgcvezPxOq1Ao)qtEV-&?@X(sCPT^8j@w^Z+Gbn#h=G0)VDry()~q zb?dSF>YDUh*S^B@q74{ay_5Ig0IEr*vSW?;0eEt4Y1~Lwz%oMRw9+A}Lv#VCX&$aL zgG&anQIWtjS2as^=S+Qfc$NTu*|LY%ofgmy9tCCjIJ@@ifSr!O2J7LK3($F%i9@xp z45`kpObV+EN;uzOP!p&QG_~OP1_uU_76BOD3+Srq@KRKdz8D0aOx8&T5GtUCiP2>N zA_dq(7>(xBy{`j0%GwVYNaII%+G)K4YS0tRNs9&aUO@AmEe;6vN3s!B%$@Z}cL=bgk?08*H(D?kV1MqxK9um}QTMsDks4Pi5fV~3Bf zhUlk*{Dvjiw>1DEZLGBNQuDOfgLNLx`2B3fCn{v0?@*;;}FQWnWFXf^2KX=N6Ry&^cKGEGEkjY)R-IjIfrggfDR zhL_1d=30JJ1H?+hNP&gU)00tqp2pg5B6n`({M*h(5s{MzWE$JELgPgwEe6F6s17IL zw0e_fsJF1B;OI7VBV`&_mG#%)NE*Ep zz5l^n@^z~Ju)=nmoo?aq%=c_0Hpb$gwx}_)OlkOn>cZ%@L?79XZ7B;%F0?FkT{60V zreYMjGI3YrG?^dncU}%ceS2q7xv=S7MF?0!9y<1&NDceF+&wOSu0g*KS5qTl!%Ob3 zMu+6>dq%oW=E*Eds~u7-oLx4n-d7~#7{MaID0;R$E0AYt1;zFqL}i4J2Std2TB>lM zija6?einkJ-TaeNXkH=WV;(0uQ4UEFqe$bPxL>;Ak`TY}P5;=P;$gdHMh~{**KMV# z(~SR}#vPmT%pVcf3!GUpnfcv@f`hb}y95=cSDanf&2WwDF!-u@LmSKhWQqC)sd&&S;a?h(w$X8!@OcGLgMYn}*0*;q_|BmR5%BU}B=VDY?%3 zEmg2?UG81R>+5U`0F(p=XR$+biV(S-ulUlqu8JQKK=?c@f+j;V3-f%?|TeUKAFW&J0)r zC%@45t^wOEH;)p*&@~ETb?7bQQj$s47p}MeH2D8`d&{sowybLuC%C&y(BSUw?(Xgm z2~Kc#4-(wnoj`z~!QI^n?tGh^lVja)ci%tv*-#X#7NzT<#vF65F^cqCfXuX`Pm&ww$J|dq@cn3&O-r zvemxQ%Tri2(}ahFNB;3i0rj&qE~i|(8{y>W6f>w!wrUqU0#G9w^)=o@A-9%+$YY%sj(Y%7^v?+%@p{+<3&rb*KagZC(Q4EKms>ABQz!P%$nj!GBUOSWT zQM~GFH44^Sa`uee4l=3N3-qf>sFYB=ch`KS22F>d#*Mn9J--!}}sO6_J=LCNlk8P#q|J_jI@8-5T!n};D_7_7M8E(vvTLVcEJx*l#A6rTl56FAIECt)3TqWyju}I z9Le`T43MTLy5iaioL*s$CY3ABo9j*`huWp)BOjx{i+p?Kf4cg{BgK}yqk(*KAeXnU z=?B85JKhBb{klf<7p-T{q6LLnYIkWFvE8-(F}R?&ik_`}fGh-HLUsoN9l=VK-zJ@) zHo5Ul35q36;*pXRT%`#5)L7-NfpN z?ayvJO;;F8YlX@CqjuhrBL^);l*o3`VxJF3dPc~V#byHep6=_q4bTiOonMmM)ozwj z=!#Vpklm=xE1Ivi16!8jXTRW7h+tUa7G;&A)u6`y|rsb2YleXft)PU@~J@%BuhiyXoI zxeV7(ZFA7$%6O)eLvu@c4h^RP*}2zy)8b2!_<9b>r_XY#kOX)xoT^@N>?Eh9lFTi| z+f;T!@e(c8A6!Su%=;!H_%&Q$ z2Z-PNlCt~>kzX4DqL+Va-2TML{}LJju=Br08vsQAf2!HaDvC)8NdnYt75`me1Q3q- z{}34cO~C5=|7rO@^a2RZ{$HP0WuM=ai~gqL^Ydc<_3r%p zSnMD7<==&3jO7XJ^B2{gpDn*G^j9dx@;6PM*HG+tO`bng zdsu!(!M}pF*HG-YAn(6xpDKE=146NacnK1tDOAU*07tgXG-rpY`rJ=$4SyTCU;1~-n0(~ql z=G6ziBZ1snG&OD-5ho~zP-jS4r)P=z0x?z296*TDMU45em^22S-Pal#HDZd;kGU&R zAV=`XUZ?A$C}_wRSakjXbwpg~SeJ1y5dMO=IbS|h@%-GYfCTG(VAw9>d6^yh&Okw; zl)xB}sbq6Ypf?hX{<1KT1M)zcW3hhD{)n_MaGHD=jqBgdqx7q)+T@E~-uQPbYu3~@k#_Aw^+I}E*`?$U@s zdwi($!uC=t1e0*FEz;P*^$Aa#3vcLbExxUZ9_-;D0c`~@fkv}|OGnD&dJB7Z)>7l- z#S5f7E)yxo^!gz&9_6cunqG{+XA{Q<5Yh?@cJ3L*3>*4Slx|ABp8=Pv46z8)gm_Ln zdjHgTy@<>(HWoG!rg<#L{7~AqBYAg7FJverX#jIx7XOiiHrl!`M<|Yo6C+p<0qzHh z<#s#S9sK%fO8Rri9ifWaGQ-oj_*8NEi-1JQO@6_rA3F#b8Pjg9aFqut=oV*i?c*_M zR@NIPJ%!B#(WML4+0wnH0STm-_@^*E1({m&H>5!r&f0CFhudI6T^d|!gx*9Z4le|U zW8(2(k`TSXGPn-!XZweeqm1$^ylmRk3^KvNTE29}s7JF`PqUJ_>3E9B_KF_*kM)`0 zYmu`DL|M#2wE{-Zq1X&hOLc^^%~A`PFGmdiv=MDooGz z_eF{4SJ7o&&sDCI6ui^G$s^vJ>>YCt3n$bss9k2$Jo}!W(yG`g>NtGojjkZ_j`@nl zm3BbU$ZvOxj%a$WZTZftLi$8T#G_R-2ezy*#hCX;A0wr9@ z*unJ7wFHxD-2F)C*X@dF^t-mb?mcDOBcoiP4~ti=v^zO0o3p|nPks>H;t8oKBr`YJHZ83)X7m=wwtAnf`tdzOMlHbb)J#j7RmmJLtdhk4p41!GcFyH3Y|l&5Lgt&7hLtW2p)<{BmiaCGBjsMNWi`e?0> zTu3}%?#h3Fef!NaxMFzbgHZSaU(JEd-Z}QPi%CO)HNoWonQ; zUSA!|YFju`+MS~LX147JVY=KpD_5z2$ABjdTZh7MhF^Z!?Dn~CximOA zwbp^5&jWFhz?;$8`&>ADuT^*Ez=a9MovvsRPGsbI$paaO!lYz|RnBI)0wN;>nLlfk z3UgRkF_RDGSRmSQPL@ldGx1AA0NNrSZ&nD&-0m%BpZgn9RVGGq$w5#^h7|Ya!Jcqv z5>0UI{))Ai9f21a+!vp&8o?J5&KPsVH?>&Zgr1mB7^QZBKP5b!oE=RJZ2kn&uMp@J z7cnw$aQxZ&E62dj{%4lrCl-3`3V=y}>H3S~{%bnomB9W5w*FLy{7;x$Qc6}sUI2i( zWhDMB=>AEX|F78yKtAQqY{V<6{|D&)0|x(;zWh5B{uO=vFKLN?p6wxg#m#3FIflx7H0iD>F@^@X8jrX`~?dGF7SU#ODI|>qpG2c_U1Nh2B;YK-m))1 zgS1P4!Wme&_NwN^dI4C{&v~sSN;>*XgtWdyh~uFk`}6}9z@gZL?>4^})^4#{Ye7gM5eyZD&+W9>VVRI3Q4ws~S9<~A09^;MY z{5$>(jd$1?C$fZyp&KcX!o={tBb)OdBcYJH=7H2*;g{gxwYjkInl@`lK_Vkb{F++> zgNz|>6$AK15Fx-2v4X{mv5Cb&0-D~443I*sNs$urI|;#qAaV$j64U$lnSx@X#p-h* zhZ`~%h{n^A_4zHogC!qW$wx*Klnn*hVPd2KdW+o0Ac5?Q#1PqxRoFt5kn|E%*8H^{ znKW)BMp?}X;KEqGS1d3D;2pFCOj5QfMV%VLGU!PfklkHGS5Lvmm-|+35 zD$_-Jb=KNSp>5qF5Wgn{MO4V%7~!blwKouB)dHKV5%2}+S!%vM+1sbN89xRH1Q{6V zC4zuvtTo^~$O?k885B^IYDwh5-tZ{#AH+AFGODrx|+;T}JwjB|7KWa%9s)cKyLp%6DM(QAT zO5!;tG%D;>4NP4JXB)o#ejgm4%GldnJT7ReyWJ(r`*Hsew~)kILx`4#(Da<;X_f`jIa5ql4v>&b zx0&Fkl4PCK^j74Wo9O6zJHB)tD#A5n+&v;@nOAV3AQqgv{v9L(8Iw8MDa zEFHI@AQ!(>s6`=gT{IM9i$*P0Nb8)@+lY9=8?oDa)jUn!?LL(l#Z@e-&6afNHP8~k zOINR?5%}axR62Gt?_=3H*rJ_Y(jDD>rQFTDz@ZBZ4-r~RXkI<}afP0|H?CHa726X0 zSSV$LDO@x(zrz~Q1tBL(M(#Lj8@j_O+S{@3$crzp8|!I*vsa6so|q*%iJNqJ1AiuM zocS^=<(2-NGs|TVnrUX_(S(gtqPX((%sYr9&ZSn7T(v;Cbyz<-LRP4WFWqEYzq1z# z8m|#2KUDVNNy)jXSXt9XJQxm=u2rCV=U|)4uN!=IcZfkH{+&lBh6LYrOT#<5kW|jO zLrpU)QQI^Mm#zRSufw;8^>wEQ(h=J<1i0ka=qs1i4-M>)uFXmt1lKvngZnFy#Q{7J zYN9oqwpsIph%hTbFiu7hUu#J4AQxbxLp^NOr`a2;=H_kHN;7@vZN_$k5D9|&Ktzv{ zimZ+Tk&+6=zd&k$mUpz=8!d9>` zoZQy0%5wN+>6pD7T;<^#A%L#`DAvSSyKMHHExa<>lF#kZyQct7Gv9Xw5*N4r)(G2! zA_+>n!eBO<)|%FXngU8tHjPqg$a`Y+M~LIHWB+Zb7F(g?h+NvSmjRmdv>cz&`y#6M zm$lbEPm3mE%SG(IUQ)WVRvgpKQ&kc#5hoJ^qo2bT0p6@ZG1S|vix8Fw4X7M0x zm#r_eJqEW2nhca8Rd)Nnmt{Kp*{@goseL8CKH{dIY1s6PYhxbPHM7B+b*W~1u{f?X zem}AycuGe`_tb7OA5+9QS5)Pr8c>lslYU)Mo#%P zT9j!e4-G3hf@S@Ndt-gEH`>@@1#bFlk3|;AgZF`PkRB$r57YA;Uw*H*jo5;H`Chue zVPokymm4jNJ